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.math.geometry.Rotation2d; 009import edu.wpi.first.wpilibj.AnalogEncoder; 010 011/** Class to control a simulated analog encoder. */ 012public class AnalogEncoderSim { 013 private final SimDouble m_simPosition; 014 015 /** 016 * Constructs from an AnalogEncoder object. 017 * 018 * @param encoder AnalogEncoder to simulate 019 */ 020 public AnalogEncoderSim(AnalogEncoder encoder) { 021 SimDeviceSim wrappedSimDevice = 022 new SimDeviceSim("AnalogEncoder" + "[" + encoder.getChannel() + "]"); 023 m_simPosition = wrappedSimDevice.getDouble("Position"); 024 } 025 026 /** 027 * Set the position using an {@link Rotation2d}. 028 * 029 * @param angle The angle. 030 */ 031 public void setPosition(Rotation2d angle) { 032 setTurns(angle.getDegrees() / 360.0); 033 } 034 035 /** 036 * Set the position of the encoder. 037 * 038 * @param turns The position. 039 */ 040 public void setTurns(double turns) { 041 m_simPosition.set(turns); 042 } 043 044 /** 045 * Get the simulated position. 046 * 047 * @return The simulated position. 048 */ 049 public double getTurns() { 050 return m_simPosition.get(); 051 } 052 053 /** 054 * Get the position as a {@link Rotation2d}. 055 * 056 * @return The position as a {@link Rotation2d}. 057 */ 058 public Rotation2d getPosition() { 059 return Rotation2d.fromDegrees(getTurns() * 360.0); 060 } 061}