Loading [MathJax]/extensions/tex2jax.js
CTRE Phoenix 6 C++ 25.4.0
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
ctre::phoenix6::hardware::core::CorePigeon2 Class Reference

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

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

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

Public Types

using Configuration = configs::Pigeon2Configuration
 

Public Member Functions

 CorePigeon2 (int deviceId, std::string canbus="")
 Constructs a new Pigeon 2 sensor object.
 
 CorePigeon2 (int deviceId, CANBus canbus)
 Constructs a new Pigeon 2 sensor object.
 
configs::Pigeon2ConfiguratorGetConfigurator ()
 Gets the configurator for this Pigeon2.
 
configs::Pigeon2Configurator const & GetConfigurator () const
 Gets the configurator for this Pigeon2.
 
sim::Pigeon2SimStateGetSimState ()
 Get the simulation state for this device.
 
StatusSignal< int > & GetVersionMajor (bool refresh=true)
 App Major Version number.
 
StatusSignal< int > & GetVersionMinor (bool refresh=true)
 App Minor Version number.
 
StatusSignal< int > & GetVersionBugfix (bool refresh=true)
 App Bugfix Version number.
 
StatusSignal< int > & GetVersionBuild (bool refresh=true)
 App Build Version number.
 
StatusSignal< int > & GetVersion (bool refresh=true)
 Full Version of firmware in device.
 
StatusSignal< int > & GetFaultField (bool refresh=true)
 Integer representing all fault flags reported by the device.
 
StatusSignal< int > & GetStickyFaultField (bool refresh=true)
 Integer representing all (persistent) sticky fault flags reported by the device.
 
StatusSignal< units::angle::degree_t > & GetYaw (bool refresh=true)
 Current reported yaw of the Pigeon2.
 
StatusSignal< units::angle::degree_t > & GetPitch (bool refresh=true)
 Current reported pitch of the Pigeon2.
 
StatusSignal< units::angle::degree_t > & GetRoll (bool refresh=true)
 Current reported roll of the Pigeon2.
 
StatusSignal< units::dimensionless::scalar_t > & GetQuatW (bool refresh=true)
 The W component of the reported Quaternion.
 
StatusSignal< units::dimensionless::scalar_t > & GetQuatX (bool refresh=true)
 The X component of the reported Quaternion.
 
StatusSignal< units::dimensionless::scalar_t > & GetQuatY (bool refresh=true)
 The Y component of the reported Quaternion.
 
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ (bool refresh=true)
 The Z component of the reported Quaternion.
 
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorX (bool refresh=true)
 The X component of the gravity vector.
 
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorY (bool refresh=true)
 The Y component of the gravity vector.
 
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorZ (bool refresh=true)
 The Z component of the gravity vector.
 
StatusSignal< units::temperature::celsius_t > & GetTemperature (bool refresh=true)
 Temperature of the Pigeon 2.
 
StatusSignal< bool > & GetNoMotionEnabled (bool refresh=true)
 Whether the no-motion calibration feature is enabled.
 
StatusSignal< units::dimensionless::scalar_t > & GetNoMotionCount (bool refresh=true)
 The number of times a no-motion event occurred, wraps at 15.
 
StatusSignal< bool > & GetTemperatureCompensationDisabled (bool refresh=true)
 Whether the temperature-compensation feature is disabled.
 
StatusSignal< units::time::second_t > & GetUpTime (bool refresh=true)
 How long the Pigeon 2's been up in seconds, caps at 255 seconds.
 
StatusSignal< units::angle::degree_t > & GetAccumGyroX (bool refresh=true)
 The accumulated gyro about the X axis without any sensor fusing.
 
StatusSignal< units::angle::degree_t > & GetAccumGyroY (bool refresh=true)
 The accumulated gyro about the Y axis without any sensor fusing.
 
StatusSignal< units::angle::degree_t > & GetAccumGyroZ (bool refresh=true)
 The accumulated gyro about the Z axis without any sensor fusing.
 
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityXWorld (bool refresh=true)
 The angular velocity (ω) of the Pigeon 2 about the X axis with respect to the world frame.
 
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityYWorld (bool refresh=true)
 The angular velocity (ω) of the Pigeon 2 about the Y axis with respect to the world frame.
 
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZWorld (bool refresh=true)
 The angular velocity (ω) of the Pigeon 2 about the Z axis with respect to the world frame.
 
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationX (bool refresh=true)
 The acceleration measured by Pigeon2 in the X direction.
 
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationY (bool refresh=true)
 The acceleration measured by Pigeon2 in the Y direction.
 
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationZ (bool refresh=true)
 The acceleration measured by Pigeon2 in the Z direction.
 
