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;
51 int32_t m_simPeriodicUid{-1};
52 std::vector<int32_t> m_simValueChangedUids;
54 static void OnValueChanged(
const char* name,
void* param, HAL_SimValueHandle handle,
55 HAL_Bool readonly,
const struct HAL_Value* value);
56 static void OnPeriodic(
void* param);
73 Pigeon2(
int deviceId, std::string canbus =
"");
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: Pigeon2.hpp:29
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 & operator=(Pigeon2 &&)=default
Pigeon2(Pigeon2 &&)=default
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:988
StatusSignal< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
StatusSignal< units::dimensionless::scalar_t > & GetQuatX()
The X component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatW()
The W component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY()
The Y component of the reported Quaternion.
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.
Definition: string_util.hpp:15