Package swervelib.imu
Class NavXSwerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.NavXSwerve
Communicates with the NavX as the IMU.
-
Constructor Summary
ConstructorsConstructorDescriptionNavXSwerve(edu.wpi.first.wpilibj.I2C.Port port) Constructor for the NavX swerve.NavXSwerve(edu.wpi.first.wpilibj.SerialPort.Port port) Constructor for the NavX swerve.NavXSwerve(edu.wpi.first.wpilibj.SPI.Port port) Constructor for the NavX swerve. -
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.voidsetOffset(edu.wpi.first.math.geometry.Rotation3d offset) Set the gyro offset.
-
Constructor Details
-
NavXSwerve
public NavXSwerve(edu.wpi.first.wpilibj.SerialPort.Port port) Constructor for the NavX swerve.- Parameters:
port- Serial Port to connect to.
-
NavXSwerve
public NavXSwerve(edu.wpi.first.wpilibj.SPI.Port port) Constructor for the NavX swerve.- Parameters:
port- SPI Port to connect to.
-
NavXSwerve
public NavXSwerve(edu.wpi.first.wpilibj.I2C.Port port) Constructor for the NavX swerve.- Parameters:
port- I2C Port to connect to.
-
-
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. -
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.
-