Class ADXRS450_Gyro

java.lang.Object
edu.wpi.first.wpilibj.ADXRS450_Gyro
All Implemented Interfaces:
Sendable, AutoCloseable

public class ADXRS450_Gyro
extends Object
implements Sendable, AutoCloseable
Use a rate gyro to return the robots heading relative to a starting position. The Gyro class tracks the robots heading based on the starting position. As the robot rotates the new heading is computed by integrating the rate of rotation returned by the sensor. When the class is instantiated, it does a short calibration routine where it samples the gyro while at rest to determine the default offset. This is subtracted from each sample to determine the heading.

This class is for the digital ADXRS450 gyro sensor that connects via SPI. Only one instance of an ADXRS Gyro is supported.

  • Constructor Details

  • Method Details

    • isConnected

      public boolean isConnected()
      Determine if the gyro is connected.
      Returns:
      true if it is connected, false otherwise.
    • calibrate

      public final void calibrate()
      Calibrate the gyro by running for a number of samples and computing the center value. Then use the center value as the Accumulator center value for subsequent measurements.

      It's important to make sure that the robot is not moving while the centering calculations are in progress, this is typically done when the robot is first turned on while it's sitting at rest before the competition starts.

    • getPort

      public int getPort()
      Get the SPI port number.
      Returns:
      The SPI port number.
    • reset

      public void reset()
      Reset the gyro.

      Resets the gyro to a heading of zero. This can be used if there is significant drift in the gyro, and it needs to be recalibrated after it has been running.

    • close

      public void close()
      Delete (free) the spi port used for the gyro and stop accumulating.
      Specified by:
      close in interface AutoCloseable
    • getAngle

      public double getAngle()
      Return the heading of the robot in degrees.

      The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

      The angle is expected to increase as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.

      This heading is based on integration of the returned rate from the gyro.

      Returns:
      the current heading of the robot in degrees.
    • getRate

      public double getRate()
      Return the rate of rotation of the gyro.

      The rate is based on the most recent reading of the gyro analog value

      The rate is expected to be positive as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.

      Returns:
      the current rate in degrees per second
    • getRotation2d

      Return the heading of the robot as a Rotation2d.

      The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

      The angle is expected to increase as the gyro turns counterclockwise when looked at from the top. It needs to follow the NWU axis convention.

      This heading is based on integration of the returned rate from the gyro.

      Returns:
      the current heading of the robot as a Rotation2d.
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Description copied from interface: Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - sendable builder