CTRE_Phoenix 5.20.2
|
#include <PigeonIMU.h>
Inherits ctre::phoenix::sensors::BasePigeon.
Inherited by ctre::phoenix::sensors::WPI_PigeonIMU.
Classes | |
struct | FusionStatus |
struct | GeneralStatus |
Public Types | |
enum | CalibrationMode { BootTareGyroAccel = 0 , Temperature = 1 , Magnetometer12Pt = 2 , Magnetometer360 = 3 , Accelerometer = 5 } |
enum | PigeonState { NoComm , Initializing , Ready , UserCalibration } |
Public Member Functions | |
PigeonIMU (int deviceNumber) | |
PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX *talonSrx) | |
PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx) | |
int | SetFusedHeading (double angleDeg, int timeoutMs=0) |
int | AddFusedHeading (double angleDeg, int timeoutMs=0) |
int | SetFusedHeadingToCompass (int timeoutMs=0) |
int | SetTemperatureCompensationDisable (bool bTempCompDisable, int timeoutMs=0) |
int | SetCompassDeclination (double angleDegOffset, int timeoutMs=0) |
int | SetCompassAngle (double angleDeg, int timeoutMs=0) |
int | EnterCalibrationMode (CalibrationMode calMode, int timeoutMs=0) |
int | GetGeneralStatus (PigeonIMU::GeneralStatus &statusToFill) |
PigeonState | GetState () |
int | GetAccelerometerAngles (double tiltAngles[3]) |
double | GetFusedHeading (FusionStatus &status) |
double | GetFusedHeading () const |
uint32_t | GetResetCount () |
uint32_t | GetResetFlags () |
ErrorCode | ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0) |
int | ConfigGetCustomParam (int paramIndex, int timeoutMs=0) |
ErrorCode | SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0) |
int | GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0) |
ErrorCode | SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs) |
int | GetFirmwareVersion () |
ErrorCode | GetFaults (PigeonIMU_Faults &toFill) |
ErrorCode | GetStickyFaults (PigeonIMU_StickyFaults &toFill) |
ErrorCode | ClearStickyFaults (int timeoutMs=0) |
virtual ctre::phoenix::ErrorCode | ConfigAllSettings (const PigeonIMUConfiguration &allConfigs, int timeoutMs=50) |
virtual void | GetAllConfigs (PigeonIMUConfiguration &allConfigs, int timeoutMs=50) |
virtual ErrorCode | ConfigFactoryDefault (int timeoutMs=50) |
Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon | |
BasePigeon (int deviceNumber, std::string const &version, std::string const &canbus="") | |
int | SetYaw (double angleDeg, int timeoutMs=0) |
int | AddYaw (double angleDeg, int timeoutMs=0) |
int | SetYawToCompass (int timeoutMs=0) |
int | SetAccumZAngle (double angleDeg, int timeoutMs=0) |
ErrorCode | GetLastError () const |
ErrorCode | Get6dQuaternion (double wxyz[4]) const |
ErrorCode | GetYawPitchRoll (double ypr[3]) const |
double | GetYaw () const |
double | GetPitch () const |
double | GetRoll () const |
int | GetAccumGyro (double xyz_deg[3]) const |
double | GetAbsoluteCompassHeading () const |
double | GetCompassHeading () const |
double | GetCompassFieldStrength () const |
double | GetTemp () const |
uint32_t | GetUpTime () const |
int | GetRawMagnetometer (int16_t rm_xyz[3]) const |
int | GetBiasedMagnetometer (int16_t bm_xyz[3]) const |
int | GetBiasedAccelerometer (int16_t ba_xyz[3]) const |
int | GetRawGyro (double xyz_dps[3]) const |
uint32_t | GetResetCount () const |
uint32_t | GetResetFlags () const |
uint32_t | GetFirmVers () const |
bool | HasResetOccurred () const |
ErrorCode | ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0) |
int | ConfigGetCustomParam (int paramIndex, int timeoutMs=0) |
ErrorCode | ConfigSetParameter (ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0) |
double | ConfigGetParameter (ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0) |
ErrorCode | ConfigGetParameter (ParamEnum param, int32_t valueToSend, int32_t &valueReceived, uint8_t &subValue, int32_t ordinal, int32_t timeoutMs) |
ErrorCode | SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0) |
int | GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0) |
ErrorCode | SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs) |
int | GetFirmwareVersion () |
ErrorCode | ClearStickyFaults (int timeoutMs=0) |
void * | GetLowLevelHandle () const |
virtual ctre::phoenix::ErrorCode | ConfigAllSettings (const BasePigeonConfiguration &allConfigs, int timeoutMs=50) |
virtual void | GetAllConfigs (BasePigeonConfiguration &allConfigs, int timeoutMs=50) |
virtual ErrorCode | ConfigFactoryDefault (int timeoutMs=50) |
virtual BasePigeonSimCollection & | GetSimCollection () |
Public Member Functions inherited from ctre::phoenix::CANBusAddressable | |
CANBusAddressable (int deviceNumber) | |
int | GetDeviceNumber () |
Static Public Member Functions | |
static std::string | ToString (PigeonIMU::PigeonState state) |
static std::string | ToString (CalibrationMode cm) |
Static Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon | |
static void | DestroyAllBasePigeons () |
Additional Inherited Members | |
Protected Member Functions inherited from ctre::phoenix::sensors::BasePigeon | |
BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx) | |
Pigeon IMU Class. Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).
Various calibration modes supported by Pigeon.
Note that you can instead use Phoenix Tuner to accomplish certain calibrations.
ctre::phoenix::sensors::PigeonIMU::PigeonIMU | ( | int | deviceNumber | ) |
Create a Pigeon object that communicates with Pigeon on CAN Bus.
deviceNumber | CAN Device Id of Pigeon [0,62] |
ctre::phoenix::sensors::PigeonIMU::PigeonIMU | ( | ctre::phoenix::motorcontrol::can::TalonSRX * | talonSrx | ) |
Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to a Talon on CAN Bus.
[[deprecated("Pass in a TalonSRX reference instead.")]]
talonSrx | Object for the TalonSRX connected via ribbon cable. |
ctre::phoenix::sensors::PigeonIMU::PigeonIMU | ( | ctre::phoenix::motorcontrol::can::TalonSRX & | talonSrx | ) |
Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to a Talon on CAN Bus.
talonSrx | Object for the TalonSRX connected via ribbon cable. |
int ctre::phoenix::sensors::PigeonIMU::AddFusedHeading | ( | double | angleDeg, |
int | timeoutMs = 0 |
||
) |
Atomically add to the Fused Heading register.
angleDeg | Degrees to add to the Fused Heading register. |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
ErrorCode ctre::phoenix::sensors::PigeonIMU::ClearStickyFaults | ( | int | timeoutMs = 0 | ) |
Clears the Sticky Faults
|
virtual |
Configures all persistent settings.
allConfigs | Object with all of the persistant settings |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
|
virtual |
Configures all persistent settings to defaults.
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
Reimplemented from ctre::phoenix::sensors::BasePigeon.
int ctre::phoenix::sensors::PigeonIMU::ConfigGetCustomParam | ( | int | paramIndex, |
int | timeoutMs = 0 |
||
) |
Gets the value of a custom parameter. This is for arbitrary use.
Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
paramIndex | Index of custom parameter. [0-1] |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
ErrorCode ctre::phoenix::sensors::PigeonIMU::ConfigSetCustomParam | ( | int | newValue, |
int | paramIndex, | ||
int | timeoutMs = 0 |
||
) |
Sets the value of a custom parameter. This is for arbitrary use.
Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
newValue | Value for custom parameter. |
paramIndex | Index of custom parameter. [0-1] |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
int ctre::phoenix::sensors::PigeonIMU::EnterCalibrationMode | ( | CalibrationMode | calMode, |
int | timeoutMs = 0 |
||
) |
Enters the Calbration mode. See the Pigeon IMU documentation for More information on Calibration.
Note that you can instead use Phoenix Tuner to accomplish this. Note you should NOT be calling this during normal robot operation.
calMode | Calibration to execute |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
int ctre::phoenix::sensors::PigeonIMU::GetAccelerometerAngles | ( | double | tiltAngles[3] | ) |
Get Accelerometer tilt angles.
tiltAngles | Array to fill with x[0], y[1], and z[2] angles in degrees. |
|
virtual |
Gets all persistant settings.
allConfigs | Object with all of the persistant settings |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
ErrorCode ctre::phoenix::sensors::PigeonIMU::GetFaults | ( | PigeonIMU_Faults & | toFill | ) |
Gets the fault status
toFill | Container for fault statuses. |
int ctre::phoenix::sensors::PigeonIMU::GetFirmwareVersion | ( | ) |
Gets the firmware version of the device.
double ctre::phoenix::sensors::PigeonIMU::GetFusedHeading | ( | ) | const |
Gets the Fused Heading
double ctre::phoenix::sensors::PigeonIMU::GetFusedHeading | ( | FusionStatus & | status | ) |
Get the current Fusion Status (including fused heading)
status | object reference to fill with fusion status flags. Caller may pass null if flags are not needed. |
int ctre::phoenix::sensors::PigeonIMU::GetGeneralStatus | ( | PigeonIMU::GeneralStatus & | statusToFill | ) |
Get the status of the current (or previousley complete) calibration.
[out] | statusToFill | Container for the status information. |
uint32_t ctre::phoenix::sensors::PigeonIMU::GetResetCount | ( | ) |
uint32_t ctre::phoenix::sensors::PigeonIMU::GetResetFlags | ( | ) |
PigeonState ctre::phoenix::sensors::PigeonIMU::GetState | ( | ) |
Gets the current Pigeon state
int ctre::phoenix::sensors::PigeonIMU::GetStatusFramePeriod | ( | PigeonIMU_StatusFrame | frame, |
int | timeoutMs = 0 |
||
) |
Gets the period of the given status frame.
frame | Frame to get the period of. |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
ErrorCode ctre::phoenix::sensors::PigeonIMU::GetStickyFaults | ( | PigeonIMU_StickyFaults & | toFill | ) |
Gets the sticky fault status
toFill | Container for sticky fault statuses. |
int ctre::phoenix::sensors::PigeonIMU::SetCompassAngle | ( | double | angleDeg, |
int | timeoutMs = 0 |
||
) |
Sets the compass angle. Although compass is absolute [0,360) degrees, the continuous compass register holds the wrap-arounds.
angleDeg | Degrees to set continuous compass angle to. |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
int ctre::phoenix::sensors::PigeonIMU::SetCompassDeclination | ( | double | angleDegOffset, |
int | timeoutMs = 0 |
||
) |
Set the declination for compass. Declination is the difference between Earth Magnetic north, and the geographic "True North".
angleDegOffset | Degrees to set Compass Declination to. |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
ErrorCode ctre::phoenix::sensors::PigeonIMU::SetControlFramePeriod | ( | PigeonIMU_ControlFrame | frame, |
int | periodMs | ||
) |
Sets the period of the given control frame.
frame | Frame whose period is to be changed. |
periodMs | Period in ms for the given frame. |
int ctre::phoenix::sensors::PigeonIMU::SetFusedHeading | ( | double | angleDeg, |
int | timeoutMs = 0 |
||
) |
Sets the Fused Heading to the specified value.
angleDeg | New fused-heading in degrees [+/- 23,040 degrees] |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
int ctre::phoenix::sensors::PigeonIMU::SetFusedHeadingToCompass | ( | int | timeoutMs = 0 | ) |
Sets the Fused Heading register to match the current compass value.
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
ErrorCode ctre::phoenix::sensors::PigeonIMU::SetStatusFramePeriod | ( | PigeonIMU_StatusFrame | statusFrame, |
uint8_t | periodMs, | ||
int | timeoutMs = 0 |
||
) |
Sets the period of the given status frame.
statusFrame | Frame whose period is to be changed. |
periodMs | Period in ms for the given frame. |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
int ctre::phoenix::sensors::PigeonIMU::SetTemperatureCompensationDisable | ( | bool | bTempCompDisable, |
int | timeoutMs = 0 |
||
) |
Disable/Enable Temp compensation. Pigeon has this on/False at boot.
bTempCompDisable | Set to "False" to enable temperature compensation. |
timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
|
static |
Gets the string representation of a CalibrationMode
cm | CalibrationMode to get the string representation of |
|
static |
Gets the string representation of a PigeonState
state | PigeonState to get the string representation of |