WPILibC++ 2024.3.2
frc::AnalogGyro Class Reference

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

#include <frc/AnalogGyro.h>

Inheritance diagram for frc::AnalogGyro:
wpi::Sendable wpi::SendableHelper< AnalogGyro >

Public Member Functions

 AnalogGyro (int channel)
 Gyro constructor using the Analog Input channel number. More...
 
 AnalogGyro (AnalogInput *channel)
 Gyro constructor with a precreated AnalogInput object. More...
 
 AnalogGyro (std::shared_ptr< AnalogInput > channel)
 Gyro constructor with a precreated AnalogInput object. More...
 
 AnalogGyro (int channel, int center, double offset)
 Gyro constructor using the Analog Input channel number with parameters for presetting the center and offset values. More...
 
 AnalogGyro (std::shared_ptr< AnalogInput > channel, int center, double offset)
 Gyro constructor with a precreated AnalogInput object and calibrated parameters. More...
 
 ~AnalogGyro () override
 
 AnalogGyro (AnalogGyro &&rhs)=default
 
AnalogGyrooperator= (AnalogGyro &&rhs)=default
 
double GetAngle () const
 Return the actual angle in degrees that the robot is currently facing. More...
 
double GetRate () const
 Return the rate of rotation of the gyro. More...
 
virtual int GetCenter () const
 Return the gyro center value. More...
 
virtual double GetOffset () const
 Return the gyro offset value. More...
 
void SetSensitivity (double voltsPerDegreePerSecond)
 Set the gyro sensitivity. More...
 
void SetDeadband (double volts)
 Set the size of the neutral zone. More...
 
void Reset ()
 Reset the gyro. More...
 
void InitGyro ()
 Initialize the gyro. More...
 
void Calibrate ()
 Calibrate the gyro by running for a number of samples and computing the center value. More...
 
Rotation2d GetRotation2d () const
 Return the heading of the robot as a Rotation2d. More...
 
std::shared_ptr< AnalogInputGetAnalogInput () const
 Gets the analog input for the gyro. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. 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< AnalogGyro >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Static Public Attributes

static constexpr int kOversampleBits = 10
 
static constexpr int kAverageBits = 0
 
static constexpr double kSamplesPerSecond = 50.0
 
static constexpr double kCalibrationSampleTime = 5.0
 
static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< AnalogGyro >
 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 gyro class must be used with a channel that is assigned one of the Analog accumulators from the FPGA. See AnalogInput for the current accumulator assignments.

This class is for gyro sensors that connect to an analog input.

Constructor & Destructor Documentation

◆ AnalogGyro() [1/6]

frc::AnalogGyro::AnalogGyro ( int  channel)
explicit

Gyro constructor using the Analog Input channel number.

Parameters
channelThe analog channel the gyro is connected to. Gyros can only be used on on-board Analog Inputs 0-1.

◆ AnalogGyro() [2/6]

frc::AnalogGyro::AnalogGyro ( AnalogInput channel)
explicit

Gyro constructor with a precreated AnalogInput object.

Use this constructor when the analog channel needs to be shared. This object will not clean up the AnalogInput object when using this constructor.

Gyros can only be used on on-board channels 0-1.

Parameters
channelA pointer to the AnalogInput object that the gyro is connected to.

◆ AnalogGyro() [3/6]

frc::AnalogGyro::AnalogGyro ( std::shared_ptr< AnalogInput channel)
explicit

Gyro constructor with a precreated AnalogInput object.

Use this constructor when the analog channel needs to be shared. This object will not clean up the AnalogInput object when using this constructor.

Parameters
channelA pointer to the AnalogInput object that the gyro is connected to.

◆ AnalogGyro() [4/6]

frc::AnalogGyro::AnalogGyro ( int  channel,
int  center,
double  offset 
)

Gyro constructor using the Analog Input channel number with parameters for presetting the center and offset values.

Bypasses calibration.

