Package swervelib.imu
Class ADIS16448Swerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.ADIS16448Swerve
IMU Swerve class for the
ADIS16448_IMU device.-
Field Summary
FieldsModifier and TypeFieldDescriptionprivate final edu.wpi.first.wpilibj.ADIS16448_IMUADIS16448_IMUdevice to read the current headings from.private booleanInversion for the gyroprivate edu.wpi.first.math.geometry.Rotation3dOffset for the ADIS16448. -
Constructor Summary
ConstructorsConstructorDescriptionConstruct the ADIS16448 imu and reset default configurations. -
Method Summary
Modifier and TypeMethodDescriptionvoidClear sticky faults on IMU.voidReset IMU to factory default.Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()Fetch the acceleration [x, y, z] from the IMU in meters per second squared.getIMU()Get the instantiated IMU object.edu.wpi.first.math.geometry.Rotation3dFetch theRotation3dfrom the IMU without any zeroing.edu.wpi.first.math.geometry.Rotation3dFetch theRotation3dfrom the IMU.voidsetInverted(boolean invertIMU) Set the gyro to invert its default directionvoidsetOffset(edu.wpi.first.math.geometry.Rotation3d offset) Set the gyro offset.
-
Field Details
-
imu
private final edu.wpi.first.wpilibj.ADIS16448_IMU imuADIS16448_IMUdevice to read the current headings from. -
offset
private edu.wpi.first.math.geometry.Rotation3d offsetOffset for the ADIS16448. -
invertedIMU
private boolean invertedIMUInversion for the gyro
-
-
Constructor Details
-
ADIS16448Swerve
public ADIS16448Swerve()Construct the ADIS16448 imu and reset default configurations. Publish the gyro to the SmartDashboard.
-
-
Method Details
-
factoryDefault
public void factoryDefault()Reset IMU to factory default.- Specified by:
factoryDefaultin classSwerveIMU
-
clearStickyFaults
public void clearStickyFaults()Clear sticky faults on IMU.- Specified by:
clearStickyFaultsin classSwerveIMU
-
setOffset
public void setOffset(edu.wpi.first.math.geometry.Rotation3d offset) Set the gyro offset. -
setInverted
public void setInverted(boolean invertIMU) Set the gyro to invert its default direction- Specified by:
setInvertedin classSwerveIMU- Parameters:
invertIMU- invert gyro direction
-
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d()Fetch theRotation3dfrom the IMU without any zeroing. Robot relative.- Specified by:
getRawRotation3din classSwerveIMU- Returns:
Rotation3dfrom the IMU.
-
getRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRotation3d()Fetch theRotation3dfrom the IMU. Robot relative.- Specified by:
getRotation3din classSwerveIMU- 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. -
getIMU
Get the instantiated IMU object.
-