Package swervelib.imu

Class Pigeon2Swerve

java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.Pigeon2Swerve

public class Pigeon2Swerve extends SwerveIMU
SwerveIMU interface for the Pigeon2
  • Constructor Details

    • Pigeon2Swerve

      public Pigeon2Swerve(int canid, String canbus)
      Generate the SwerveIMU for pigeon.
      Parameters:
      canid - CAN ID for the pigeon
      canbus - CAN Bus name the pigeon resides on.
    • Pigeon2Swerve

      public Pigeon2Swerve(int canid)
      Generate the SwerveIMU for pigeon.
      Parameters:
      canid - CAN ID for the pigeon
  • 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.
    • 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.