CTRE Phoenix Pro C++ 23.0.12
ctre::phoenixpro::hardware::core::CorePigeon2 Class Reference

Class description for the Pigeon 2 IMU sensor that measures orientation. More...

#include <ctre/phoenixpro/core/CorePigeon2.hpp>

Inheritance diagram for ctre::phoenixpro::hardware::core::CorePigeon2:
ctre::phoenixpro::hardware::ParentDevice ctre::phoenixpro::hardware::Pigeon2

Public Member Functions

 CorePigeon2 (int deviceId, std::string canbus="")
 Constructs a new Pigeon 2 sensor object. More...
 
 CorePigeon2 (CorePigeon2 const &)=delete
 
CorePigeon2operator= (CorePigeon2 const &)=delete
 
bool HasResetOccurred ()
 
configs::Pigeon2ConfiguratorGetConfigurator ()
 Gets the configurator for this Pigeon2. More...
 
configs::Pigeon2Configurator const & GetConfigurator () const
 Gets the configurator for this Pigeon2. More...
 
sim::Pigeon2SimStateGetSimState ()
 Get the simulation state for this device. More...
 
StatusSignalValue< int > & GetVersionMajor ()
 App Major Version number. More...
 
StatusSignalValue< int > & GetVersionMinor ()
 App Minor Version number. More...
 
StatusSignalValue< int > & GetVersionBugfix ()
 App Bugfix Version number. More...
 
StatusSignalValue< int > & GetVersionBuild ()
 App Build Version number. More...
 
StatusSignalValue< int > & GetVersion ()
 Full Version. More...
 
StatusSignalValue< int > & GetFaultField ()
 Integer representing all faults. More...
 
StatusSignalValue< int > & GetStickyFaultField ()
 Integer representing all sticky faults. More...
 
StatusSignalValue< units::angle::degree_t > & GetYaw ()
 Current reported yaw of the Pigeon2. More...
 
StatusSignalValue< units::angle::degree_t > & GetPitch ()
 Current reported pitch of the Pigeon2. More...
 
StatusSignalValue< units::angle::degree_t > & GetRoll ()
 Current reported roll of the Pigeon2. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatW ()
 The W component of the reported Quaternion. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatX ()
 The X component of the reported Quaternion. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatY ()
 The Y component of the reported Quaternion. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetQuatZ ()
 The Z component of the reported Quaternion. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetGravityVectorX ()
 The X component of the gravity vector. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetGravityVectorY ()
 The Y component of the gravity vector. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetGravityVectorZ ()
 The Z component of the gravity vector. More...
 
StatusSignalValue< units::temperature::celsius_t > & GetTemperature ()
 Temperature of the Pigeon 2. More...
 
StatusSignalValue< bool > & GetNoMotionEnabled ()
 Whether the no-motion calibration feature is enabled. More...
 
StatusSignalValue< units::dimensionless::scalar_t > & GetNoMotionCount ()
 The number of times a no-motion event occurred, wraps at 15. More...
 
StatusSignalValue< bool > & GetTemperatureCompensationDisabled ()
 Whether the temperature-compensation feature is disabled. More...
 
StatusSignalValue< units::time::second_t > & GetUpTime ()
 How long the Pigeon 2's been up in seconds, caps at 255 seconds. More...
 
StatusSignalValue< units::angle::degree_t > & GetAccumGyroX ()
 The accumulated gyro about the X axis without any sensor fusing. More...
 
StatusSignalValue< units::angle::degree_t > & GetAccumGyroY ()
 The accumulated gyro about the Y axis without any sensor fusing. More...
 
StatusSignalValue< units::angle::degree_t > & GetAccumGyroZ ()
 The accumulated gyro about the Z axis without any sensor fusing. More...
 
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityX ()
 The angular velocity (ω) of the Pigeon 2 about the X axis. More...
 
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityY ()
 The angular velocity (ω) of the Pigeon 2 about the Y axis. More...
 
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZ ()
 The angular velocity (ω) of the Pigeon 2 about the Z axis. More...
 
StatusSignalValue< units::acceleration::standard_gravity_t > & GetAccelerationX ()
 The acceleration measured by Pigeon2 in the X direction. More...
 
StatusSignalValue< units::acceleration::standard_gravity_t > & GetAccelerationY ()
 The acceleration measured by Pigeon2 in the Y direction. More...
 
