CTRE_Phoenix 5.20.2
ctre::phoenix::sensors::BasePigeon Class Reference

#include <BasePigeon.h>

Inherits ctre::phoenix::CANBusAddressable.

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

Public Member Functions

 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 BasePigeonSimCollectionGetSimCollection ()
 
- Public Member Functions inherited from ctre::phoenix::CANBusAddressable
 CANBusAddressable (int deviceNumber)
 
int GetDeviceNumber ()
 

Static Public Member Functions

static void DestroyAllBasePigeons ()
 

Protected Member Functions

 BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx)
 

Detailed Description

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

Constructor & Destructor Documentation

◆ BasePigeon()

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.

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

Member Function Documentation

◆ AddYaw()

int ctre::phoenix::sensors::BasePigeon::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::BasePigeon::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::BasePigeon::ConfigAllSettings ( const BasePigeonConfiguration 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::BasePigeon::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 in ctre::phoenix::sensors::PigeonIMU.

◆ ConfigGetCustomParam()

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

◆ DestroyAllBasePigeons()

static void ctre::phoenix::sensors::BasePigeon::DestroyAllBasePigeons ( )
static

Destructs all pigeon objects

◆ Get6dQuaternion()

ErrorCode ctre::phoenix::sensors::BasePigeon::Get6dQuaternion ( double  wxyz[4]) const

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::BasePigeon::GetAbsoluteCompassHeading ( ) const

Get the absolute compass heading.

Returns
compass heading [0,360) degrees.

◆ GetAccumGyro()

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

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::BasePigeon::GetAllConfigs ( BasePigeonConfiguration 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::BasePigeon::GetBiasedAccelerometer ( int16_t  ba_xyz[3]) const

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::BasePigeon::GetBiasedMagnetometer ( int16_t  bm_xyz[3]) const

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::BasePigeon::GetCompassFieldStrength ( ) const

Gets the compass' measured magnetic field strength.

Returns
field strength in Microteslas (uT).

◆ GetCompassHeading()

double ctre::phoenix::sensors::BasePigeon::GetCompassHeading ( ) const

Get the continuous compass heading.

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

◆ GetFirmVers()

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

◆ GetFirmwareVersion()

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

◆ GetLastError()

ErrorCode ctre::phoenix::sensors::BasePigeon::GetLastError ( ) const

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::BasePigeon::GetLowLevelHandle ( ) const
inline
Returns
Pigeon resource handle.

◆ GetPitch()

double ctre::phoenix::sensors::BasePigeon::GetPitch ( ) const

Get the pitch from the Pigeon

Returns
Pitch

◆ GetRawGyro()

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

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::BasePigeon::GetRawMagnetometer ( int16_t  rm_xyz[3]) const

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::BasePigeon::GetResetCount ( ) const
Returns
number of times Pigeon Reset

◆ GetResetFlags()

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

◆ GetRoll()

double ctre::phoenix::sensors::BasePigeon::GetRoll ( ) const

Get the roll from the Pigeon

Returns
Roll

◆ GetSimCollection()

virtual BasePigeonSimCollection & ctre::phoenix::sensors::BasePigeon::GetSimCollection ( )
virtual
Returns
object that can set simulation inputs.

◆ GetStatusFramePeriod()

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

◆ GetTemp()

double ctre::phoenix::sensors::BasePigeon::GetTemp ( ) const

Gets the temperature of the pigeon.

Returns
Temperature in ('C)

◆ GetUpTime()

uint32_t ctre::phoenix::sensors::BasePigeon::GetUpTime ( ) const

Gets the current Pigeon uptime.

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

◆ GetYaw()

double ctre::phoenix::sensors::BasePigeon::GetYaw ( ) const

Get the yaw from the Pigeon

Returns
Yaw

◆ GetYawPitchRoll()

ErrorCode ctre::phoenix::sensors::BasePigeon::GetYawPitchRoll ( double  ypr[3]) const

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::BasePigeon::HasResetOccurred ( ) const
Returns
true iff a reset has occurred since last call.

◆ SetAccumZAngle()

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

◆ SetControlFramePeriod()

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

◆ SetStatusFramePeriod()

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

◆ SetYaw()

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

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