CTRE_Phoenix 5.20.2
com.ctre.phoenix.sensors.PigeonIMU Class Reference

Inherits com.ctre.phoenix.sensors.BasePigeon.

Inherited by com.ctre.phoenix.sensors.WPI_PigeonIMU.

Classes

enum  CalibrationMode
 
class  FusionStatus
 
class  GeneralStatus
 
enum  PigeonState
 

Public Member Functions

 PigeonIMU (int deviceNumber)
 
 PigeonIMU (TalonSRX talonSrx)
 
ErrorCode setFusedHeading (double angleDeg, int timeoutMs)
 
ErrorCode setFusedHeading (double angleDeg)
 
ErrorCode addFusedHeading (double angleDeg, int timeoutMs)
 
ErrorCode addFusedHeading (double angleDeg)
 
ErrorCode setFusedHeadingToCompass (int timeoutMs)
 
ErrorCode setFusedHeadingToCompass ()
 
ErrorCode setTemperatureCompensationDisable (boolean bTempCompDisable, int timeoutMs)
 
ErrorCode setTemperatureCompensationDisable (boolean bTempCompDisable)
 
ErrorCode setCompassDeclination (double angleDegOffset, int timeoutMs)
 
ErrorCode setCompassDeclination (double angleDegOffset)
 
ErrorCode setCompassAngle (double angleDeg, int timeoutMs)
 
ErrorCode setCompassAngle (double angleDeg)
 
ErrorCode enterCalibrationMode (CalibrationMode calMode, int timeoutMs)
 
ErrorCode enterCalibrationMode (CalibrationMode calMode)
 
ErrorCode getGeneralStatus (GeneralStatus toFill)
 
PigeonState getState ()
 
double getFusedHeading (FusionStatus toFill)
 
double getFusedHeading ()
 
ErrorCode getAccelerometerAngles (double[] tiltAngles)
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs)
 
ErrorCode configFactoryDefault (int timeoutMs)
 
ErrorCode configFactoryDefault ()
 
ErrorCode getFaults (PigeonIMU_Faults toFill)
 
ErrorCode getStickyFaults (PigeonIMU_Faults toFill)
 
- Public Member Functions inherited from com.ctre.phoenix.sensors.BasePigeon
 BasePigeon (int deviceNumber, String version, String canbus)
 
 BasePigeon (int deviceNumber, String version)
 
ErrorCode DestroyObject ()
 
BasePigeonSimCollection getSimCollection ()
 
ErrorCode setYaw (double angleDeg, int timeoutMs)
 
ErrorCode setYaw (double angleDeg)
 
ErrorCode addYaw (double angleDeg, int timeoutMs)
 
ErrorCode addYaw (double angleDeg)
 
ErrorCode setYawToCompass (int timeoutMs)
 
ErrorCode setYawToCompass ()
 
ErrorCode setAccumZAngle (double angleDeg, int timeoutMs)
 
ErrorCode setAccumZAngle (double angleDeg)
 
ErrorCode getLastError ()
 
ErrorCode get6dQuaternion (double[] wxyz)
 
ErrorCode getYawPitchRoll (double[] ypr_deg)
 
double getYaw ()
 
double getPitch ()
 
double getRoll ()
 
ErrorCode getAccumGyro (double[] xyz_deg)
 
double getAbsoluteCompassHeading ()
 
double getCompassHeading ()
 
double getCompassFieldStrength ()
 
double getTemp ()
 
int getUpTime ()
 
ErrorCode getRawMagnetometer (short[] rm_xyz)
 
ErrorCode getBiasedMagnetometer (short[] bm_xyz)
 
ErrorCode getBiasedAccelerometer (short[] ba_xyz)
 
ErrorCode getRawGyro (double[] xyz_dps)
 
int getResetCount ()
 
int getResetFlags ()
 
int getFirmwareVersion ()
 
boolean hasResetOccurred ()
 
ErrorCode configSetCustomParam (int newValue, int paramIndex, int timeoutMs)
 
ErrorCode configSetCustomParam (int newValue, int paramIndex)
 
int configGetCustomParam (int paramIndex, int timoutMs)
 
int configGetCustomParam (int paramIndex)
 
ErrorCode configSetParameter (ParamEnum param, double value, int subValue, int ordinal, int timeoutMs)
 
ErrorCode configSetParameter (ParamEnum param, double value, int subValue, int ordinal)
 
ErrorCode configSetParameter (int param, double value, int subValue, int ordinal, int timeoutMs)
 
ErrorCode configSetParameter (int param, double value, int subValue, int ordinal)
 
double configGetParameter (ParamEnum param, int ordinal, int timeoutMs)
 
double configGetParameter (ParamEnum param, int ordinal)
 
double configGetParameter (int param, int ordinal, int timeoutMs)
 
double configGetParameter (int param, int ordinal)
 
ErrorCode setStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, int periodMs, int timeoutMs)
 
ErrorCode setStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, int periodMs)
 
ErrorCode setStatusFramePeriod (int statusFrame, int periodMs, int timeoutMs)
 
ErrorCode setStatusFramePeriod (int statusFrame, int periodMs)
 
int getStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs)
 
int getStatusFramePeriod (PigeonIMU_StatusFrame frame)
 
ErrorCode setControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs)
 
ErrorCode setControlFramePeriod (int frame, int periodMs)
 
ErrorCode clearStickyFaults (int timeoutMs)
 
ErrorCode clearStickyFaults ()
 
int getDeviceID ()
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
ErrorCode configAllSettings (PigeonIMUConfiguration allConfigs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs, int timeoutMs)
 
void getAllConfigs (PigeonIMUConfiguration allConfigs)
 
