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 static org.wpilib.util.ErrorMessages.requireNonNullParam;
008
009import org.wpilib.hardware.discrete.CounterBase;
010import org.wpilib.hardware.hal.EncoderJNI;
011import org.wpilib.hardware.hal.HAL;
012import org.wpilib.hardware.hal.SimDevice;
013import org.wpilib.util.sendable.Sendable;
014import org.wpilib.util.sendable.SendableBuilder;
015import org.wpilib.util.sendable.SendableRegistry;
016
017/**
018 * Class to read quadrature encoders.
019 *
020 * <p>Quadrature encoders are devices that count shaft rotation and can sense direction. The output
021 * of the Encoder class is an integer that can count either up or down, and can go negative for
022 * reverse direction counting. When creating Encoders, a direction can be supplied that inverts the
023 * sense of the output to make code more readable if the encoder is mounted such that forward
024 * movement generates negative values. Quadrature encoders have two digital outputs, an A Channel
025 * and a B Channel, that are out of phase with each other for direction sensing.
026 *
027 * <p>All encoders will immediately start counting - reset() them if you need them to be zeroed
028 * before use.
029 */
030public class Encoder implements CounterBase, Sendable, AutoCloseable {
031  private final EncodingType m_encodingType;
032
033  int m_encoder; // the HAL encoder object
034
035  /**
036   * Common initialization code for Encoders. This code allocates resources for Encoders and is
037   * common to all constructors.
038   *
039   * <p>The encoder will start counting immediately.
040   *
041   * @param aChannel The a channel.
042   * @param bChannel The b channel.
043   * @param reverseDirection If true, counts down instead of up (this is all relative)
044   */
045  private void initEncoder(
046      int aChannel, int bChannel, boolean reverseDirection, final EncodingType type) {
047    m_encoder = EncoderJNI.initializeEncoder(aChannel, bChannel, reverseDirection, type.value);
048
049    String typeStr =
050        switch (type) {
051          case k1X -> "Encoder:1x";
052          case k2X -> "Encoder:2x";
053          case k4X -> "Encoder:4x";
054          default -> "Encoder";
055        };
056    HAL.reportUsage("IO[" + aChannel + "," + bChannel + "]", typeStr);
057
058    int fpgaIndex = getFPGAIndex();
059    SendableRegistry.add(this, "Encoder", fpgaIndex);
060  }
061
062  /**
063   * Encoder constructor. Construct a Encoder given a and b channels.
064   *
065   * <p>The encoder will start counting immediately.
066   *
067   * @param channelA The 'a' channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
068   * @param channelB The 'b' channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
069   * @param reverseDirection represents the orientation of the encoder and inverts the output values
070   *     if necessary so forward represents positive values.
071   */
072  public Encoder(final int channelA, final int channelB, boolean reverseDirection) {
073    this(channelA, channelB, reverseDirection, EncodingType.k4X);
074  }
075
076  /**
077   * Encoder constructor. Construct an Encoder given a and b channels.
078   *
079   * <p>The encoder will start counting immediately.
080   *
081   * @param channelA The a channel digital input channel.
082   * @param channelB The b channel digital input channel.
083   */
084  public Encoder(final int channelA, final int channelB) {
085    this(channelA, channelB, false);
086  }
087
088  /**
089   * Encoder constructor. Construct an Encoder given a and b channels.
090   *
091   * <p>The encoder will start counting immediately.
092   *
093   * @param channelA The a channel digital input channel.
094   * @param channelB The b channel digital input channel.
095   * @param reverseDirection represents the orientation of the encoder and inverts the output values
096   *     if necessary so forward represents positive values.
097   * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
098   *     selected, then an encoder FPGA object is used and the returned counts will be 4x the
099   *     encoder spec'd value since all rising and falling edges are counted. If 1X or 2X are
100   *     selected, then a counter object will be used and the returned value will either exactly
101   *     match the spec'd count or be double (2x) the spec'd count.
102   */
103  @SuppressWarnings("this-escape")
104  public Encoder(
105      final int channelA,
106      final int channelB,
107      boolean reverseDirection,
108      final EncodingType encodingType) {
109    requireNonNullParam(encodingType, "encodingType", "Encoder");
110
111    m_encodingType = encodingType;
112    // SendableRegistry.addChild(this, m_aSource);
113    // SendableRegistry.addChild(this, m_bSource);
114    initEncoder(channelA, channelB, reverseDirection, encodingType);
115  }
116
117  /**
118   * Get the FPGA index of the encoder.
119   *
120   * @return The Encoder's FPGA index.
121   */
122  public int getFPGAIndex() {
123    return EncoderJNI.getEncoderFPGAIndex(m_encoder);
124  }
125
126  /**
127   * Used to divide raw edge counts down to spec'd counts.
128   *
129   * @return The encoding scale factor 1x, 2x, or 4x, per the requested encoding type.
130   */
131  public int getEncodingScale() {
132    return EncoderJNI.getEncoderEncodingScale(m_encoder);
133  }
134
135  @Override
136  public void close() {
137    SendableRegistry.remove(this);
138    // if (m_aSource != null && m_allocatedA) {
139    //   m_aSource.close();
140    //   m_allocatedA = false;
141    // }
142    // if (m_bSource != null && m_allocatedB) {
143    //   m_bSource.close();
144    //   m_allocatedB = false;
145    // }
146    // if (m_indexSource != null && m_allocatedI) {
147    //   m_indexSource.close();
148    //   m_allocatedI = false;
149    // }
150
151    // m_aSource = null;
152    // m_bSource = null;
153    // m_indexSource = null;
154    EncoderJNI.freeEncoder(m_encoder);
155    m_encoder = 0;
156  }
157
158  /**
159   * Gets the raw value from the encoder. The raw value is the actual count unscaled by the 1x, 2x,
160   * or 4x scale factor.
161   *
162   * @return Current raw count from the encoder
163   */
164  public int getRaw() {
165    return EncoderJNI.getEncoderRaw(m_encoder);
166  }
167
168  /**
169   * Gets the current count. Returns the current count on the Encoder. This method compensates for
170   * the decoding type.
171   *
172   * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale factor.
173   */
174  @Override
175  public int get() {
176    return EncoderJNI.getEncoder(m_encoder);
177  }
178
179  /** Reset the Encoder distance to zero. Resets the current count to zero on the encoder. */
180  @Override
181  public void reset() {
182    EncoderJNI.resetEncoder(m_encoder);
183  }
184
185  /**
186   * Returns the period of the most recent pulse. Returns the period of the most recent Encoder
187   * pulse in seconds. This method compensates for the decoding type.
188   *
189   * <p><b>Warning:</b> This returns unscaled periods. Use getRate() for rates that are scaled using
190   * the value from setDistancePerPulse().
191   *
192   * @return Period in seconds of the most recent pulse.
193   * @deprecated Use getRate() in favor of this method.
194   */
195  @Override
196  @Deprecated
197  public double getPeriod() {
198    return EncoderJNI.getEncoderPeriod(m_encoder);
199  }
200
201  /**
202   * Sets the maximum period for stopped detection. Sets the value that represents the maximum
203   * period of the Encoder before it will assume that the attached device is stopped. This timeout
204   * allows users to determine if the wheels or other shaft has stopped rotating. This method
205   * compensates for the decoding type.
206   *
207   * @param maxPeriod The maximum time between rising and falling edges before the FPGA will report
208   *     the device stopped. This is expressed in seconds.
209   * @deprecated Use setMinRate() in favor of this method. This takes unscaled periods and
210   *     setMinRate() scales using value from setDistancePerPulse().
211   */
212  @Override
213  @Deprecated
214  public void setMaxPeriod(double maxPeriod) {
215    EncoderJNI.setEncoderMaxPeriod(m_encoder, maxPeriod);
216  }
217
218  /**
219   * Determine if the encoder is stopped. Using the MaxPeriod value, a boolean is returned that is
220   * true if the encoder is considered stopped and false if it is still moving. A stopped encoder is
221   * one where the most recent pulse width exceeds the MaxPeriod.
222   *
223   * @return True if the encoder is considered stopped.
224   */
225  @Override
226  public boolean getStopped() {
227    return EncoderJNI.getEncoderStopped(m_encoder);
228  }
229
230  /**
231   * The last direction the encoder value changed.
232   *
233   * @return The last direction the encoder value changed.
234   */
235  @Override
236  public boolean getDirection() {
237    return EncoderJNI.getEncoderDirection(m_encoder);
238  }
239
240  /**
241   * Get the distance the robot has driven since the last reset as scaled by the value from {@link
242   * #setDistancePerPulse(double)}.
243   *
244   * @return The distance driven since the last reset
245   */
246  public double getDistance() {
247    return EncoderJNI.getEncoderDistance(m_encoder);
248  }
249
250  /**
251   * Get the current rate of the encoder. Units are distance per second as scaled by the value from
252   * setDistancePerPulse().
253   *
254   * @return The current rate of the encoder.
255   */
256  public double getRate() {
257    return EncoderJNI.getEncoderRate(m_encoder);
258  }
259
260  /**
261   * Set the minimum rate of the device before the hardware reports it stopped.
262   *
263   * @param minRate The minimum rate. The units are in distance per second as scaled by the value
264   *     from setDistancePerPulse().
265   */
266  public void setMinRate(double minRate) {
267    EncoderJNI.setEncoderMinRate(m_encoder, minRate);
268  }
269
270  /**
271   * Set the distance per pulse for this encoder. This sets the multiplier used to determine the
272   * distance driven based on the count value from the encoder. Do not include the decoding type in
273   * this scale. The library already compensates for the decoding type. Set this value based on the
274   * encoder's rated Pulses per Revolution and factor in gearing reductions following the encoder
275   * shaft. This distance can be in any units you like, linear or angular.
276   *
277   * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
278   */
279  public void setDistancePerPulse(double distancePerPulse) {
280    EncoderJNI.setEncoderDistancePerPulse(m_encoder, distancePerPulse);
281  }
282
283  /**
284   * Get the distance per pulse for this encoder.
285   *
286   * @return The scale factor that will be used to convert pulses to useful units.
287   */
288  public double getDistancePerPulse() {
289    return EncoderJNI.getEncoderDistancePerPulse(m_encoder);
290  }
291
292  /**
293   * Set the direction sensing for this encoder. This sets the direction sensing on the encoder so
294   * that it could count in the correct software direction regardless of the mounting.
295   *
296   * @param reverseDirection true if the encoder direction should be reversed
297   */
298  public void setReverseDirection(boolean reverseDirection) {
299    EncoderJNI.setEncoderReverseDirection(m_encoder, reverseDirection);
300  }
301
302  /**
303   * Set the Samples to Average which specifies the number of samples of the timer to average when
304   * calculating the period. Perform averaging to account for mechanical imperfections or as
305   * oversampling to increase resolution.
306   *
307   * @param samplesToAverage The number of samples to average from 1 to 127.
308   */
309  public void setSamplesToAverage(int samplesToAverage) {
310    EncoderJNI.setEncoderSamplesToAverage(m_encoder, samplesToAverage);
311  }
312
313  /**
314   * Get the Samples to Average which specifies the number of samples of the timer to average when
315   * calculating the period. Perform averaging to account for mechanical imperfections or as
316   * oversampling to increase resolution.
317   *
318   * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
319   */
320  public int getSamplesToAverage() {
321    return EncoderJNI.getEncoderSamplesToAverage(m_encoder);
322  }
323
324  /**
325   * Indicates this input is used by a simulated device.
326   *
327   * @param device simulated device handle
328   */
329  public void setSimDevice(SimDevice device) {
330    EncoderJNI.setEncoderSimDevice(m_encoder, device.getNativeHandle());
331  }
332
333  /**
334   * Gets the decoding scale factor for scaling raw values to full counts.
335   *
336   * @return decoding scale factor
337   */
338  public double getDecodingScaleFactor() {
339    return switch (m_encodingType) {
340      case k1X -> 1.0;
341      case k2X -> 0.5;
342      case k4X -> 0.25;
343    };
344  }
345
346  @Override
347  public void initSendable(SendableBuilder builder) {
348    if (EncoderJNI.getEncoderEncodingType(m_encoder) == EncodingType.k4X.value) {
349      builder.setSmartDashboardType("Quadrature Encoder");
350    } else {
351      builder.setSmartDashboardType("Encoder");
352    }
353
354    builder.addDoubleProperty("Velocity", this::getRate, null);
355    builder.addDoubleProperty("Distance", this::getDistance, null);
356    builder.addDoubleProperty("Distance per Tick", this::getDistancePerPulse, null);
357  }
358}