CTRE Phoenix C++ 5.33.1
WPI_Pigeon2.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
49/**
50 * Pigeon 2 Class. Class supports communicating over CANbus.
51 *
52 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
53 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
54 * Phoenix 6 API. A migration guide is available at
55 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
56 *
57 * If the Phoenix 5 API must be used for this device, the device must have 22.X
58 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
59 * the firmware year dropdown.
60 */
61class [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
62 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
63 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
64WPI_Pigeon2 : public Pigeon2,
65 public wpi::Sendable,
66 public wpi::SendableHelper<WPI_Pigeon2>
67{
68 public:
69 /**
70 * Construtor for WPI_Pigeon2.
71 *
72 * @param deviceNumber CAN Device ID of the Pigeon 2.
73 * @param canbus Name of the CANbus; can be a CANivore device name or serial number.
74 * Pass in nothing or "rio" to use the roboRIO.
75 */
76 WPI_Pigeon2(int deviceNumber, std::string const &canbus = "");
77
79
80 WPI_Pigeon2() = delete;
81 WPI_Pigeon2(WPI_Pigeon2 const &) = delete;
82 WPI_Pigeon2 &operator=(WPI_Pigeon2 const &) = delete;
83
84 void InitSendable(wpi::SendableBuilder& builder) override;
85
86 /**
87 * \brief Resets the Pigeon 2 to a heading of zero.
88 *
89 * \details This can be used if there is significant drift in the gyro,
90 * and it needs to be recalibrated after it has been running.
91 */
92 void Reset();
93 /**
94 * \brief Returns the heading of the robot in degrees.
95 *
96 * The angle increases as the Pigeon 2 turns clockwise when looked
97 * at from the top. This follows the NED axis convention.
98 *
99 * \details The angle is continuous; that is, it will continue from
100 * 360 to 361 degrees. This allows for algorithms that wouldn't want
101 * to see a discontinuity in the gyro output as it sweeps past from
102 * 360 to 0 on the second time around.
103 *
104 * \returns The current heading of the robot in degrees
105 */
106 double GetAngle() const;
107 /**
108 * \brief Returns the rate of rotation of the Pigeon 2.
109 *
110 * The rate is positive as the Pigeon 2 turns clockwise when looked
111 * at from the top.
112 *
113 * \returns The current rate in degrees per second
114 */
115 double GetRate() const;
116 /**
117 * \brief Returns the heading of the robot as a frc#Rotation2d.
118 *
119 * The angle increases as the Pigeon 2 turns counterclockwise when
120 * looked at from the top. This follows the NWU axis convention.
121 *
122 * \details The angle is continuous; that is, it will continue from
123 * 360 to 361 degrees. This allows for algorithms that wouldn't want
124 * to see a discontinuity in the gyro output as it sweeps past from
125 * 360 to 0 on the second time around.
126 *
127 * \returns The current heading of the robot as a frc#Rotation2d
128 */
129 frc::Rotation2d GetRotation2d() const;
130
131 private:
132 void Init();
133
134 DeviceType m_simType;
135
136 hal::SimDevice m_simPigeon;
137 hal::SimDouble m_simYaw;
138 hal::SimDouble m_simRawYaw;
139
140 static void OnValueChanged(const char* name, void* param, HAL_SimValueHandle handle,
141 HAL_Bool readonly, const struct HAL_Value* value);
142 static void OnPeriodic(void* param);
143};
144
145} //namespace sensors
146} //namespace phoenix
147} //namespace ctre
Pigeon 2 Class.
Definition: Pigeon2.h:228
Pigeon 2 Class.
Definition: WPI_Pigeon2.h:67
double GetAngle() const
Returns the heading of the robot in degrees.
void Reset()
Resets the Pigeon 2 to a heading of zero.
frc::Rotation2d GetRotation2d() const
Returns the heading of the robot as a frc::Rotation2d.
WPI_Pigeon2 & operator=(WPI_Pigeon2 const &)=delete
double GetRate() const
Returns the rate of rotation of the Pigeon 2.
void InitSendable(wpi::SendableBuilder &builder) override
WPI_Pigeon2(WPI_Pigeon2 const &)=delete
WPI_Pigeon2(int deviceNumber, std::string const &canbus="")
Construtor for WPI_Pigeon2.
namespace ctre
Definition: paramEnum.h:5