WPILibC++ 2023.4.3
|
Use a rate gyro to return the robots heading relative to a starting position. More...
#include <frc/ADXRS450_Gyro.h>
Public Member Functions | |
ADXRS450_Gyro () | |
Gyro constructor on onboard CS0. More... | |
ADXRS450_Gyro (SPI::Port port) | |
Gyro constructor on the specified SPI port. More... | |
~ADXRS450_Gyro () override=default | |
ADXRS450_Gyro (ADXRS450_Gyro &&)=default | |
ADXRS450_Gyro & | operator= (ADXRS450_Gyro &&)=default |
bool | IsConnected () const |
double | GetAngle () const override |
Return the actual angle in degrees that the robot is currently facing. More... | |
double | GetRate () const override |
Return the rate of rotation of the gyro. More... | |
void | Reset () override |
Reset the gyro. More... | |
void | Calibrate () final |
Initialize the gyro. More... | |
int | GetPort () const |
Get the SPI port number. More... | |
void | InitSendable (wpi::SendableBuilder &builder) override |
Initializes this Sendable object. More... | |
Public Member Functions inherited from frc::Gyro | |
Gyro ()=default | |
virtual | ~Gyro ()=default |
Gyro (Gyro &&)=default | |
Gyro & | operator= (Gyro &&)=default |
virtual void | Calibrate ()=0 |
Calibrate the gyro. More... | |
virtual void | Reset ()=0 |
Reset the gyro. More... | |
virtual double | GetAngle () const =0 |
Return the heading of the robot in degrees. More... | |
virtual double | GetRate () const =0 |
Return the rate of rotation of the gyro. More... | |
virtual Rotation2d | GetRotation2d () const |
Return the heading of the robot as a Rotation2d. More... | |
Public Member Functions inherited from wpi::Sendable | |
virtual | ~Sendable ()=default |
virtual void | InitSendable (SendableBuilder &builder)=0 |
Initializes this Sendable object. More... | |
Public Member Functions inherited from wpi::SendableHelper< ADXRS450_Gyro > | |
SendableHelper (const SendableHelper &rhs)=default | |
SendableHelper (SendableHelper &&rhs) | |
SendableHelper & | operator= (const SendableHelper &rhs)=default |
SendableHelper & | operator= (SendableHelper &&rhs) |
Additional Inherited Members | |
Protected Member Functions inherited from wpi::SendableHelper< ADXRS450_Gyro > | |
SendableHelper ()=default | |
~SendableHelper () | |
Use a rate gyro to return the robots heading relative to a starting position.
The Gyro class tracks the robots heading based on the starting position. As the robot rotates the new heading is computed by integrating the rate of rotation returned by the sensor. When the class is instantiated, it does a short calibration routine where it samples the gyro while at rest to determine the default offset. This is subtracted from each sample to determine the heading.
This class is for the digital ADXRS450 gyro sensor that connects via SPI. Only one instance of an ADXRS Gyro is supported.
frc::ADXRS450_Gyro::ADXRS450_Gyro | ( | ) |
Gyro constructor on onboard CS0.
|
explicit |
|
overridedefault |
|
default |
|
finalvirtual |
Initialize the gyro.
Calibrate the gyro by running for a number of samples and computing the center value. Then use the center value as the Accumulator center value for subsequent measurements.
It's important to make sure that the robot is not moving while the centering calculations are in progress, this is typically done when the robot is first turned on while it's sitting at rest before the competition starts.
Implements frc::Gyro.
|
overridevirtual |
Return the actual angle in degrees that the robot is currently facing.
The angle is based on integration of the returned rate from the gyro. The angle is continuous, that is it will continue from 360->361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps from 360 to 0 on the second time around.
Implements frc::Gyro.
|
overridevirtual |
Return the rate of rotation of the gyro.
The rate is based on the most recent reading of the gyro.
Implements frc::Gyro.
|
overridevirtual |
bool frc::ADXRS450_Gyro::IsConnected | ( | ) | const |
|
default |
|
overridevirtual |
Reset the gyro.
Resets the gyro to a heading of zero. This can be used if there is significant drift in the gyro and it needs to be recalibrated after it has been running.
Implements frc::Gyro.