WPILibC++ 2024.3.2
ADXRS450_Gyro.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
7#include <stdint.h>
8
9#include <hal/SimDevice.h>
12
13#include "frc/SPI.h"
15
16namespace frc {
17
18/**
19 * Use a rate gyro to return the robots heading relative to a starting position.
20 *
21 * The %Gyro class tracks the robots heading based on the starting position. As
22 * the robot rotates the new heading is computed by integrating the rate of
23 * rotation returned by the sensor. When the class is instantiated, it does a
24 * short calibration routine where it samples the gyro while at rest to
25 * determine the default offset. This is subtracted from each sample to
26 * determine the heading.
27 *
28 * This class is for the digital ADXRS450 gyro sensor that connects via SPI.
29 * Only one instance of an ADXRS %Gyro is supported.
30 */
32 public wpi::SendableHelper<ADXRS450_Gyro> {
33 public:
34 /**
35 * %Gyro constructor on onboard CS0.
36 */
38
39 /**
40 * %Gyro constructor on the specified SPI port.
41 *
42 * @param port The SPI port the gyro is attached to.
43 */
44 explicit ADXRS450_Gyro(SPI::Port port);
45
46 ~ADXRS450_Gyro() override = default;
47
50
51 bool IsConnected() const;
52
53 /**
54 * Return the actual angle in degrees that the robot is currently facing.
55 *
56 * The angle is based on integration of the returned rate from the gyro.
57 * The angle is continuous, that is it will continue from 360->361 degrees.
58 * This allows algorithms that wouldn't want to see a discontinuity in the
59 * gyro output as it sweeps from 360 to 0 on the second time around.
60 *
61 * @return the current heading of the robot in degrees.
62 */
63 double GetAngle() const;
64
65 /**
66 * Return the rate of rotation of the gyro
67 *
68 * The rate is based on the most recent reading of the gyro.
69 *
70 * @return the current rate in degrees per second
71 */
72 double GetRate() const;
73
74 /**
75 * Reset the gyro.
76 *
77 * Resets the gyro to a heading of zero. This can be used if there is
78 * significant drift in the gyro and it needs to be recalibrated after it has
79 * been running.
80 */
81 void Reset();
82
83 /**
84 * Calibrate the gyro by running for a number of samples and computing the
85 * center value. Then use the center value as the Accumulator center value for
86 * subsequent measurements.
87 *
88 * It's important to make sure that the robot is not moving while the
89 * centering calculations are in progress, this is typically done when the
90 * robot is first turned on while it's sitting at rest before the competition
91 * starts.
92 */
93 void Calibrate();
94
95 /**
96 * Return the heading of the robot as a Rotation2d.
97 *
98 * The angle is continuous, that is it will continue from 360 to 361 degrees.
99 * This allows algorithms that wouldn't want to see a discontinuity in the
100 * gyro output as it sweeps past from 360 to 0 on the second time around.
101 *
102 * The angle is expected to increase as the gyro turns counterclockwise when
103 * looked at from the top. It needs to follow the NWU axis convention.
104 *
105 * @return the current heading of the robot as a Rotation2d. This heading is
106 * based on integration of the returned rate from the gyro.
107 */
109
110 /**
111 * Get the SPI port number.
112 *
113 * @return The SPI port number.
114 */
115 int GetPort() const;
116
117 void InitSendable(wpi::SendableBuilder& builder) override;
118
119 private:
120 SPI m_spi;
121 SPI::Port m_port;
122 bool m_connected{false};
123
124 hal::SimDevice m_simDevice;
125 hal::SimBoolean m_simConnected;
126 hal::SimDouble m_simAngle;
127 hal::SimDouble m_simRate;
128
129 uint16_t ReadRegister(int reg);
130};
131
132} // namespace frc
Use a rate gyro to return the robots heading relative to a starting position.
Definition: ADXRS450_Gyro.h:32
int GetPort() const
Get the SPI port number.
void Reset()
Reset the gyro.
double GetAngle() const
Return the actual angle in degrees that the robot is currently facing.
ADXRS450_Gyro & operator=(ADXRS450_Gyro &&)=default
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
ADXRS450_Gyro(SPI::Port port)
Gyro constructor on the specified SPI port.
bool IsConnected() const
~ADXRS450_Gyro() override=default
Rotation2d GetRotation2d() const
Return the heading of the robot as a Rotation2d.
double GetRate() const
Return the rate of rotation of the gyro.
ADXRS450_Gyro()
Gyro constructor on onboard CS0.
void Calibrate()
Calibrate the gyro by running for a number of samples and computing the center value.
ADXRS450_Gyro(ADXRS450_Gyro &&)=default
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
SPI bus interface class.
Definition: SPI.h:26
Port
SPI port.
Definition: SPI.h:31
C++ wrapper around a HAL simulator boolean value handle.
Definition: SimDevice.h:608
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:642
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:533
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15