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