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

Pigeon 2 Class. More...

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

Inheritance diagram for ctre::phoenix::sensors::Pigeon2:
ctre::phoenix::sensors::BasePigeon ctre::phoenix::CANBusAddressable ctre::phoenix::sensors::WPI_Pigeon2

Public Member Functions

 Pigeon2 (int deviceNumber, std::string const &canbus="")
 Create a Pigeon object that communicates with Pigeon on CAN Bus. More...
 
ErrorCode GetFaults (Pigeon2_Faults &toFill)
 Gets the fault status. More...
 
ErrorCode GetStickyFaults (Pigeon2_StickyFaults &toFill)
 Gets the sticky fault status. More...
 
ErrorCode ConfigMountPose (AxisDirection forward, AxisDirection up, int timeoutMs=50)
 Configure the Mount Pose using the primary axis. More...
 
ErrorCode ConfigMountPose (double yaw, double pitch, double roll, int timeoutMs=0)
 Configure the mounting pose of the Pigeon2. More...
 
ErrorCode ConfigMountPoseYaw (double yaw, int timeoutMs=0)
 Configure the mounting pose Yaw of the Pigeon2. More...
 
ErrorCode ConfigMountPosePitch (double pitch, int timeoutMs=0)
 Configure the mounting pose Pitch of the Pigeon2. More...
 
ErrorCode ConfigMountPoseRoll (double roll, int timeoutMs=0)
 Configure the mounting pose Roll of the Pigeon2. More...
 
ErrorCode ConfigXAxisGyroError (double err, int timeoutMs=0)
 Configures the X Axis Gyroscope Error for 1 rotation. More...
 
ErrorCode ConfigYAxisGyroError (double err, int timeoutMs=0)
 Configures the Y Axis Gyroscope Error for 1 rotation. More...
 
ErrorCode ConfigZAxisGyroError (double err, int timeoutMs=0)
 Configures the Z Axis Gyroscope Error for 1 rotation. More...
 
ErrorCode ConfigEnableCompass (bool enable, int timeoutMs=0)
 Enables the magnetometer fusion for Pigeon2. More...
 
ErrorCode ConfigDisableTemperatureCompensation (bool disable, int timeoutMs=0)
 Disables temperature compensation from Pigeon2. More...
 
ErrorCode ConfigDisableNoMotionCalibration (bool disable, int timeoutMs=0)
 Disables the no-motion calibration from Pigeon2. More...
 
ErrorCode ZeroGyroBiasNow (int timeoutMs=0)
 Performs an offset calibration on gyro bias. More...
 
ErrorCode GetGravityVector (double gravVector[3]) const
 Get the Gravity Vector. More...
 
ErrorCode ConfigAllSettings (Pigeon2Configuration &settings, int timeoutMs=50)
 Configures all persistent settings. More...
 
void GetAllConfigs (Pigeon2Configuration &allConfigs, int timeoutMs=50)
 Gets all persistant settings. 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 ()
 

Additional Inherited Members

- Static Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon
static void DestroyAllBasePigeons ()
 Destructs all pigeon objects. More...
 
- Protected Member Functions inherited from ctre::phoenix::sensors::BasePigeon
 BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx)
 

Detailed Description

Pigeon 2 Class.

Class supports communicating over CANbus.


// Example usage of a Pigeon 2
Pigeon2 pigeon{0}; // creates a new Pigeon2 with ID 0

Pigeon2Configuration config;
// set mount pose as rolled 90 degrees counter-clockwise
config.MountPoseYaw = 0;
config.MountPosePitch = 0;
config.MountPoseRoll = 90;
pigeon.ConfigAllSettings(config);

std::cout << pigeon.GetYaw() << std::endl; // prints the yaw of the Pigeon
std::cout << pigeon.GetPitch() << std::endl; // prints the pitch of the Pigeon
std::cout << pigeon.GetRoll() << std::endl; // prints the roll of the Pigeon

double gravityVec[3];
pigeon.GetGravityVector(gravityVec); // gets the gravity vector of the Pigeon 2

ErrorCode error = pigeon.GetLastError(); // gets the last error generated by the Pigeon
Pigeon2_Faults faults;
ErrorCode faultsError = pigeon.GetFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated
Deprecated:
This device's Phoenix 5 API is deprecated for removal in the 2025 season. Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API. A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.

If the Phoenix 5 API must be used for this device, the device must have 22.X firmware. This firmware is available in Tuner X after selecting Phoenix 5 in the firmware year dropdown.

Constructor & Destructor Documentation

◆ Pigeon2()

