14#include <units/acceleration.h>
15#include <units/angle.h>
16#include <units/angular_velocity.h>
17#include <units/dimensionless.h>
18#include <units/magnetic_field_strength.h>
19#include <units/temperature.h>
20#include <units/time.h>
21#include <units/voltage.h>
149 std::stringstream ss;
161 std::stringstream ss;
171 ctre::phoenix::StatusCode
Deserialize(
const std::string& to_deserialize)
456 ctre::phoenix::StatusCode
SetYaw(units::angle::degree_t newValue)
473 ctre::phoenix::StatusCode
SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
475 std::stringstream ss;
520 std::stringstream ss;
557 std::stringstream ss;
596 std::stringstream ss;
635 std::stringstream ss;
672 std::stringstream ss;
709 std::stringstream ss;
746 std::stringstream ss;
783 std::stringstream ss;
822 std::stringstream ss;
861 std::stringstream ss;
898 std::stringstream ss;
935 std::stringstream ss;
972 std::stringstream ss;
1039 std::unique_ptr<sim::Pigeon2SimState> _simState{};
1052 if (_simState ==
nullptr)
1053 _simState = std::make_unique<sim::Pigeon2SimState>(*
this);
2278 ctre::phoenix::StatusCode
SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
2290 ctre::phoenix::StatusCode
SetYaw(units::angle::degree_t newValue)
2292 return SetYaw(newValue, 0.050_s);
ii that the Software will be uninterrupted or error free
Definition: CTRE_LICENSE.txt:226
CTREXPORT int c_ctre_phoenix6_serialize_double(int spn, double value, char **str)
@ OK
No Error.
Definition: StatusCodes.h:1196
@ NotSupported
This is not supported.
Definition: StatusCodes.h:1809
Configs to trim the Pigeon2's gyroscope.
Definition: Configs.hpp:308
std::string Serialize() const override
Definition: Configs.hpp:410
std::string ToString() const override
Definition: Configs.hpp:398
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition: Configs.hpp:420
Configs for Pigeon 2's Mount Pose configuration.
Definition: Configs.hpp:174
std::string ToString() const override
Definition: Configs.hpp:264
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition: Configs.hpp:286
std::string Serialize() const override
Definition: Configs.hpp:276
Definition: Configs.hpp:28
Definition: Configurator.hpp:22
ctre::phoenix::StatusCode SetConfigsPrivate(const std::string &serializedString, units::time::second_t timeoutSeconds, bool futureProofConfigs, bool overrideIfDuplicate)
Definition: Configurator.hpp:42
ctre::phoenix::StatusCode GetConfigsPrivate(std::string &serializedString, units::time::second_t timeoutSeconds) const
Definition: Configurator.hpp:65
units::time::second_t DefaultTimeoutSeconds
The default amount of time to wait for a config.
Definition: Configurator.hpp:27
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:40
Pigeon2Configuration & WithMountPose(MountPoseConfigs newMountPose)
Modifies this configuration's MountPose parameter and returns itself for method-chaining and easier t...
Definition: CorePigeon2.hpp:99
Pigeon2FeaturesConfigs Pigeon2Features
Configs to enable/disable various features of the Pigeon2.
Definition: CorePigeon2.hpp:84
Pigeon2Configuration & WithPigeon2Features(Pigeon2FeaturesConfigs newPigeon2Features)
Modifies this configuration's Pigeon2Features parameter and returns itself for method-chaining and ea...
Definition: CorePigeon2.hpp:138
GyroTrimConfigs GyroTrim
Configs to trim the Pigeon2's gyroscope.
Definition: CorePigeon2.hpp:76
std::string ToString() const
Get the string representation of this configuration.
Definition: CorePigeon2.hpp:147
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize)
Take a string and deserialize it to this configuration.
Definition: CorePigeon2.hpp:171
bool FutureProofConfigs
True if we should factory default newer unsupported configs, false to leave newer unsupported configs...
Definition: CorePigeon2.hpp:55
Pigeon2Configuration & WithGyroTrim(GyroTrimConfigs newGyroTrim)
Modifies this configuration's GyroTrim parameter and returns itself for method-chaining and easier to...
Definition: CorePigeon2.hpp:120
MountPoseConfigs MountPose
Configs for Pigeon 2's Mount Pose configuration.
Definition: CorePigeon2.hpp:65
std::string Serialize() const
Get the serialized form of this configuration.
Definition: CorePigeon2.hpp:159
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:187
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:616
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:404
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:302
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:917
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:842
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:728
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:970
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:255
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:933
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:473
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:707
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:781
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:555
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:391
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:456
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:594
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:436
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:820
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:577
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:744
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:765
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:241
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:271
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:422
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:376
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:880
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:654
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:518
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:344
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:896
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:284
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:331
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:954
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:633
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:670
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:691
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:223
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:859
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:498
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:316
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs) const
Refreshes the values of the specified config group.
Definition: CorePigeon2.hpp:209
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:803
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs)
Applies the contents of the specified config to the device.
Definition: CorePigeon2.hpp:362
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:539
Configs to enable/disable various features of the Pigeon2.
Definition: Configs.hpp:439
std::string ToString() const override
Definition: Configs.hpp:516
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition: Configs.hpp:538
std::string Serialize() const override
Definition: Configs.hpp:528
Abstract Control Request class that other control requests extend for use.
Definition: ControlRequest.hpp:28
Definition: DeviceIdentifier.hpp:19
Parent class for all devices.
Definition: ParentDevice.hpp:29
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:988
StatusSignal< bool > & GetFault_BootIntoMotion()
Motion Detected during bootup.
StatusSignal< int > & GetVersionMinor()
App Minor Version number.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityXWorld()
Angular Velocity world X.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:2366
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:2445
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldZ()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
StatusSignal< units::angle::degree_t > & GetPitch()
Current reported pitch of the Pigeon2.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:2412
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:2490
StatusSignal< int > & GetVersion()
Full Version.
StatusSignal< units::angle::degree_t > & GetAccumGyroX()
The accumulated gyro about the X axis without any sensor fusing.
StatusSignal< units::dimensionless::scalar_t > & GetNoMotionCount()
The number of times a no-motion event occurred, wraps at 15.
StatusSignal< units::angle::degree_t > & GetRoll()
Current reported roll of the Pigeon2.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldY()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
StatusSignal< bool > & GetStickyFault_SaturatedAccelerometer()
Accelerometer values are saturated.
StatusSignal< int > & GetVersionBugfix()
App Bugfix Version number.
StatusSignal< bool > & GetStickyFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected.
StatusSignal< bool > & GetFault_SaturatedAccelerometer()
Accelerometer values are saturated.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:2320
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:2514
StatusSignal< bool > & GetStickyFault_Hardware()
Hardware fault occurred.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldY()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction.
StatusSignal< bool > & GetFault_BootupMagnetometer()
Bootup checks failed: Magnetometer.
StatusSignal< units::temperature::celsius_t > & GetTemperature()
Temperature of the Pigeon 2.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition: CorePigeon2.hpp:2502
StatusSignal< bool > & GetStickyFault_BootDuringEnable()
Device boot while detecting the enable signal.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldX()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
ctre::phoenix::StatusCode SetControl(controls::ControlRequest &request)
Control motor with generic control request object.
Definition: CorePigeon2.hpp:2249
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:2570
StatusSignal< units::dimensionless::scalar_t > & GetQuatX()
The X component of the reported Quaternion.
StatusSignal< units::angle::degree_t > & GetAccumGyroZ()
The accumulated gyro about the Z axis without any sensor fusing.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorX()
The X component of the gravity vector.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:2592
StatusSignal< bool > & GetStickyFault_LoopTimeSlow()
Motion stack loop time was slower than expected.
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition: CorePigeon2.hpp:1020
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:2342
StatusSignal< bool > & GetFault_UnlicensedFeatureInUse()
An unlicensed feature is in use, device may not behave as expected.
StatusSignal< bool > & GetStickyFault_UnlicensedFeatureInUse()
An unlicensed feature is in use, device may not behave as expected.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue, units::time::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:2278
configs::Pigeon2Configurator const & GetConfigurator() const
Gets the configurator for this Pigeon2.
Definition: CorePigeon2.hpp:1032
StatusSignal< int > & GetVersionMajor()
App Major Version number.
StatusSignal< units::time::second_t > & GetUpTime()
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorZ()
The Z component of the gravity vector.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition: CorePigeon2.hpp:2581
StatusSignal< units::voltage::volt_t > & GetSupplyVoltage()
Measured supply voltage to the Pigeon2.
StatusSignal< units::dimensionless::scalar_t > & GetQuatW()
The W component of the reported Quaternion.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationY()
The acceleration measured by Pigeon2 in the Y direction.
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition: CorePigeon2.hpp:2305
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:2537
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:2434
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetMagneticFieldX()
The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY()
The Y component of the reported Quaternion.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:2478
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityYWorld()
Angular Velocity Quaternion Y Component.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition: CorePigeon2.hpp:2548
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZDevice()
The angular velocity (ω) of the Pigeon 2 about the device's Z axis.
StatusSignal< bool > & GetStickyFault_BootupMagnetometer()
Bootup checks failed: Magnetometer.
StatusSignal< bool > & GetFault_BootDuringEnable()
Device boot while detecting the enable signal.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:2378
StatusSignal< int > & GetFaultField()
Integer representing all faults.
StatusSignal< bool > & GetIsProLicensed()
Whether the device is Phoenix Pro licensed.
StatusSignal< bool > & GetStickyFault_BootupGyroscope()
Bootup checks failed: Gyroscope.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition: CorePigeon2.hpp:2526
ctre::phoenix::StatusCode SetControl(controls::ControlRequest &&request)
Control motor with generic control request object.
Definition: CorePigeon2.hpp:2265
StatusSignal< bool > & GetFault_SaturatedGyroscope()
Gyroscope values are saturated.
StatusSignal< bool > & GetFault_Undervoltage()
Device supply voltage dropped to near brownout levels.
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ()
The Z component of the reported Quaternion.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZWorld()
Angular Velocity Quaternion Z Component.
StatusSignal< bool > & GetFault_DataAcquiredLate()
Motion stack data acquisition was slower than expected.
StatusSignal< int > & GetStickyFaultField()
Integer representing all sticky faults.
StatusSignal< bool > & GetStickyFault_BootIntoMotion()
Motion Detected during bootup.
StatusSignal< bool > & GetStickyFault_SaturatedMagnetometer()
Magnetometer values are saturated.
CorePigeon2(CorePigeon2 &&)=default
StatusSignal< bool > & GetStickyFault_Undervoltage()
Device supply voltage dropped to near brownout levels.
StatusSignal< bool > & GetFault_BootupAccelerometer()
Bootup checks failed: Accelerometer.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition: CorePigeon2.hpp:2354
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition: CorePigeon2.hpp:2423
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition: CorePigeon2.hpp:2467
CorePigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
StatusSignal< bool > & GetFault_SaturatedMagnetometer()
Magnetometer values are saturated.
StatusSignal< bool > & GetNoMotionEnabled()
Whether the no-motion calibration feature is enabled.
StatusSignal< units::magnetic_field_strength::microtesla_t > & GetRawMagneticFieldZ()
The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction.
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition: CorePigeon2.hpp:2331
StatusSignal< bool > & GetTemperatureCompensationDisabled()
Whether the temperature-compensation feature is disabled.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityYDevice()
The angular velocity (ω) of the Pigeon 2 about the device's Y axis.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition: CorePigeon2.hpp:2290
StatusSignal< bool > & GetFault_BootupGyroscope()
Bootup checks failed: Gyroscope.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorY()
The Y component of the gravity vector.
StatusSignal< bool > & GetFault_Hardware()
Hardware fault occurred.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition: CorePigeon2.hpp:2390
StatusSignal< bool > & GetStickyFault_SaturatedGyroscope()
Gyroscope values are saturated.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationZ()
The acceleration measured by Pigeon2 in the Z direction.
CorePigeon2 & operator=(CorePigeon2 &&)=default
StatusSignal< int > & GetVersionBuild()
App Build Version number.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition: CorePigeon2.hpp:2401
StatusSignal< bool > & GetFault_LoopTimeSlow()
Motion stack loop time was slower than expected.
StatusSignal< bool > & GetStickyFault_BootupAccelerometer()
Bootup checks failed: Accelerometer.
StatusSignal< units::angle::degree_t > & GetAccumGyroY()
The accumulated gyro about the Y axis without any sensor fusing.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition: CorePigeon2.hpp:2559
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition: CorePigeon2.hpp:2456
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationX()
The acceleration measured by Pigeon2 in the X direction.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityXDevice()
The angular velocity (ω) of the Pigeon 2 about the device's X axis.
sim::Pigeon2SimState & GetSimState()
Get the simulation state for this device.
Definition: CorePigeon2.hpp:1050
Class to control the state of a simulated hardware::Pigeon2.
Definition: Pigeon2SimState.hpp:30
Definition: string_util.hpp:15