Package swervelib.imu
Class ADIS16448Swerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.ADIS16448Swerve
IMU Swerve class for the
ADIS16448_IMU device.-
Field Summary
Fields -
Constructor Summary
ConstructorsConstructorDescriptionConstruct the ADIS16448 imu and reset default configurations. -
Method Summary
Modifier and TypeMethodDescriptionvoidClear sticky faults on IMU.voidReset IMU to factory default.getIMU()Get the instantiated IMU object.voidgetYawPitchRoll(double[] yprArray) Fetch the yaw/pitch/roll from the IMU.voidsetYaw(double yaw) Set the yaw in degrees.
-
Field Details
-
imu
private final edu.wpi.first.wpilibj.ADIS16448_IMU imuADIS16448_IMUdevice to read the current headings from. -
yawOffset
private double yawOffsetOffset for the ADIS16448 yaw reading.
-
-
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
-
setYaw
public void setYaw(double yaw) Set the yaw in degrees. -
getYawPitchRoll
public void getYawPitchRoll(double[] yprArray) Fetch the yaw/pitch/roll from the IMU.- Specified by:
getYawPitchRollin classSwerveIMU- Parameters:
yprArray- Array which will be filled with {yaw, pitch, roll} in degrees.
-
getIMU
Get the instantiated IMU object.
-