WPILibC++
2018.4.1-20180926150325-1206-g8b1274d
|
Use a rate gyro to return the robots heading relative to a starting position. More...
#include <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 (AnalogGyro &&rhs) | |
AnalogGyro & | operator= (AnalogGyro &&rhs) |
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 () override |
Reset the gyro. More... | |
virtual void | InitGyro () |
Initialize the gyro. More... | |
void | Calibrate () override |
Calibrate the gyro by running for a number of samples and computing the center value. More... | |
![]() | |
GyroBase (GyroBase &&)=default | |
GyroBase & | operator= (GyroBase &&)=default |
double | PIDGet () override |
Get the PIDOutput for the PIDSource base object. More... | |
void | InitSendable (SendableBuilder &builder) override |
Initializes this Sendable object. More... | |
![]() | |
Gyro (Gyro &&)=default | |
Gyro & | operator= (Gyro &&)=default |
![]() | |
ErrorBase (ErrorBase &&)=default | |
ErrorBase & | operator= (ErrorBase &&)=default |
virtual Error & | GetError () |
Retrieve the current error. More... | |
virtual const Error & | GetError () const |
Retrieve the current error. More... | |
virtual void | ClearError () const |
Clear the current error information associated with this sensor. | |
virtual void | SetErrnoError (const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const |
Set error information associated with a C library call that set an error to the "errno" global variable. More... | |
virtual void | SetImaqError (int success, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const |
Set the current error information associated from the nivision Imaq API. More... | |
virtual void | SetError (Error::Code code, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const |
Set the current error information associated with this sensor. More... | |
virtual void | SetErrorRange (Error::Code code, int32_t minRange, int32_t maxRange, int32_t requestedValue, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const |
Set the current error information associated with this sensor. More... | |
virtual void | SetWPIError (const wpi::Twine &errorMessage, Error::Code code, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) const |
Set the current error information associated with this sensor. More... | |
virtual void | CloneError (const ErrorBase &rhs) const |
virtual bool | StatusIsFatal () const |
Check if the current error code represents a fatal error. More... | |
![]() | |
SendableBase (bool addLiveWindow=true) | |
Creates an instance of the sensor base. More... | |
SendableBase (SendableBase &&rhs) | |
SendableBase & | operator= (SendableBase &&rhs) |
std::string | GetName () const final |
Gets the name of this Sendable object. More... | |
void | SetName (const wpi::Twine &name) final |
Sets the name of this Sendable object. More... | |
std::string | GetSubsystem () const final |
Gets the subsystem name of this Sendable object. More... | |
void | SetSubsystem (const wpi::Twine &subsystem) final |
Sets the subsystem name of this Sendable object. More... | |
![]() | |
Sendable (Sendable &&)=default | |
Sendable & | operator= (Sendable &&)=default |
void | SetName (const wpi::Twine &subsystem, const wpi::Twine &name) |
Sets both the subsystem name and device name of this Sendable object. More... | |
![]() | |
virtual void | SetPIDSourceType (PIDSourceType pidSource) |
Set which parameter you are using as a process control variable. More... | |
virtual PIDSourceType | GetPIDSourceType () const |
Protected Attributes | |
std::shared_ptr< AnalogInput > | m_analog |
![]() | |
Error | m_error |
![]() | |
PIDSourceType | m_pidSource = PIDSourceType::kDisplacement |
Additional Inherited Members | |
![]() | |
static void | SetGlobalError (Error::Code code, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) |
static void | SetGlobalWPIError (const wpi::Twine &errorMessage, const wpi::Twine &contextMessage, wpi::StringRef filename, wpi::StringRef function, int lineNumber) |
static const Error & | GetGlobalError () |
Retrieve the current global error. | |
![]() | |
void | AddChild (std::shared_ptr< Sendable > child) |
Add a child component. More... | |
void | AddChild (void *child) |
Add a child component. More... | |
void | SetName (const wpi::Twine &moduleType, int channel) |
Sets the name of the sensor with a channel number. More... | |
void | SetName (const wpi::Twine &moduleType, int moduleNumber, int channel) |
Sets the name of the sensor with a module and channel number. More... | |
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. |
|
overridevirtual |
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 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.
|
virtual |
Initialize the gyro.
Calibration is handled by Calibrate().
|
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.
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 |