Package swervelib.imu
Class SwerveIMU
java.lang.Object
swervelib.imu.SwerveIMU
- Direct Known Subclasses:
ADIS16448Swerve,ADIS16470Swerve,ADXRS450Swerve,AnalogGyroSwerve,NavXSwerve,Pigeon2Swerve,PigeonSwerve
Swerve IMU abstraction to define a standard interface with a swerve drive.
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionabstract voidClear sticky faults on IMU.abstract voidReset IMU to factory default.abstract Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()Fetch the acceleration [x, y, z] from the IMU in meters per second squared.abstract ObjectgetIMU()Get the instantiated IMU object.abstract edu.wpi.first.math.geometry.Rotation3dFetch theRotation3dfrom the IMU without any zeroing.abstract edu.wpi.first.math.geometry.Rotation3dFetch theRotation3dfrom the IMU.abstract voidsetOffset(edu.wpi.first.math.geometry.Rotation3d offset) Set the gyro offset.
-
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 aRotation3d.
-
getRawRotation3d
public abstract edu.wpi.first.math.geometry.Rotation3d getRawRotation3d()Fetch theRotation3dfrom the IMU without any zeroing. Robot relative.- Returns:
Rotation3dfrom the IMU.
-
getRotation3d
public abstract edu.wpi.first.math.geometry.Rotation3d getRotation3d()Fetch theRotation3dfrom the IMU. Robot relative.- Returns:
Rotation3dfrom the IMU.
-
getAccel
Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns empty.- Returns:
Translation3dof the acceleration as anOptional.
-
getIMU
Get the instantiated IMU object.- Returns:
- IMU object.
-