ErrorCode configFactoryDefault (int timeoutMs)
 
ErrorCode configFactoryDefault ()
 
long getHandle ()
 

Additional Inherited Members

- Protected Member Functions inherited from com.ctre.phoenix.sensors.BasePigeon
 BasePigeon (long handle)
 

Detailed Description

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

Constructor & Destructor Documentation

◆ PigeonIMU() [1/2]

com.ctre.phoenix.sensors.PigeonIMU.PigeonIMU ( int  deviceNumber)
inline

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

Parameters
deviceNumberCAN Device Id of Pigeon [0,62]

◆ PigeonIMU() [2/2]

com.ctre.phoenix.sensors.PigeonIMU.PigeonIMU ( TalonSRX  talonSrx)
inline

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() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.addFusedHeading ( double  angleDeg)
inline

Atomically add to the Fused Heading register.

Parameters
angleDegDegrees to add to the Fused Heading register
Returns
Error Code generated by function. 0 indicates no error.

◆ addFusedHeading() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.addFusedHeading ( double  angleDeg,
int  timeoutMs 
)
inline

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.

◆ configAllSettings() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.configAllSettings ( PigeonIMUConfiguration  allConfigs)
inline

Configures all persistent settings (overloaded so timeoutMs is 50 ms).

Parameters
allConfigsObject with all of the persistant settings
Returns
Error Code generated by function. 0 indicates no error.

Reimplemented from com.ctre.phoenix.sensors.BasePigeon.

◆ configAllSettings() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.configAllSettings ( PigeonIMUConfiguration  allConfigs,
int  timeoutMs 
)
inline

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.

Reimplemented from com.ctre.phoenix.sensors.BasePigeon.

◆ configFactoryDefault() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.configFactoryDefault ( )
inline

Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms).

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

Reimplemented from com.ctre.phoenix.sensors.BasePigeon.

◆ configFactoryDefault() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.configFactoryDefault ( int  timeoutMs)
inline

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 com.ctre.phoenix.sensors.BasePigeon.

◆ enterCalibrationMode() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.enterCalibrationMode ( CalibrationMode  calMode)
inline

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 using this in your normal robot application.

Parameters
calModeCalibration to execute
Returns
Error Code generated by function. 0 indicates no error.

◆ enterCalibrationMode() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.enterCalibrationMode ( CalibrationMode  calMode,
int  timeoutMs 
)
inline

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()

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.getAccelerometerAngles ( double[]  tiltAngles)
inline

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() [1/2]

void com.ctre.phoenix.sensors.PigeonIMU.getAllConfigs ( PigeonIMUConfiguration  allConfigs)
inline

Gets all persistant settings (overloaded so timeoutMs is 50 ms).

Parameters
allConfigsObject with all of the persistant settings

Reimplemented from com.ctre.phoenix.sensors.BasePigeon.

◆ getAllConfigs() [2/2]

void com.ctre.phoenix.sensors.PigeonIMU.getAllConfigs ( PigeonIMUConfiguration  allConfigs,
int  timeoutMs 
)
inline

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.

Reimplemented from com.ctre.phoenix.sensors.BasePigeon.

◆ getFaults()

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.getFaults ( PigeonIMU_Faults  toFill)
inline

Gets the fault status

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

◆ getFusedHeading() [1/2]

double com.ctre.phoenix.sensors.PigeonIMU.getFusedHeading ( )
inline

Gets the Fused Heading

Returns
The fused heading in degrees.

◆ getFusedHeading() [2/2]

double com.ctre.phoenix.sensors.PigeonIMU.getFusedHeading ( FusionStatus  toFill)
inline

Get the current Fusion Status (including fused heading)

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

◆ getGeneralStatus()

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.getGeneralStatus ( GeneralStatus  toFill)
inline

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

Parameters
toFillContainer for the status information.
Returns
Error Code generated by function. 0 indicates no error.

◆ getState()

PigeonState com.ctre.phoenix.sensors.PigeonIMU.getState ( )
inline

Gets the current Pigeon state

Returns
PigeonState enum

◆ getStickyFaults()

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.getStickyFaults ( PigeonIMU_Faults  toFill)
inline

Gets the sticky fault status

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

◆ setCompassAngle() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setCompassAngle ( double  angleDeg)
inline

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

◆ setCompassAngle() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setCompassAngle ( double  angleDeg,
int  timeoutMs 
)
inline

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() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setCompassDeclination ( double  angleDegOffset)
inline

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

◆ setCompassDeclination() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setCompassDeclination ( double  angleDegOffset,
int  timeoutMs 
)
inline

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.

◆ setFusedHeading() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setFusedHeading ( double  angleDeg)
inline

Sets the Fused Heading to the specified value.

Parameters
angleDegNew fused-heading in degrees [+/- 23,040 degrees]
Returns
Error Code generated by function. 0 indicates no error.

◆ setFusedHeading() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setFusedHeading ( double  angleDeg,
int  timeoutMs 
)
inline

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() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setFusedHeadingToCompass ( )
inline

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

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

◆ setFusedHeadingToCompass() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setFusedHeadingToCompass ( int  timeoutMs)
inline

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.

◆ setTemperatureCompensationDisable() [1/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setTemperatureCompensationDisable ( boolean  bTempCompDisable)
inline

Disable/Enable Temp compensation. Pigeon has this on/False at boot.

Parameters
bTempCompDisableSet to "False" to enable temperature compensation.
Returns
Error Code generated by function. 0 indicates no error.

◆ setTemperatureCompensationDisable() [2/2]

ErrorCode com.ctre.phoenix.sensors.PigeonIMU.setTemperatureCompensationDisable ( boolean  bTempCompDisable,
int  timeoutMs 
)
inline

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.

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