20#include <units/acceleration.h>
21#include <units/angle.h>
22#include <units/angular_velocity.h>
23#include <units/dimensionless.h>
24#include <units/magnetic_field_strength.h>
25#include <units/temperature.h>
26#include <units/time.h>
27#include <units/voltage.h>
272 return Refresh(configs, DefaultTimeoutSeconds);
304 return Apply(configs, DefaultTimeoutSeconds);
334 return Refresh(configs, DefaultTimeoutSeconds);
365 return Apply(configs, DefaultTimeoutSeconds);
379 return SetConfigsPrivate(configs.
Serialize(), timeoutSeconds,
false,
false);
394 return Refresh(configs, DefaultTimeoutSeconds);
425 return Apply(configs, DefaultTimeoutSeconds);
439 return SetConfigsPrivate(configs.
Serialize(), timeoutSeconds,
false,
false);
454 return Refresh(configs, DefaultTimeoutSeconds);
485 return Apply(configs, DefaultTimeoutSeconds);
499 return SetConfigsPrivate(configs.
Serialize(), timeoutSeconds,
false,
false);
514 return Refresh(configs, DefaultTimeoutSeconds);
545 return Apply(configs, DefaultTimeoutSeconds);
559 return SetConfigsPrivate(configs.
Serialize(), timeoutSeconds,
false,
false);
579 return SetYaw(newValue, DefaultTimeoutSeconds);
615 return ClearStickyFaults(DefaultTimeoutSeconds);
650 return ClearStickyFault_Hardware(DefaultTimeoutSeconds);
682 return ClearStickyFault_Undervoltage(DefaultTimeoutSeconds);
715 return ClearStickyFault_BootDuringEnable(DefaultTimeoutSeconds);
748 return ClearStickyFault_UnlicensedFeatureInUse(DefaultTimeoutSeconds);
780 return ClearStickyFault_BootupAccelerometer(DefaultTimeoutSeconds);
811 return ClearStickyFault_BootupGyroscope(DefaultTimeoutSeconds);
842 return ClearStickyFault_BootupMagnetometer(DefaultTimeoutSeconds);
873 return ClearStickyFault_BootIntoMotion(DefaultTimeoutSeconds);
905 return ClearStickyFault_DataAcquiredLate(DefaultTimeoutSeconds);
938 return ClearStickyFault_LoopTimeSlow(DefaultTimeoutSeconds);
970 return ClearStickyFault_SaturatedMagnetometer(DefaultTimeoutSeconds);
1001 return ClearStickyFault_SaturatedAccelerometer(DefaultTimeoutSeconds);
1032 return ClearStickyFault_SaturatedGyroscope(DefaultTimeoutSeconds);
1054#if defined(_WIN32) || defined(_WIN64)
1055#pragma warning(push)
1056#pragma warning(disable : 4250)
1126 std::unique_ptr<sim::Pigeon2SimState> _simState{};
1139 if (_simState ==
nullptr)
1140 _simState = std::make_unique<sim::Pigeon2SimState>(*
this);
2475 return GetConfigurator().SetYaw(newValue, timeoutSeconds);
2487 return SetYaw(newValue, 0.100_s);
2502 return GetConfigurator().ClearStickyFaults(timeoutSeconds);
2517 return ClearStickyFaults(0.100_s);
2528 return GetConfigurator().ClearStickyFault_Hardware(timeoutSeconds);
2539 return ClearStickyFault_Hardware(0.100_s);
2551 return GetConfigurator().ClearStickyFault_Undervoltage(timeoutSeconds);
2563 return ClearStickyFault_Undervoltage(0.100_s);
2575 return GetConfigurator().ClearStickyFault_BootDuringEnable(timeoutSeconds);
2587 return ClearStickyFault_BootDuringEnable(0.100_s);
2599 return GetConfigurator().ClearStickyFault_UnlicensedFeatureInUse(timeoutSeconds);
2611 return ClearStickyFault_UnlicensedFeatureInUse(0.100_s);
2622 return GetConfigurator().ClearStickyFault_BootupAccelerometer(timeoutSeconds);
2633 return ClearStickyFault_BootupAccelerometer(0.100_s);
2644 return GetConfigurator().ClearStickyFault_BootupGyroscope(timeoutSeconds);
2655 return ClearStickyFault_BootupGyroscope(0.100_s);
2666 return GetConfigurator().ClearStickyFault_BootupMagnetometer(timeoutSeconds);
2677 return ClearStickyFault_BootupMagnetometer(0.100_s);
2688 return GetConfigurator().ClearStickyFault_BootIntoMotion(timeoutSeconds);
2699 return ClearStickyFault_BootIntoMotion(0.100_s);
2711 return GetConfigurator().ClearStickyFault_DataAcquiredLate(timeoutSeconds);
2723 return ClearStickyFault_DataAcquiredLate(0.100_s);
2735 return GetConfigurator().ClearStickyFault_LoopTimeSlow(timeoutSeconds);
2747 return ClearStickyFault_LoopTimeSlow(0.100_s);
2758 return GetConfigurator().ClearStickyFault_SaturatedMagnetometer(timeoutSeconds);
2769 return ClearStickyFault_SaturatedMagnetometer(0.100_s);
2780 return GetConfigurator().ClearStickyFault_SaturatedAccelerometer(timeoutSeconds);
2791 return ClearStickyFault_SaturatedAccelerometer(0.100_s);
2802 return GetConfigurator().ClearStickyFault_SaturatedGyroscope(timeoutSeconds);
2813 return ClearStickyFault_SaturatedGyroscope(0.100_s);
2817#if defined(_WIN32) || defined(_WIN64)
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:474
Custom Params.
Definition CustomParamsConfigs.hpp:23
std::string Serialize() const final
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Configs to trim the Pigeon2's gyroscope.
Definition GyroTrimConfigs.hpp:27
std::string Serialize() const final
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Configs for Pigeon 2's Mount Pose configuration.
Definition MountPoseConfigs.hpp:25
std::string Serialize() const final
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Definition Configuration.hpp:17
Definition Configurator.hpp:18
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:46
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
Take a string and deserialize it to this configuration.
Pigeon2FeaturesConfigs Pigeon2Features
Configs to enable/disable various features of the Pigeon2.
Definition CorePigeon2.hpp:113
constexpr Pigeon2Configuration & WithGyroTrim(GyroTrimConfigs newGyroTrim)
Modifies this configuration's GyroTrim parameter and returns itself for method-chaining and easier to...
Definition CorePigeon2.hpp:176
CustomParamsConfigs CustomParams
Custom Params.
Definition CorePigeon2.hpp:126
GyroTrimConfigs GyroTrim
Configs to trim the Pigeon2's gyroscope.
Definition CorePigeon2.hpp:98
std::string ToString() const override
Get the string representation of this configuration.
constexpr Pigeon2Configuration()=default
bool FutureProofConfigs
True if we should factory default newer unsupported configs, false to leave newer unsupported configs...
Definition CorePigeon2.hpp:63
constexpr Pigeon2Configuration & WithMountPose(MountPoseConfigs newMountPose)
Modifies this configuration's MountPose parameter and returns itself for method-chaining and easier t...
Definition CorePigeon2.hpp:148
std::string Serialize() const final
Get the serialized form of this configuration.
MountPoseConfigs MountPose
Configs for Pigeon 2's Mount Pose configuration.
Definition CorePigeon2.hpp:80
constexpr Pigeon2Configuration & WithPigeon2Features(Pigeon2FeaturesConfigs newPigeon2Features)
Modifies this configuration's Pigeon2Features parameter and returns itself for method-chaining and ea...
Definition CorePigeon2.hpp:201
constexpr Pigeon2Configuration & WithCustomParams(CustomParamsConfigs newCustomParams)
Modifies this configuration's CustomParams parameter and returns itself for method-chaining and easie...
Definition CorePigeon2.hpp:224
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:251
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:713
ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs, units::time::second_t timeoutSeconds)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:557
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:465
ctre::phoenix::StatusCode Apply(const MountPoseConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:363
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:999
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:936
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:840
ctre::phoenix::StatusCode Apply(const CustomParamsConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:543
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
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:316
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:746
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
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 ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
ctre::phoenix::StatusCode Refresh(Pigeon2FeaturesConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:452
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:577
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
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:497
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_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:680
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:871
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:302
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 Refresh(MountPoseConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:332
ctre::phoenix::StatusCode Apply(const Pigeon2FeaturesConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:483
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:437
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:968
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:778
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:405
ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:512
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
ctre::phoenix::StatusCode Refresh(MountPoseConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:345
ctre::phoenix::StatusCode Refresh(GyroTrimConfigs &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:392
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:1030
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:809
ctre::phoenix::StatusCode Refresh(CustomParamsConfigs &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:525
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs, units::time::second_t timeoutSeconds) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:284
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:613
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:377
ctre::phoenix::StatusCode Refresh(Pigeon2Configuration &configs) const
Refreshes the values of the specified config group.
Definition CorePigeon2.hpp:270
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:903
ctre::phoenix::StatusCode Apply(const GyroTrimConfigs &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:423
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:648
Configs to enable/disable various features of the Pigeon2.
Definition Pigeon2FeaturesConfigs.hpp:24
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
std::string Serialize() const final
Common interface implemented by all control requests.
Definition ControlRequest.hpp:27
Definition DeviceIdentifier.hpp:16
Parent class for all devices.
Definition ParentDevice.hpp:23
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1063
StatusSignal< bool > & GetTemperatureCompensationDisabled(bool refresh=true)
Whether the temperature-compensation feature is disabled.
StatusSignal< units::dimensionless::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
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::angle::degree_t > & GetRoll(bool refresh=true)
Current reported roll of the Pigeon2.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationZ(bool refresh=true)
The acceleration measured by Pigeon2 in the Z direction.
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.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage()
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:2561
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2664
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer()
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2631
ctre::phoenix::StatusCode SetControl(controls::ControlRequest const &request)
Control device with generic control request object.
StatusSignal< units::angle::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< bool > & GetFault_SaturatedMagnetometer(bool refresh=true)
Magnetometer values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:2709
ctre::phoenix::StatusCode ClearStickyFault_UnlicensedFeatureInUse()
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
Definition CorePigeon2.hpp:2609
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< bool > & GetStickyFault_BootupGyroscope(bool refresh=true)
Bootup checks failed: Gyroscope.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
StatusSignal< bool > & GetFault_LoopTimeSlow(bool refresh=true)
Motion stack loop time was slower than expected.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorY(bool refresh=true)
The Y component of the gravity vector.
StatusSignal< bool > & GetFault_SaturatedAccelerometer(bool refresh=true)
Accelerometer values are saturated.
StatusSignal< bool > & GetStickyFault_UnlicensedFeatureInUse(bool refresh=true)
An unlicensed feature is in use, device may not behave as expected.
StatusSignal< units::angle::degree_t > & GetAccumGyroX(bool refresh=true)
The accumulated gyro about the X axis without any sensor fusing.
StatusSignal< int > & GetVersion(bool refresh=true)
Full Version of firmware in device.
ctre::phoenix::StatusCode ClearStickyFaults()
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:2515
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2733
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.
ctre::phoenix::StatusCode ClearStickyFault_DataAcquiredLate()
Clear sticky fault: Motion stack data acquisition was slower than expected.
Definition CorePigeon2.hpp:2721
StatusSignal< bool > & GetStickyFault_SaturatedMagnetometer(bool refresh=true)
Magnetometer values are saturated.
StatusSignal< bool > & GetStickyFault_BootIntoMotion(bool refresh=true)
Motion Detected during bootup.
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.
CorePigeon2(int deviceId, CANBus canbus={})
Constructs a new Pigeon 2 sensor object.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer()
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:2789
StatusSignal< int > & GetStickyFaultField(bool refresh=true)
Integer representing all (persistent) sticky fault flags reported by the device.
StatusSignal< bool > & GetNoMotionEnabled(bool refresh=true)
Whether the no-motion calibration feature is enabled.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope()
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:2811
StatusSignal< units::angle::degree_t > & GetPitch(bool refresh=true)
Current reported pitch of the Pigeon2.
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1107
StatusSignal< bool > & GetFault_SaturatedGyroscope(bool refresh=true)
Gyroscope values are saturated.
ctre::phoenix::StatusCode ClearStickyFault_Hardware()
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:2537
StatusSignal< units::angle::degree_t > & GetAccumGyroY(bool refresh=true)
The accumulated gyro about the Y axis without any sensor fusing.
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:2473
StatusSignal< bool > & GetStickyFault_Undervoltage(bool refresh=true)
Device supply voltage dropped to near brownout levels.
StatusSignal< units::voltage::volt_t > & GetSupplyVoltage(bool refresh=true)
Measured supply voltage to the Pigeon2.
configs::Pigeon2Configurator const & GetConfigurator() const
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1119
StatusSignal< bool > & GetFault_BootupGyroscope(bool refresh=true)
Bootup checks failed: Gyroscope.
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationX(bool refresh=true)
The acceleration measured by Pigeon2 in the X direction.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Gyroscope values are saturated.
Definition CorePigeon2.hpp:2800
StatusSignal< units::dimensionless::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< bool > & GetStickyFault_Hardware(bool refresh=true)
Hardware fault occurred.
StatusSignal< bool > & GetStickyFault_SaturatedAccelerometer(bool refresh=true)
Accelerometer values are saturated.
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.
ctre::phoenix::StatusCode ClearStickyFaults(units::time::second_t timeoutSeconds)
Clear the sticky faults in the device.
Definition CorePigeon2.hpp:2500
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2756
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope()
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2653
StatusSignal< bool > & GetFault_Undervoltage(bool refresh=true)
Device supply voltage dropped to near brownout levels.
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion()
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:2697
ctre::phoenix::StatusCode ClearStickyFault_SaturatedMagnetometer()
Clear sticky fault: Magnetometer values are saturated.
Definition CorePigeon2.hpp:2767
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::dimensionless::scalar_t > & GetNoMotionCount(bool refresh=true)
The number of times a no-motion event occurred, wraps at 15.
StatusSignal< units::time::second_t > & GetUpTime(bool refresh=true)
How long the Pigeon 2's been up in seconds, caps at 255 seconds.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable(units::time::second_t timeoutSeconds)
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:2573
StatusSignal< int > & GetVersionMajor(bool refresh=true)
App Major Version number.
StatusSignal< bool > & GetFault_BootIntoMotion(bool refresh=true)
Motion Detected during bootup.
ctre::phoenix::StatusCode ClearStickyFault_LoopTimeSlow()
Clear sticky fault: Motion stack loop time was slower than expected.
Definition CorePigeon2.hpp:2745
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::dimensionless::scalar_t > & GetGravityVectorX(bool refresh=true)
The X component of the gravity vector.
StatusSignal< bool > & GetStickyFault_SaturatedGyroscope(bool refresh=true)
Gyroscope values are saturated.
StatusSignal< bool > & GetFault_BootupAccelerometer(bool refresh=true)
Bootup checks failed: Accelerometer.
StatusSignal< bool > & GetStickyFault_BootDuringEnable(bool refresh=true)
Device boot while detecting the enable signal.
StatusSignal< int > & GetFaultField(bool refresh=true)
Integer representing all fault flags reported by the device.
StatusSignal< bool > & GetFault_BootupMagnetometer(bool refresh=true)
Bootup checks failed: Magnetometer.
StatusSignal< units::temperature::celsius_t > & GetTemperature(bool refresh=true)
Temperature of the Pigeon 2.
CorePigeon2(int deviceId, std::string canbus)
Constructs a new Pigeon 2 sensor object.
ctre::phoenix::StatusCode ClearStickyFault_Undervoltage(units::time::second_t timeoutSeconds)
Clear sticky fault: Device supply voltage dropped to near brownout levels.
Definition CorePigeon2.hpp:2549
ctre::phoenix::StatusCode ClearStickyFault_BootupGyroscope(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Gyroscope.
Definition CorePigeon2.hpp:2642
ctre::phoenix::StatusCode ClearStickyFault_BootIntoMotion(units::time::second_t timeoutSeconds)
Clear sticky fault: Motion Detected during bootup.
Definition CorePigeon2.hpp:2686
StatusSignal< bool > & GetFault_UnlicensedFeatureInUse(bool refresh=true)
An unlicensed feature is in use, device may not behave as expected.
StatusSignal< int > & GetVersionBugfix(bool refresh=true)
App Bugfix Version number.
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.
Definition CorePigeon2.hpp:2597
ctre::phoenix::StatusCode ClearStickyFault_Hardware(units::time::second_t timeoutSeconds)
Clear sticky fault: Hardware fault occurred.
Definition CorePigeon2.hpp:2526
StatusSignal< bool > & GetFault_BootDuringEnable(bool refresh=true)
Device boot while detecting the enable signal.
StatusSignal< bool > & GetStickyFault_LoopTimeSlow(bool refresh=true)
Motion stack loop time was slower than expected.
StatusSignal< bool > & GetFault_DataAcquiredLate(bool refresh=true)
Motion stack data acquisition was slower than expected.
StatusSignal< bool > & GetIsProLicensed(bool refresh=true)
Whether the device is Phoenix Pro licensed.
ctre::phoenix::StatusCode SetYaw(units::angle::degree_t newValue)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:2485
StatusSignal< units::acceleration::standard_gravity_t > & GetAccelerationY(bool refresh=true)
The acceleration measured by Pigeon2 in the Y direction.
ctre::phoenix::StatusCode ClearStickyFault_BootDuringEnable()
Clear sticky fault: Device boot while detecting the enable signal.
Definition CorePigeon2.hpp:2585
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetGravityVectorZ(bool refresh=true)
The Z component of the gravity vector.
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< int > & GetVersionBuild(bool refresh=true)
App Build Version number.
ctre::phoenix::StatusCode ClearStickyFault_BootupAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Bootup checks failed: Accelerometer.
Definition CorePigeon2.hpp:2620
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< bool > & GetStickyFault_BootupAccelerometer(bool refresh=true)
Bootup checks failed: Accelerometer.
StatusSignal< units::angle::degree_t > & GetAccumGyroZ(bool refresh=true)
The accumulated gyro about the Z axis without any sensor fusing.
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< bool > & GetStickyFault_BootupMagnetometer(bool refresh=true)
Bootup checks failed: Magnetometer.
ctre::phoenix::StatusCode ClearStickyFault_SaturatedAccelerometer(units::time::second_t timeoutSeconds)
Clear sticky fault: Accelerometer values are saturated.
Definition CorePigeon2.hpp:2778
ctre::phoenix::StatusCode ClearStickyFault_BootupMagnetometer()
Clear sticky fault: Bootup checks failed: Magnetometer.
Definition CorePigeon2.hpp:2675
StatusSignal< bool > & GetStickyFault_DataAcquiredLate(bool refresh=true)
Motion stack data acquisition was slower than expected.
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< int > & GetVersionMinor(bool refresh=true)
App Minor Version number.
StatusSignal< bool > & GetFault_Hardware(bool refresh=true)
Hardware fault occurred.
sim::Pigeon2SimState & GetSimState()
Get the simulation state for this device.
Definition CorePigeon2.hpp:1137
Class to control the state of a simulated hardware::Pigeon2.
Definition Pigeon2SimState.hpp:31
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
Definition motor_constants.h:14