StatusSignalValue< units::acceleration::standard_gravity_t > & GetAccelerationZ ()
 The acceleration measured by Pigeon2 in the Z direction. More...
 
StatusSignalValue< units::voltage::volt_t > & GetSupplyVoltage ()
 Measured supply voltage to the Pigeon2. More...
 
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldX ()
 The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction. More...
 
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldY ()
 The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. More...
 
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldZ ()
 The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. More...
 
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldX ()
 The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction. More...
 
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldY ()
 The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. More...
 
StatusSignalValue< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldZ ()
 The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. More...
 
StatusSignalValue< bool > & GetFault_Hardware ()
 Hardware fault occurred. More...
 
StatusSignalValue< bool > & GetStickyFault_Hardware ()
 Hardware fault occurred. More...
 
StatusSignalValue< bool > & GetFault_Undervoltage ()
 Device supply voltage dropped to near brownout levels. More...
 
StatusSignalValue< bool > & GetStickyFault_Undervoltage ()
 Device supply voltage dropped to near brownout levels. More...
 
StatusSignalValue< bool > & GetFault_BootDuringEnable ()
 Device boot while detecting the enable signal. More...
 
StatusSignalValue< bool > & GetStickyFault_BootDuringEnable ()
 Device boot while detecting the enable signal. More...
 
StatusSignalValue< bool > & GetFault_BootupAccelerometer ()
 Bootup checks failed: Accelerometer. More...
 
StatusSignalValue< bool > & GetStickyFault_BootupAccelerometer ()
 Bootup checks failed: Accelerometer. More...
 
StatusSignalValue< bool > & GetFault_BootupGyroscope ()
 Bootup checks failed: Gyroscope. More...
 
StatusSignalValue< bool > & GetStickyFault_BootupGyroscope ()
 Bootup checks failed: Gyroscope. More...
 
StatusSignalValue< bool > & GetFault_BootupMagnetometer ()
 Bootup checks failed: Magnetometer. More...
 
StatusSignalValue< bool > & GetStickyFault_BootupMagnetometer ()
 Bootup checks failed: Magnetometer. More...
 
StatusSignalValue< bool > & GetFault_BootIntoMotion ()
 Motion Detected during bootup. More...
 
StatusSignalValue< bool > & GetStickyFault_BootIntoMotion ()
 Motion Detected during bootup. More...
 
StatusSignalValue< bool > & GetFault_DataAcquiredLate ()
 Motion stack data acquisition was slower than expected. More...
 
StatusSignalValue< bool > & GetStickyFault_DataAcquiredLate ()
 Motion stack data acquisition was slower than expected. More...
 
StatusSignalValue< bool > & GetFault_LoopTimeSlow ()
 Motion stack loop time was slower than expected. More...
 
StatusSignalValue< bool > & GetStickyFault_LoopTimeSlow ()
 Motion stack loop time was slower than expected. More...
 
StatusSignalValue< bool > & GetFault_SaturatedMagneter ()
 Magnetometer values are saturated. More...
 
StatusSignalValue< bool > & GetStickyFault_SaturatedMagneter ()
 Magnetometer values are saturated. More...
 
StatusSignalValue< bool > & GetFault_SaturatedAccelometer ()
 Accelerometer values are saturated. More...
 
StatusSignalValue< bool > & GetStickyFault_SaturatedAccelometer ()
 Accelerometer values are saturated. More...
 
StatusSignalValue< bool > & GetFault_SaturatedGyrosscope ()
 Gyroscope values are saturated. More...
 
StatusSignalValue< bool > & GetStickyFault_SaturatedGyrosscope ()
 Gyroscope values are saturated. More...
 
ctre::phoenix::StatusCode SetControl (controls::ControlRequest &request)
 Control motor with generic control request object. More...
 
ctre::phoenix::StatusCode SetControl (controls::ControlRequest &&request)
 Control motor with generic control request object. More...
 