StatusSignal< units::voltage::volt_t > & GetSupplyVoltage (bool refresh=true)
 Measured supply voltage to the Pigeon2.
 
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityXDevice (bool refresh=true)
 The angular velocity (ω) of the Pigeon 2 about the device's X axis.
 
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityYDevice (bool refresh=true)
 The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
 
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZDevice (bool refresh=true)
 The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
 
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldX (bool refresh=true)
 The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
 
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldY (bool refresh=true)
 The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
 
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldZ (bool refresh=true)
 The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
 
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldX (bool refresh=true)
 The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
 
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldY (bool refresh=true)
 The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
 
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldZ (bool refresh=true)
 The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
 
StatusSignal< bool > & GetIsProLicensed (bool refresh=true)
 Whether the device is Phoenix Pro licensed.
 
StatusSignal< bool > & GetFault_Hardware (bool refresh=true)
 Hardware fault occurred.
 
StatusSignal< bool > & GetStickyFault_Hardware (bool refresh=true)
 Hardware fault occurred.
 
StatusSignal< bool > & GetFault_Undervoltage (bool refresh=true)
 Device supply voltage dropped to near brownout levels.
 
StatusSignal< bool > & GetStickyFault_Undervoltage (bool refresh=true)
 Device supply voltage dropped to near brownout levels.
 
StatusSignal< bool > & GetFault_BootDuringEnable (bool refresh=true)
 Device boot while detecting the enable signal.
 
StatusSignal< bool > & GetStickyFault_BootDuringEnable (bool refresh=true)
 Device boot while detecting the enable signal.
 
StatusSignal< bool > & GetFault_UnlicensedFeatureInUse (bool refresh=true)
 An unlicensed feature is in use, device may not behave as expected.
 
StatusSignal< bool > & GetStickyFault_UnlicensedFeatureInUse (bool refresh=true)
 An unlicensed feature is in use, device may not behave as expected.
 
StatusSignal< bool > & GetFault_BootupAccelerometer (bool refresh=true)
 Bootup checks failed: Accelerometer.
 
StatusSignal< bool > & GetStickyFault_BootupAccelerometer (bool refresh=true)
 Bootup checks failed: Accelerometer.
 
StatusSignal< bool > & GetFault_BootupGyroscope (bool refresh=true)
 Bootup checks failed: Gyroscope.
 
StatusSignal< bool > & GetStickyFault_BootupGyroscope (bool refresh=true)
 Bootup checks failed: Gyroscope.
 
StatusSignal< bool > & GetFault_BootupMagnetometer (bool refresh=true)
 Bootup checks failed: Magnetometer.
 
StatusSignal< bool > & GetStickyFault_BootupMagnetometer (bool refresh=true)
 Bootup checks failed: Magnetometer.
 
StatusSignal< bool > & GetFault_BootIntoMotion (bool refresh=true)
 Motion Detected during bootup.
 
StatusSignal< bool > & GetStickyFault_BootIntoMotion (bool refresh=true)
 Motion Detected during bootup.
 
StatusSignal< bool > & GetFault_DataAcquiredLate (bool refresh=true)
 Motion stack data acquisition was slower than expected.
 
StatusSignal< bool > & GetStickyFault_DataAcquiredLate (bool refresh=true)
 Motion stack data acquisition was slower than expected.
 
StatusSignal< bool > & GetFault_LoopTimeSlow (bool refresh=true)
 Motion stack loop time was slower than expected.
 
StatusSignal< bool > & GetStickyFault_LoopTimeSlow (bool refresh=true)
 Motion stack loop time was slower than expected.
 
StatusSignal< bool > & GetFault_SaturatedMagnetometer (bool refresh=true)
 Magnetometer values are saturated.
 
StatusSignal< bool > & GetStickyFault_SaturatedMagnetometer (bool refresh=true)
 Magnetometer values are saturated.
 
StatusSignal< bool > & GetFault_SaturatedAccelerometer (bool refresh=true)
 Accelerometer values are saturated.
 
StatusSignal< bool > & GetStickyFault_SaturatedAccelerometer (bool refresh=true)
 Accelerometer values are saturated.
 
