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

Inherited by com.ctre.phoenix.sensors.Pigeon2, and com.ctre.phoenix.sensors.PigeonIMU.

Public Member Functions

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

Protected Member Functions

 BasePigeon (long handle)
 

Detailed Description

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

Constructor & Destructor Documentation

◆ BasePigeon() [1/2]

com.ctre.phoenix.sensors.BasePigeon.BasePigeon ( int  deviceNumber,
String  version,
String  canbus 
)
inline

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

Parameters
deviceNumberCAN Device Id of Pigeon [0,62]
versionVersion of the PigeonIMU
canbusName of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number

◆ BasePigeon() [2/2]

com.ctre.phoenix.sensors.BasePigeon.BasePigeon ( int  deviceNumber,
String  version 
)
inline

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

Parameters
deviceNumberCAN Device Id of Pigeon [0,62]
versionVersion of the PigeonIMU

Member Function Documentation

◆ addYaw() [1/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.addYaw ( double  angleDeg)
inline

Atomically add to the Yaw register.

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

◆ addYaw() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.addYaw ( double  angleDeg,
int  timeoutMs 
)
inline

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

ErrorCode com.ctre.phoenix.sensors.BasePigeon.clearStickyFaults ( )
inline

Clears the Sticky Faults

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

◆ clearStickyFaults() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.clearStickyFaults ( int  timeoutMs)
inline

Clears the Sticky Faults

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.

◆ configAllSettings() [1/2]

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

◆ configAllSettings() [2/2]

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

◆ configFactoryDefault() [1/2]

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

◆ configFactoryDefault() [2/2]

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

◆ configGetCustomParam() [1/2]

int com.ctre.phoenix.sensors.BasePigeon.configGetCustomParam ( int  paramIndex)
inline

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]
Returns
Value of the custom param.

◆ configGetCustomParam() [2/2]

int com.ctre.phoenix.sensors.BasePigeon.configGetCustomParam ( int  paramIndex,
int  timoutMs 
)
inline

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]
timoutMsTimeout 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/4]

double com.ctre.phoenix.sensors.BasePigeon.configGetParameter ( int  param,
int  ordinal 
)
inline

Gets a parameter.

Parameters
paramParameter enumeration.
ordinalOrdinal of parameter.
Returns
Value of parameter.

◆ configGetParameter() [2/4]

double com.ctre.phoenix.sensors.BasePigeon.configGetParameter ( int  param,
int  ordinal,
int  timeoutMs 
)
inline

Gets a parameter.

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() [3/4]

double com.ctre.phoenix.sensors.BasePigeon.configGetParameter ( ParamEnum  param,
int  ordinal 
)
inline

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.
Returns
Value of parameter.

◆ configGetParameter() [4/4]

double com.ctre.phoenix.sensors.BasePigeon.configGetParameter ( ParamEnum  param,
int  ordinal,
int  timeoutMs 
)
inline

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.