ctre::phoenix::StatusCode SetYaw (units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
 The yaw to set the Pigeon2 to right now. More...
 
ctre::phoenix::StatusCode SetYaw (units::angle::degree_t newValue)
 The yaw to set the Pigeon2 to right now. More...
 
ctre::phoenix::StatusCode ClearStickyFaults (units::time::second_t timeoutSeconds)
 Clear the sticky faults in the device. More...
 
ctre::phoenix::StatusCode ClearStickyFaults ()
 Clear the sticky faults in the device. More...
 
- Public Member Functions inherited from ctre::phoenixpro::hardware::ParentDevice
 ParentDevice (int deviceID, std::string model, std::string canbus)
 
int GetDeviceID () const
 
const std::string & GetCANBus () const
 
std::shared_ptr< const controls::ControlRequestGetAppliedControl () const
 Get the latest applied control. More...
 
std::shared_ptr< controls::ControlRequestGetAppliedControl ()
 Get the latest applied control. More...
 

Additional Inherited Members

- Static Public Attributes inherited from ctre::phoenixpro::hardware::ParentDevice
static constexpr double kDefaultControlRatePeriodsSec = 0.010
 
- Protected Member Functions inherited from ctre::phoenixpro::hardware::ParentDevice
virtual void ReportIfTooOld ()=0
 
virtual ctre::phoenix::StatusCode SetControlPrivate (controls::ControlRequest &request)
 
template<typename T >
StatusSignalValue< T > & LookupStatusSignalValue (uint16_t spn, std::string signalName, bool reportOnConstruction)
 
template<typename T >
StatusSignalValue< T > & LookupStatusSignalValue (uint16_t spn, uint16_t mapper_iter, std::function< std::map< int, StatusSignalValue< T > >()> map_filler, std::string signalName, bool reportOnConstruction)
 
template<typename T , typename U >
StatusSignalValue< T > LookupDimensionlessStatusSignalValue (uint16_t spn, std::string signalName)
 Returns a unitless version of the StatusSignalValue by value. More...
 
void ReportIfTooOld (int minMajor, int minMinor, int minBugfix, int minBuild)
 
- Protected Attributes inherited from ctre::phoenixpro::hardware::ParentDevice
DeviceIdentifier deviceIdentifier
 

Detailed Description

Class description for the Pigeon 2 IMU sensor that measures orientation.

Constructor & Destructor Documentation

◆ CorePigeon2() [1/2]

ctre::phoenixpro::hardware::core::CorePigeon2::CorePigeon2 ( int  deviceId,
std::string  canbus = "" 
)

Constructs a new Pigeon 2 sensor object.

Parameters
deviceIdID of the device, as configured in Phoenix Tuner.
canbusName of the CAN bus this device is on. Possible CAN bus strings are:
  • "rio" for the native roboRIO CAN bus
  • CANivore name or serial number
  • SocketCAN interface (non-FRC Linux only)
  • "*" for any CANivore seen by the program
  • empty string (default) to select the default for the system:
    • "rio" on roboRIO
    • "can0" on Linux
    • "*" on Windows

◆ CorePigeon2() [2/2]

ctre::phoenixpro::hardware::core::CorePigeon2::CorePigeon2 ( CorePigeon2 const &  )
delete

Member Function Documentation

◆ ClearStickyFaults() [1/2]

ctre::phoenix::StatusCode ctre::phoenixpro::hardware::core::CorePigeon2::ClearStickyFaults ( )
inline

Clear the sticky faults in the device.

This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.

This will wait up to 0.050 seconds (50ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFaults() [2/2]

ctre::phoenix::StatusCode ctre::phoenixpro::hardware::core::CorePigeon2::ClearStickyFaults ( units::time::second_t  timeoutSeconds)
inline

Clear the sticky faults in the device.

This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.

Parameters
timeoutSecondsMaximum time to wait up to in seconds.
Returns
StatusCode of the set command

◆ GetAccelerationX()

StatusSignalValue< units::acceleration::standard_gravity_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAccelerationX ( )

The acceleration measured by Pigeon2 in the X direction.

This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.

Minimum Value: -2.0 Maximum Value: 1.99993896484375 Default Value: 0 Units: g

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AccelerationX Status Signal Value object

◆ GetAccelerationY()

StatusSignalValue< units::acceleration::standard_gravity_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAccelerationY ( )

The acceleration measured by Pigeon2 in the Y direction.

This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.

Minimum Value: -2.0 Maximum Value: 1.99993896484375 Default Value: 0 Units: g

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AccelerationY Status Signal Value object

◆ GetAccelerationZ()

StatusSignalValue< units::acceleration::standard_gravity_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAccelerationZ ( )

The acceleration measured by Pigeon2 in the Z direction.

This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.

Minimum Value: -2.0 Maximum Value: 1.99993896484375 Default Value: 0 Units: g

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AccelerationZ Status Signal Value object

◆ GetAccumGyroX()

StatusSignalValue< units::angle::degree_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAccumGyroX ( )

The accumulated gyro about the X axis without any sensor fusing.

Minimum Value: -23040.0 Maximum Value: 23039.9560546875 Default Value: 0 Units: deg

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AccumGyroX Status Signal Value object

◆ GetAccumGyroY()

StatusSignalValue< units::angle::degree_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAccumGyroY ( )

The accumulated gyro about the Y axis without any sensor fusing.

Minimum Value: -23040.0 Maximum Value: 23039.9560546875 Default Value: 0 Units: deg

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AccumGyroY Status Signal Value object

◆ GetAccumGyroZ()

StatusSignalValue< units::angle::degree_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAccumGyroZ ( )

The accumulated gyro about the Z axis without any sensor fusing.

Minimum Value: -23040.0 Maximum Value: 23039.9560546875 Default Value: 0 Units: deg

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AccumGyroZ Status Signal Value object

◆ GetAngularVelocityX()

StatusSignalValue< units::angular_velocity::degrees_per_second_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAngularVelocityX ( )

The angular velocity (ω) of the Pigeon 2 about the X axis.

Minimum Value: -1998.048780487805 Maximum Value: 1997.987804878049 Default Value: 0 Units: dps

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AngularVelocityX Status Signal Value object

◆ GetAngularVelocityY()

StatusSignalValue< units::angular_velocity::degrees_per_second_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAngularVelocityY ( )

The angular velocity (ω) of the Pigeon 2 about the Y axis.

Minimum Value: -1998.048780487805 Maximum Value: 1997.987804878049 Default Value: 0 Units: dps

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AngularVelocityY Status Signal Value object

◆ GetAngularVelocityZ()

StatusSignalValue< units::angular_velocity::degrees_per_second_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetAngularVelocityZ ( )

The angular velocity (ω) of the Pigeon 2 about the Z axis.

Minimum Value: -1998.048780487805 Maximum Value: 1997.987804878049 Default Value: 0 Units: dps

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
AngularVelocityZ Status Signal Value object

◆ GetConfigurator() [1/2]

configs::Pigeon2Configurator & ctre::phoenixpro::hardware::core::CorePigeon2::GetConfigurator ( )
inline

Gets the configurator for this Pigeon2.

Gets the configurator for this Pigeon2

Returns
Configurator for this Pigeon2

◆ GetConfigurator() [2/2]

configs::Pigeon2Configurator const & ctre::phoenixpro::hardware::core::CorePigeon2::GetConfigurator ( ) const
inline

Gets the configurator for this Pigeon2.

Gets the configurator for this Pigeon2

Returns
Configurator for this Pigeon2

◆ GetFault_BootDuringEnable()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_BootDuringEnable ( )

Device boot while detecting the enable signal.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_BootDuringEnable Status Signal Value object

◆ GetFault_BootIntoMotion()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_BootIntoMotion ( )

Motion Detected during bootup.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_BootIntoMotion Status Signal Value object

◆ GetFault_BootupAccelerometer()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_BootupAccelerometer ( )

Bootup checks failed: Accelerometer.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_BootupAccelerometer Status Signal Value object

◆ GetFault_BootupGyroscope()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_BootupGyroscope ( )

Bootup checks failed: Gyroscope.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_BootupGyroscope Status Signal Value object

◆ GetFault_BootupMagnetometer()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_BootupMagnetometer ( )

Bootup checks failed: Magnetometer.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_BootupMagnetometer Status Signal Value object

◆ GetFault_DataAcquiredLate()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_DataAcquiredLate ( )

Motion stack data acquisition was slower than expected.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_DataAcquiredLate Status Signal Value object

◆ GetFault_Hardware()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_Hardware ( )

Hardware fault occurred.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_Hardware Status Signal Value object

◆ GetFault_LoopTimeSlow()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_LoopTimeSlow ( )

Motion stack loop time was slower than expected.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_LoopTimeSlow Status Signal Value object

◆ GetFault_SaturatedAccelometer()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_SaturatedAccelometer ( )

Accelerometer values are saturated.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_SaturatedAccelometer Status Signal Value object

◆ GetFault_SaturatedGyrosscope()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_SaturatedGyrosscope ( )

Gyroscope values are saturated.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_SaturatedGyrosscope Status Signal Value object

◆ GetFault_SaturatedMagneter()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_SaturatedMagneter ( )

Magnetometer values are saturated.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_SaturatedMagneter Status Signal Value object

◆ GetFault_Undervoltage()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFault_Undervoltage ( )

Device supply voltage dropped to near brownout levels.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
Fault_Undervoltage Status Signal Value object

◆ GetFaultField()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetFaultField ( )

Integer representing all faults.

This returns the fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetFault_*() methods instead.

Minimum Value: 0 Maximum Value: 1048575 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
FaultField Status Signal Value object

◆ GetGravityVectorX()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetGravityVectorX ( )

The X component of the gravity vector.

This is the X component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes "Down" is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.

Minimum Value: -1.000030518509476 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
GravityVectorX Status Signal Value object

◆ GetGravityVectorY()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetGravityVectorY ( )

The Y component of the gravity vector.

This is the X component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes "Down" is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.

Minimum Value: -1.000030518509476 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
GravityVectorY Status Signal Value object

◆ GetGravityVectorZ()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetGravityVectorZ ( )

The Z component of the gravity vector.

This is the Z component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes "Down" is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.

Minimum Value: -1.000030518509476 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
GravityVectorZ Status Signal Value object

◆ GetMagneticFieldX()

StatusSignalValue< units::magnetic_field_strength::microtesla_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetMagneticFieldX ( )

The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.

This is only valid after performing a magnetometer calibration.

Minimum Value: -19660.8 Maximum Value: 19660.2 Default Value: 0 Units: uT

Default Rates: CAN: 5.0 Hz

Returns
MagneticFieldX Status Signal Value object

◆ GetMagneticFieldY()

StatusSignalValue< units::magnetic_field_strength::microtesla_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetMagneticFieldY ( )

The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.

This is only valid after performing a magnetometer calibration.

Minimum Value: -19660.8 Maximum Value: 19660.2 Default Value: 0 Units: uT

Default Rates: CAN: 5.0 Hz

Returns
MagneticFieldY Status Signal Value object

◆ GetMagneticFieldZ()

StatusSignalValue< units::magnetic_field_strength::microtesla_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetMagneticFieldZ ( )

The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.

This is only valid after performing a magnetometer calibration.

Minimum Value: -19660.8 Maximum Value: 19660.2 Default Value: 0 Units: uT

Default Rates: CAN: 5.0 Hz

Returns
MagneticFieldZ Status Signal Value object

◆ GetNoMotionCount()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetNoMotionCount ( )

The number of times a no-motion event occurred, wraps at 15.

Minimum Value: 0 Maximum Value: 15 Default Value: 0 Units:

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
NoMotionCount Status Signal Value object

◆ GetNoMotionEnabled()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetNoMotionEnabled ( )

Whether the no-motion calibration feature is enabled.

Default Value: 0

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
NoMotionEnabled Status Signal Value object

◆ GetPitch()

StatusSignalValue< units::angle::degree_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetPitch ( )

Current reported pitch of the Pigeon2.

Minimum Value: -90.0 Maximum Value: 89.9560546875 Default Value: 0 Units: deg

Default Rates: CAN: 100.0 Hz

Returns
Pitch Status Signal Value object

◆ GetQuatW()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetQuatW ( )

The W component of the reported Quaternion.

Minimum Value: -1.0001220852154804 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 50.0 Hz CAN FD: 100.0 Hz

Returns
QuatW Status Signal Value object

◆ GetQuatX()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetQuatX ( )

The X component of the reported Quaternion.

Minimum Value: -1.0001220852154804 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 50.0 Hz CAN FD: 100.0 Hz

Returns
QuatX Status Signal Value object

◆ GetQuatY()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetQuatY ( )

The Y component of the reported Quaternion.

Minimum Value: -1.0001220852154804 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 50.0 Hz CAN FD: 100.0 Hz

Returns
QuatY Status Signal Value object

◆ GetQuatZ()

StatusSignalValue< units::dimensionless::scalar_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetQuatZ ( )

The Z component of the reported Quaternion.

Minimum Value: -1.0001220852154804 Maximum Value: 1.0 Default Value: 0 Units:

Default Rates: CAN 2.0: 50.0 Hz CAN FD: 100.0 Hz

Returns
QuatZ Status Signal Value object

◆ GetRawMagneticFieldX()

StatusSignalValue< units::magnetic_field_strength::microtesla_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetRawMagneticFieldX ( )

The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.

This is only valid after performing a magnetometer calibration.

Minimum Value: -19660.8 Maximum Value: 19660.2 Default Value: 0 Units: uT

Default Rates: CAN: 5.0 Hz

Returns
RawMagneticFieldX Status Signal Value object

◆ GetRawMagneticFieldY()

StatusSignalValue< units::magnetic_field_strength::microtesla_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetRawMagneticFieldY ( )

The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.

This is only valid after performing a magnetometer calibration.

Minimum Value: -19660.8 Maximum Value: 19660.2 Default Value: 0 Units: uT

Default Rates: CAN: 5.0 Hz

Returns
RawMagneticFieldY Status Signal Value object

◆ GetRawMagneticFieldZ()

StatusSignalValue< units::magnetic_field_strength::microtesla_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetRawMagneticFieldZ ( )

The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.

This is only valid after performing a magnetometer calibration.

Minimum Value: -19660.8 Maximum Value: 19660.2 Default Value: 0 Units: uT

Default Rates: CAN: 5.0 Hz

Returns
RawMagneticFieldZ Status Signal Value object

◆ GetRoll()

StatusSignalValue< units::angle::degree_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetRoll ( )

Current reported roll of the Pigeon2.

Minimum Value: -180.0 Maximum Value: 179.9560546875 Default Value: 0 Units: deg

Default Rates: CAN: 100.0 Hz

Returns
Roll Status Signal Value object

◆ GetSimState()

sim::Pigeon2SimState & ctre::phoenixpro::hardware::core::CorePigeon2::GetSimState ( )
inline

Get the simulation state for this device.

This function reuses an allocated simulation state object, so it is safe to call this function multiple times in a robot loop.

Returns
Simulation state

◆ GetStickyFault_BootDuringEnable()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_BootDuringEnable ( )

Device boot while detecting the enable signal.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_BootDuringEnable Status Signal Value object

◆ GetStickyFault_BootIntoMotion()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_BootIntoMotion ( )

Motion Detected during bootup.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_BootIntoMotion Status Signal Value object

◆ GetStickyFault_BootupAccelerometer()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_BootupAccelerometer ( )

Bootup checks failed: Accelerometer.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_BootupAccelerometer Status Signal Value object

◆ GetStickyFault_BootupGyroscope()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_BootupGyroscope ( )

Bootup checks failed: Gyroscope.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_BootupGyroscope Status Signal Value object

◆ GetStickyFault_BootupMagnetometer()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_BootupMagnetometer ( )

Bootup checks failed: Magnetometer.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_BootupMagnetometer Status Signal Value object

◆ GetStickyFault_DataAcquiredLate()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_DataAcquiredLate ( )

Motion stack data acquisition was slower than expected.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_DataAcquiredLate Status Signal Value object

◆ GetStickyFault_Hardware()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_Hardware ( )

Hardware fault occurred.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_Hardware Status Signal Value object

◆ GetStickyFault_LoopTimeSlow()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_LoopTimeSlow ( )

Motion stack loop time was slower than expected.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_LoopTimeSlow Status Signal Value object

◆ GetStickyFault_SaturatedAccelometer()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_SaturatedAccelometer ( )

Accelerometer values are saturated.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_SaturatedAccelometer Status Signal Value object

◆ GetStickyFault_SaturatedGyrosscope()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_SaturatedGyrosscope ( )

Gyroscope values are saturated.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_SaturatedGyrosscope Status Signal Value object

◆ GetStickyFault_SaturatedMagneter()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_SaturatedMagneter ( )

Magnetometer values are saturated.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_SaturatedMagneter Status Signal Value object

◆ GetStickyFault_Undervoltage()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFault_Undervoltage ( )

Device supply voltage dropped to near brownout levels.

Default Value: False

Default Rates: CAN: 4.0 Hz

Returns
StickyFault_Undervoltage Status Signal Value object

◆ GetStickyFaultField()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetStickyFaultField ( )

Integer representing all sticky faults.

This returns the persistent "sticky" fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetStickyFault_*() methods instead.

Minimum Value: 0 Maximum Value: 1048575 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
StickyFaultField Status Signal Value object

◆ GetSupplyVoltage()

StatusSignalValue< units::voltage::volt_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetSupplyVoltage ( )

Measured supply voltage to the Pigeon2.

Minimum Value: 0.0 Maximum Value: 31.99951171875 Default Value: 0 Units: V

Default Rates: CAN: 10.0 Hz

Returns
SupplyVoltage Status Signal Value object

◆ GetTemperature()

StatusSignalValue< units::temperature::celsius_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetTemperature ( )

Temperature of the Pigeon 2.

Minimum Value: -128.0 Maximum Value: 127.99609375 Default Value: 0 Units: ℃

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
Temperature Status Signal Value object

◆ GetTemperatureCompensationDisabled()

StatusSignalValue< bool > & ctre::phoenixpro::hardware::core::CorePigeon2::GetTemperatureCompensationDisabled ( )

Whether the temperature-compensation feature is disabled.

Default Value: 0

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
TemperatureCompensationDisabled Status Signal Value object

◆ GetUpTime()

StatusSignalValue< units::time::second_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetUpTime ( )

How long the Pigeon 2's been up in seconds, caps at 255 seconds.

Minimum Value: 0 Maximum Value: 255 Default Value: 0 Units: s

Default Rates: CAN 2.0: 10.0 Hz CAN FD: 100.0 Hz

Returns
UpTime Status Signal Value object

◆ GetVersion()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetVersion ( )

Full Version.

The format is a four byte value.

Full Version of firmware in device. The format is a four byte value.

Minimum Value: 0 Maximum Value: 4294967295 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
Version Status Signal Value object

◆ GetVersionBugfix()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetVersionBugfix ( )

App Bugfix Version number.

Minimum Value: 0 Maximum Value: 255 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
VersionBugfix Status Signal Value object

◆ GetVersionBuild()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetVersionBuild ( )

App Build Version number.

Minimum Value: 0 Maximum Value: 255 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
VersionBuild Status Signal Value object

◆ GetVersionMajor()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetVersionMajor ( )

App Major Version number.

Minimum Value: 0 Maximum Value: 255 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
VersionMajor Status Signal Value object

◆ GetVersionMinor()

StatusSignalValue< int > & ctre::phoenixpro::hardware::core::CorePigeon2::GetVersionMinor ( )

App Minor Version number.

Minimum Value: 0 Maximum Value: 255 Default Value: 0 Units:

Default Rates: CAN: 4.0 Hz

Returns
VersionMinor Status Signal Value object

◆ GetYaw()

StatusSignalValue< units::angle::degree_t > & ctre::phoenixpro::hardware::core::CorePigeon2::GetYaw ( )

Current reported yaw of the Pigeon2.

Minimum Value: -368640.0 Maximum Value: 368639.99725341797 Default Value: 0 Units: deg

Default Rates: CAN: 100.0 Hz

Returns
Yaw Status Signal Value object

◆ HasResetOccurred()

bool ctre::phoenixpro::hardware::core::CorePigeon2::HasResetOccurred ( )
Returns
true if device has reset since the previous call of this routine.

◆ operator=()

CorePigeon2 & ctre::phoenixpro::hardware::core::CorePigeon2::operator= ( CorePigeon2 const &  )
delete

◆ SetControl() [1/2]

ctre::phoenix::StatusCode ctre::phoenixpro::hardware::core::CorePigeon2::SetControl ( controls::ControlRequest &&  request)
inline

Control motor with generic control request object.

User must make sure the specified object is castable to a valid control request, otherwise this function will fail at run-time and return the corresponding StatusCode

Parameters
requestControl object to request of the device
Returns
Status Code of the request, 0 is OK

◆ SetControl() [2/2]

ctre::phoenix::StatusCode ctre::phoenixpro::hardware::core::CorePigeon2::SetControl ( controls::ControlRequest request)
inline

Control motor with generic control request object.

User must make sure the specified object is castable to a valid control request, otherwise this function will fail at run-time and return the NotSupported StatusCode

Parameters
requestControl object to request of the device
Returns
Status Code of the request, 0 is OK

◆ SetYaw() [1/2]

ctre::phoenix::StatusCode ctre::phoenixpro::hardware::core::CorePigeon2::SetYaw ( units::angle::degree_t  newValue)
inline

The yaw to set the Pigeon2 to right now.

This will wait up to 0.050 seconds (50ms) by default.

Parameters
newValueValue to set to.
Returns
StatusCode of the set command

◆ SetYaw() [2/2]

ctre::phoenix::StatusCode ctre::phoenixpro::hardware::core::CorePigeon2::SetYaw ( units::angle::degree_t  newValue,
units::time::second_t  timeoutSeconds 
)
inline

The yaw to set the Pigeon2 to right now.

Parameters
newValueValue to set to.
timeoutSecondsMaximum time to wait up to in seconds.
Returns
StatusCode of the set command

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