Parameters
channelThe analog channel the gyro is connected to. Gyros can only be used on on-board Analog Inputs 0-1.
centerPreset uncalibrated value to use as the accumulator center value.
offsetPreset uncalibrated value to use as the gyro offset.

◆ AnalogGyro() [5/6]

frc::AnalogGyro::AnalogGyro ( std::shared_ptr< AnalogInput channel,
int  center,
double  offset 
)

Gyro constructor with a precreated AnalogInput object and calibrated parameters.

Use this constructor when the analog channel needs to be shared. This object will not clean up the AnalogInput object when using this constructor.

Parameters
channelA pointer to the AnalogInput object that the gyro is connected to.
centerPreset uncalibrated value to use as the accumulator center value.
offsetPreset uncalibrated value to use as the gyro offset.

◆ ~AnalogGyro()

frc::AnalogGyro::~AnalogGyro ( )
override

◆ AnalogGyro() [6/6]

frc::AnalogGyro::AnalogGyro ( AnalogGyro &&  rhs)
default

Member Function Documentation

◆ Calibrate()

void frc::AnalogGyro::Calibrate ( )

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.

◆ GetAnalogInput()

std::shared_ptr< AnalogInput > frc::AnalogGyro::GetAnalogInput ( ) const

Gets the analog input for the gyro.

Returns
AnalogInput

◆ GetAngle()

double frc::AnalogGyro::GetAngle ( ) const

Return the actual angle in degrees that the robot is currently facing.

The angle is based on the current accumulator value corrected by the oversampling rate, the gyro type and the A/D calibration values. 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. This heading is based on integration of the returned rate from the gyro.

◆ GetCenter()

virtual int frc::AnalogGyro::GetCenter ( ) const
virtual

Return the gyro center value.

If run after calibration, the center value can be used as a preset later.

Returns
the current center value

◆ GetOffset()

virtual double frc::AnalogGyro::GetOffset ( ) const
virtual

Return the gyro offset value.

If run after calibration, the offset value can be used as a preset later.

Returns
the current offset value

◆ GetRate()

double frc::AnalogGyro::GetRate ( ) const

Return the rate of rotation of the gyro.

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

Returns
the current rate in degrees per second

◆ GetRotation2d()

Rotation2d frc::AnalogGyro::GetRotation2d ( ) const

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.

◆ InitGyro()

void frc::AnalogGyro::InitGyro ( )

Initialize the gyro.

Calibration is handled by Calibrate().

◆ InitSendable()

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

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ operator=()

AnalogGyro & frc::AnalogGyro::operator= ( AnalogGyro &&  rhs)
default

◆ Reset()

void frc::AnalogGyro::Reset ( )

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.

◆ SetDeadband()

void frc::AnalogGyro::SetDeadband ( double  volts)

Set the size of the neutral zone.

Any voltage from the gyro less than this amount from the center is considered stationary. Setting a deadband will decrease the amount of drift when the gyro isn't rotating, but will make it less accurate.

Parameters
voltsThe size of the deadband in volts

◆ SetSensitivity()

void frc::AnalogGyro::SetSensitivity ( double  voltsPerDegreePerSecond)

Set the gyro sensitivity.

This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent calculations to allow the code to work with multiple gyros. This value is typically found in the gyro datasheet.

Parameters
voltsPerDegreePerSecondThe sensitivity in Volts/degree/second

Member Data Documentation

◆ kAverageBits

constexpr int frc::AnalogGyro::kAverageBits = 0
staticconstexpr

◆ kCalibrationSampleTime

constexpr double frc::AnalogGyro::kCalibrationSampleTime = 5.0
staticconstexpr

◆ kDefaultVoltsPerDegreePerSecond

constexpr double frc::AnalogGyro::kDefaultVoltsPerDegreePerSecond = 0.007
staticconstexpr

◆ kOversampleBits

constexpr int frc::AnalogGyro::kOversampleBits = 10
staticconstexpr

◆ kSamplesPerSecond

constexpr double frc::AnalogGyro::kSamplesPerSecond = 50.0
staticconstexpr

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