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