CTRE Phoenix 6 C++ 26.0.0-beta-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 "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#if defined(_WIN32) || defined(_WIN64)
24#pragma warning(push)
25#pragma warning(disable : 4250)
26#endif
27
28/**
29 * Class description for the Pigeon 2 IMU sensor that measures orientation.
30 */
32 public wpi::Sendable,
33 public wpi::SendableHelper<Pigeon2>
34{
35 /*
36 * The StatusSignal getters are copies so that calls
37 * to the WPI interface do not update any references
38 *
39 * These are also mutable so the const getter methods are
40 * properly managed.
41 */
42 mutable StatusSignal<units::angle::degree_t> m_yawGetter = GetYaw(false);
44 mutable StatusSignal<units::dimensionless::scalar_t> m_quatWGetter = GetQuatW(false);
45 mutable StatusSignal<units::dimensionless::scalar_t> m_quatXGetter = GetQuatX(false);
46 mutable StatusSignal<units::dimensionless::scalar_t> m_quatYGetter = GetQuatY(false);
47 mutable StatusSignal<units::dimensionless::scalar_t> m_quatZGetter = GetQuatZ(false);
48
49 hal::SimDevice m_simPigeon;
50 hal::SimDouble m_simSupplyVoltage;
51 hal::SimDouble m_simYaw;
52 hal::SimDouble m_simRawYaw;
53 hal::SimDouble m_simPitch;
54 hal::SimDouble m_simRoll;
55 hal::SimDouble m_simAngularVelocityX;
56 hal::SimDouble m_simAngularVelocityY;
57 hal::SimDouble m_simAngularVelocityZ;
58
59 int32_t m_simPeriodicUid{-1};
60 std::vector<int32_t> m_simValueChangedUids;
61
62 static void OnValueChanged(
63 const char* name, void* param, HAL_SimValueHandle handle,
64 HAL_Bool readonly, const struct HAL_Value* value
65 );
66 static void OnPeriodic(void* param);
67
68public:
69 /**
70 * Constructs a new Pigeon 2 sensor object.
71 *
72 * \param deviceId ID of the device, as configured in Phoenix Tuner
73 * \param canbus The CAN bus this device is on
74 */
75 Pigeon2(int deviceId, CANBus canbus = {});
76 /**
77 * Constructs a new Pigeon 2 sensor object.
78 *
79 * \param deviceId ID of the device, as configured in Phoenix Tuner
80 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
81 * - "rio" for the native roboRIO CAN bus
82 * - CANivore name or serial number
83 * - SocketCAN interface (non-FRC Linux only)
84 * - "*" for any CANivore seen by the program
85 * - empty string (default) to select the default for the system:
86 * - "rio" on roboRIO
87 * - "can0" on Linux
88 * - "*" on Windows
89 *
90 * \deprecated Constructing devices with a CAN bus string is deprecated for removal
91 * in the 2027 season. Construct devices using a CANBus instance instead.
92 */
93 [[deprecated(
94 "Constructing devices with a CAN bus string is deprecated for removal "
95 "in the 2027 season. Construct devices using a CANBus instance instead."
96 )]]
97 Pigeon2(int deviceId, std::string canbus);
98
100
101 void InitSendable(wpi::SendableBuilder& builder) override;
102
103 /**
104 * \brief Resets the Pigeon 2 to a heading of zero.
105 *
106 * \details This can be used if there is significant drift in the gyro,
107 * and it needs to be recalibrated after it has been running.
108 */
109 void Reset();
110 /**
111 * \brief Returns the heading of the robot as a frc#Rotation2d.
112 *
113 * The angle increases as the Pigeon 2 turns counterclockwise when
114 * looked at from the top. This follows the NWU axis convention.
115 *
116 * \details The angle is continuous; that is, it will continue from
117 * 360 to 361 degrees. This allows for algorithms that wouldn't want
118 * to see a discontinuity in the gyro output as it sweeps past from
119 * 360 to 0 on the second time around.
120 *
121 * \returns The current heading of the robot as a frc#Rotation2d
122 */
123 frc::Rotation2d GetRotation2d() const;
124 /**
125 * \brief Returns the orientation of the robot as a frc#Rotation3d
126 * created from the quaternion signals.
127 *
128 * \returns The current orientation of the robot as a frc#Rotation3d
129 */
130 frc::Rotation3d GetRotation3d() const;
131};
132
133#if defined(_WIN32) || defined(_WIN64)
134#pragma warning(pop)
135#endif
136
137}
138}
139}
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:474
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:34
Pigeon2(int deviceId, std::string canbus)
Constructs a new Pigeon 2 sensor object.
void Reset()
Resets the Pigeon 2 to a heading of zero.
void InitSendable(wpi::SendableBuilder &builder) override
frc::Rotation3d GetRotation3d() const
Returns the orientation of the robot as a frc#Rotation3d created from the quaternion signals.
Pigeon2(int deviceId, CANBus canbus={})
Constructs a new Pigeon 2 sensor object.
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:1063
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 motor_constants.h:14