WPILibC++ 2023.4.3-108-ge5452e3
|
Use a rate gyro to return the robots heading relative to a starting position. More...
#include <frc/AnalogGyro.h>
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 | |
AnalogGyro & | operator= (AnalogGyro &&rhs)=default |
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... | |
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 () final |
Reset the gyro. More... | |
void | InitGyro () |
Initialize the gyro. More... | |
void | Calibrate () final |
Calibrate the gyro. More... | |
std::shared_ptr< AnalogInput > | GetAnalogInput () 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 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< AnalogGyro > | |
SendableHelper (const SendableHelper &rhs)=default | |
SendableHelper (SendableHelper &&rhs) | |
SendableHelper & | operator= (const SendableHelper &rhs)=default |
SendableHelper & | operator= (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 |
Protected Attributes | |
std::shared_ptr< AnalogInput > | m_analog |
Additional Inherited Members | |
Protected Member Functions inherited from wpi::SendableHelper< AnalogGyro > | |
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 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.
|
explicit |
Gyro constructor using the Analog Input channel number.
channel | The analog channel the gyro is connected to. Gyros can only be used on on-board Analog Inputs 0-1. |
|
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.
channel | A pointer to the AnalogInput object that the gyro is connected to. |
|
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.
channel | A pointer to the AnalogInput object that the gyro is connected to. |
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.
channel | The analog channel the gyro is connected to. Gyros can only be used on on-board Analog Inputs 0-1. |
center | Preset uncalibrated value to use as the accumulator center value. |
offset | Preset uncalibrated value to use as the gyro offset. |
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.
channel | A pointer to the AnalogInput object that the gyro is connected to. |
center | Preset uncalibrated value to use as the accumulator center value. |
offset | Preset uncalibrated value to use as the gyro offset. |
|
override |
|
default |
|
finalvirtual |
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.
Implements frc::Gyro.
std::shared_ptr< AnalogInput > frc::AnalogGyro::GetAnalogInput | ( | ) | const |
Gets the analog input for the gyro.
|
overridevirtual |
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.
Implements frc::Gyro.
|
virtual |
Return the gyro center value.
If run after calibration, the center value can be used as a preset later.
|
virtual |
Return the gyro offset value.
If run after calibration, the offset value can be used as a preset later.
|
overridevirtual |
Return the rate of rotation of the gyro.
The rate is based on the most recent reading of the gyro analog value
Implements frc::Gyro.
void frc::AnalogGyro::InitGyro | ( | ) |
Initialize the gyro.
Calibration is handled by Calibrate().
|
overridevirtual |
|
default |
|
finalvirtual |
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.
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.
volts | The size of the deadband in volts |
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.
voltsPerDegreePerSecond | The sensitivity in Volts/degree/second |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
protected |