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 org.wpilib.hardware.rotation;
006
007import org.wpilib.hardware.discrete.AnalogInput;
008import org.wpilib.hardware.hal.HAL;
009import org.wpilib.hardware.hal.SimDevice;
010import org.wpilib.hardware.hal.SimDevice.Direction;
011import org.wpilib.hardware.hal.SimDouble;
012import org.wpilib.math.util.MathUtil;
013import org.wpilib.system.RobotController;
014import org.wpilib.util.sendable.Sendable;
015import org.wpilib.util.sendable.SendableBuilder;
016import org.wpilib.util.sendable.SendableRegistry;
017
018/** Class for supporting continuous analog encoders, such as the US Digital MA3. */
019public class AnalogEncoder implements Sendable, AutoCloseable {
020  private final AnalogInput m_analogInput;
021  private boolean m_ownsAnalogInput;
022  private double m_fullRange;
023  private double m_expectedZero;
024  private double m_sensorMin;
025  private double m_sensorMax = 1.0;
026  private boolean m_isInverted;
027
028  private SimDevice m_simDevice;
029  private SimDouble m_simPosition;
030
031  /**
032   * Construct a new AnalogEncoder attached to a specific AnalogIn channel.
033   *
034   * @param channel the analog input channel to attach to
035   * @param fullRange the value to report at maximum travel
036   * @param expectedZero the reading where you would expect a 0 from get()
037   */
038  public AnalogEncoder(int channel, double fullRange, double expectedZero) {
039    this(new AnalogInput(channel), fullRange, expectedZero);
040    m_ownsAnalogInput = true;
041  }
042
043  /**
044   * Construct a new AnalogEncoder attached to a specific AnalogInput.
045   *
046   * @param analogInput the analog input to attach to
047   * @param fullRange the value to report at maximum travel
048   * @param expectedZero the reading where you would expect a 0 from get()
049   */
050  @SuppressWarnings("this-escape")
051  public AnalogEncoder(AnalogInput analogInput, double fullRange, double expectedZero) {
052    m_analogInput = analogInput;
053    init(fullRange, expectedZero);
054  }
055
056  /**
057   * Construct a new AnalogEncoder attached to a specific AnalogIn channel.
058   *
059   * <p>This has a fullRange of 1 and an expectedZero of 0.
060   *
061   * @param channel the analog input channel to attach to
062   */
063  public AnalogEncoder(int channel) {
064    this(channel, 1.0, 0.0);
065  }
066
067  /**
068   * Construct a new AnalogEncoder attached to a specific AnalogInput.
069   *
070   * <p>This has a fullRange of 1 and an expectedZero of 0.
071   *
072   * @param analogInput the analog input to attach to
073   */
074  @SuppressWarnings("this-escape")
075  public AnalogEncoder(AnalogInput analogInput) {
076    this(analogInput, 1.0, 0.0);
077  }
078
079  private void init(double fullRange, double expectedZero) {
080    m_simDevice = SimDevice.create("AnalogEncoder", m_analogInput.getChannel());
081
082    if (m_simDevice != null) {
083      m_simPosition = m_simDevice.createDouble("Position", Direction.kInput, 0.0);
084    }
085
086    m_fullRange = fullRange;
087    m_expectedZero = expectedZero;
088
089    HAL.reportUsage("IO", m_analogInput.getChannel(), "AnalogEncoder");
090
091    SendableRegistry.add(this, "Analog Encoder", m_analogInput.getChannel());
092  }
093
094  private double mapSensorRange(double pos) {
095    // map sensor range
096    if (pos < m_sensorMin) {
097      pos = m_sensorMin;
098    }
099    if (pos > m_sensorMax) {
100      pos = m_sensorMax;
101    }
102    pos = (pos - m_sensorMin) / (m_sensorMax - m_sensorMin);
103    return pos;
104  }
105
106  /**
107   * Get the encoder value.
108   *
109   * @return the encoder value scaled by the full range input
110   */
111  public double get() {
112    if (m_simPosition != null) {
113      return m_simPosition.get();
114    }
115
116    double analog = m_analogInput.getVoltage();
117    double pos = analog / RobotController.getVoltage3V3();
118
119    // Map sensor range if range isn't full
120    pos = mapSensorRange(pos);
121
122    // Compute full range and offset
123    pos = pos * m_fullRange - m_expectedZero;
124
125    // Map from 0 - Full Range
126    double result = MathUtil.inputModulus(pos, 0, m_fullRange);
127    // Invert if necessary
128    if (m_isInverted) {
129      return m_fullRange - result;
130    }
131    return result;
132  }
133
134  /**
135   * Set the encoder voltage percentage range. Analog sensors are not always fully stable at the end
136   * of their travel ranges. Shrinking this range down can help mitigate issues with that.
137   *
138   * @param min minimum voltage percentage (0-1 range)
139   * @param max maximum voltage percentage (0-1 range)
140   */
141  public void setVoltagePercentageRange(double min, double max) {
142    m_sensorMin = Math.clamp(min, 0.0, 1.0);
143    m_sensorMax = Math.clamp(max, 0.0, 1.0);
144  }
145
146  /**
147   * Set if this encoder is inverted.
148   *
149   * @param inverted true to invert the encoder, false otherwise
150   */
151  public void setInverted(boolean inverted) {
152    m_isInverted = inverted;
153  }
154
155  /**
156   * Get the channel number.
157   *
158   * @return The channel number.
159   */
160  public int getChannel() {
161    return m_analogInput.getChannel();
162  }
163
164  @Override
165  public void close() {
166    if (m_ownsAnalogInput) {
167      m_analogInput.close();
168    }
169    if (m_simDevice != null) {
170      m_simDevice.close();
171    }
172  }
173
174  @Override
175  public void initSendable(SendableBuilder builder) {
176    builder.setSmartDashboardType("AbsoluteEncoder");
177    builder.addDoubleProperty("Position", this::get, null);
178  }
179}