CTRE Phoenix 6 C++ 24.3.0
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();
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
51 int32_t m_simPeriodicUid{-1};
52 std::vector<int32_t> m_simValueChangedUids;
53
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);
57
58public:
59 /**
60 * Constructs a new Pigeon 2 sensor object.
61 *
62 * \param deviceId ID of the device, as configured in Phoenix Tuner.
63 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
64 * - "rio" for the native roboRIO CAN bus
65 * - CANivore name or serial number
66 * - SocketCAN interface (non-FRC Linux only)
67 * - "*" for any CANivore seen by the program
68 * - empty string (default) to select the default for the system:
69 * - "rio" on roboRIO
70 * - "can0" on Linux
71 * - "*" on Windows
72 */
73 Pigeon2(int deviceId, std::string canbus = "");
75
76 Pigeon2(Pigeon2 &&) = default;
77 Pigeon2 &operator=(Pigeon2 &&) = default;
78
79 void InitSendable(wpi::SendableBuilder& builder) override;
80
81 /**
82 * \brief Resets the Pigeon 2 to a heading of zero.
83 *
84 * \details This can be used if there is significant drift in the gyro,
85 * and it needs to be recalibrated after it has been running.
86 */
87 void Reset();
88 /**
89 * \brief Returns the heading of the robot in degrees.
90 *
91 * The angle increases as the Pigeon 2 turns clockwise when looked
92 * at from the top. This follows the NED axis convention.
93 *
94 * \details The angle is continuous; that is, it will continue from
95 * 360 to 361 degrees. This allows for algorithms that wouldn't want
96 * to see a discontinuity in the gyro output as it sweeps past from
97 * 360 to 0 on the second time around.
98 *
99 * \returns The current heading of the robot in degrees
100 */
101 double GetAngle() const;
102 /**
103 * \brief Returns the rate of rotation of the Pigeon 2.
104 *
105 * The rate is positive as the Pigeon 2 turns clockwise when looked
106 * at from the top.
107 *
108 * \returns The current rate in degrees per second
109 */
110 double GetRate() const;
111 /**
112 * \brief Returns the heading of the robot as a frc#Rotation2d.
113 *
114 * The angle increases as the Pigeon 2 turns counterclockwise when
115 * looked at from the top. This follows the NWU axis convention.
116 *
117 * \details The angle is continuous; that is, it will continue from
118 * 360 to 361 degrees. This allows for algorithms that wouldn't want
119 * to see a discontinuity in the gyro output as it sweeps past from
120 * 360 to 0 on the second time around.
121 *
122 * \returns The current heading of the robot as a frc#Rotation2d
123 */
124 frc::Rotation2d GetRotation2d() const;
125 /**
126 * \brief Returns the orientation of the robot as a frc#Rotation3d
127 * created from the quaternion signals.
128 *
129 * \returns The current orientation of the robot as a frc#Rotation3d
130 */
131 frc::Rotation3d GetRotation3d() const;
132};
133
134}
135}
136}
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: Pigeon2.hpp:29
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 & operator=(Pigeon2 &&)=default
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:988
StatusSignal< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
StatusSignal< units::dimensionless::scalar_t > & GetQuatX()
The X component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatW()
The W component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatY()
The Y component of the reported Quaternion.
StatusSignal< units::dimensionless::scalar_t > & GetQuatZ()
The Z component of the reported Quaternion.
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZWorld()
Angular Velocity Quaternion Z Component.
Definition: string_util.hpp:15