Package swervelib.imu

Class CanandgyroSwerve

java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.CanandgyroSwerve

public class CanandgyroSwerve extends SwerveIMU
SwerveIMU interface for the Boron Candandgyro by Redux Robotics
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    (package private) com.reduxrobotics.sensors.canandgyro.Canandgyro
    Boron Canandgyro by Redux Robotics.
    private boolean
    Inversion for the gyro
    private edu.wpi.first.math.geometry.Rotation3d
    Offset for the Boron Canandgyro.
    static double
    Wait time for status frames to show up.
  • Constructor Summary

    Constructors
    Constructor
    Description
    CanandgyroSwerve(int canid)
    Generate the SwerveIMU for Canandgyro.
  • 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.
    double
    Fetch the rotation rate from the IMU in degrees per second.
    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

    • STATUS_TIMEOUT_SECONDS

      public static double STATUS_TIMEOUT_SECONDS
      Wait time for status frames to show up.
    • imu

      com.reduxrobotics.sensors.canandgyro.Canandgyro imu
      Boron Canandgyro by Redux Robotics.
    • offset

      private edu.wpi.first.math.geometry.Rotation3d offset
      Offset for the Boron Canandgyro.
    • invertedIMU

      private boolean invertedIMU
      Inversion for the gyro
  • Constructor Details

    • CanandgyroSwerve

      public CanandgyroSwerve(int canid)
      Generate the SwerveIMU for Canandgyro.
      Parameters:
      canid - CAN ID for the Boron Canandgyro
  • 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.
    • getRate

      public double getRate()
      Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
      Specified by:
      getRate in class SwerveIMU
      Returns:
      Double of the rotation rate as an Optional.
    • getIMU

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