CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
ctre::phoenix6::hardware::Pigeon2 Class Reference

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

#include <ctre/phoenix6/Pigeon2.hpp>

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

Public Member Functions

 Pigeon2 (int deviceId, std::string canbus="")
 Constructs a new Pigeon 2 sensor object.
 
 Pigeon2 (int deviceId, CANBus canbus)
 Constructs a new Pigeon 2 sensor object.
 
 ~Pigeon2 ()
 
void InitSendable (wpi::SendableBuilder &builder) override
 
void Reset ()
 Resets the Pigeon 2 to a heading of zero.
 
double GetAngle () const
 Returns the heading of the robot in degrees.
 
double GetRate () const
 Returns the rate of rotation of the Pigeon 2.
 
frc::Rotation2d GetRotation2d () const
 Returns the heading of the robot as a frc::Rotation2d.
 
frc::Rotation3d GetRotation3d () const
 Returns the orientation of the robot as a frc::Rotation3d created from the quaternion signals.
 
- Public Member Functions inherited from ctre::phoenix6::hardware::core::CorePigeon2
 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 constGetConfigurator () 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< TLookupDimensionlessStatusSignal (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.

Constructor & Destructor Documentation

◆ Pigeon2() [1/2]

ctre::phoenix6::hardware::Pigeon2::Pigeon2 ( 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

◆ Pigeon2() [2/2]

ctre::phoenix6::hardware::Pigeon2::Pigeon2 ( 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.

◆ ~Pigeon2()

ctre::phoenix6::hardware::Pigeon2::~Pigeon2 ( )

Member Function Documentation

◆ GetAngle()

double ctre::phoenix6::hardware::Pigeon2::GetAngle ( ) const

Returns the heading of the robot in degrees.

The angle increases as the Pigeon 2 turns clockwise when looked at from the top. This follows the NED axis convention.

The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

Deprecated
This API is deprecated for removal in the 2026 season. Users should use GetYaw instead. Note that Yaw is CCW+, whereas this API is CW+.
Returns
The current heading of the robot in degrees

◆ GetRate()

double ctre::phoenix6::hardware::Pigeon2::GetRate ( ) const

Returns the rate of rotation of the Pigeon 2.

The rate is positive as the Pigeon 2 turns clockwise when looked at from the top.

Deprecated
This API is deprecated for removal in the 2026 season. Users should use GetAngularVelocityZWorld instead. Note that AngularVelocityZWorld is CCW+, whereas this API is CW+.
Returns
The current rate in degrees per second

◆ GetRotation2d()

frc::Rotation2d ctre::phoenix6::hardware::Pigeon2::GetRotation2d ( ) const

Returns the heading of the robot as a frc::Rotation2d.

The angle increases as the Pigeon 2 turns counterclockwise when looked at from the top. This follows the NWU axis convention.

The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

Returns
The current heading of the robot as a frc::Rotation2d

◆ GetRotation3d()

frc::Rotation3d ctre::phoenix6::hardware::Pigeon2::GetRotation3d ( ) const

Returns the orientation of the robot as a frc::Rotation3d created from the quaternion signals.

Returns
The current orientation of the robot as a frc::Rotation3d

◆ InitSendable()

void ctre::phoenix6::hardware::Pigeon2::InitSendable ( wpi::SendableBuilder & builder)
override

◆ Reset()

void ctre::phoenix6::hardware::Pigeon2::Reset ( )

Resets the Pigeon 2 to a heading of zero.

This can be used if there is significant drift in the gyro, and it needs to be recalibrated after it has been running.


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