22#pragma GCC diagnostic push
23#pragma GCC diagnostic ignored "-Wconversion"
26#pragma warning(disable : 4522 4458 4522)
29#include "frc/geometry/Rotation2d.h"
30#include "wpi/sendable/Sendable.h"
31#include "wpi/sendable/SendableHelper.h"
32#include "wpi/raw_ostream.h"
33#include <hal/SimDevice.h>
37#pragma GCC diagnostic pop
51 public wpi::SendableHelper<WPI_PigeonIMU>
123 DeviceType m_simType;
125 hal::SimDevice m_simPigeon;
126 hal::SimDouble m_simFusedHeading;
127 hal::SimDouble m_simRawHeading;
129 static void OnValueChanged(
const char* name,
void* param, HAL_SimValueHandle handle,
130 HAL_Bool readonly,
const struct HAL_Value* value);
131 static void OnPeriodic(
void* param);
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: TalonSRX.h:145
Pigeon IMU Class.
Definition: PigeonIMU.h:85
Definition: WPI_PigeonIMU.h:52
WPI_PigeonIMU(int deviceNumber)
Construtor for WPI_PigeonIMU.
void Reset()
Resets the Pigeon IMU to a heading of zero.
void InitSendable(wpi::SendableBuilder &builder) override
WPI_PigeonIMU(ctre::phoenix::motorcontrol::can::TalonSRX &talon)
Construtor for WPI_PigeonIMU.
double GetRate() const
Returns the rate of rotation of the Pigeon IMU.
frc::Rotation2d GetRotation2d() const
Returns the heading of the robot as a frc::Rotation2d.
WPI_PigeonIMU & operator=(WPI_PigeonIMU const &)=delete
double GetAngle() const
Returns the heading of the robot in degrees.
WPI_PigeonIMU(WPI_PigeonIMU const &)=delete
namespace ctre
Definition: paramEnum.h:5