CTRE Phoenix Pro C++ 23.0.12
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
11
12#include "frc/interfaces/Gyro.h"
13#include "frc/geometry/Rotation2d.h"
14#include "wpi/sendable/Sendable.h"
15#include "wpi/sendable/SendableBuilder.h"
16#include "wpi/sendable/SendableHelper.h"
17#include <hal/SimDevice.h>
18
19
20namespace ctre {
21namespace phoenixpro {
22namespace hardware {
23
24/**
25 * Class description for the Pigeon 2 IMU sensor that measures orientation.
26 */
28 public frc::Gyro,
29 public wpi::Sendable,
30 public wpi::SendableHelper<Pigeon2>
31{
32 /**
33 * The StatusSignalValue getters are copies so that calls
34 * to the WPI interface do not update any references
35 *
36 * These are also mutable so the const getter methods are
37 * properly managed.
38 */
41
42 static constexpr phoenix::platform::DeviceType kSimDeviceType = phoenix::platform::DeviceType::PRO_Pigeon2Type;
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 void InitSendable(wpi::SendableBuilder& builder) override;
77
78 /**
79 * This function does nothing; it exists
80 * to satisfy the WPILib Gyro interface.
81 *
82 * Pigeon 2 does not require manual calibration.
83 */
84 void Calibrate() final {}
85 void Reset() final;
86 double GetAngle() const override;
87 double GetRate() const override;
88
89 frc::Rotation2d GetRotation2d() const override;
90};
91
92}
93}
94}
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: Pigeon2.hpp:31
frc::Rotation2d GetRotation2d() const override
Pigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
double GetAngle() const override
void Calibrate() final
This function does nothing; it exists to satisfy the WPILib Gyro interface.
Definition: Pigeon2.hpp:84
void InitSendable(wpi::SendableBuilder &builder) override
double GetRate() const override
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:477
StatusSignalValue< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZ()
The angular velocity (ω) of the Pigeon 2 about the Z axis.
StatusSignalValue< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
DeviceType
Enumeration of all supported device types.
Definition: DeviceType.hpp:26
Definition: string_util.hpp:14