WPILibC++ 2023.4.3
frc::Gyro Class Referenceabstract

Interface for yaw rate gyros. More...

#include <frc/interfaces/Gyro.h>

Inheritance diagram for frc::Gyro:
frc::ADXRS450_Gyro frc::AnalogGyro

Public Member Functions

 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...
 

Detailed Description

Interface for yaw rate gyros.

Constructor & Destructor Documentation

◆ Gyro() [1/2]

frc::Gyro::Gyro ( )
default

◆ ~Gyro()

virtual frc::Gyro::~Gyro ( )
virtualdefault

◆ Gyro() [2/2]

frc::Gyro::Gyro ( Gyro &&  )
default

Member Function Documentation

◆ Calibrate()

virtual void frc::Gyro::Calibrate ( )
pure virtual

Calibrate the gyro.

It's important to make sure that the robot is not moving while the calibration is in progress, this is typically done when the robot is first turned on while it's sitting at rest before the match starts.

Implemented in frc::ADXRS450_Gyro, and frc::AnalogGyro.

◆ GetAngle()

virtual double frc::Gyro::GetAngle ( ) const
pure virtual

Return the heading of the robot in degrees.

The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

The angle is expected to increase as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.

Returns
the current heading of the robot in degrees. This heading is based on integration of the returned rate from the gyro.

Implemented in frc::ADXRS450_Gyro, and frc::AnalogGyro.

◆ GetRate()

virtual double frc::Gyro::GetRate ( ) const
pure virtual

Return the rate of rotation of the gyro.

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

The rate is expected to be positive as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.

Returns
the current rate in degrees per second

Implemented in frc::ADXRS450_Gyro, and frc::AnalogGyro.

◆ GetRotation2d()

virtual Rotation2d frc::Gyro::GetRotation2d ( ) const
inlinevirtual

Return the heading of the robot as a Rotation2d.

The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

The angle is expected to increase as the gyro turns counterclockwise when looked at from the top. It needs to follow the NWU axis convention.

Returns
the current heading of the robot as a Rotation2d. This heading is based on integration of the returned rate from the gyro.

◆ operator=()

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

◆ Reset()

virtual void frc::Gyro::Reset ( )
pure virtual

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.

Implemented in frc::AnalogGyro, and frc::ADXRS450_Gyro.


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