CTRE Phoenix 6 C++ 26.50.0-alpha-1
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 <wpi/hal/SimDevice.hpp>
12#include <wpi/math/geometry/Rotation2d.hpp>
13#include <wpi/math/geometry/Rotation3d.hpp>
14
15namespace ctre {
16namespace phoenix6 {
17namespace hardware {
18
19#if defined(_WIN32) || defined(_WIN64)
20#pragma warning(push)
21#pragma warning(disable : 4250)
22#endif
23
24/**
25 * Class description for the Pigeon 2 IMU sensor that measures orientation.
26 */
27class Pigeon2 : public core::CorePigeon2 {
28 /*
29 * The StatusSignal getters are copies so that calls
30 * to the WPI interface do not update any references
31 *
32 * These are also mutable so the const getter methods are
33 * properly managed.
34 */
35 mutable StatusSignal<wpi::units::degree_t> m_yawGetter = GetYaw(false);
37 mutable StatusSignal<wpi::units::scalar_t> m_quatWGetter = GetQuatW(false);
38 mutable StatusSignal<wpi::units::scalar_t> m_quatXGetter = GetQuatX(false);
39 mutable StatusSignal<wpi::units::scalar_t> m_quatYGetter = GetQuatY(false);
40 mutable StatusSignal<wpi::units::scalar_t> m_quatZGetter = GetQuatZ(false);
41
42 wpi::hal::SimDevice m_simPigeon;
43 wpi::hal::SimDouble m_simSupplyVoltage;
44 wpi::hal::SimDouble m_simYaw;
45 wpi::hal::SimDouble m_simRawYaw;
46 wpi::hal::SimDouble m_simPitch;
47 wpi::hal::SimDouble m_simRoll;
48 wpi::hal::SimDouble m_simAngularVelocityX;
49 wpi::hal::SimDouble m_simAngularVelocityY;
50 wpi::hal::SimDouble m_simAngularVelocityZ;
51
52 int32_t m_simPeriodicUid{-1};
53 std::vector<int32_t> m_simValueChangedUids;
54
55 static void OnValueChanged(
56 const char* name, void* param, HAL_SimValueHandle handle,
57 HAL_Bool readonly, const struct HAL_Value* value
58 );
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 The CAN bus this device is on
67 */
68 Pigeon2(int deviceId, CANBus canbus);
69
71
72 /**
73 * \brief Constructs a stubbed-out Pigeon2, where all status signals, controls,
74 * configs, etc. perform no action and immediately return OK. This can be used to
75 * silence error messages for devices that have been completely removed from the robot.
76 *
77 * \returns Stubbed-out Pigeon2
78 */
79 static Pigeon2 None()
80 {
81 return Pigeon2{-1, CANBus{}};
82 }
83
84 /**
85 * \brief Resets the Pigeon 2 to a heading of zero.
86 *
87 * \details This can be used if there is significant drift in the gyro,
88 * and it needs to be recalibrated after it has been running.
89 */
90 void Reset()
91 {
92 SetYaw(0_deg);
93 }
94 /**
95 * \brief Returns the heading of the Pigeon 2 as a wpi#math#Rotation2d.
96 *
97 * The angle increases as the Pigeon 2 turns counterclockwise when
98 * looked at from the top. This follows the NWU axis convention.
99 *
100 * \returns The current heading of the Pigeon 2 as a wpi#math#Rotation2d
101 */
102 wpi::math::Rotation2d GetRotation2d() const
103 {
104 /* Rotation2d and Pigeon2 are both ccw+ */
105 return wpi::math::Rotation2d{m_yawGetter.Refresh().GetValue()};
106 }
107 /**
108 * \brief Returns the orientation of the Pigeon 2 as a wpi#math#Rotation3d
109 * created from the quaternion signals.
110 *
111 * \returns The current orientation of the Pigeon 2 as a wpi#math#Rotation3d
112 */
113 wpi::math::Rotation3d GetRotation3d() const
114 {
115 return wpi::math::Rotation3d{GetQuaternion()};
116 }
117 /**
118 * \brief Returns the orientation of the Pigeon 2 as a wpi#math#Quaternion.
119 *
120 * \returns The current orientation of the Pigeon 2 as a wpi#math#Quaternion
121 */
122 wpi::math::Quaternion GetQuaternion() const
123 {
124 BaseStatusSignal::RefreshAll(m_quatWGetter, m_quatXGetter, m_quatYGetter, m_quatZGetter);
125 return wpi::math::Quaternion{m_quatWGetter.GetValue(), m_quatXGetter.GetValue(), m_quatYGetter.GetValue(), m_quatZGetter.GetValue()};
126 }
127};
128
129#if defined(_WIN32) || defined(_WIN64)
130#pragma warning(pop)
131#endif
132
133}
134}
135}
static ctre::phoenix::StatusCode RefreshAll(Signals &... signals)
Performs a non-blocking refresh on all provided signals.
Definition StatusSignal.hpp:429
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:563
wpi::math::Rotation2d GetRotation2d() const
Returns the heading of the Pigeon 2 as a wpi::math::Rotation2d.
Definition Pigeon2.hpp:102
Pigeon2(int deviceId, CANBus canbus)
Constructs a new Pigeon 2 sensor object.
void Reset()
Resets the Pigeon 2 to a heading of zero.
Definition Pigeon2.hpp:90
wpi::math::Rotation3d GetRotation3d() const
Returns the orientation of the Pigeon 2 as a wpi::math::Rotation3d created from the quaternion signal...
Definition Pigeon2.hpp:113
static Pigeon2 None()
Constructs a stubbed-out Pigeon2, where all status signals, controls, configs, etc.
Definition Pigeon2.hpp:79
wpi::math::Quaternion GetQuaternion() const
Returns the orientation of the Pigeon 2 as a wpi::math::Quaternion.
Definition Pigeon2.hpp:122
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1062
StatusSignal< wpi::units::scalar_t > & GetQuatX(bool refresh=true)
The X component of the reported Quaternion.
ctre::phoenix::StatusCode SetYaw(wpi::units::degree_t newValue, wpi::units::second_t timeoutSeconds)
The yaw to set the Pigeon2 to right now.
Definition CorePigeon2.hpp:2454
StatusSignal< wpi::units::scalar_t > & GetQuatW(bool refresh=true)
The W component of the reported Quaternion.
StatusSignal< wpi::units::scalar_t > & GetQuatY(bool refresh=true)
The Y component of the reported Quaternion.
StatusSignal< wpi::units::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< wpi::units::degree_t > & GetYaw(bool refresh=true)
Current reported yaw of the Pigeon2.
StatusSignal< wpi::units::scalar_t > & GetQuatZ(bool refresh=true)
The Z component of the reported Quaternion.
Definition ExternalFeedbackConfigs.hpp:17
Definition ExternalFeedbackConfigs.hpp:16
Definition motor_constants.h:14