Package swervelib.imu
Class PigeonSwerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.PigeonSwerve
SwerveIMU interface for the
WPI_PigeonIMU
.-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionvoid
Clear sticky faults on IMU.void
Reset IMU to factory default.getAccel()
Fetch the acceleration [x, y, z] from the IMU in meters per second squared.getIMU()
Get the instantiatedWPI_PigeonIMU
IMU object.double
getRate()
Fetch the rotation rate from the IMU in degrees per second.Fetch theRotation3d
from the IMU without any zeroing.Fetch theRotation3d
from the IMU.void
setInverted
(boolean invertIMU) Set the gyro to invert its default directionvoid
setOffset
(Rotation3d offset) Set the gyro offset.
-
Constructor Details
-
PigeonSwerve
public PigeonSwerve(int canid) Generate the SwerveIMU forWPI_PigeonIMU
.- Parameters:
canid
- CAN ID for theWPI_PigeonIMU
, does not support CANBus.
-
-
Method Details
-
factoryDefault
public void factoryDefault()Reset IMU to factory default.- 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
.
-
getRate
public double getRate()Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty. -
getIMU
Get the instantiatedWPI_PigeonIMU
IMU object.
-