CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
Pigeon2.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
10
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>
17
18
19namespace ctre {
20namespace phoenix6 {
21namespace hardware {
22
23/**
24 * Class description for the Pigeon 2 IMU sensor that measures orientation.
25 */
27 public wpi::Sendable,
28 public wpi::SendableHelper<Pigeon2>
29{
30 /*
31 * The StatusSignal getters are copies so that calls
32 * to the WPI interface do not update any references
33 *
34 * These are also mutable so the const getter methods are
35 * properly managed.
36 */
37 mutable StatusSignal<units::angle::degree_t> m_yawGetter = GetYaw(false);
39 mutable StatusSignal<units::dimensionless::scalar_t> m_quatWGetter = GetQuatW(false);
40 mutable StatusSignal<units::dimensionless::scalar_t> m_quatXGetter = GetQuatX(false);
41 mutable StatusSignal<units::dimensionless::scalar_t> m_quatYGetter = GetQuatY(false);
42 mutable StatusSignal<units::dimensionless::scalar_t> m_quatZGetter = GetQuatZ(false);
43
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;
50 hal::SimDouble m_simAngularVelocityX;
51 hal::SimDouble m_simAngularVelocityY;
52 hal::SimDouble m_simAngularVelocityZ;
53
54 int32_t m_simPeriodicUid{-1};
55 std::vector<int32_t> m_simValueChangedUids;
56
57 static void OnValueChanged(const char* name, void* param, HAL_SimValueHandle handle,
58 HAL_Bool readonly, const struct HAL_Value* value);
59 static void OnPeriodic(void* param);
60
61public:
62 /**
63 * Constructs a new Pigeon 2 sensor object.
64 *
65 * \param deviceId ID of the device, as configured in Phoenix Tuner.
66 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
67 * - "rio" for the native roboRIO CAN bus
68 * - CANivore name or serial number
69 * - SocketCAN interface (non-FRC Linux only)
70 * - "*" for any CANivore seen by the program
71 * - empty string (default) to select the default for the system:
72 * - "rio" on roboRIO
73 * - "can0" on Linux
74 * - "*" on Windows
75 */
76 Pigeon2(int deviceId, std::string canbus = "");
77 /**
78 * Constructs a new Pigeon 2 sensor object.
79 *
80 * \param deviceId ID of the device, as configured in Phoenix Tuner.
81 * \param canbus The CAN bus this device is on.
82 */
84 Pigeon2{deviceId, std::string{canbus.GetName()}}
85 {}
86
88
89 void InitSendable(wpi::SendableBuilder& builder) override;
90
91 /**
92 * \brief Resets the Pigeon 2 to a heading of zero.
93 *
94 * \details This can be used if there is significant drift in the gyro,
95 * and it needs to be recalibrated after it has been running.
96 */
97 void Reset();
98 /**
99 * \brief Returns the heading of the robot in degrees.
100 *
101 * The angle increases as the Pigeon 2 turns clockwise when looked
102 * at from the top. This follows the NED axis convention.
103 *
104 * \details The angle is continuous; that is, it will continue from
105 * 360 to 361 degrees. This allows for algorithms that wouldn't want
106 * to see a discontinuity in the gyro output as it sweeps past from
107 * 360 to 0 on the second time around.
108 *
109 * \deprecated This API is deprecated for removal in the 2026 season.
110 * Users should use #GetYaw instead. Note that Yaw is CCW+, whereas
111 * this API is CW+.
112 *
113 * \returns The current heading of the robot in degrees
114 */
115 [[deprecated("This API is deprecated for removal in the 2026 season."
116 "Users should use GetYaw() instead."
117 "Note that Yaw is CCW+, whereas this API is CW+.")]]
118 double GetAngle() const;
119 /**
120 * \brief Returns the rate of rotation of the Pigeon 2.
121 *
122 * The rate is positive as the Pigeon 2 turns clockwise when looked
123 * at from the top.
124 *
125 * \deprecated This API is deprecated for removal in the 2026 season.
126 * Users should use #GetAngularVelocityZWorld instead. Note that
127 * AngularVelocityZWorld is CCW+, whereas this API is CW+.
128 *
129 * \returns The current rate in degrees per second
130 */
131 [[deprecated("This API is deprecated for removal in the 2026 season."
132 "Users should use GetAngularVelocityZWorld() instead."
133 "Note that AngularVelocityZWorld is CCW+, whereas this API is CW+.")]]
134 double GetRate() const;
135 /**
136 * \brief Returns the heading of the robot as a frc#Rotation2d.
137 *
138 * The angle increases as the Pigeon 2 turns counterclockwise when
139 * looked at from the top. This follows the NWU axis convention.
140 *
141 * \details The angle is continuous; that is, it will continue from
142 * 360 to 361 degrees. This allows for algorithms that wouldn't want
143 * to see a discontinuity in the gyro output as it sweeps past from
144 * 360 to 0 on the second time around.
145 *
146 * \returns The current heading of the robot as a frc#Rotation2d
147 */
148 frc::Rotation2d GetRotation2d() const;
149 /**
150 * \brief Returns the orientation of the robot as a frc#Rotation3d
151 * created from the quaternion signals.
152 *
153 * \returns The current orientation of the robot as a frc#Rotation3d
154 */
155 frc::Rotation3d GetRotation3d() const;
156};
157
158}
159}
160}
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:657
StatusSignal< T > & LookupStatusSignal(uint16_t spn, std::string signalName, bool reportOnConstruction, bool refresh)
Definition ParentDevice.hpp:553
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:29
Pigeon2(int deviceId, CANBus canbus)
Constructs a new Pigeon 2 sensor object.
Definition Pigeon2.hpp:83
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(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:1116
StatusSignal< units::dimensionless::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
StatusSignal< units::angle::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZWorld(bool refresh=true)
The angular velocity (ω) of the Pigeon 2 about the Z axis with respect to the world frame.
StatusSignal< units::dimensionless::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
Definition StatusCodes.h:18
Definition span.hpp:401