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 SimDeviceSim wrappedSimDevice = 022 new SimDeviceSim("DutyCycle:DutyCycleEncoder" + "[" + encoder.getSourceChannel() + "]"); 023 m_simPosition = wrappedSimDevice.getDouble("position"); 024 m_simDistancePerRotation = wrappedSimDevice.getDouble("distance_per_rot"); 025 } 026 027 /** 028 * Set the position in turns. 029 * 030 * @param turns The position. 031 */ 032 public void set(double turns) { 033 m_simPosition.set(turns); 034 } 035 036 /** 037 * Set the position. 038 * 039 * @param distance The position. 040 */ 041 public void setDistance(double distance) { 042 m_simPosition.set(distance / m_simDistancePerRotation.get()); 043 } 044}