WPILibC++ 2024.3.2
AnalogGyro.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/Types.h>
12
14
15namespace frc {
16
17class AnalogInput;
18
19/**
20 * Use a rate gyro to return the robots heading relative to a starting position.
21 * The Gyro class tracks the robots heading based on the starting position. As
22 * the robot rotates the new heading is computed by integrating the rate of
23 * rotation returned by the sensor. When the class is instantiated, it does a
24 * short calibration routine where it samples the gyro while at rest to
25 * determine the default offset. This is subtracted from each sample to
26 * determine the heading. This gyro class must be used with a channel that is
27 * assigned one of the Analog accumulators from the FPGA. See AnalogInput for
28 * the current accumulator assignments.
29 *
30 * This class is for gyro sensors that connect to an analog input.
31 */
33 public wpi::SendableHelper<AnalogGyro> {
34 public:
35 static constexpr int kOversampleBits = 10;
36 static constexpr int kAverageBits = 0;
37 static constexpr double kSamplesPerSecond = 50.0;
38 static constexpr double kCalibrationSampleTime = 5.0;
39 static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007;
40
41 /**
42 * %Gyro constructor using the Analog Input channel number.
43 *
44 * @param channel The analog channel the gyro is connected to. Gyros can only
45 * be used on on-board Analog Inputs 0-1.
46 */
47 explicit AnalogGyro(int channel);
48
49 /**
50 * Gyro constructor with a precreated AnalogInput object.
51 *
52 * Use this constructor when the analog channel needs to be shared.
53 * This object will not clean up the AnalogInput object when using this
54 * constructor.
55 *
56 * Gyros can only be used on on-board channels 0-1.
57 *
58 * @param channel A pointer to the AnalogInput object that the gyro is
59 * connected to.
60 */
61 explicit AnalogGyro(AnalogInput* channel);
62
63 /**
64 * %Gyro constructor with a precreated AnalogInput object.
65 *
66 * Use this constructor when the analog channel needs to be shared.
67 * This object will not clean up the AnalogInput object when using this
68 * constructor.
69 *
70 * @param channel A pointer to the AnalogInput object that the gyro is
71 * connected to.
72 */
73 explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
74
75 /**
76 * %Gyro constructor using the Analog Input channel number with parameters for
77 * presetting the center and offset values. Bypasses calibration.
78 *
79 * @param channel The analog channel the gyro is connected to. Gyros can only
80 * be used on on-board Analog Inputs 0-1.
81 * @param center Preset uncalibrated value to use as the accumulator center
82 * value.
83 * @param offset Preset uncalibrated value to use as the gyro offset.
84 */
85 AnalogGyro(int channel, int center, double offset);
86
87 /**
88 * %Gyro constructor with a precreated AnalogInput object and calibrated
89 * parameters.
90 *
91 * Use this constructor when the analog channel needs to be shared.
92 * This object will not clean up the AnalogInput object when using this
93 * constructor.
94 *
95 * @param channel A pointer to the AnalogInput object that the gyro is
96 * connected to.
97 * @param center Preset uncalibrated value to use as the accumulator center
98 * value.
99 * @param offset Preset uncalibrated value to use as the gyro offset.
100 */
101 AnalogGyro(std::shared_ptr<AnalogInput> channel, int center, double offset);
102
103 ~AnalogGyro() override;
104
105 AnalogGyro(AnalogGyro&& rhs) = default;
106 AnalogGyro& operator=(AnalogGyro&& rhs) = default;
107
108 /**
109 * Return the actual angle in degrees that the robot is currently facing.
110 *
111 * The angle is based on the current accumulator value corrected by the
112 * oversampling rate, the gyro type and the A/D calibration values. The angle
113 * is continuous, that is it will continue from 360->361 degrees. This allows
114 * algorithms that wouldn't want to see a discontinuity in the gyro output as
115 * it sweeps from 360 to 0 on the second time around.
116 *
117 * @return The current heading of the robot in degrees. This heading is based
118 * on integration of the returned rate from the gyro.
119 */
120 double GetAngle() const;
121
122 /**
123 * Return the rate of rotation of the gyro
124 *
125 * The rate is based on the most recent reading of the gyro analog value
126 *
127 * @return the current rate in degrees per second
128 */
129 double GetRate() const;
130
131 /**
132 * Return the gyro center value. If run after calibration,
133 * the center value can be used as a preset later.
134 *
135 * @return the current center value
136 */
137 virtual int GetCenter() const;
138
139 /**
140 * Return the gyro offset value. If run after calibration,
141 * the offset value can be used as a preset later.
142 *
143 * @return the current offset value
144 */
145 virtual double GetOffset() const;
146
147 /**
148 * Set the gyro sensitivity.
149 *
150 * This takes the number of volts/degree/second sensitivity of the gyro and
151 * uses it in subsequent calculations to allow the code to work with multiple
152 * gyros. This value is typically found in the gyro datasheet.
153 *
154 * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
155 */
156 void SetSensitivity(double voltsPerDegreePerSecond);
157
158 /**
159 * Set the size of the neutral zone.
160 *
161 * Any voltage from the gyro less than this amount from the center is
162 * considered stationary. Setting a deadband will decrease the amount of
163 * drift when the gyro isn't rotating, but will make it less accurate.
164 *
165 * @param volts The size of the deadband in volts
166 */
167 void SetDeadband(double volts);
168
169 /**
170 * Reset the gyro.
171 *
172 * Resets the gyro to a heading of zero. This can be used if there is
173 * significant drift in the gyro and it needs to be recalibrated after it has
174 * been running.
175 */
176 void Reset();
177
178 /**
179 * Initialize the gyro.
180 *
181 * Calibration is handled by Calibrate().
182 */
183 void InitGyro();
184
185 /**
186 * Calibrate the gyro by running for a number of samples and computing the
187 * center value. Then use the center value as the Accumulator center value for
188 * subsequent measurements.
189 *
190 * It's important to make sure that the robot is not moving while the
191 * centering calculations are in progress, this is typically done when the
192 * robot is first turned on while it's sitting at rest before the competition
193 * starts.
194 */
195 void Calibrate();
196
197 /**
198 * Return the heading of the robot as a Rotation2d.
199 *
200 * The angle is continuous, that is it will continue from 360 to 361 degrees.
201 * This allows algorithms that wouldn't want to see a discontinuity in the
202 * gyro output as it sweeps past from 360 to 0 on the second time around.
203 *
204 * The angle is expected to increase as the gyro turns counterclockwise when
205 * looked at from the top. It needs to follow the NWU axis convention.
206 *
207 * @return the current heading of the robot as a Rotation2d. This heading is
208 * based on integration of the returned rate from the gyro.
209 */
211
212 /**
213 * Gets the analog input for the gyro.
214 *
215 * @return AnalogInput
216 */
217 std::shared_ptr<AnalogInput> GetAnalogInput() const;
218
219 void InitSendable(wpi::SendableBuilder& builder) override;
220
221 private:
222 std::shared_ptr<AnalogInput> m_analog;
223 hal::Handle<HAL_GyroHandle> m_gyroHandle;
224};
225
226} // namespace frc
Use a rate gyro to return the robots heading relative to a starting position.
Definition: AnalogGyro.h:33
~AnalogGyro() override
static constexpr double kCalibrationSampleTime
Definition: AnalogGyro.h:38
void SetDeadband(double volts)
Set the size of the neutral zone.
AnalogGyro(AnalogGyro &&rhs)=default
void Calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.
virtual double GetOffset() const
Return the gyro offset value.
static constexpr int kAverageBits
Definition: AnalogGyro.h:36
AnalogGyro(AnalogInput *channel)
Gyro constructor with a precreated AnalogInput object.
AnalogGyro(std::shared_ptr< AnalogInput > channel, int center, double offset)
Gyro constructor with a precreated AnalogInput object and calibrated parameters.
AnalogGyro(std::shared_ptr< AnalogInput > channel)
Gyro constructor with a precreated AnalogInput object.
AnalogGyro(int channel)
Gyro constructor using the Analog Input channel number.
static constexpr int kOversampleBits
Definition: AnalogGyro.h:35
void Reset()
Reset the gyro.
double GetAngle() const
Return the actual angle in degrees that the robot is currently facing.
std::shared_ptr< AnalogInput > GetAnalogInput() const
Gets the analog input for the gyro.
static constexpr double kDefaultVoltsPerDegreePerSecond
Definition: AnalogGyro.h:39
AnalogGyro(int channel, int center, double offset)
Gyro constructor using the Analog Input channel number with parameters for presetting the center and ...
virtual int GetCenter() const
Return the gyro center value.
void InitGyro()
Initialize the gyro.
void SetSensitivity(double voltsPerDegreePerSecond)
Set the gyro sensitivity.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
static constexpr double kSamplesPerSecond
Definition: AnalogGyro.h:37
Rotation2d GetRotation2d() const
Return the heading of the robot as a Rotation2d.
double GetRate() const
Return the rate of rotation of the gyro.
AnalogGyro & operator=(AnalogGyro &&rhs)=default
Analog input class.
Definition: AnalogInput.h:31
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
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:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15