11#include "frc/geometry/Rotation2d.h"
12#include "frc/geometry/Rotation3d.h"
13#include "wpi/sendable/Sendable.h"
14#include "wpi/sendable/SendableBuilder.h"
15#include "wpi/sendable/SendableHelper.h"
16#include <hal/SimDevice.h>
28 public wpi::SendableHelper<Pigeon2>
44 hal::SimDevice m_simPigeon;
45 hal::SimDouble m_simSupplyVoltage;
46 hal::SimDouble m_simYaw;
47 hal::SimDouble m_simRawYaw;
48 hal::SimDouble m_simPitch;
49 hal::SimDouble m_simRoll;
50 hal::SimDouble m_simAngularVelocityX;
51 hal::SimDouble m_simAngularVelocityY;
52 hal::SimDouble m_simAngularVelocityZ;
55 std::vector<int32_t> m_simValueChangedUids;
59 static void OnPeriodic(
void*
param);
115 [[deprecated(
"This API is deprecated for removal in the 2026 season."
116 "Users should use GetYaw() instead."
117 "Note that Yaw is CCW+, whereas this API is CW+.")]]
131 [[deprecated(
"This API is deprecated for removal in the 2026 season."
132 "Users should use GetAngularVelocityZWorld() instead."
133 "Note that AngularVelocityZWorld is CCW+, whereas this API is CW+.")]]
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:657
StatusSignal< T > & LookupStatusSignal(uint16_t spn, std::string signalName, bool reportOnConstruction, bool refresh)
Definition ParentDevice.hpp:553
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:29
Pigeon2(int deviceId, CANBus canbus)
Constructs a new Pigeon 2 sensor object.
Definition Pigeon2.hpp:83
double GetRate() const
Returns the rate of rotation of the Pigeon 2.
void Reset()
Resets the Pigeon 2 to a heading of zero.
double GetAngle() const
Returns the heading of the robot in degrees.
void InitSendable(wpi::SendableBuilder &builder) override
Pigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
frc::Rotation3d GetRotation3d() const
Returns the orientation of the robot as a frc::Rotation3d created from the quaternion signals.
frc::Rotation2d GetRotation2d() const
Returns the heading of the robot as a frc::Rotation2d.
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1116
StatusSignal< units::dimensionless::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
StatusSignal< units::angle::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
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::dimensionless::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
Definition StatusCodes.h:18