Package swervelib.imu
Class AnalogGyroSwerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.AnalogGyroSwerve
- All Implemented Interfaces:
AutoCloseable
Creates a IMU for
AnalogGyro devices, only uses yaw.-
Constructor Summary
ConstructorsConstructorDescriptionAnalogGyroSwerve(int channel) Analog port in which the gyroscope is connected. -
Method Summary
Modifier and TypeMethodDescriptionvoidClear sticky faults on IMU.voidclose()voidReset IMU to factory default.getAccel()Fetch the acceleration [x, y, z] from the IMU in meters per second squared.getIMU()Get the instantiated IMU object.Fetch theRotation3dfrom the IMU without any zeroing.Fetch theRotation3dfrom the IMU.Fetch the rotation rate from the IMU asMutAngularVelocityvoidsetInverted(boolean invertIMU) Set the gyro to invert its default directionvoidsetOffset(Rotation3d offset) Set the gyro offset.
-
Constructor Details
-
AnalogGyroSwerve
public AnalogGyroSwerve(int channel) Analog port in which the gyroscope is connected. Can only be attached to analog ports 0 or 1.- Parameters:
channel- Analog port 0 or 1.
-
-
Method Details
-
close
public void close()- Specified by:
closein interfaceAutoCloseable- Specified by:
closein classSwerveIMU
-
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
Set the gyro offset.- Specified by:
setOffsetin classSwerveIMU- Parameters:
offset- gyro offset as aRotation3d.
-
setInverted
public void setInverted(boolean invertIMU) Set the gyro to invert its default direction- Specified by:
setInvertedin classSwerveIMU- Parameters:
invertIMU- invert gyro direction
-
getRawRotation3d
Fetch theRotation3dfrom the IMU without any zeroing. Robot relative.- Specified by:
getRawRotation3din classSwerveIMU- Returns:
Rotation3dfrom the IMU.
-
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.- Specified by:
getAccelin classSwerveIMU- Returns:
Translation3dof the acceleration as anOptional.
-
getYawAngularVelocity
Description copied from class:SwerveIMUFetch the rotation rate from the IMU asMutAngularVelocity- Specified by:
getYawAngularVelocityin classSwerveIMU- Returns:
MutAngularVelocityof the rotation rate.
-
getIMU
Get the instantiated IMU object.
-