CTRE Phoenix C++ 5.33.1
ctre::phoenix::sensors::PigeonIMU Class Reference

Pigeon IMU Class. More...

#include <ctre/phoenix/sensors/PigeonIMU.h>

Inheritance diagram for ctre::phoenix::sensors::PigeonIMU:
ctre::phoenix::sensors::BasePigeon ctre::phoenix::CANBusAddressable ctre::phoenix::sensors::WPI_PigeonIMU

Classes

struct  FusionStatus
 Data object for holding fusion information. More...
 
struct  GeneralStatus
 Data object for status on current calibration and general status. More...
 

Public Types

enum  CalibrationMode {
  BootTareGyroAccel = 0 , Temperature = 1 , Magnetometer12Pt = 2 , Magnetometer360 = 3 ,
  Accelerometer = 5
}
 Various calibration modes supported by Pigeon. More...
 
enum  PigeonState { NoComm , Initializing , Ready , UserCalibration }
 Overall state of the Pigeon. More...
 

Public Member Functions

 PigeonIMU (int deviceNumber)
 Create a Pigeon object that communicates with Pigeon on CAN Bus. More...
 
 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. More...
 
 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. More...
 
int SetFusedHeading (double angleDeg, int timeoutMs=0)
 Sets the Fused Heading to the specified value. More...
 
int AddFusedHeading (double angleDeg, int timeoutMs=0)
 Atomically add to the Fused Heading register. More...
 
int SetFusedHeadingToCompass (int timeoutMs=0)
 Sets the Fused Heading register to match the current compass value. More...
 
int SetTemperatureCompensationDisable (bool bTempCompDisable, int timeoutMs=0)
 Disable/Enable Temp compensation. More...
 
int SetCompassDeclination (double angleDegOffset, int timeoutMs=0)
 Set the declination for compass. More...
 
int SetCompassAngle (double angleDeg, int timeoutMs=0)
 Sets the compass angle. More...
 
int EnterCalibrationMode (CalibrationMode calMode, int timeoutMs=0)
 Enters the Calbration mode. More...
 
int GetGeneralStatus (PigeonIMU::GeneralStatus &statusToFill)
 Get the status of the current (or previousley complete) calibration. More...
 
PigeonState GetState ()
 Gets the current Pigeon state. More...
 
int GetAccelerometerAngles (double tiltAngles[3])
 Get Accelerometer tilt angles. More...
 
double GetFusedHeading (FusionStatus &status)
 Get the current Fusion Status (including fused heading) More...
 
double GetFusedHeading () const
 Gets the Fused Heading. More...
 
uint32_t GetResetCount ()
 
uint32_t GetResetFlags ()
 
ErrorCode ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0)
 Sets the value of a custom parameter. More...
 
int ConfigGetCustomParam (int paramIndex, int timeoutMs=0)
 Gets the value of a custom parameter. More...
 
ErrorCode SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0)
 Sets the period of the given status frame. More...
 
int GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0)
 Gets the period of the given status frame. More...
 
ErrorCode SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs)
 Sets the period of the given control frame. More...
 
int GetFirmwareVersion ()
 Gets the firmware version of the device. More...
 
ErrorCode GetFaults (PigeonIMU_Faults &toFill)
 Gets the fault status. More...
 
ErrorCode GetStickyFaults (PigeonIMU_StickyFaults &toFill)
 Gets the sticky fault status. More...
 
ErrorCode ClearStickyFaults (int timeoutMs=0)
 Clears the Sticky Faults. More...
 
virtual ctre::phoenix::ErrorCode ConfigAllSettings (const PigeonIMUConfiguration &allConfigs, int timeoutMs=50)
 Configures all persistent settings. More...
 
virtual void GetAllConfigs (PigeonIMUConfiguration &allConfigs, int timeoutMs=50)
 Gets all persistant settings. More...
 
virtual ErrorCode ConfigFactoryDefault (int timeoutMs=50)
 Configures all persistent settings to defaults. More...
 
- Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon
 BasePigeon (int deviceNumber, std::string const &version, std::string const &canbus="")
 Create a Pigeon object that communicates with Pigeon on CAN Bus. More...
 
 ~BasePigeon ()
 
int SetYaw (double angleDeg, int timeoutMs=0)
 Sets the Yaw register to the specified value. More...
 
