Package swervelib.imu

Class SwerveIMU

java.lang.Object
swervelib.imu.SwerveIMU
Direct Known Subclasses:
ADIS16448Swerve, ADIS16470Swerve, ADXRS450Swerve, AnalogGyroSwerve, NavXSwerve, Pigeon2Swerve, PigeonSwerve

public abstract class SwerveIMU extends Object
Swerve IMU abstraction to define a standard interface with a swerve drive.
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    abstract void
    Clear sticky faults on IMU.
    abstract void
    Reset IMU to factory default.
    abstract Optional<edu.wpi.first.math.geometry.Translation3d>
    Fetch the acceleration [x, y, z] from the IMU in meters per second squared.
    abstract Object
    Get the instantiated IMU object.
    abstract edu.wpi.first.math.geometry.Rotation3d
    Fetch the Rotation3d from the IMU without any zeroing.
    abstract edu.wpi.first.math.geometry.Rotation3d
    Fetch the Rotation3d from the IMU.
    abstract void
    setInverted(boolean invertIMU)
    Set the gyro to invert its default direction.
    abstract void
    setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
    Set the gyro offset.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • SwerveIMU

      public SwerveIMU()
  • Method Details

    • factoryDefault

      public abstract void factoryDefault()
      Reset IMU to factory default.
    • clearStickyFaults

      public abstract void clearStickyFaults()
      Clear sticky faults on IMU.
    • setOffset

      public abstract void setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
      Set the gyro offset.
      Parameters:
      offset - gyro offset as a Rotation3d.
    • setInverted

      public abstract void setInverted(boolean invertIMU)
      Set the gyro to invert its default direction.
      Parameters:
      invertIMU - gyro direction
    • getRawRotation3d

      public abstract edu.wpi.first.math.geometry.Rotation3d getRawRotation3d()
      Fetch the Rotation3d from the IMU without any zeroing. Robot relative.
      Returns:
      Rotation3d from the IMU.
    • getRotation3d

      public abstract edu.wpi.first.math.geometry.Rotation3d getRotation3d()
      Fetch the Rotation3d from the IMU. Robot relative.
      Returns:
      Rotation3d from the IMU.
    • getAccel

      public abstract Optional<edu.wpi.first.math.geometry.Translation3d> getAccel()
      Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns empty.
      Returns:
      Translation3d of the acceleration as an Optional.
    • getIMU

      public abstract Object getIMU()
      Get the instantiated IMU object.
      Returns:
      IMU object.