WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
Encoder.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <memory>
8
9#include <hal/Encoder.h>
10#include <hal/Types.h>
13
14#include "frc/CounterBase.h"
15
16namespace frc {
17/**
18 * Class to read quad encoders.
19 *
20 * Quadrature encoders are devices that count shaft rotation and can sense
21 * direction. The output of the QuadEncoder class is an integer that can count
22 * either up or down, and can go negative for reverse direction counting. When
23 * creating QuadEncoders, a direction is supplied that changes the sense of the
24 * output to make code more readable if the encoder is mounted such that forward
25 * movement generates negative values. Quadrature encoders have two digital
26 * outputs, an A Channel and a B Channel that are out of phase with each other
27 * to allow the FPGA to do direction sensing.
28 *
29 * All encoders will immediately start counting - Reset() them if you need them
30 * to be zeroed before use.
31 */
32class Encoder : public CounterBase,
33 public wpi::Sendable,
34 public wpi::SendableHelper<Encoder> {
35 public:
36 /**
37 * Encoder constructor.
38 *
39 * Construct a Encoder given a and b channels.
40 *
41 * The counter will start counting immediately.
42 *
43 * @param aChannel The a channel DIO channel. 0-9 are on-board, 10-25
44 * are on the MXP port
45 * @param bChannel The b channel DIO channel. 0-9 are on-board, 10-25
46 * are on the MXP port
47 * @param reverseDirection represents the orientation of the encoder and
48 * inverts the output values if necessary so forward
49 * represents positive values.
50 * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
51 * decoding. If 4X is selected, then an encoder FPGA
52 * object is used and the returned counts will be 4x
53 * the encoder spec'd value since all rising and
54 * falling edges are counted. If 1X or 2X are selected
55 * then a counter object will be used and the returned
56 * value will either exactly match the spec'd count or
57 * be double (2x) the spec'd count.
58 */
59 Encoder(int aChannel, int bChannel, bool reverseDirection = false,
60 EncodingType encodingType = k4X);
61
62 Encoder(Encoder&&) = default;
63 Encoder& operator=(Encoder&&) = default;
64
65 ~Encoder() override = default;
66
67 // CounterBase interface
68 /**
69 * Gets the current count.
70 *
71 * Returns the current count on the Encoder. This method compensates for the
72 * decoding type.
73 *
74 * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale
75 * factor.
76 */
77 int Get() const override;
78
79 /**
80 * Reset the Encoder distance to zero.
81 *
82 * Resets the current count to zero on the encoder.
83 */
84 void Reset() override;
85
86 /**
87 * Returns the period of the most recent pulse.
88 *
89 * Returns the period of the most recent Encoder pulse in seconds. This method
90 * compensates for the decoding type.
91 *
92 * Warning: This returns unscaled periods. Use GetRate() for rates that are
93 * scaled using the value from SetDistancePerPulse().
94 *
95 * @return Period in seconds of the most recent pulse.
96 * @deprecated Use getRate() in favor of this method.
97 */
98 [[deprecated("Use GetRate() in favor of this method")]]
99 units::second_t GetPeriod() const override;
100
101 /**
102 * Sets the maximum period for stopped detection.
103 *
104 * Sets the value that represents the maximum period of the Encoder before it
105 * will assume that the attached device is stopped. This timeout allows users
106 * to determine if the wheels or other shaft has stopped rotating.
107 * This method compensates for the decoding type.
108 *
109 * @param maxPeriod The maximum time between rising and falling edges before
110 * the FPGA will report the device stopped. This is expressed
111 * in seconds.
112 * @deprecated Use SetMinRate() in favor of this method. This takes unscaled
113 * periods and SetMinRate() scales using value from
114 * SetDistancePerPulse().
115 */
116 [[deprecated(
117 "Use SetMinRate() in favor of this method. This takes unscaled periods "
118 "and SetMinRate() scales using value from SetDistancePerPulse().")]]
119 void SetMaxPeriod(units::second_t maxPeriod) override;
120
121 /**
122 * Determine if the encoder is stopped.
123 *
124 * Using the MaxPeriod value, a boolean is returned that is true if the
125 * encoder is considered stopped and false if it is still moving. A stopped
126 * encoder is one where the most recent pulse width exceeds the MaxPeriod.
127 *
128 * @return True if the encoder is considered stopped.
129 */
130 bool GetStopped() const override;
131
132 /**
133 * The last direction the encoder value changed.
134 *
135 * @return The last direction the encoder value changed.
136 */
137 bool GetDirection() const override;
138
139 /**
140 * Gets the raw value from the encoder.
141 *
142 * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
143 * factor.
144 *
145 * @return Current raw count from the encoder
146 */
147 int GetRaw() const;
148
149 /**
150 * The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
151 *
152 * Used to divide raw edge counts down to spec'd counts.
153 */
154 int GetEncodingScale() const;
155
156 /**
157 * Get the distance the robot has driven since the last reset.
158 *
159 * @return The distance driven since the last reset as scaled by the value
160 * from SetDistancePerPulse().
161 */
162 double GetDistance() const;
163
164 /**
165 * Get the current rate of the encoder.
166 *
167 * Units are distance per second as scaled by the value from
168 * SetDistancePerPulse().
169 *
170 * @return The current rate of the encoder.
171 */
172 double GetRate() const;
173
174 /**
175 * Set the minimum rate of the device before the hardware reports it stopped.
176 *
177 * @param minRate The minimum rate. The units are in distance per second as
178 * scaled by the value from SetDistancePerPulse().
179 */
180 void SetMinRate(double minRate);
181
182 /**
183 * Set the distance per pulse for this encoder.
184 *
185 * This sets the multiplier used to determine the distance driven based on the
186 * count value from the encoder.
187 *
188 * Do not include the decoding type in this scale. The library already
189 * compensates for the decoding type.
190 *
191 * Set this value based on the encoder's rated Pulses per Revolution and
192 * factor in gearing reductions following the encoder shaft.
193 *
194 * This distance can be in any units you like, linear or angular.
195 *
196 * @param distancePerPulse The scale factor that will be used to convert
197 * pulses to useful units.
198 */
199 void SetDistancePerPulse(double distancePerPulse);
200
201 /**
202 * Get the distance per pulse for this encoder.
203 *
204 * @return The scale factor that will be used to convert pulses to useful
205 * units.
206 */
207 double GetDistancePerPulse() const;
208
209 /**
210 * Set the direction sensing for this encoder.
211 *
212 * This sets the direction sensing on the encoder so that it could count in
213 * the correct software direction regardless of the mounting.
214 *
215 * @param reverseDirection true if the encoder direction should be reversed
216 */
217 void SetReverseDirection(bool reverseDirection);
218
219 /**
220 * Set the Samples to Average which specifies the number of samples of the
221 * timer to average when calculating the period.
222 *
223 * Perform averaging to account for mechanical imperfections or as
224 * oversampling to increase resolution.
225 *
226 * @param samplesToAverage The number of samples to average from 1 to 127.
227 */
228 void SetSamplesToAverage(int samplesToAverage);
229
230 /**
231 * Get the Samples to Average which specifies the number of samples of the
232 * timer to average when calculating the period.
233 *
234 * Perform averaging to account for mechanical imperfections or as
235 * oversampling to increase resolution.
236 *
237 * @return The number of samples being averaged (from 1 to 127)
238 */
240
241 /**
242 * Indicates this encoder is used by a simulated device.
243 *
244 * @param device simulated device handle
245 */
247
248 int GetFPGAIndex() const;
249
250 void InitSendable(wpi::SendableBuilder& builder) override;
251
252 private:
253 /**
254 * Common initialization code for Encoders.
255 *
256 * This code allocates resources for Encoders and is common to all
257 * constructors. The counter will start counting immediately.
258 * @param aChannel The a channel.
259 * @param bChannel The b channel.
260 * @param reverseDirection If true, counts down instead of up (this is all
261 * relative)
262 * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
263 * decoding. If 4X is selected, then an encoder FPGA
264 * object is used and the returned counts will be 4x
265 * the encoder spec'd value since all rising and
266 * falling edges are counted. If 1X or 2X are selected
267 * then a counter object will be used and the returned
268 * value will either exactly match the spec'd count or
269 * be double (2x) the spec'd count.
270 */
271 void InitEncoder(int aChannel, int bChannel, bool reverseDirection,
272 EncodingType encodingType);
273
274 /**
275 * The scale needed to convert a raw counter value into a number of encoder
276 * pulses.
277 */
278 double DecodingScaleFactor() const;
279
281};
282
283} // namespace frc
Interface for counting the number of ticks on a digital input channel.
Definition CounterBase.h:20
EncodingType
Definition CounterBase.h:22
@ k4X
Definition CounterBase.h:22
Class to read quad encoders.
Definition Encoder.h:34
int GetFPGAIndex() const
int GetRaw() const
Gets the raw value from the encoder.
Encoder(int aChannel, int bChannel, bool reverseDirection=false, EncodingType encodingType=k4X)
Encoder constructor.
bool GetDirection() const override
The last direction the encoder value changed.
void SetMinRate(double minRate)
Set the minimum rate of the device before the hardware reports it stopped.
int Get() const override
Gets the current count.
void SetReverseDirection(bool reverseDirection)
Set the direction sensing for this encoder.
int GetEncodingScale() const
The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
void Reset() override
Reset the Encoder distance to zero.
double GetRate() const
Get the current rate of the encoder.
void SetSimDevice(HAL_SimDeviceHandle device)
Indicates this encoder is used by a simulated device.
void SetSamplesToAverage(int samplesToAverage)
Set the Samples to Average which specifies the number of samples of the timer to average when calcula...
int GetSamplesToAverage() const
Get the Samples to Average which specifies the number of samples of the timer to average when calcula...
void SetMaxPeriod(units::second_t maxPeriod) override
Sets the maximum period for stopped detection.
Encoder & operator=(Encoder &&)=default
void SetDistancePerPulse(double distancePerPulse)
Set the distance per pulse for this encoder.
bool GetStopped() const override
Determine if the encoder is stopped.
~Encoder() override=default
double GetDistance() const
Get the distance the robot has driven since the last reset.
double GetDistancePerPulse() const
Get the distance per pulse for this encoder.
units::second_t GetPeriod() const override
Returns the period of the most recent pulse.
Encoder(Encoder &&)=default
A move-only C++ wrapper around a HAL handle.
Definition Types.h:98
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.h:21
Interface for Sendable objects.
Definition Sendable.h:16
HAL_Handle HAL_SimDeviceHandle
Definition Types.h:51
Definition SystemServer.h:9