Loading [MathJax]/extensions/tex2jax.js
CTRE Phoenix 6 C++ 23.10.0-alpha-8
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros
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/interfaces/Gyro.h"
12#include "frc/geometry/Rotation2d.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 frc::Gyro,
28 public wpi::Sendable,
29 public wpi::SendableHelper<Pigeon2>
30{
31 /**
32 * The StatusSignal getters are copies so that calls
33 * to the WPI interface do not update any references
34 *
35 * These are also mutable so the const getter methods are
36 * properly managed.
37 */
38 mutable StatusSignal<units::angle::degree_t> m_yawGetter = GetYaw();
40
41 hal::SimDevice m_simPigeon;
42 hal::SimDouble m_simSupplyVoltage;
43 hal::SimDouble m_simYaw;
44 hal::SimDouble m_simRawYaw;
45 hal::SimDouble m_simPitch;
46 hal::SimDouble m_simRoll;
47
48 int32_t m_simPeriodicUid{-1};
49 std::vector<int32_t> m_simValueChangedUids;
50
51 static void OnValueChanged(const char* name, void* param, HAL_SimValueHandle handle,
52 HAL_Bool readonly, const struct HAL_Value* value);
53 static void OnPeriodic(void* param);
54
55public:
56 /**
57 * Constructs a new Pigeon 2 sensor object.
58 *
59 * \param deviceId ID of the device, as configured in Phoenix Tuner.
60 * \param canbus Name of the CAN bus this device is on. Possible CAN bus strings are:
61 * - "rio" for the native roboRIO CAN bus
62 * - CANivore name or serial number
63 * - SocketCAN interface (non-FRC Linux only)
64 * - "*" for any CANivore seen by the program
65 * - empty string (default) to select the default for the system:
66 * - "rio" on roboRIO
67 * - "can0" on Linux
68 * - "*" on Windows
69 */
70 Pigeon2(int deviceId, std::string canbus = "");
72
73 void InitSendable(wpi::SendableBuilder& builder) override;
74
75 /**
76 * This function does nothing; it exists
77 * to satisfy the WPILib Gyro interface.
78 *
79 * Pigeon 2 does not require manual calibration.
80 */
81 void Calibrate() final {}
82 void Reset() final;
83 double GetAngle() const override;
84 double GetRate() const override;
85
86 frc::Rotation2d GetRotation2d() const override;
87};
88
89}
90}
91}
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: Pigeon2.hpp:30
void InitSendable(wpi::SendableBuilder &builder) override
Pigeon2(int deviceId, std::string canbus="")
Constructs a new Pigeon 2 sensor object.
frc::Rotation2d GetRotation2d() const override
void Calibrate() final
This function does nothing; it exists to satisfy the WPILib Gyro interface.
Definition: Pigeon2.hpp:81
double GetAngle() const override
double GetRate() const override
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition: CorePigeon2.hpp:905
StatusSignal< units::angular_velocity::degrees_per_second_t > & GetAngularVelocityZ()
The angular velocity (ω) of the Pigeon 2 about the Z axis.
StatusSignal< units::angle::degree_t > & GetYaw()
Current reported yaw of the Pigeon2.
Definition: ManualEvent.hpp:12