int AddYaw (double angleDeg, int timeoutMs=0)
 Atomically add to the Yaw register. More...
 
int SetYawToCompass (int timeoutMs=0)
 Sets the Yaw register to match the current compass value. More...
 
int SetAccumZAngle (double angleDeg, int timeoutMs=0)
 Sets the AccumZAngle. More...
 
ErrorCode GetLastError () const
 Call GetLastError() generated by this object. More...
 
ErrorCode Get6dQuaternion (double wxyz[4]) const
 Get 6d Quaternion data. More...
 
ErrorCode GetYawPitchRoll (double ypr[3]) const
 Get Yaw, Pitch, and Roll data. More...
 
double GetYaw () const
 Get the yaw from the Pigeon. More...
 
double GetPitch () const
 Get the pitch from the Pigeon. More...
 
double GetRoll () const
 Get the roll from the Pigeon. More...
 
int GetAccumGyro (double xyz_deg[3]) const
 Get AccumGyro data. More...
 
double GetAbsoluteCompassHeading () const
 Get the absolute compass heading. More...
 
double GetCompassHeading () const
 Get the continuous compass heading. More...
 
double GetCompassFieldStrength () const
 Gets the compass' measured magnetic field strength. More...
 
double GetTemp () const
 Gets the temperature of the pigeon. More...
 
uint32_t GetUpTime () const
 Gets the current Pigeon uptime. More...
 
int GetRawMagnetometer (int16_t rm_xyz[3]) const
 Get Raw Magnetometer data. More...
 
int GetBiasedMagnetometer (int16_t bm_xyz[3]) const
 Get Biased Magnetometer data. More...
 
int GetBiasedAccelerometer (int16_t ba_xyz[3]) const
 Get Biased Accelerometer data. More...
 
int GetRawGyro (double xyz_dps[3]) const
 Get Raw Gyro data. More...
 
uint32_t GetResetCount () const
 
uint32_t GetResetFlags () const
 
uint32_t GetFirmVers () const
 
bool HasResetOccurred () const
 
ErrorCode ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0)
 Sets the value of a custom parameter. More...
 
int ConfigGetCustomParam (int paramIndex, int timeoutMs=0)
 Gets the value of a custom parameter. More...
 
ErrorCode ConfigSetParameter (ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0)
 Sets a parameter. More...
 
double ConfigGetParameter (ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0)
 Gets a parameter. More...
 
ErrorCode ConfigGetParameter (ParamEnum param, int32_t valueToSend, int32_t &valueReceived, uint8_t &subValue, int32_t ordinal, int32_t timeoutMs)
 Gets a parameter by passing an int by reference. More...
 
ErrorCode SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0)
 Sets the period of the given status frame. More...
 
int GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0)
 Gets the period of the given status frame. More...
 
ErrorCode SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs)
 Sets the period of the given control frame. More...
 
int GetFirmwareVersion ()
 Gets the firmware version of the device. More...
 
ErrorCode ClearStickyFaults (int timeoutMs=0)
 Clears the Sticky Faults. More...
 
void * GetLowLevelHandle () const
 
virtual ctre::phoenix::ErrorCode ConfigAllSettings (const BasePigeonConfiguration &allConfigs, int timeoutMs=50)
 Configures all persistent settings. More...
 
virtual void GetAllConfigs (BasePigeonConfiguration &allConfigs, int timeoutMs=50)
 Gets all persistant settings. More...
 
virtual ErrorCode ConfigFactoryDefault (int timeoutMs=50)
 Configures all persistent settings to defaults. More...
 
virtual BasePigeonSimCollectionGetSimCollection ()
 
- Public Member Functions inherited from ctre::phoenix::CANBusAddressable
 CANBusAddressable (int deviceNumber)
 Constructor for a CANBusAddressable device. More...
 
int GetDeviceNumber ()
 

Static Public Member Functions

static std::string ToString (PigeonIMU::PigeonState state)
 Gets the string representation of a PigeonState. More...
 
static std::string ToString (CalibrationMode cm)
 Gets the string representation of a CalibrationMode. More...
 
- Static Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon
static void DestroyAllBasePigeons ()
 Destructs all pigeon objects. More...
 

Additional Inherited Members

- Protected Member Functions inherited from ctre::phoenix::sensors::BasePigeon
 BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx)
 

Detailed Description

Pigeon IMU Class.

Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).

