Package swervelib.imu

Class AnalogGyroSwerve

java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.AnalogGyroSwerve

public class AnalogGyroSwerve extends SwerveIMU
Creates a IMU for AnalogGyro devices, only uses yaw.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    private final edu.wpi.first.wpilibj.AnalogGyro
    Gyroscope object.
    private boolean
    Inversion for the gyro
    private edu.wpi.first.math.geometry.Rotation3d
    Offset for the analog gyro.
  • Constructor Summary

    Constructors
    Constructor
    Description
    AnalogGyroSwerve(int channel)
    Analog port in which the gyroscope is connected.
  • Method Summary

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

    • gyro

      private final edu.wpi.first.wpilibj.AnalogGyro gyro
      Gyroscope object.
    • offset

      private edu.wpi.first.math.geometry.Rotation3d offset
      Offset for the analog gyro.
    • invertedIMU

      private boolean invertedIMU
      Inversion for the gyro
  • Constructor Details

    • AnalogGyroSwerve

      public AnalogGyroSwerve(int channel)
      Analog port in which the gyroscope is connected. Can only be attached to analog ports 0 or 1.
      Parameters:
      channel - Analog port 0 or 1.
  • Method Details

    • factoryDefault

      public void factoryDefault()
      Reset IMU to factory default.
      Specified by:
      factoryDefault in class SwerveIMU
    • clearStickyFaults

      public void clearStickyFaults()
      Clear sticky faults on IMU.
      Specified by:
      clearStickyFaults in class SwerveIMU
    • setOffset

      public void setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
      Set the gyro offset.
      Specified by:
      setOffset in class SwerveIMU
      Parameters:
      offset - gyro offset as a Rotation3d.
    • setInverted

      public void setInverted(boolean invertIMU)
      Set the gyro to invert its default direction
      Specified by:
      setInverted in class SwerveIMU
      Parameters:
      invertIMU - invert gyro direction
    • getRawRotation3d

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

      public edu.wpi.first.math.geometry.Rotation3d getRotation3d()
      Fetch the Rotation3d from the IMU. Robot relative.
      Specified by:
      getRotation3d in class SwerveIMU
      Returns:
      Rotation3d from the IMU.
    • getAccel

      public 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.
      Specified by:
      getAccel in class SwerveIMU
      Returns:
      Translation3d of the acceleration as an Optional.
    • getIMU

      public Object getIMU()
      Get the instantiated IMU object.
      Specified by:
      getIMU in class SwerveIMU
      Returns:
      IMU object.