11#include <wpi/hal/SimDevice.hpp>
12#include <wpi/math/geometry/Rotation2d.hpp>
13#include <wpi/math/geometry/Rotation3d.hpp>
19#if defined(_WIN32) || defined(_WIN64)
21#pragma warning(disable : 4250)
42 wpi::hal::SimDevice m_simPigeon;
43 wpi::hal::SimDouble m_simSupplyVoltage;
44 wpi::hal::SimDouble m_simYaw;
45 wpi::hal::SimDouble m_simRawYaw;
46 wpi::hal::SimDouble m_simPitch;
47 wpi::hal::SimDouble m_simRoll;
48 wpi::hal::SimDouble m_simAngularVelocityX;
49 wpi::hal::SimDouble m_simAngularVelocityY;
50 wpi::hal::SimDouble m_simAngularVelocityZ;
52 int32_t m_simPeriodicUid{-1};
53 std::vector<int32_t> m_simValueChangedUids;
55 static void OnValueChanged(
56 const char* name,
void* param, HAL_SimValueHandle handle,
57 HAL_Bool readonly,
const struct HAL_Value* value
59 static void OnPeriodic(
void* param);
105 return wpi::math::Rotation2d{m_yawGetter.Refresh().GetValue()};
125 return wpi::math::Quaternion{m_quatWGetter.GetValue(), m_quatXGetter.GetValue(), m_quatYGetter.GetValue(), m_quatZGetter.GetValue()};
129#if defined(_WIN32) || defined(_WIN64)
static ctre::phoenix::StatusCode RefreshAll(Signals &... signals)
Performs a non-blocking refresh on all provided signals.
Definition StatusSignal.hpp:429
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:563
wpi::math::Rotation2d GetRotation2d() const
Returns the heading of the Pigeon 2 as a wpi::math::Rotation2d.
Definition Pigeon2.hpp:102
Pigeon2(int deviceId, CANBus canbus)
Constructs a new Pigeon 2 sensor object.
void Reset()
Resets the Pigeon 2 to a heading of zero.
Definition Pigeon2.hpp:90
wpi::math::Rotation3d GetRotation3d() const
Returns the orientation of the Pigeon 2 as a wpi::math::Rotation3d created from the quaternion signal...
Definition Pigeon2.hpp:113
static Pigeon2 None()
Constructs a stubbed-out Pigeon2, where all status signals, controls, configs, etc.
Definition Pigeon2.hpp:79
wpi::math::Quaternion GetQuaternion() const
Returns the orientation of the Pigeon 2 as a wpi::math::Quaternion.
Definition Pigeon2.hpp:122
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1062
StatusSignal< wpi::units::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue, wpi::units::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:2454
StatusSignal< wpi::units::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< wpi::units::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
StatusSignal< wpi::units::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< wpi::units::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< wpi::units::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
Definition ExternalFeedbackConfigs.hpp:17
Definition ExternalFeedbackConfigs.hpp:16
Definition motor_constants.h:14