CTRE Phoenix C++ 5.33.1
WPI_PigeonIMU.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2/**
3 * WPI Compliant Pigeon class.
4 * WPILIB's object model requires many interfaces to be implemented to use
5 * the various features.
6 * This includes...
7 * - LiveWindow/Test mode features
8 * - getRotation2d/Gyro Interface
9 * - Simulation Hooks
10 */
11
12#pragma once
13
17
18#include <mutex>
19
20//Need to disable certain warnings for WPI headers.
21#if __GNUC__
22#pragma GCC diagnostic push
23#pragma GCC diagnostic ignored "-Wconversion"
24#elif _MSC_VER
25#pragma warning(push)
26#pragma warning(disable : 4522 4458 4522)
27#endif
28
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>
34
35//Put the warning settings back to normal
36#if __GNUC__
37#pragma GCC diagnostic pop
38#elif _MSC_VER
39#pragma warning(pop)
40#endif
41
42namespace ctre
43{
44namespace phoenix
45{
46namespace sensors
47{
48
49class WPI_PigeonIMU : public PigeonIMU,
50 public wpi::Sendable,
51 public wpi::SendableHelper<WPI_PigeonIMU>
52{
53 public:
54 /**
55 * Construtor for WPI_PigeonIMU.
56 *
57 * @param deviceNumber CAN Device ID of the Pigeon IMU.
58 */
59 WPI_PigeonIMU(int deviceNumber);
60 /**
61 * Construtor for WPI_PigeonIMU.
62 *
63 * @param talon The Talon SRX ribbon-cabled to Pigeon.
64 */
66
68
69 WPI_PigeonIMU() = delete;
70 WPI_PigeonIMU(WPI_PigeonIMU const &) = delete;
72
73 void InitSendable(wpi::SendableBuilder& builder) override;
74
75 /**
76 * \brief Resets the Pigeon IMU to a heading of zero.
77 *
78 * \details This can be used if there is significant drift in the gyro,
79 * and it needs to be recalibrated after it has been running.
80 */
81 void Reset();
82 /**
83 * \brief Returns the heading of the robot in degrees.
84 *
85 * The angle increases as the Pigeon IMU turns clockwise when looked
86 * at from the top. This follows the NED axis convention.
87 *
88 * \details The angle is continuous; that is, it will continue from
89 * 360 to 361 degrees. This allows for algorithms that wouldn't want
90 * to see a discontinuity in the gyro output as it sweeps past from
91 * 360 to 0 on the second time around.
92 *
93 * \returns The current heading of the robot in degrees
94 */
95 double GetAngle() const;
96 /**
97 * \brief Returns the rate of rotation of the Pigeon IMU.
98 *
99 * The rate is positive as the Pigeon IMU turns clockwise when looked
100 * at from the top.
101 *
102 * \returns The current rate in degrees per second
103 */
104 double GetRate() const;
105 /**
106 * \brief Returns the heading of the robot as a frc#Rotation2d.
107 *
108 * The angle increases as the Pigeon IMU turns counterclockwise when
109 * looked at from the top. This follows the NWU axis convention.
110 *
111 * \details The angle is continuous; that is, it will continue from
112 * 360 to 361 degrees. This allows for algorithms that wouldn't want
113 * to see a discontinuity in the gyro output as it sweeps past from
114 * 360 to 0 on the second time around.
115 *
116 * \returns The current heading of the robot as a frc#Rotation2d
117 */
118 frc::Rotation2d GetRotation2d() const;
119
120 private:
121 void Init();
122
123 DeviceType m_simType;
124
125 hal::SimDevice m_simPigeon;
126 hal::SimDouble m_simFusedHeading;
127 hal::SimDouble m_simRawHeading;
128
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);
132};
133
134} //namespace sensors
135} //namespace phoenix
136} //namespace ctre
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