12#include "frc/interfaces/Gyro.h"
13#include "frc/geometry/Rotation2d.h"
14#include "wpi/sendable/Sendable.h"
15#include "wpi/sendable/SendableBuilder.h"
16#include "wpi/sendable/SendableHelper.h"
17#include <hal/SimDevice.h>
30 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:31
frc::Rotation2d GetRotation2d() const override
Pigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
double GetAngle() const override
void Calibrate() final
This function does nothing; it exists to satisfy the WPILib Gyro interface.
Definition: Pigeon2.hpp:84
void InitSendable(wpi::SendableBuilder &builder) override
double GetRate() const override
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:477
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZ()
The angular velocity (ω) of the Pigeon 2 about the Z axis.
StatusSignalValue< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
Definition: string_util.hpp:14