◆ configSetCustomParam() [1/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.configSetCustomParam ( int  newValue,
int  paramIndex 
)
inline

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

◆ configSetCustomParam() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.configSetCustomParam ( int  newValue,
int  paramIndex,
int  timeoutMs 
)
inline

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

ErrorCode com.ctre.phoenix.sensors.BasePigeon.configSetParameter ( int  param,
double  value,
int  subValue,
int  ordinal 
)
inline

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

◆ configSetParameter() [2/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.configSetParameter ( int  param,
double  value,
int  subValue,
int  ordinal,
int  timeoutMs 
)
inline

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.

◆ configSetParameter() [3/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.configSetParameter ( ParamEnum  param,
double  value,
int  subValue,
int  ordinal 
)
inline

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

◆ configSetParameter() [4/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.configSetParameter ( ParamEnum  param,
double  value,
int  subValue,
int  ordinal,
int  timeoutMs 
)
inline

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.

◆ DestroyObject()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.DestroyObject ( )
inline

Destructor for Pigeon

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

◆ get6dQuaternion()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.get6dQuaternion ( double[]  wxyz)
inline

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 com.ctre.phoenix.sensors.BasePigeon.getAbsoluteCompassHeading ( )
inline

Get the absolute compass heading.

Returns
compass heading [0,360) degrees.

◆ getAccumGyro()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getAccumGyro ( double[]  xyz_deg)
inline

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

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

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

Parameters
allConfigsObject with all of the persistant settings

Reimplemented in com.ctre.phoenix.sensors.PigeonIMU.

◆ getAllConfigs() [2/2]

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

◆ getBiasedAccelerometer()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getBiasedAccelerometer ( short[]  ba_xyz)
inline

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

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getBiasedMagnetometer ( short[]  bm_xyz)
inline

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 com.ctre.phoenix.sensors.BasePigeon.getCompassFieldStrength ( )
inline

Gets the compass' measured magnetic field strength.

Returns
field strength in Microteslas (uT).

◆ getCompassHeading()

double com.ctre.phoenix.sensors.BasePigeon.getCompassHeading ( )
inline

Get the continuous compass heading.

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

◆ getDeviceID()

int com.ctre.phoenix.sensors.BasePigeon.getDeviceID ( )
inline
Returns
The Device Number

◆ getFirmwareVersion()

int com.ctre.phoenix.sensors.BasePigeon.getFirmwareVersion ( )
inline

Gets the firmware version of the device.

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

◆ getLastError()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getLastError ( )
inline

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.

◆ getPitch()

double com.ctre.phoenix.sensors.BasePigeon.getPitch ( )
inline

Get the pitch from the Pigeon

Returns
Pitch

◆ getRawGyro()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getRawGyro ( double[]  xyz_dps)
inline

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

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getRawMagnetometer ( short[]  rm_xyz)
inline

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

int com.ctre.phoenix.sensors.BasePigeon.getResetCount ( )
inline
Returns
number of times Pigeon Reset

◆ getResetFlags()

int com.ctre.phoenix.sensors.BasePigeon.getResetFlags ( )
inline
Returns
Reset flags for Pigeon

◆ getRoll()

double com.ctre.phoenix.sensors.BasePigeon.getRoll ( )
inline

Get the roll from the Pigeon

Returns
Roll

◆ getSimCollection()

BasePigeonSimCollection com.ctre.phoenix.sensors.BasePigeon.getSimCollection ( )
inline
Returns
object that can set simulation inputs.

◆ getStatusFramePeriod() [1/2]

int com.ctre.phoenix.sensors.BasePigeon.getStatusFramePeriod ( PigeonIMU_StatusFrame  frame)
inline

Gets the period of the given status frame.

Parameters
frameFrame to get the period of.
Returns
Period of the given status frame.

◆ getStatusFramePeriod() [2/2]

int com.ctre.phoenix.sensors.BasePigeon.getStatusFramePeriod ( PigeonIMU_StatusFrame  frame,
int  timeoutMs 
)
inline

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.

◆ getTemp()

double com.ctre.phoenix.sensors.BasePigeon.getTemp ( )
inline

Gets the temperature of the pigeon.

Returns
Temperature in ('C)

◆ getUpTime()

int com.ctre.phoenix.sensors.BasePigeon.getUpTime ( )
inline

Gets the current Pigeon uptime.

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

◆ getYaw()

double com.ctre.phoenix.sensors.BasePigeon.getYaw ( )
inline

Get the yaw from the Pigeon

Returns
Yaw

◆ getYawPitchRoll()

ErrorCode com.ctre.phoenix.sensors.BasePigeon.getYawPitchRoll ( double[]  ypr_deg)
inline

Get Yaw, Pitch, and Roll data.

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

boolean com.ctre.phoenix.sensors.BasePigeon.hasResetOccurred ( )
inline
Returns
true iff a reset has occurred since last call.

◆ setAccumZAngle() [1/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setAccumZAngle ( double  angleDeg)
inline

Sets the AccumZAngle.

Parameters
angleDegDegrees to set AccumZAngle to.
Returns
Error Code generated by function. 0 indicates no error.

◆ setAccumZAngle() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setAccumZAngle ( double  angleDeg,
int  timeoutMs 
)
inline

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.

◆ setControlFramePeriod() [1/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setControlFramePeriod ( int  frame,
int  periodMs 
)
inline

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.

◆ setControlFramePeriod() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setControlFramePeriod ( PigeonIMU_ControlFrame  frame,
int  periodMs 
)
inline

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.

◆ setStatusFramePeriod() [1/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setStatusFramePeriod ( int  statusFrame,
int  periodMs 
)
inline

Sets the period of the given status frame.

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

◆ setStatusFramePeriod() [2/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setStatusFramePeriod ( int  statusFrame,
int  periodMs,
int  timeoutMs 
)
inline

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.

◆ setStatusFramePeriod() [3/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setStatusFramePeriod ( PigeonIMU_StatusFrame  statusFrame,
int  periodMs 
)
inline

Sets the period of the given status frame.

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

◆ setStatusFramePeriod() [4/4]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setStatusFramePeriod ( PigeonIMU_StatusFrame  statusFrame,
int  periodMs,
int  timeoutMs 
)
inline

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.

◆ setYaw() [1/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setYaw ( double  angleDeg)
inline

Sets the Yaw register to the specified value.

Parameters
angleDegNew yaw in degrees [+/- 368,640 degrees]
Returns
Error Code generated by function. 0 indicates no error.

◆ setYaw() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setYaw ( double  angleDeg,
int  timeoutMs 
)
inline

Sets the Yaw register to the specified value.

Parameters
angleDegNew yaw in degrees [+/- 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() [1/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setYawToCompass ( )
inline

Sets the Yaw register to match the current compass value.

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

◆ setYawToCompass() [2/2]

ErrorCode com.ctre.phoenix.sensors.BasePigeon.setYawToCompass ( int  timeoutMs)
inline

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.

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