Member Enumeration Documentation

◆ CalibrationMode

Various calibration modes supported by Pigeon.

Note that you can instead use Phoenix Tuner to accomplish certain calibrations.

Enumerator
BootTareGyroAccel 

Boot-Calibrate the pigeon.

Temperature 

Temperature-Calibrate the pigeon.

Magnetometer12Pt 

Magnetometer-Calibrate the pigeon using the 12pt process.

Magnetometer360 

Magnetometer-Calibrate the pigeon using 360 turns.

Accelerometer 

Calibrate the pigeon accelerometer.

◆ PigeonState

Overall state of the Pigeon.

Enumerator
NoComm 

No communications with Pigeon.

Initializing 

Pigeon is initializing.

Ready 

Pigeon is ready.

UserCalibration 

Pigeon is calibrating due to user.

Constructor & Destructor Documentation

◆ PigeonIMU() [1/3]

ctre::phoenix::sensors::PigeonIMU::PigeonIMU ( int  deviceNumber)

Create a Pigeon object that communicates with Pigeon on CAN Bus.

Parameters
deviceNumberCAN Device Id of Pigeon [0,62]

◆ PigeonIMU() [2/3]

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.")]]

Parameters
talonSrxObject for the TalonSRX connected via ribbon cable.

◆ PigeonIMU() [3/3]

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.

Parameters
talonSrxObject for the TalonSRX connected via ribbon cable.

Member Function Documentation

◆ AddFusedHeading()

int ctre::phoenix::sensors::PigeonIMU::AddFusedHeading ( double  angleDeg,
int  timeoutMs = 0 
)

Atomically add to the Fused Heading register.

Parameters
angleDegDegrees to add to the Fused Heading register.
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ ClearStickyFaults()

ErrorCode ctre::phoenix::sensors::PigeonIMU::ClearStickyFaults ( int  timeoutMs = 0)

Clears the Sticky Faults.

Returns
Error Code generated by function. 0 indicates no error.

◆ ConfigAllSettings()

virtual ctre::phoenix::ErrorCode ctre::phoenix::sensors::PigeonIMU::ConfigAllSettings ( const PigeonIMUConfiguration allConfigs,
int  timeoutMs = 50 
)
virtual

Configures all persistent settings.

Parameters
allConfigsObject with all of the persistant settings
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ ConfigFactoryDefault()

virtual ErrorCode ctre::phoenix::sensors::PigeonIMU::ConfigFactoryDefault ( int  timeoutMs = 50)
virtual

Configures all persistent settings to defaults.

Parameters
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

Reimplemented from ctre::phoenix::sensors::BasePigeon.

◆ ConfigGetCustomParam()

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.

Parameters
paramIndexIndex of custom parameter. [0-1]
timeoutMsTimeout 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.
Returns
Value of the custom param.

◆ ConfigSetCustomParam()

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.

Parameters
newValueValue for custom parameter.
paramIndexIndex of custom parameter. [0-1]
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ EnterCalibrationMode()

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.

Parameters
calModeCalibration to execute
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ GetAccelerometerAngles()

int ctre::phoenix::sensors::PigeonIMU::GetAccelerometerAngles ( double  tiltAngles[3])

Get Accelerometer tilt angles.

Parameters
tiltAnglesArray to fill with x[0], y[1], and z[2] angles in degrees.
Returns
The last ErrorCode generated.

◆ GetAllConfigs()

virtual void ctre::phoenix::sensors::PigeonIMU::GetAllConfigs ( PigeonIMUConfiguration allConfigs,
int  timeoutMs = 50 
)
virtual

Gets all persistant settings.

Parameters
allConfigsObject with all of the persistant settings
timeoutMsTimeout 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.

◆ GetFaults()

ErrorCode ctre::phoenix::sensors::PigeonIMU::GetFaults ( PigeonIMU_Faults toFill)

Gets the fault status.

Parameters
toFillContainer for fault statuses.
Returns
Error Code generated by function. 0 indicates no error.

◆ GetFirmwareVersion()

int ctre::phoenix::sensors::PigeonIMU::GetFirmwareVersion ( )

Gets the firmware version of the device.

Returns
param holds the firmware version of the device. Device must be powered cycled at least once.

◆ GetFusedHeading() [1/2]

double ctre::phoenix::sensors::PigeonIMU::GetFusedHeading ( ) const