ctre::phoenix::sensors::Pigeon2::Pigeon2 ( int  deviceNumber,
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

◆ ConfigAllSettings()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigAllSettings ( Pigeon2Configuration settings,
int  timeoutMs = 50 
)

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.

◆ ConfigDisableNoMotionCalibration()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigDisableNoMotionCalibration ( bool  disable,
int  timeoutMs = 0 
)

Disables the no-motion calibration from Pigeon2.

Parameters
disableBoolean to disable/enable no-motion calibration
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
ErrorCode Status of the config response

◆ ConfigDisableTemperatureCompensation()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigDisableTemperatureCompensation ( bool  disable,
int  timeoutMs = 0 
)

Disables temperature compensation from Pigeon2.

Parameters
disableBoolean to disable/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
ErrorCode Status of the config response

◆ ConfigEnableCompass()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigEnableCompass ( bool  enable,
int  timeoutMs = 0 
)

Enables the magnetometer fusion for Pigeon2.

This is not recommended for FRC use

Parameters
enableBoolean to enable/disable magnetometer fusion
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
ErrorCode Status of the config response

◆ ConfigMountPose() [1/2]

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPose ( AxisDirection  forward,
AxisDirection  up,
int  timeoutMs = 50 
)

Configure the Mount Pose using the primary axis.

This is useful if the Pigeon 2.0 is mounted straight, and you only need to describe what axis is forward and what axis is up.

Parameters
forwardAxis that points forward from the robot
upAxis that points up from the robot
timeoutMsConfig timeout in milliseconds.
Returns
OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.

◆ ConfigMountPose() [2/2]

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPose ( double  yaw,
double  pitch,
double  roll,
int  timeoutMs = 0 
)

Configure the mounting pose of the Pigeon2.

This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current orientation, referenced from the robot's point of view.

This is only necessary if the Pigeon2 is mounted at an exotic angle near the gimbal lock point or not forward.

If the pigeon is relatively flat and pointed forward, this is not needed.

Examples:

If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw, 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.

If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it pitched 90 degrees clockwise.

Parameters
yawYaw angle needed to reach the current orientation in degrees.
pitchPitch angle needed to reach the current orientation in degrees.
rollRoll angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
Worst error code of all config sets.

◆ ConfigMountPosePitch()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPosePitch ( double  pitch,
int  timeoutMs = 0 
)

Configure the mounting pose Pitch of the Pigeon2.

See configMountPose(double, double, double, int)

Parameters
pitchPitch angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode of configSet

◆ ConfigMountPoseRoll()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPoseRoll ( double  roll,
int  timeoutMs = 0 
)

Configure the mounting pose Roll of the Pigeon2.

See configMountPose(double, double, double, int)

Parameters
rollRoll angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode of configSet

◆ ConfigMountPoseYaw()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPoseYaw ( double  yaw,
int  timeoutMs = 0 
)

Configure the mounting pose Yaw of the Pigeon2.

See configMountPose(double, double, double, int)

Parameters
yawYaw angle needed to reach the current orientation in degrees.
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode of configSet

◆ ConfigXAxisGyroError()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigXAxisGyroError ( double  err,
int  timeoutMs = 0 
)

Configures the X Axis Gyroscope Error for 1 rotation.

Parameters
errDegrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode fo configSet

◆ ConfigYAxisGyroError()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigYAxisGyroError ( double  err,
int  timeoutMs = 0 
)

Configures the Y Axis Gyroscope Error for 1 rotation.

Parameters
errDegrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode fo configSet

◆ ConfigZAxisGyroError()

ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigZAxisGyroError ( double  err,
int  timeoutMs = 0 
)

Configures the Z Axis Gyroscope Error for 1 rotation.

Parameters
errDegrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
timeoutMsConfig timeout in milliseconds.
Returns
ErrorCode fo configSet

◆ GetAllConfigs()

void ctre::phoenix::sensors::Pigeon2::GetAllConfigs ( Pigeon2Configuration allConfigs,
int  timeoutMs = 50 
)

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::Pigeon2::GetFaults ( Pigeon2_Faults toFill)

Gets the fault status.

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

◆ GetGravityVector()

ErrorCode ctre::phoenix::sensors::Pigeon2::GetGravityVector ( double  gravVector[3]) const

Get the Gravity Vector.

This provides a vector that points toward ground. This is useful for applications like an arm, where the z-value of the gravity vector corresponds to the feed-forward needed to hold the arm steady. The gravity vector is calculated after the mount pose, so if the pigeon is where it was mounted, the gravity vector is {0, 0, 1}.

Parameters
gravVectorPass in a double array of size 3 to get the gravity vector
Returns
Errorcode of getter

◆ GetStickyFaults()

ErrorCode ctre::phoenix::sensors::Pigeon2::GetStickyFaults ( Pigeon2_StickyFaults toFill)

Gets the sticky fault status.

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

◆ ZeroGyroBiasNow()

ErrorCode ctre::phoenix::sensors::Pigeon2::ZeroGyroBiasNow ( int  timeoutMs = 0)

Performs an offset calibration on gyro bias.

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
ErrorCode Status of the config response

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