WPILibC++ 2023.4.3-108-ge5452e3
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"
14#include "frc/interfaces/Gyro.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 */
31class ADXRS450_Gyro : public Gyro,
32 public wpi::Sendable,
33 public wpi::SendableHelper<ADXRS450_Gyro> {
34 public:
35 /**
36 * %Gyro constructor on onboard CS0.
37 */
39
40 /**
41 * %Gyro constructor on the specified SPI port.
42 *
43 * @param port The SPI port the gyro is attached to.
44 */
45 explicit ADXRS450_Gyro(SPI::Port port);
46
47 ~ADXRS450_Gyro() override = default;
48
51
52 bool IsConnected() const;
53
54 /**
55 * Return the actual angle in degrees that the robot is currently facing.
56 *
57 * The angle is based on integration of the returned rate from the gyro.
58 * The angle is continuous, that is it will continue from 360->361 degrees.
59 * This allows algorithms that wouldn't want to see a discontinuity in the
60 * gyro output as it sweeps from 360 to 0 on the second time around.
61 *
62 * @return the current heading of the robot in degrees.
63 */
64 double GetAngle() const override;
65
66 /**
67 * Return the rate of rotation of the gyro
68 *
69 * The rate is based on the most recent reading of the gyro.
70 *
71 * @return the current rate in degrees per second
72 */
73 double GetRate() const override;
74
75 /**
76 * Reset the gyro.
77 *
78 * Resets the gyro to a heading of zero. This can be used if there is
79 * significant drift in the gyro and it needs to be recalibrated after it has
80 * been running.
81 */
82 void Reset() override;
83
84 /**
85 * Initialize the gyro.
86 *
87 * Calibrate the gyro by running for a number of samples and computing the
88 * center value. Then use the center value as the Accumulator center value for
89 * subsequent measurements.
90 *
91 * It's important to make sure that the robot is not moving while the
92 * centering calculations are in progress, this is typically done when the
93 * robot is first turned on while it's sitting at rest before the competition
94 * starts.
95 */
96 void Calibrate() final;
97
98 /**
99 * Get the SPI port number.
100 *
101 * @return The SPI port number.
102 */
103 int GetPort() const;
104
105 void InitSendable(wpi::SendableBuilder& builder) override;
106
107 private:
108 SPI m_spi;
109 SPI::Port m_port;
110 bool m_connected{false};
111
112 hal::SimDevice m_simDevice;
113 hal::SimBoolean m_simConnected;
114 hal::SimDouble m_simAngle;
115 hal::SimDouble m_simRate;
116
117 uint16_t ReadRegister(int reg);
118};
119
120} // namespace frc
Use a rate gyro to return the robots heading relative to a starting position.
Definition: ADXRS450_Gyro.h:33
int GetPort() const
Get the SPI port number.
double GetRate() const override
Return the rate of rotation of the gyro.
ADXRS450_Gyro & operator=(ADXRS450_Gyro &&)=default
void Calibrate() final
Initialize the gyro.
void Reset() override
Reset the gyro.
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
double GetAngle() const override
Return the actual angle in degrees that the robot is currently facing.
ADXRS450_Gyro()
Gyro constructor on onboard CS0.
ADXRS450_Gyro(ADXRS450_Gyro &&)=default
Interface for yaw rate gyros.
Definition: Gyro.h:16
SPI bus interface class.
Definition: SPI.h:26
Port
Definition: SPI.h:28
C++ wrapper around a HAL simulator boolean value handle.
Definition: SimDevice.h:610
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:644
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:535
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
::uint16_t uint16_t
Definition: Meta.h:54
Definition: AprilTagPoseEstimator.h:15
Definition: AprilTagFieldLayout.h:18