Class WPI_PigeonIMU

All Implemented Interfaces:
Sendable, AutoCloseable

public class WPI_PigeonIMU
extends PigeonIMU
implements Sendable, AutoCloseable
  • Constructor Details

  • Method Details

    • close

      public void close()
      Specified by:
      close in interface AutoCloseable
    • reset

      public void reset()
      Resets the Pigeon IMU 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.

    • getAngle

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

      The angle increases as the Pigeon IMU turns clockwise when looked at from the top. This follows the NED axis convention.

      The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.

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

      public double getRate()
      Returns the rate of rotation of the Pigeon IMU.

      The rate is positive as the Pigeon IMU turns clockwise when looked at from the top.

      Returns:
      The current rate in degrees per second
    • getRotation2d

      Returns the heading of the robot as a Rotation2d.

      The angle increases as the Pigeon IMU turns counterclockwise when looked at from the top. This follows the NWU axis convention.

      The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.

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

      public void initSendable​(SendableBuilder builder)
      Specified by:
      initSendable in interface Sendable