001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj.interfaces;
006
007import edu.wpi.first.math.geometry.Rotation2d;
008
009/**
010 * Interface for yaw rate gyros.
011 *
012 * @deprecated This interface is being removed with no replacement.
013 */
014@Deprecated(since = "2024", forRemoval = true)
015public interface Gyro extends AutoCloseable {
016  /**
017   * Calibrate the gyro. It's important to make sure that the robot is not moving while the
018   * calibration is in progress, this is typically done when the robot is first turned on while it's
019   * sitting at rest before the match starts.
020   */
021  void calibrate();
022
023  /**
024   * Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is significant
025   * drift in the gyro, and it needs to be recalibrated after it has been running.
026   */
027  void reset();
028
029  /**
030   * Return the heading of the robot in degrees.
031   *
032   * <p>The angle is continuous, that is it will continue from 360 to 361 degrees. This allows
033   * algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from
034   * 360 to 0 on the second time around.
035   *
036   * <p>The angle is expected to increase as the gyro turns clockwise when looked at from the top.
037   * It needs to follow the NED axis convention.
038   *
039   * <p>This heading is based on integration of the returned rate from the gyro.
040   *
041   * @return the current heading of the robot in degrees.
042   */
043  double getAngle();
044
045  /**
046   * Return the rate of rotation of the gyro.
047   *
048   * <p>The rate is based on the most recent reading of the gyro analog value
049   *
050   * <p>The rate is expected to be positive as the gyro turns clockwise when looked at from the top.
051   * It needs to follow the NED axis convention.
052   *
053   * @return the current rate in degrees per second
054   */
055  double getRate();
056
057  /**
058   * Return the heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}.
059   *
060   * <p>The angle is continuous, that is it will continue from 360 to 361 degrees. This allows
061   * algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from
062   * 360 to 0 on the second time around.
063   *
064   * <p>The angle is expected to increase as the gyro turns counterclockwise when looked at from the
065   * top. It needs to follow the NWU axis convention.
066   *
067   * <p>This heading is based on integration of the returned rate from the gyro.
068   *
069   * @return the current heading of the robot as a {@link edu.wpi.first.math.geometry.Rotation2d}.
070   */
071  default Rotation2d getRotation2d() {
072    return Rotation2d.fromDegrees(-getAngle());
073  }
074}