Gets the Fused Heading.

Returns
The fused heading in degrees.

◆ GetFusedHeading() [2/2]

double ctre::phoenix::sensors::PigeonIMU::GetFusedHeading ( FusionStatus status)

Get the current Fusion Status (including fused heading)

Parameters
statusobject reference to fill with fusion status flags. Caller may pass null if flags are not needed.
Returns
The fused heading in degrees.

◆ GetGeneralStatus()

int ctre::phoenix::sensors::PigeonIMU::GetGeneralStatus ( PigeonIMU::GeneralStatus statusToFill)

Get the status of the current (or previousley complete) calibration.

Parameters
[out]statusToFillContainer for the status information.
Returns
Error Code generated by function. 0 indicates no error.

◆ GetResetCount()

uint32_t ctre::phoenix::sensors::PigeonIMU::GetResetCount ( )
Returns
number of times Pigeon Reset

◆ GetResetFlags()

uint32_t ctre::phoenix::sensors::PigeonIMU::GetResetFlags ( )
Returns
Reset flags for Pigeon

◆ GetState()

PigeonState ctre::phoenix::sensors::PigeonIMU::GetState ( )

Gets the current Pigeon state.

Returns
PigeonState enum

◆ GetStatusFramePeriod()

int ctre::phoenix::sensors::PigeonIMU::GetStatusFramePeriod ( PigeonIMU_StatusFrame  frame,
int  timeoutMs = 0 
)

Gets the period of the given status frame.

Parameters
frameFrame to get the period of.
timeoutMsTimeout 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.
Returns
Period of the given status frame.

◆ GetStickyFaults()

ErrorCode ctre::phoenix::sensors::PigeonIMU::GetStickyFaults ( PigeonIMU_StickyFaults toFill)

Gets the sticky fault status.

Parameters
toFillContainer for sticky fault statuses.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetCompassAngle()

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.

Parameters
angleDegDegrees to set continuous compass angle to.
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetCompassDeclination()

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

Parameters
angleDegOffsetDegrees to set Compass Declination to.
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetControlFramePeriod()

ErrorCode ctre::phoenix::sensors::PigeonIMU::SetControlFramePeriod ( PigeonIMU_ControlFrame  frame,
int  periodMs 
)

Sets the period of the given control frame.

Parameters
frameFrame whose period is to be changed.
periodMsPeriod in ms for the given frame.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetFusedHeading()

int ctre::phoenix::sensors::PigeonIMU::SetFusedHeading ( double  angleDeg,
int  timeoutMs = 0 
)

Sets the Fused Heading to the specified value.

Parameters
angleDegNew fused-heading in degrees [+/- 23,040 degrees]
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetFusedHeadingToCompass()

int ctre::phoenix::sensors::PigeonIMU::SetFusedHeadingToCompass ( int  timeoutMs = 0)

Sets the Fused Heading register to match the current compass value.

Parameters
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetStatusFramePeriod()

ErrorCode ctre::phoenix::sensors::PigeonIMU::SetStatusFramePeriod ( PigeonIMU_StatusFrame  statusFrame,
uint8_t  periodMs,
int  timeoutMs = 0 
)

Sets the period of the given status frame.

Parameters
statusFrameFrame whose period is to be changed.
periodMsPeriod in ms for the given frame.
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ SetTemperatureCompensationDisable()

int ctre::phoenix::sensors::PigeonIMU::SetTemperatureCompensationDisable ( bool  bTempCompDisable,
int  timeoutMs = 0 
)

Disable/Enable Temp compensation.

Pigeon has this on/False at boot.

Parameters
bTempCompDisableSet to "False" to enable temperature compensation.
timeoutMsTimeout 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.
Returns
Error Code generated by function. 0 indicates no error.

◆ ToString() [1/2]

static std::string ctre::phoenix::sensors::PigeonIMU::ToString ( CalibrationMode  cm)
static

Gets the string representation of a CalibrationMode.

Parameters
cmCalibrationMode to get the string representation of
Returns
string representation of specified CalibrationMode

◆ ToString() [2/2]

static std::string ctre::phoenix::sensors::PigeonIMU::ToString ( PigeonIMU::PigeonState  state)
static

Gets the string representation of a PigeonState.

Parameters
statePigeonState to get the string representation of
Returns
string representation of specified PigeonState

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