WPILibC++ 2024.3.2
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 <units/angle.h>
8
10
11namespace frc {
12
13/**
14 * Interface for yaw rate gyros.
15 *
16 * @deprecated This interface is being removed with no replacement.
17 */
18class [[deprecated(
19 "This interface is being removed with no replacement.")]] Gyro {
20 public:
21 Gyro() = default;
22 virtual ~Gyro() = default;
23
24 Gyro(Gyro&&) = default;
25 Gyro& operator=(Gyro&&) = default;
26
27 /**
28 * Calibrate the gyro. It's important to make sure that the robot is not
29 * moving while the calibration is in progress, this is typically
30 * done when the robot is first turned on while it's sitting at rest before
31 * the match starts.
32 */
33 virtual void Calibrate() = 0;
34
35 /**
36 * Reset the gyro. Resets the gyro to a heading of zero. This can be used if
37 * there is significant drift in the gyro and it needs to be recalibrated
38 * after it has been running.
39 */
40 virtual void Reset() = 0;
41
42 /**
43 * Return the heading of the robot in degrees.
44 *
45 * The angle is continuous, that is it will continue from 360 to 361 degrees.
46 * This allows algorithms that wouldn't want to see a discontinuity in the
47 * gyro output as it sweeps past from 360 to 0 on the second time around.
48 *
49 * The angle is expected to increase as the gyro turns clockwise when looked
50 * at from the top. It needs to follow the NED axis convention.
51 *
52 * @return the current heading of the robot in degrees. This heading is based
53 * on integration of the returned rate from the gyro.
54 */
55 virtual double GetAngle() const = 0;
56
57 /**
58 * Return the rate of rotation of the gyro.
59 *
60 * The rate is based on the most recent reading of the gyro analog value.
61 *
62 * The rate is expected to be positive as the gyro turns clockwise when looked
63 * at from the top. It needs to follow the NED axis convention.
64 *
65 * @return the current rate in degrees per second
66 */
67 virtual double GetRate() const = 0;
68
69 /**
70 * Return the heading of the robot as a Rotation2d.
71 *
72 * The angle is continuous, that is it will continue from 360 to 361 degrees.
73 * This allows algorithms that wouldn't want to see a discontinuity in the
74 * gyro output as it sweeps past from 360 to 0 on the second time around.
75 *
76 * The angle is expected to increase as the gyro turns counterclockwise when
77 * looked at from the top. It needs to follow the NWU axis convention.
78 *
79 * @return the current heading of the robot as a Rotation2d. This heading is
80 * based on integration of the returned rate from the gyro.
81 */
82 virtual Rotation2d GetRotation2d() const {
83 return units::degree_t{-GetAngle()};
84 }
85};
86
87} // namespace frc
Interface for yaw rate gyros.
Definition: Gyro.h:19
virtual double GetRate() const =0
Return the rate of rotation of the gyro.
virtual double GetAngle() const =0
Return the heading of the robot in degrees.
virtual void Calibrate()=0
Calibrate the gyro.
virtual ~Gyro()=default
Gyro()=default
Gyro & operator=(Gyro &&)=default
virtual Rotation2d GetRotation2d() const
Return the heading of the robot as a Rotation2d.
Definition: Gyro.h:82
virtual void Reset()=0
Reset the gyro.
Gyro(Gyro &&)=default
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Definition: AprilTagPoseEstimator.h:15