CTRE Phoenix 6 C++ 24.3.0
|
Class description for the Pigeon 2 IMU sensor that measures orientation. More...
#include <ctre/phoenix6/Pigeon2.hpp>
Public Member Functions | |
Pigeon2 (int deviceId, std::string canbus="") | |
Constructs a new Pigeon 2 sensor object. More... | |
~Pigeon2 () | |
Pigeon2 (Pigeon2 &&)=default | |
Pigeon2 & | operator= (Pigeon2 &&)=default |
void | InitSendable (wpi::SendableBuilder &builder) override |
void | Reset () |
Resets the Pigeon 2 to a heading of zero. More... | |
double | GetAngle () const |
Returns the heading of the robot in degrees. More... | |
double | GetRate () const |
Returns the rate of rotation of the Pigeon 2. More... | |
frc::Rotation2d | GetRotation2d () const |
Returns the heading of the robot as a frc::Rotation2d. More... | |
frc::Rotation3d | GetRotation3d () const |
Returns the orientation of the robot as a frc::Rotation3d created from the quaternion signals. More... | |
Public Member Functions inherited from ctre::phoenix6::hardware::core::CorePigeon2 | |
CorePigeon2 (int deviceId, std::string canbus="") | |
Constructs a new Pigeon 2 sensor object. More... | |
CorePigeon2 (CorePigeon2 &&)=default | |
CorePigeon2 & | operator= (CorePigeon2 &&)=default |
configs::Pigeon2Configurator & | GetConfigurator () |
Gets the configurator for this Pigeon2. More... | |
configs::Pigeon2Configurator const & | GetConfigurator () const |
Gets the configurator for this Pigeon2. More... | |
sim::Pigeon2SimState & | GetSimState () |
Get the simulation state for this device. More... | |
StatusSignal< int > & | GetVersionMajor () |
App Major Version number. More... | |
StatusSignal< int > & | GetVersionMinor () |
App Minor Version number. More... | |
StatusSignal< int > & | GetVersionBugfix () |
App Bugfix Version number. More... | |
StatusSignal< int > & | GetVersionBuild () |
App Build Version number. More... | |
StatusSignal< int > & | GetVersion () |
Full Version. More... | |
StatusSignal< int > & | GetFaultField () |
Integer representing all faults. More... | |
StatusSignal< int > & | GetStickyFaultField () |
Integer representing all sticky faults. More... | |
StatusSignal< units::angle::degree_t > & | GetYaw () |
Current reported yaw of the Pigeon2. More... | |
StatusSignal< units::angle::degree_t > & | GetPitch () |
Current reported pitch of the Pigeon2. More... | |
StatusSignal< units::angle::degree_t > & | GetRoll () |
Current reported roll of the Pigeon2. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetQuatW () |
The W component of the reported Quaternion. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetQuatX () |
The X component of the reported Quaternion. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetQuatY () |
The Y component of the reported Quaternion. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetQuatZ () |
The Z component of the reported Quaternion. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetGravityVectorX () |
The X component of the gravity vector. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetGravityVectorY () |
The Y component of the gravity vector. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetGravityVectorZ () |
The Z component of the gravity vector. More... | |
StatusSignal< units::temperature::celsius_t > & | GetTemperature () |
Temperature of the Pigeon 2. More... | |
StatusSignal< bool > & | GetNoMotionEnabled () |
Whether the no-motion calibration feature is enabled. More... | |
StatusSignal< units::dimensionless::scalar_t > & | GetNoMotionCount () |
The number of times a no-motion event occurred, wraps at 15. More... | |
StatusSignal< bool > & | GetTemperatureCompensationDisabled () |
Whether the temperature-compensation feature is disabled. More... | |
StatusSignal< units::time::second_t > & | GetUpTime () |
How long the Pigeon 2's been up in seconds, caps at 255 seconds. More... | |
StatusSignal< units::angle::degree_t > & | GetAccumGyroX () |
The accumulated gyro about the X axis without any sensor fusing. More... | |
StatusSignal< units::angle::degree_t > & | GetAccumGyroY () |
The accumulated gyro about the Y axis without any sensor fusing. More... | |
StatusSignal< units::angle::degree_t > & | GetAccumGyroZ () |
The accumulated gyro about the Z axis without any sensor fusing. More... | |
StatusSignal< units::angular_velocity::degrees_per_second_t > & | GetAngularVelocityXWorld () |
Angular Velocity world X. More... | |
StatusSignal< units::angular_velocity::degrees_per_second_t > & | GetAngularVelocityYWorld () |
Angular Velocity Quaternion Y Component. More... | |
StatusSignal< units::angular_velocity::degrees_per_second_t > & | GetAngularVelocityZWorld () |
Angular Velocity Quaternion Z Component. More... | |
StatusSignal< units::acceleration::standard_gravity_t > & | GetAccelerationX () |
The acceleration measured by Pigeon2 in the X direction. More... | |
StatusSignal< units::acceleration::standard_gravity_t > & | GetAccelerationY () |
The acceleration measured by Pigeon2 in the Y direction. More... | |
StatusSignal< units::acceleration::standard_gravity_t > & | GetAccelerationZ () |
The acceleration measured by Pigeon2 in the Z direction. More... | |
StatusSignal< units::voltage::volt_t > & | GetSupplyVoltage () |
Measured supply voltage to the Pigeon2. More... | |
StatusSignal< units::angular_velocity::degrees_per_second_t > & | GetAngularVelocityXDevice () |
The angular velocity (ω) of the Pigeon 2 about the device's X axis. More... | |
StatusSignal< units::angular_velocity::degrees_per_second_t > & | GetAngularVelocityYDevice () |
The angular velocity (ω) of the Pigeon 2 about the device's Y axis. More... | |
StatusSignal< units::angular_velocity::degrees_per_second_t > & | GetAngularVelocityZDevice () |
The angular velocity (ω) of the Pigeon 2 about the device's Z axis. More... | |
StatusSignal< units::magnetic_field_strength::microtesla_t > & | GetMagneticFieldX () |
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction. More... | |
StatusSignal< units::magnetic_field_strength::microtesla_t > & | GetMagneticFieldY () |
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. More... | |
StatusSignal< units::magnetic_field_strength::microtesla_t > & | GetMagneticFieldZ () |
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. More... | |
StatusSignal< units::magnetic_field_strength::microtesla_t > & | GetRawMagneticFieldX () |
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction. More... | |
StatusSignal< units::magnetic_field_strength::microtesla_t > & | GetRawMagneticFieldY () |
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. More... | |
StatusSignal< units::magnetic_field_strength::microtesla_t > & | GetRawMagneticFieldZ () |
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. More... | |
StatusSignal< bool > & | GetIsProLicensed () |
Whether the device is Phoenix Pro licensed. More... | |
StatusSignal< bool > & | GetFault_Hardware () |
Hardware fault occurred. More... | |
StatusSignal< bool > & | GetStickyFault_Hardware () |
Hardware fault occurred. More... | |
StatusSignal< bool > & | GetFault_Undervoltage () |
Device supply voltage dropped to near brownout levels. More... | |
StatusSignal< bool > & | GetStickyFault_Undervoltage () |
Device supply voltage dropped to near brownout levels. More... | |
StatusSignal< bool > & | GetFault_BootDuringEnable () |
Device boot while detecting the enable signal. More... | |
StatusSignal< bool > & | GetStickyFault_BootDuringEnable () |
Device boot while detecting the enable signal. More... | |
StatusSignal< bool > & | GetFault_UnlicensedFeatureInUse () |
An unlicensed feature is in use, device may not behave as expected. More... | |
StatusSignal< bool > & | GetStickyFault_UnlicensedFeatureInUse () |
An unlicensed feature is in use, device may not behave as expected. More... | |
StatusSignal< bool > & | GetFault_BootupAccelerometer () |
Bootup checks failed: Accelerometer. More... | |
StatusSignal< bool > & | GetStickyFault_BootupAccelerometer () |
Bootup checks failed: Accelerometer. More... | |
StatusSignal< bool > & | GetFault_BootupGyroscope () |
Bootup checks failed: Gyroscope. More... | |
StatusSignal< bool > & | GetStickyFault_BootupGyroscope () |
Bootup checks failed: Gyroscope. More... | |
StatusSignal< bool > & | GetFault_BootupMagnetometer () |
Bootup checks failed: Magnetometer. More... | |
StatusSignal< bool > & | GetStickyFault_BootupMagnetometer () |
Bootup checks failed: Magnetometer. More... | |
StatusSignal< bool > & | GetFault_BootIntoMotion () |
Motion Detected during bootup. More... | |
StatusSignal< bool > & | GetStickyFault_BootIntoMotion () |
Motion Detected during bootup. More... | |
StatusSignal< bool > & | GetFault_DataAcquiredLate () |
Motion stack data acquisition was slower than expected. More... | |
StatusSignal< bool > & | GetStickyFault_DataAcquiredLate () |
Motion stack data acquisition was slower than expected. More... | |
StatusSignal< bool > & | GetFault_LoopTimeSlow () |
Motion stack loop time was slower than expected. More... | |
StatusSignal< bool > & | GetStickyFault_LoopTimeSlow () |
Motion stack loop time was slower than expected. More... | |
StatusSignal< bool > & | GetFault_SaturatedMagnetometer () |
Magnetometer values are saturated. More... | |
StatusSignal< bool > & | GetStickyFault_SaturatedMagnetometer () |
Magnetometer values are saturated. More... | |
StatusSignal< bool > & | GetFault_SaturatedAccelerometer () |
Accelerometer values are saturated. More... | |
StatusSignal< bool > & | GetStickyFault_SaturatedAccelerometer () |
Accelerometer values are saturated. More... | |
StatusSignal< bool > & | GetFault_SaturatedGyroscope () |
Gyroscope values are saturated. More... | |
StatusSignal< bool > & | GetStickyFault_SaturatedGyroscope () |
Gyroscope values are saturated. More... | |
ctre::phoenix::StatusCode | SetControl (controls::ControlRequest &request) |
Control motor with generic control request object. More... | |
ctre::phoenix::StatusCode | SetControl (controls::ControlRequest &&request) |
Control motor with generic control request object. More... | |
ctre::phoenix::StatusCode | SetYaw (units::angle::degree_t newValue, units::time::second_t timeoutSeconds) |
The yaw to set the Pigeon2 to right now. More... | |
ctre::phoenix::StatusCode | SetYaw (units::angle::degree_t newValue) |
The yaw to set the Pigeon2 to right now. More... | |
ctre::phoenix::StatusCode | ClearStickyFaults (units::time::second_t timeoutSeconds) |
Clear the sticky faults in the device. More... | |
ctre::phoenix::StatusCode | ClearStickyFaults () |
Clear the sticky faults in the device. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_Hardware (units::time::second_t timeoutSeconds) |
Clear sticky fault: Hardware fault occurred. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_Hardware () |
Clear sticky fault: Hardware fault occurred. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_Undervoltage (units::time::second_t timeoutSeconds) |
Clear sticky fault: Device supply voltage dropped to near brownout levels. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_Undervoltage () |
Clear sticky fault: Device supply voltage dropped to near brownout levels. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootDuringEnable (units::time::second_t timeoutSeconds) |
Clear sticky fault: Device boot while detecting the enable signal. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootDuringEnable () |
Clear sticky fault: Device boot while detecting the enable signal. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootupAccelerometer (units::time::second_t timeoutSeconds) |
Clear sticky fault: Bootup checks failed: Accelerometer. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootupAccelerometer () |
Clear sticky fault: Bootup checks failed: Accelerometer. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootupGyroscope (units::time::second_t timeoutSeconds) |
Clear sticky fault: Bootup checks failed: Gyroscope. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootupGyroscope () |
Clear sticky fault: Bootup checks failed: Gyroscope. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootupMagnetometer (units::time::second_t timeoutSeconds) |
Clear sticky fault: Bootup checks failed: Magnetometer. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootupMagnetometer () |
Clear sticky fault: Bootup checks failed: Magnetometer. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootIntoMotion (units::time::second_t timeoutSeconds) |
Clear sticky fault: Motion Detected during bootup. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_BootIntoMotion () |
Clear sticky fault: Motion Detected during bootup. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_DataAcquiredLate (units::time::second_t timeoutSeconds) |
Clear sticky fault: Motion stack data acquisition was slower than expected. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_DataAcquiredLate () |
Clear sticky fault: Motion stack data acquisition was slower than expected. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_LoopTimeSlow (units::time::second_t timeoutSeconds) |
Clear sticky fault: Motion stack loop time was slower than expected. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_LoopTimeSlow () |
Clear sticky fault: Motion stack loop time was slower than expected. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_SaturatedMagnetometer (units::time::second_t timeoutSeconds) |
Clear sticky fault: Magnetometer values are saturated. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_SaturatedMagnetometer () |
Clear sticky fault: Magnetometer values are saturated. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_SaturatedAccelerometer (units::time::second_t timeoutSeconds) |
Clear sticky fault: Accelerometer values are saturated. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_SaturatedAccelerometer () |
Clear sticky fault: Accelerometer values are saturated. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_SaturatedGyroscope (units::time::second_t timeoutSeconds) |
Clear sticky fault: Gyroscope values are saturated. More... | |
ctre::phoenix::StatusCode | ClearStickyFault_SaturatedGyroscope () |
Clear sticky fault: Gyroscope values are saturated. More... | |
Public Member Functions inherited from ctre::phoenix6::hardware::ParentDevice | |
ParentDevice (int deviceID, std::string model, std::string canbus) | |
virtual | ~ParentDevice ()=default |
ParentDevice (ParentDevice &&)=default | |
ParentDevice & | operator= (ParentDevice &&)=default |
int | GetDeviceID () const |
const std::string & | GetNetwork () const |
uint64_t | GetDeviceHash () const |
Gets a number unique for this device's hardware type and ID. More... | |
std::shared_ptr< const controls::ControlRequest > | GetAppliedControl () const |
Get the latest applied control. More... | |
std::shared_ptr< controls::ControlRequest > | GetAppliedControl () |
Get the latest applied control. More... | |
bool | HasResetOccurred () |
std::function< bool()> | GetResetOccurredChecker () const |
StatusSignal< double > & | GetGenericSignal (uint32_t signal) |
This is a reserved routine for internal testing. More... | |
ctre::phoenix::StatusCode | OptimizeBusUtilization (units::frequency::hertz_t optimizedFreqHz=0_Hz, units::time::second_t timeoutSeconds=50_ms) |
Optimizes the device's bus utilization by reducing the update frequencies of its status signals. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
Protected Member Functions inherited from ctre::phoenix6::hardware::ParentDevice | |
virtual ctre::phoenix::StatusCode | SetControlPrivate (controls::ControlRequest &request) |
template<typename T > | |
StatusSignal< T > & | LookupStatusSignal (uint16_t spn, std::string signalName, bool reportOnConstruction) |
template<typename T > | |
StatusSignal< T > & | LookupStatusSignal (uint16_t spn, uint16_t mapper_iter, std::function< std::map< int, StatusSignal< T > >()> map_filler, std::string signalName, bool reportOnConstruction) |
template<typename T , typename U > | |
StatusSignal< T > | LookupDimensionlessStatusSignal (uint16_t spn, std::string signalName) |
Returns a unitless version of the StatusSignal by value. More... | |
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. More... | |
Class description for the Pigeon 2 IMU sensor that measures orientation.
ctre::phoenix6::hardware::Pigeon2::Pigeon2 | ( | int | deviceId, |
std::string | canbus = "" |
||
) |
Constructs a new Pigeon 2 sensor object.
deviceId | ID of the device, as configured in Phoenix Tuner. |
canbus | Name of the CAN bus this device is on. Possible CAN bus strings are:
|
ctre::phoenix6::hardware::Pigeon2::~Pigeon2 | ( | ) |
|
default |
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.
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.
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.
frc::Rotation3d ctre::phoenix6::hardware::Pigeon2::GetRotation3d | ( | ) | const |
Returns the orientation of the robot as a frc::Rotation3d created from the quaternion signals.
|
override |
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.