StatusSignal< bool > & GetFault_SaturatedGyroscope (bool refresh=true)
 Gyroscope values are saturated.
 
StatusSignal< bool > & GetStickyFault_SaturatedGyroscope (bool refresh=true)
 Gyroscope values are saturated.
 
ctre::phoenix::StatusCode SetControl (const controls::ControlRequest &request)
 Control device with generic control request object.
 
ctre::phoenix::StatusCode SetYaw (units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
 The yaw to set the Pigeon2 to right now.
 
ctre::phoenix::StatusCode SetYaw (units::angle::degree_t newValue)
 The yaw to set the Pigeon2 to right now.
 
ctre::phoenix::StatusCode ClearStickyFaults (units::time::second_t timeoutSeconds)
 Clear the sticky faults in the device.
 
ctre::phoenix::StatusCode ClearStickyFaults ()
 Clear the sticky faults in the device.
 
ctre::phoenix::StatusCode ClearStickyFault_Hardware (units::time::second_t timeoutSeconds)
 Clear sticky fault: Hardware fault occurred.
 
ctre::phoenix::StatusCode ClearStickyFault_Hardware ()
 Clear sticky fault: Hardware fault occurred.
 
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage (units::time::second_t timeoutSeconds)
 Clear sticky fault: Device supply voltage dropped to near brownout levels.
 
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage ()
 Clear sticky fault: Device supply voltage dropped to near brownout levels.
 
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable (units::time::second_t timeoutSeconds)
 Clear sticky fault: Device boot while detecting the enable signal.
 
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable ()
 Clear sticky fault: Device boot while detecting the enable signal.
 
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse (units::time::second_t timeoutSeconds)
 Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
 
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse ()
 Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
 
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer (units::time::second_t timeoutSeconds)
 Clear sticky fault: Bootup checks failed: Accelerometer.
 
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer ()
 Clear sticky fault: Bootup checks failed: Accelerometer.
 
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope (units::time::second_t timeoutSeconds)
 Clear sticky fault: Bootup checks failed: Gyroscope.
 
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope ()
 Clear sticky fault: Bootup checks failed: Gyroscope.
 
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer (units::time::second_t timeoutSeconds)
 Clear sticky fault: Bootup checks failed: Magnetometer.
 
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer ()
 Clear sticky fault: Bootup checks failed: Magnetometer.
 
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion (units::time::second_t timeoutSeconds)
 Clear sticky fault: Motion Detected during bootup.
 
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion ()
 Clear sticky fault: Motion Detected during bootup.
 
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate (units::time::second_t timeoutSeconds)
 Clear sticky fault: Motion stack data acquisition was slower than expected.
 
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate ()
 Clear sticky fault: Motion stack data acquisition was slower than expected.
 
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow (units::time::second_t timeoutSeconds)
 Clear sticky fault: Motion stack loop time was slower than expected.
 
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow ()
 Clear sticky fault: Motion stack loop time was slower than expected.
 
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer (units::time::second_t timeoutSeconds)
 Clear sticky fault: Magnetometer values are saturated.
 
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer ()
 Clear sticky fault: Magnetometer values are saturated.
 
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer (units::time::second_t timeoutSeconds)
 Clear sticky fault: Accelerometer values are saturated.
 
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer ()
 Clear sticky fault: Accelerometer values are saturated.
 
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope (units::time::second_t timeoutSeconds)
 Clear sticky fault: Gyroscope values are saturated.
 
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope ()
 Clear sticky fault: Gyroscope values are saturated.
 
- Public Member Functions inherited from ctre::phoenix6::hardware::ParentDevice
 ParentDevice (int deviceID, std::string model, std::string canbus)
 
virtual ~ParentDevice ()=default
 
 ParentDevice (ParentDevice const &)=delete
 
ParentDeviceoperator= (ParentDevice const &)=delete
 
int GetDeviceID () const
 
const std::string & GetNetwork () const
 
uint64_t GetDeviceHash () const
 Gets a number unique for this device's hardware type and ID.
 
std::shared_ptr< const controls::ControlRequestGetAppliedControl () const
 Get the latest applied control.
 
std::shared_ptr< controls::ControlRequestGetAppliedControl ()
 Get the latest applied control.
 
bool HasResetOccurred ()
 
std::function< bool()> GetResetOccurredChecker () const
 
bool IsConnected (units::second_t maxLatencySeconds=500_ms)
 Returns whether the device is still connected to the robot.
 
StatusSignal< double > & GetGenericSignal (uint32_t signal, bool refresh=true)
 This is a reserved routine for internal testing.
 
ctre::phoenix::StatusCode OptimizeBusUtilization (units::frequency::hertz_t optimizedFreqHz=0_Hz, units::time::second_t timeoutSeconds=100_ms)
 Optimizes the device's bus utilization by reducing the update frequencies of its status signals.
 
ctre::phoenix::StatusCode ResetSignalFrequencies (units::time::second_t timeoutSeconds=100_ms)
 Resets the update frequencies of all the device's status signals to the defaults.
 

Additional Inherited Members

- Static Public Member Functions inherited from ctre::phoenix6::hardware::ParentDevice
template<typename... Devices, typename = std::enable_if_t<is_all_device_v<Devices...>>>
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll (Devices &... devices)
 Optimizes the bus utilization of the provided devices by reducing the update frequencies of their status signals.
 
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll (const std::vector< ParentDevice * > &devices)
 Optimizes the bus utilization of the provided devices by reducing the update frequencies of their status signals.
 
template<size_t N>
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll (const std::array< ParentDevice *, N > &devices)
 Optimizes the bus utilization of the provided devices by reducing the update frequencies of their status signals.
 
template<typename... Devices, typename = std::enable_if_t<is_all_device_v<Devices...>>>
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll (units::frequency::hertz_t optimizedFreqHz, Devices &... devices)
 Optimizes the bus utilization of the provided devices by reducing the update frequencies of their status signals.
 
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll (units::frequency::hertz_t optimizedFreqHz, const std::vector< ParentDevice * > &devices)
 Optimizes the bus utilization of the provided devices by reducing the update frequencies of their status signals.
 
template<size_t N>
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll (units::frequency::hertz_t optimizedFreqHz, const std::array< ParentDevice *, N > &devices)
 Optimizes the bus utilization of the provided devices by reducing the update frequencies of their status signals.
 
template<typename... Devices, typename = std::enable_if_t<is_all_device_v<Devices...>>>
static ctre::phoenix::StatusCode ResetSignalFrequenciesForAll (Devices &... devices)
 Resets the update frequencies of all the devices' status signals to the defaults.
 
static ctre::phoenix::StatusCode ResetSignalFrequenciesForAll (const std::vector< ParentDevice * > &devices)
 Resets the update frequencies of all the devices' status signals to the defaults.
 
template<size_t N>
static ctre::phoenix::StatusCode ResetSignalFrequenciesForAll (const std::array< ParentDevice *, N > &devices)
 Resets the update frequencies of all the devices' status signals to the defaults.
 
- Protected Member Functions inherited from ctre::phoenix6::hardware::ParentDevice
virtual ctre::phoenix::StatusCode SetControlPrivate (const controls::ControlRequest &request)
 
template<typename T >
StatusSignal< T > & LookupStatusSignal (uint16_t spn, std::string signalName, bool reportOnConstruction, bool refresh)
 
template<typename T >
StatusSignal< T > & LookupStatusSignal (uint16_t spn, std::function< std::map< uint16_t, std::string >()> mapFiller, std::string signalName, bool reportOnConstruction, bool refresh)
 
template<typename T , typename U >
StatusSignal< T > LookupDimensionlessStatusSignal (uint16_t spn, std::string signalName, bool refresh)
 Returns a unitless version of the StatusSignal by value.
 
- Protected Attributes inherited from ctre::phoenix6::hardware::ParentDevice
DeviceIdentifier deviceIdentifier
 
- Static Protected Attributes inherited from ctre::phoenix6::hardware::ParentDevice
static controls::EmptyControl _emptyControl {}
 
template<typename... Devices>
static constexpr bool is_all_device_v = is_all_device<Devices...>::value
 Whether all types passed in are subclasses of ParentDevice.
 

Detailed Description

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

Member Typedef Documentation

◆ Configuration

Constructor & Destructor Documentation

◆ CorePigeon2() [1/2]

ctre::phoenix6::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::phoenix6::hardware::core::CorePigeon2::CorePigeon2 ( int deviceId,
CANBus canbus )
inline

Constructs a new Pigeon 2 sensor object.

Parameters
deviceIdID of the device, as configured in Phoenix Tuner.
canbusThe CAN bus this device is on.

Member Function Documentation

◆ ClearStickyFault_BootDuringEnable() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootDuringEnable ( )
inline

Clear sticky fault: Device boot while detecting the enable signal.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_BootDuringEnable() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootDuringEnable ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Device boot while detecting the enable signal.

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

◆ ClearStickyFault_BootIntoMotion() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootIntoMotion ( )
inline

Clear sticky fault: Motion Detected during bootup.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_BootIntoMotion() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootIntoMotion ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Motion Detected during bootup.

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

◆ ClearStickyFault_BootupAccelerometer() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootupAccelerometer ( )
inline

Clear sticky fault: Bootup checks failed: Accelerometer.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_BootupAccelerometer() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootupAccelerometer ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Bootup checks failed: Accelerometer.

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

◆ ClearStickyFault_BootupGyroscope() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootupGyroscope ( )
inline

Clear sticky fault: Bootup checks failed: Gyroscope.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_BootupGyroscope() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootupGyroscope ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Bootup checks failed: Gyroscope.

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

◆ ClearStickyFault_BootupMagnetometer() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootupMagnetometer ( )
inline

Clear sticky fault: Bootup checks failed: Magnetometer.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_BootupMagnetometer() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_BootupMagnetometer ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Bootup checks failed: Magnetometer.

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

◆ ClearStickyFault_DataAcquiredLate() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_DataAcquiredLate ( )
inline

Clear sticky fault: Motion stack data acquisition was slower than expected.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_DataAcquiredLate() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_DataAcquiredLate ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Motion stack data acquisition was slower than expected.

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

◆ ClearStickyFault_Hardware() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_Hardware ( )
inline

Clear sticky fault: Hardware fault occurred.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_Hardware() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_Hardware ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Hardware fault occurred.

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

◆ ClearStickyFault_LoopTimeSlow() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_LoopTimeSlow ( )
inline

Clear sticky fault: Motion stack loop time was slower than expected.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_LoopTimeSlow() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_LoopTimeSlow ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Motion stack loop time was slower than expected.

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

◆ ClearStickyFault_SaturatedAccelerometer() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_SaturatedAccelerometer ( )
inline

Clear sticky fault: Accelerometer values are saturated.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_SaturatedAccelerometer() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_SaturatedAccelerometer ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Accelerometer values are saturated.

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

◆ ClearStickyFault_SaturatedGyroscope() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_SaturatedGyroscope ( )
inline

Clear sticky fault: Gyroscope values are saturated.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_SaturatedGyroscope() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_SaturatedGyroscope ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Gyroscope values are saturated.

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

◆ ClearStickyFault_SaturatedMagnetometer() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_SaturatedMagnetometer ( )
inline

Clear sticky fault: Magnetometer values are saturated.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_SaturatedMagnetometer() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_SaturatedMagnetometer ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Magnetometer values are saturated.

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

◆ ClearStickyFault_Undervoltage() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_Undervoltage ( )
inline

Clear sticky fault: Device supply voltage dropped to near brownout levels.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_Undervoltage() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_Undervoltage ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: Device supply voltage dropped to near brownout levels.

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

◆ ClearStickyFault_UnlicensedFeatureInUse() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_UnlicensedFeatureInUse ( )
inline

Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.

This will wait up to 0.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFault_UnlicensedFeatureInUse() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::hardware::core::CorePigeon2::ClearStickyFault_UnlicensedFeatureInUse ( units::time::second_t timeoutSeconds)
inline

Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.

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

◆ ClearStickyFaults() [1/2]

ctre::phoenix::StatusCode ctre::phoenix6::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.100 seconds (100ms) by default.

Returns
StatusCode of the set command

◆ ClearStickyFaults() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::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()

StatusSignal< units::acceleration::standard_gravity_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAccelerationX ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AccelerationX Status Signal Object

◆ GetAccelerationY()

StatusSignal< units::acceleration::standard_gravity_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAccelerationY ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AccelerationY Status Signal Object

◆ GetAccelerationZ()

StatusSignal< units::acceleration::standard_gravity_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAccelerationZ ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AccelerationZ Status Signal Object

◆ GetAccumGyroX()

StatusSignal< units::angle::degree_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAccumGyroX ( bool refresh = true)

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: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AccumGyroX Status Signal Object

◆ GetAccumGyroY()

StatusSignal< units::angle::degree_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAccumGyroY ( bool refresh = true)

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: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AccumGyroY Status Signal Object

◆ GetAccumGyroZ()

StatusSignal< units::angle::degree_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAccumGyroZ ( bool refresh = true)

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: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AccumGyroZ Status Signal Object

◆ GetAngularVelocityXDevice()

StatusSignal< units::angular_velocity::degrees_per_second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAngularVelocityXDevice ( bool refresh = true)

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

This value is not mount-calibrated.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AngularVelocityXDevice Status Signal Object

◆ GetAngularVelocityXWorld()

StatusSignal< units::angular_velocity::degrees_per_second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAngularVelocityXWorld ( bool refresh = true)

The angular velocity (ω) of the Pigeon 2 about the X axis with respect to the world frame.

This value is mount-calibrated.

  • Minimum Value: -2048.0
  • Maximum Value: 2047.99609375
  • Default Value: 0
  • Units: dps

Default Rates:

  • CAN 2.0: 10.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AngularVelocityXWorld Status Signal Object

◆ GetAngularVelocityYDevice()

StatusSignal< units::angular_velocity::degrees_per_second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAngularVelocityYDevice ( bool refresh = true)

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

This value is not mount-calibrated.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AngularVelocityYDevice Status Signal Object

◆ GetAngularVelocityYWorld()

StatusSignal< units::angular_velocity::degrees_per_second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAngularVelocityYWorld ( bool refresh = true)

The angular velocity (ω) of the Pigeon 2 about the Y axis with respect to the world frame.

This value is mount-calibrated.

  • Minimum Value: -2048.0
  • Maximum Value: 2047.99609375
  • Default Value: 0
  • Units: dps

Default Rates:

  • CAN 2.0: 10.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AngularVelocityYWorld Status Signal Object

◆ GetAngularVelocityZDevice()

StatusSignal< units::angular_velocity::degrees_per_second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAngularVelocityZDevice ( bool refresh = true)

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

This value is not mount-calibrated.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AngularVelocityZDevice Status Signal Object

◆ GetAngularVelocityZWorld()

StatusSignal< units::angular_velocity::degrees_per_second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetAngularVelocityZWorld ( bool refresh = true)

The angular velocity (ω) of the Pigeon 2 about the Z axis with respect to the world frame.

This value is mount-calibrated.

  • Minimum Value: -2048.0
  • Maximum Value: 2047.99609375
  • Default Value: 0
  • Units: dps

Default Rates:

  • CAN 2.0: 10.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
AngularVelocityZWorld Status Signal Object

◆ GetConfigurator() [1/2]

configs::Pigeon2Configurator & ctre::phoenix6::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::phoenix6::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()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_BootDuringEnable ( bool refresh = true)

Device boot while detecting the enable signal.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_BootDuringEnable Status Signal Object

◆ GetFault_BootIntoMotion()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_BootIntoMotion ( bool refresh = true)

Motion Detected during bootup.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_BootIntoMotion Status Signal Object

◆ GetFault_BootupAccelerometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_BootupAccelerometer ( bool refresh = true)

Bootup checks failed: Accelerometer.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_BootupAccelerometer Status Signal Object

◆ GetFault_BootupGyroscope()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_BootupGyroscope ( bool refresh = true)

Bootup checks failed: Gyroscope.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_BootupGyroscope Status Signal Object

◆ GetFault_BootupMagnetometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_BootupMagnetometer ( bool refresh = true)

Bootup checks failed: Magnetometer.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_BootupMagnetometer Status Signal Object

◆ GetFault_DataAcquiredLate()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_DataAcquiredLate ( bool refresh = true)

Motion stack data acquisition was slower than expected.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_DataAcquiredLate Status Signal Object

◆ GetFault_Hardware()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_Hardware ( bool refresh = true)

Hardware fault occurred.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_Hardware Status Signal Object

◆ GetFault_LoopTimeSlow()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_LoopTimeSlow ( bool refresh = true)

Motion stack loop time was slower than expected.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_LoopTimeSlow Status Signal Object

◆ GetFault_SaturatedAccelerometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_SaturatedAccelerometer ( bool refresh = true)

Accelerometer values are saturated.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_SaturatedAccelerometer Status Signal Object

◆ GetFault_SaturatedGyroscope()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_SaturatedGyroscope ( bool refresh = true)

Gyroscope values are saturated.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_SaturatedGyroscope Status Signal Object

◆ GetFault_SaturatedMagnetometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_SaturatedMagnetometer ( bool refresh = true)

Magnetometer values are saturated.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_SaturatedMagnetometer Status Signal Object

◆ GetFault_Undervoltage()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_Undervoltage ( bool refresh = true)

Device supply voltage dropped to near brownout levels.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_Undervoltage Status Signal Object

◆ GetFault_UnlicensedFeatureInUse()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetFault_UnlicensedFeatureInUse ( bool refresh = true)

An unlicensed feature is in use, device may not behave as expected.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Fault_UnlicensedFeatureInUse Status Signal Object

◆ GetFaultField()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetFaultField ( bool refresh = true)

Integer representing all 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: 4294967295
  • Default Value: 0
  • Units:

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
FaultField Status Signal Object

◆ GetGravityVectorX()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetGravityVectorX ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
GravityVectorX Status Signal Object

◆ GetGravityVectorY()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetGravityVectorY ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
GravityVectorY Status Signal Object

◆ GetGravityVectorZ()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetGravityVectorZ ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
GravityVectorZ Status Signal Object

◆ GetIsProLicensed()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetIsProLicensed ( bool refresh = true)

Whether the device is Phoenix Pro licensed.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
IsProLicensed Status Signal Object

◆ GetMagneticFieldX()

StatusSignal< units::magnetic_field_strength::microtesla_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetMagneticFieldX ( bool refresh = true)

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: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
MagneticFieldX Status Signal Object

◆ GetMagneticFieldY()

StatusSignal< units::magnetic_field_strength::microtesla_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetMagneticFieldY ( bool refresh = true)

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: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
MagneticFieldY Status Signal Object

◆ GetMagneticFieldZ()

StatusSignal< units::magnetic_field_strength::microtesla_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetMagneticFieldZ ( bool refresh = true)

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: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
MagneticFieldZ Status Signal Object

◆ GetNoMotionCount()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetNoMotionCount ( bool refresh = true)

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: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
NoMotionCount Status Signal Object

◆ GetNoMotionEnabled()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetNoMotionEnabled ( bool refresh = true)

Whether the no-motion calibration feature is enabled.

  • Default Value: 0

Default Rates:

  • CAN 2.0: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
NoMotionEnabled Status Signal Object

◆ GetPitch()

StatusSignal< units::angle::degree_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetPitch ( bool refresh = true)

Current reported pitch of the Pigeon2.

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

Default Rates:

  • CAN 2.0: 100.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Pitch Status Signal Object

◆ GetQuatW()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetQuatW ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
QuatW Status Signal Object

◆ GetQuatX()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetQuatX ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
QuatX Status Signal Object

◆ GetQuatY()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetQuatY ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
QuatY Status Signal Object

◆ GetQuatZ()

StatusSignal< units::dimensionless::scalar_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetQuatZ ( bool refresh = true)

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 (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
QuatZ Status Signal Object

◆ GetRawMagneticFieldX()

StatusSignal< units::magnetic_field_strength::microtesla_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetRawMagneticFieldX ( bool refresh = true)

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: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
RawMagneticFieldX Status Signal Object

◆ GetRawMagneticFieldY()

StatusSignal< units::magnetic_field_strength::microtesla_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetRawMagneticFieldY ( bool refresh = true)

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: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
RawMagneticFieldY Status Signal Object

◆ GetRawMagneticFieldZ()

StatusSignal< units::magnetic_field_strength::microtesla_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetRawMagneticFieldZ ( bool refresh = true)

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: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
RawMagneticFieldZ Status Signal Object

◆ GetRoll()

StatusSignal< units::angle::degree_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetRoll ( bool refresh = true)

Current reported roll of the Pigeon2.

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

Default Rates:

  • CAN 2.0: 100.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Roll Status Signal Object

◆ GetSimState()

sim::Pigeon2SimState & ctre::phoenix6::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()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_BootDuringEnable ( bool refresh = true)

Device boot while detecting the enable signal.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_BootDuringEnable Status Signal Object

◆ GetStickyFault_BootIntoMotion()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_BootIntoMotion ( bool refresh = true)

Motion Detected during bootup.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_BootIntoMotion Status Signal Object

◆ GetStickyFault_BootupAccelerometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_BootupAccelerometer ( bool refresh = true)

Bootup checks failed: Accelerometer.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_BootupAccelerometer Status Signal Object

◆ GetStickyFault_BootupGyroscope()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_BootupGyroscope ( bool refresh = true)

Bootup checks failed: Gyroscope.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_BootupGyroscope Status Signal Object

◆ GetStickyFault_BootupMagnetometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_BootupMagnetometer ( bool refresh = true)

Bootup checks failed: Magnetometer.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_BootupMagnetometer Status Signal Object

◆ GetStickyFault_DataAcquiredLate()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_DataAcquiredLate ( bool refresh = true)

Motion stack data acquisition was slower than expected.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_DataAcquiredLate Status Signal Object

◆ GetStickyFault_Hardware()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_Hardware ( bool refresh = true)

Hardware fault occurred.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_Hardware Status Signal Object

◆ GetStickyFault_LoopTimeSlow()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_LoopTimeSlow ( bool refresh = true)

Motion stack loop time was slower than expected.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_LoopTimeSlow Status Signal Object

◆ GetStickyFault_SaturatedAccelerometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_SaturatedAccelerometer ( bool refresh = true)

Accelerometer values are saturated.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_SaturatedAccelerometer Status Signal Object

◆ GetStickyFault_SaturatedGyroscope()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_SaturatedGyroscope ( bool refresh = true)

Gyroscope values are saturated.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_SaturatedGyroscope Status Signal Object

◆ GetStickyFault_SaturatedMagnetometer()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_SaturatedMagnetometer ( bool refresh = true)

Magnetometer values are saturated.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_SaturatedMagnetometer Status Signal Object

◆ GetStickyFault_Undervoltage()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_Undervoltage ( bool refresh = true)

Device supply voltage dropped to near brownout levels.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_Undervoltage Status Signal Object

◆ GetStickyFault_UnlicensedFeatureInUse()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFault_UnlicensedFeatureInUse ( bool refresh = true)

An unlicensed feature is in use, device may not behave as expected.

  • Default Value: False

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFault_UnlicensedFeatureInUse Status Signal Object

◆ GetStickyFaultField()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetStickyFaultField ( bool refresh = true)

Integer representing all (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: 4294967295
  • Default Value: 0
  • Units:

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
StickyFaultField Status Signal Object

◆ GetSupplyVoltage()

StatusSignal< units::voltage::volt_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetSupplyVoltage ( bool refresh = true)

Measured supply voltage to the Pigeon2.

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

Default Rates:

  • CAN 2.0: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
SupplyVoltage Status Signal Object

◆ GetTemperature()

StatusSignal< units::temperature::celsius_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetTemperature ( bool refresh = true)

Temperature of the Pigeon 2.

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

Default Rates:

  • CAN 2.0: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Temperature Status Signal Object

◆ GetTemperatureCompensationDisabled()

StatusSignal< bool > & ctre::phoenix6::hardware::core::CorePigeon2::GetTemperatureCompensationDisabled ( bool refresh = true)

Whether the temperature-compensation feature is disabled.

  • Default Value: 0

Default Rates:

  • CAN 2.0: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
TemperatureCompensationDisabled Status Signal Object

◆ GetUpTime()

StatusSignal< units::time::second_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetUpTime ( bool refresh = true)

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: 4.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
UpTime Status Signal Object

◆ GetVersion()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetVersion ( bool refresh = true)

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

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Version Status Signal Object

◆ GetVersionBugfix()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetVersionBugfix ( bool refresh = true)

App Bugfix Version number.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
VersionBugfix Status Signal Object

◆ GetVersionBuild()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetVersionBuild ( bool refresh = true)

App Build Version number.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
VersionBuild Status Signal Object

◆ GetVersionMajor()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetVersionMajor ( bool refresh = true)

App Major Version number.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
VersionMajor Status Signal Object

◆ GetVersionMinor()

StatusSignal< int > & ctre::phoenix6::hardware::core::CorePigeon2::GetVersionMinor ( bool refresh = true)

App Minor Version number.

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

Default Rates:

  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
VersionMinor Status Signal Object

◆ GetYaw()

StatusSignal< units::angle::degree_t > & ctre::phoenix6::hardware::core::CorePigeon2::GetYaw ( bool refresh = true)

Current reported yaw of the Pigeon2.

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

Default Rates:

  • CAN 2.0: 100.0 Hz
  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Parameters
refreshWhether to refresh the StatusSignal before returning it; defaults to true
Returns
Yaw Status Signal Object

◆ SetControl()

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

Control device 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::phoenix6::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.100 seconds (100ms) by default.

Parameters
newValueValue to set to. Units are in deg.
Returns
StatusCode of the set command

◆ SetYaw() [2/2]

ctre::phoenix::StatusCode ctre::phoenix6::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. Units are in deg.
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: