WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
XRPGyro.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
8
9#include <hal/SimDevice.h>
10#include <units/angle.h>
12
13namespace frc {
14
15/**
16 * @ingroup xrp_api
17 * @{
18 */
19
20/**
21 * Use a rate gyro to return the robots heading relative to a starting position.
22 *
23 * This class is for the XRP onboard gyro, and will only work in
24 * simulation/XRP mode. Only one instance of a XRPGyro is supported.
25 */
26class XRPGyro {
27 public:
28 /**
29 * Constructs an XRPGyro.
30 *
31 * <p>Only one instance of a XRPGyro is supported.
32 */
34
35 /**
36 * Return the actual angle in radians that the robot is currently facing.
37 *
38 * The angle is based on integration of the returned rate form the gyro.
39 * The angle is continuous, that is, it will continue from 2π->2.1π.
40 * This allows algorithms that wouldn't want to see a discontinuity in the
41 * gyro output as it sweeps from 2π to 0 radians on the second time around.
42 *
43 * @return the current heading of the robot in radians.
44 */
45 units::radian_t GetAngle() const;
46
47 /**
48 * Gets the angle the robot is facing.
49 *
50 * @return A Rotation2d with the current heading.
51 */
53
54 /**
55 * Return the rate of rotation of the gyro
56 *
57 * The rate is based on the most recent reading of the gyro.
58 *
59 * @return the current rate in radians per second
60 */
61 units::radians_per_second_t GetRate() const;
62
63 /**
64 * Gets the rate of turn in radians-per-second around the X-axis.
65 *
66 * @return rate of turn in radians-per-second
67 */
68 units::radians_per_second_t GetRateX() const;
69
70 /**
71 * Gets the rate of turn in radians-per-second around the Y-axis.
72 *
73 * @return rate of turn in radians-per-second
74 */
75 units::radians_per_second_t GetRateY() const;
76
77 /**
78 * Gets the rate of turn in radians-per-second around the Z-axis.
79 *
80 * @return rate of turn in radians-per-second
81 */
82 units::radians_per_second_t GetRateZ() const;
83
84 /**
85 * Gets the currently reported angle around the X-axis.
86 *
87 * @return current angle around X-axis in radians
88 */
89 units::radian_t GetAngleX() const;
90
91 /**
92 * Gets the currently reported angle around the Y-axis.
93 *
94 * @return current angle around Y-axis in radians
95 */
96 units::radian_t GetAngleY() const;
97
98 /**
99 * Gets the currently reported angle around the Z-axis.
100 *
101 * @return current angle around Z-axis in radians
102 */
103 units::radian_t GetAngleZ() const;
104
105 /**
106 * Reset the gyro angles to 0.
107 */
108 void Reset();
109
110 private:
111 hal::SimDevice m_simDevice;
112 hal::SimDouble m_simRateX;
113 hal::SimDouble m_simRateY;
114 hal::SimDouble m_simRateZ;
115 hal::SimDouble m_simAngleX;
116 hal::SimDouble m_simAngleY;
117 hal::SimDouble m_simAngleZ;
118
119 units::radian_t m_angleXOffset = 0_rad;
120 units::radian_t m_angleYOffset = 0_rad;
121 units::radian_t m_angleZOffset = 0_rad;
122};
123
124/** @} */
125
126} // namespace frc
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Use a rate gyro to return the robots heading relative to a starting position.
Definition XRPGyro.h:26
units::radians_per_second_t GetRateX() const
Gets the rate of turn in radians-per-second around the X-axis.
units::radians_per_second_t GetRateZ() const
Gets the rate of turn in radians-per-second around the Z-axis.
void Reset()
Reset the gyro angles to 0.
units::radian_t GetAngle() const
Return the actual angle in radians that the robot is currently facing.
units::radian_t GetAngleX() const
Gets the currently reported angle around the X-axis.
units::radians_per_second_t GetRateY() const
Gets the rate of turn in radians-per-second around the Y-axis.
units::radians_per_second_t GetRate() const
Return the rate of rotation of the gyro.
frc::Rotation2d GetRotation2d() const
Gets the angle the robot is facing.
units::radian_t GetAngleY() const
Gets the currently reported angle around the Y-axis.
XRPGyro()
Constructs an XRPGyro.
units::radian_t GetAngleZ() const
Gets the currently reported angle around the Z-axis.
A move-only C++ wrapper around a HAL simulator device handle.
Definition SimDevice.h:645
C++ wrapper around a HAL simulator double value handle.
Definition SimDevice.h:536
Definition CAN.h:11