001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj.simulation; 006 007import edu.wpi.first.hal.SimDouble; 008import edu.wpi.first.wpilibj.DutyCycleEncoder; 009 010/** Class to control a simulated duty cycle encoder. */ 011public class DutyCycleEncoderSim { 012 private final SimDouble m_simPosition; 013 private final SimDouble m_simDistancePerRotation; 014 015 /** 016 * Constructs from an DutyCycleEncoder object. 017 * 018 * @param encoder DutyCycleEncoder to simulate 019 */ 020 public DutyCycleEncoderSim(DutyCycleEncoder encoder) { 021 this(encoder.getSourceChannel()); 022 } 023 024 /** 025 * Constructs from a digital input channel. 026 * 027 * @param channel digital input channel. 028 */ 029 public DutyCycleEncoderSim(int channel) { 030 SimDeviceSim wrappedSimDevice = new SimDeviceSim("DutyCycle:DutyCycleEncoder", channel); 031 m_simPosition = wrappedSimDevice.getDouble("position"); 032 m_simDistancePerRotation = wrappedSimDevice.getDouble("distance_per_rot"); 033 } 034 035 /** 036 * Set the position in turns. 037 * 038 * @param turns The position. 039 */ 040 public void set(double turns) { 041 m_simPosition.set(turns); 042 } 043 044 /** 045 * Set the position. 046 * 047 * @param distance The position. 048 */ 049 public void setDistance(double distance) { 050 m_simPosition.set(distance / m_simDistancePerRotation.get()); 051 } 052}