WPILibC++ 2023.4.3-108-ge5452e3
frc::ADXRS450_Gyro Class Reference

Use a rate gyro to return the robots heading relative to a starting position. More...

#include <frc/ADXRS450_Gyro.h>

Inheritance diagram for frc::ADXRS450_Gyro:
frc::Gyro wpi::Sendable wpi::SendableHelper< ADXRS450_Gyro >

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_Gyrooperator= (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
 
Gyrooperator= (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)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< ADXRS450_Gyro >
 SendableHelper ()=default
 
 ~SendableHelper ()
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ADXRS450_Gyro() [1/3]

frc::ADXRS450_Gyro::ADXRS450_Gyro ( )

Gyro constructor on onboard CS0.

◆ ADXRS450_Gyro() [2/3]

frc::ADXRS450_Gyro::ADXRS450_Gyro ( SPI::Port  port)
explicit

Gyro constructor on the specified SPI port.

Parameters
portThe SPI port the gyro is attached to.

◆ ~ADXRS450_Gyro()

frc::ADXRS450_Gyro::~ADXRS450_Gyro ( )
overridedefault

◆ ADXRS450_Gyro() [3/3]

frc::ADXRS450_Gyro::ADXRS450_Gyro ( ADXRS450_Gyro &&  )
default

Member Function Documentation

◆ Calibrate()

void frc::ADXRS450_Gyro::Calibrate ( )
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.

◆ GetAngle()

double frc::ADXRS450_Gyro::GetAngle ( ) const
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.

Returns
the current heading of the robot in degrees.

Implements frc::Gyro.

◆ GetPort()

int frc::ADXRS450_Gyro::GetPort ( ) const

Get the SPI port number.

Returns
The SPI port number.

◆ GetRate()

double frc::ADXRS450_Gyro::GetRate ( ) const
overridevirtual

Return the rate of rotation of the gyro.

The rate is based on the most recent reading of the gyro.

Returns
the current rate in degrees per second

Implements frc::Gyro.

◆ InitSendable()

void frc::ADXRS450_Gyro::InitSendable ( wpi::SendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ IsConnected()

bool frc::ADXRS450_Gyro::IsConnected ( ) const

◆ operator=()

ADXRS450_Gyro & frc::ADXRS450_Gyro::operator= ( ADXRS450_Gyro &&  )
default

◆ Reset()

void frc::ADXRS450_Gyro::Reset ( )
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.


The documentation for this class was generated from the following file: