CTRE_Phoenix  5.19.4
ctre::phoenix::sensors::PigeonIMU Class Reference

#include <PigeonIMU.h>

Inherits ctre::phoenix::CANBusAddressable.

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)
 
int SetYaw (double angleDeg, int timeoutMs=0)
 
int AddYaw (double angleDeg, int timeoutMs=0)
 
int SetYawToCompass (int timeoutMs=0)
 
int SetFusedHeading (double angleDeg, int timeoutMs=0)
 
int AddFusedHeading (double angleDeg, int timeoutMs=0)
 
int SetFusedHeadingToCompass (int timeoutMs=0)
 
int SetAccumZAngle (double angleDeg, 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)
 
ErrorCode GetLastError ()
 
int Get6dQuaternion (double wxyz[4])
 
int GetYawPitchRoll (double ypr[3])
 
int GetAccumGyro (double xyz_deg[3])
 
double GetAbsoluteCompassHeading ()
 
double GetCompassHeading ()
 
double GetCompassFieldStrength ()
 
double GetTemp ()
 
PigeonState GetState ()
 
uint32_t GetUpTime ()
 
int GetRawMagnetometer (int16_t rm_xyz[3])
 
int GetBiasedMagnetometer (int16_t bm_xyz[3])
 
int GetBiasedAccelerometer (int16_t ba_xyz[3])
 
int GetRawGyro (double xyz_dps[3])
 
int GetAccelerometerAngles (double tiltAngles[3])
 
double GetFusedHeading (FusionStatus &status)
 
double GetFusedHeading ()
 
uint32_t GetResetCount ()
 
uint32_t GetResetFlags ()
 
uint32_t GetFirmVers ()
 
bool HasResetOccurred ()
 
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 GetFaults (PigeonIMU_Faults &toFill)
 
ErrorCode GetStickyFaults (PigeonIMU_StickyFaults &toFill)
 
ErrorCode ClearStickyFaults (int timeoutMs=0)
 
void * GetLowLevelHandle ()
 
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::CANBusAddressable
 CANBusAddressable (int deviceNumber)
 
int GetDeviceNumber ()
 

Static Public Member Functions

static void DestroyAllPigeonIMUs ()
 
static std::string ToString (PigeonIMU::PigeonState state)
 
static std::string ToString (CalibrationMode cm)
 

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/2]

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/2]

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.

◆ AddYaw()

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

Atomically add to the Yaw register.

Parameters
angleDegDegrees to add to the Yaw 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.

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

◆ ConfigGetParameter() [1/2]

double ctre::phoenix::sensors::PigeonIMU::ConfigGetParameter ( ctre::phoenix::ParamEnum  param,
int  ordinal,
int  timeoutMs = 0 
)

Gets a parameter. Generally this is not used. This can be utilized in

  • Using new features without updating API installation.
  • Errata workarounds to circumvent API implementation.
  • Allows for rapid testing / unit testing of firmware.

    Parameters
    paramParameter enumeration.
    ordinalOrdinal of parameter.
    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 parameter.

◆ ConfigGetParameter() [2/2]

ErrorCode ctre::phoenix::sensors::PigeonIMU::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

Parameters
paramParameter enumeration
valueToSendValue to send to parameter
valueReceivedReference to integer to receive
subValueSubValue of parameter
ordinalOrdinal of parameter
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.

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

◆ ConfigSetParameter()

ErrorCode ctre::phoenix::sensors::PigeonIMU::ConfigSetParameter ( ParamEnum  param,
double  value,
uint8_t  subValue,
int  ordinal,
int  timeoutMs = 0 
)

Sets a parameter. Generally this is not used. This can be utilized in

  • Using new features without updating API installation.
  • Errata workarounds to circumvent API implementation.
  • Allows for rapid testing / unit testing of firmware.
Parameters
paramParameter enumeration.
valueValue of parameter.
subValueSubvalue for parameter. Maximum value of 255.
ordinalOrdinal of parameter.
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.

◆ DestroyAllPigeonIMUs()

static void ctre::phoenix::sensors::PigeonIMU::DestroyAllPigeonIMUs ( )
static

Destructs all pigeon objects

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

◆ Get6dQuaternion()

int ctre::phoenix::sensors::PigeonIMU::Get6dQuaternion ( double  wxyz[4])

Get 6d Quaternion data.

Parameters
wxyzArray to fill with quaternion data w[0], x[1], y[2], z[3]
Returns
The last ErrorCode generated.

◆ GetAbsoluteCompassHeading()

double ctre::phoenix::sensors::PigeonIMU::GetAbsoluteCompassHeading ( )

Get the absolute compass heading.

Returns
compass heading [0,360) degrees.

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

◆ GetAccumGyro()

int ctre::phoenix::sensors::PigeonIMU::GetAccumGyro ( double  xyz_deg[3])

Get AccumGyro data. AccumGyro is the integrated gyro value on each axis.

Parameters
xyz_degArray to fill with x[0], y[1], and z[2] AccumGyro data
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.

◆ GetBiasedAccelerometer()

int ctre::phoenix::sensors::PigeonIMU::GetBiasedAccelerometer ( int16_t  ba_xyz[3])

Get Biased Accelerometer data.

Parameters
ba_xyzArray to fill with x[0], y[1], and z[2] data. These are in fixed point notation Q2.14. eg. 16384 = 1G
Returns
The last ErrorCode generated.

◆ GetBiasedMagnetometer()

int ctre::phoenix::sensors::PigeonIMU::GetBiasedMagnetometer ( int16_t  bm_xyz[3])

Get Biased Magnetometer data.

Parameters
bm_xyzArray to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.
Returns
The last ErrorCode generated.

◆ GetCompassFieldStrength()

double ctre::phoenix::sensors::PigeonIMU::GetCompassFieldStrength ( )

Gets the compass' measured magnetic field strength.

Returns
field strength in Microteslas (uT).

◆ GetCompassHeading()

double ctre::phoenix::sensors::PigeonIMU::GetCompassHeading ( )

Get the continuous compass heading.

Returns
continuous compass heading [-23040, 23040) degrees. Use SetCompassHeading to modify the wrap-around portion.

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

◆ GetFirmVers()

uint32_t ctre::phoenix::sensors::PigeonIMU::GetFirmVers ( )
Returns
firmware version of Pigeon

◆ 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 ( 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.

◆ GetFusedHeading() [2/2]

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

Gets the Fused Heading

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.

◆ GetLastError()

ErrorCode ctre::phoenix::sensors::PigeonIMU::GetLastError ( )

Call GetLastError() generated by this object. Not all functions return an error code but can potentially report errors.

This function can be used to retrieve those error codes.

Returns
The last ErrorCode generated.

◆ GetLowLevelHandle()

void* ctre::phoenix::sensors::PigeonIMU::GetLowLevelHandle ( )
inline
Returns
Pigeon resource handle.

◆ GetRawGyro()

int ctre::phoenix::sensors::PigeonIMU::GetRawGyro ( double  xyz_dps[3])

Get Raw Gyro data.

Parameters
xyz_dpsArray to fill with x[0], y[1], and z[2] data in degrees per second.
Returns
The last ErrorCode generated.

◆ GetRawMagnetometer()

int ctre::phoenix::sensors::PigeonIMU::GetRawMagnetometer ( int16_t  rm_xyz[3])

Get Raw Magnetometer data.

Parameters
rm_xyzArray to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.
Returns
The last ErrorCode generated.

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

◆ GetTemp()

double ctre::phoenix::sensors::PigeonIMU::GetTemp ( )

Gets the temperature of the pigeon.

Returns
Temperature in ('C)

◆ GetUpTime()

uint32_t ctre::phoenix::sensors::PigeonIMU::GetUpTime ( )

Gets the current Pigeon uptime.

Returns
How long has Pigeon been running in whole seconds. Value caps at 255.

◆ GetYawPitchRoll()

int ctre::phoenix::sensors::PigeonIMU::GetYawPitchRoll ( double  ypr[3])

Get Yaw, Pitch, and Roll data.

Parameters
yprArray to fill with yaw[0], pitch[1], and roll[2] data. Yaw is within [-368,640, +368,640] degrees. Pitch is within [-90,+90] degrees. Roll is within [-90,+90] degrees.
Returns
The last ErrorCode generated.

◆ HasResetOccurred()

bool ctre::phoenix::sensors::PigeonIMU::HasResetOccurred ( )
Returns
true iff a reset has occurred since last call.

◆ SetAccumZAngle()

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

Sets the AccumZAngle.

Parameters
angleDegDegrees to set AccumZAngle 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.

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

◆ SetYaw()

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

Sets the Yaw register to the specified value.

Parameters
angleDegDegree of Yaw [+/- 368,640 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.

◆ SetYawToCompass()

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

Sets the Yaw 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.

◆ ToString() [1/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

◆ ToString() [2/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

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