Package swervelib.imu
Class NavXSwerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.NavXSwerve
- All Implemented Interfaces:
AutoCloseable
Communicates with the NavX(
AHRS
) as the IMU.-
Constructor Summary
ConstructorsConstructorDescriptionNavXSwerve
(com.studica.frc.AHRS.NavXComType port) Constructor for the NavX(AHRS
) swerve. -
Method Summary
Modifier and TypeMethodDescriptionvoid
Clear sticky faults on IMU.void
close()
void
Reset offset to current gyro reading.getAccel()
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.getIMU()
Get the instantiated NavX(AHRS
) IMU object.Fetch theRotation3d
from the IMU without any zeroing.Fetch theRotation3d
from the IMU.Fetch the rotation rate from the IMU asMutAngularVelocity
void
setInverted
(boolean invertIMU) Set the gyro to invert its default directionvoid
setOffset
(Rotation3d offset) Set the gyro offset.
-
Constructor Details
-
Method Details
-
close
public void close()- Specified by:
close
in interfaceAutoCloseable
- Specified by:
close
in classSwerveIMU
-
factoryDefault
public void factoryDefault()Reset offset to current gyro reading. Does not call NavX(AHRS.reset()
) because it has been reported to be too slow.- Specified by:
factoryDefault
in classSwerveIMU
-
clearStickyFaults
public void clearStickyFaults()Clear sticky faults on IMU.- Specified by:
clearStickyFaults
in classSwerveIMU
-
setOffset
Set the gyro offset.- Specified by:
setOffset
in classSwerveIMU
- Parameters:
offset
- gyro offset as aRotation3d
.
-
setInverted
public void setInverted(boolean invertIMU) Set the gyro to invert its default direction- Specified by:
setInverted
in classSwerveIMU
- Parameters:
invertIMU
- invert gyro direction
-
getRawRotation3d
Fetch theRotation3d
from the IMU without any zeroing. Robot relative.- Specified by:
getRawRotation3d
in classSwerveIMU
- Returns:
Rotation3d
from the IMU.
-
getRotation3d
Fetch theRotation3d
from the IMU. Robot relative.- Specified by:
getRotation3d
in classSwerveIMU
- Returns:
Rotation3d
from 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:
getAccel
in classSwerveIMU
- Returns:
Translation3d
of the acceleration as anOptional
.
-
getYawAngularVelocity
Description copied from class:SwerveIMU
Fetch the rotation rate from the IMU asMutAngularVelocity
- Specified by:
getYawAngularVelocity
in classSwerveIMU
- Returns:
MutAngularVelocity
of the rotation rate.
-
getIMU
Get the instantiated NavX(AHRS
) IMU object.
-