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