Package swervelib.imu
Class SwerveIMU
java.lang.Object
swervelib.imu.SwerveIMU
- All Implemented Interfaces:
AutoCloseable
- Direct Known Subclasses:
ADIS16448Swerve,ADIS16470Swerve,ADXRS450Swerve,AnalogGyroSwerve,CanandgyroSwerve,NavXSwerve,Pigeon2Swerve,PigeonSwerve,PigeonViaTalonSRXSwerve
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 voidclose()abstract voidReset IMU to factory default.abstract Optional<Translation3d>getAccel()Fetch the acceleration [x, y, z] from the IMU in meters per second squared.abstract ObjectgetIMU()Get the instantiated IMU object.abstract Rotation3dFetch theRotation3dfrom the IMU without any zeroing.abstract Rotation3dFetch theRotation3dfrom the IMU.abstract MutAngularVelocityFetch the rotation rate from the IMU asMutAngularVelocityabstract voidsetInverted(boolean invertIMU) Set the gyro to invert its default direction.abstract voidsetOffset(Rotation3d offset) Set the gyro offset.
-
Constructor Details
-
SwerveIMU
public SwerveIMU()
-
-
Method Details
-
close
public abstract void close()- Specified by:
closein interfaceAutoCloseable
-
factoryDefault
public abstract void factoryDefault()Reset IMU to factory default. -
clearStickyFaults
public abstract void clearStickyFaults()Clear sticky faults on IMU. -
setOffset
Set the gyro offset.- Parameters:
offset- gyro offset as aRotation3d.
-
setInverted
public abstract void setInverted(boolean invertIMU) Set the gyro to invert its default direction.- Parameters:
invertIMU- gyro direction
-
getRawRotation3d
Fetch theRotation3dfrom the IMU without any zeroing. Robot relative.- Returns:
Rotation3dfrom the IMU.
-
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.
-
getYawAngularVelocity
Fetch the rotation rate from the IMU asMutAngularVelocity- Returns:
MutAngularVelocityof the rotation rate.
-
getIMU
Get the instantiated IMU object.- Returns:
- IMU object.
-