Package swervelib.imu
Class PigeonSwerve
java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.PigeonSwerve
SwerveIMU interface for the Pigeon.
-
Field Summary
FieldsModifier and TypeFieldDescription(package private) com.ctre.phoenix.sensors.WPI_PigeonIMUPigeon v1 IMU device. -
Constructor Summary
Constructors -
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, inverts them all if SwerveIMU is inverted.voidsetYaw(double yaw) Set the yaw in degrees.
-
Field Details
-
imu
com.ctre.phoenix.sensors.WPI_PigeonIMU imuPigeon v1 IMU device.
-
-
Constructor Details
-
PigeonSwerve
public PigeonSwerve(int canid) Generate the SwerveIMU for pigeon.- Parameters:
canid- CAN ID for the pigeon, does not support CANBus.
-
-
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, inverts them all if SwerveIMU is inverted.- Specified by:
getYawPitchRollin classSwerveIMU- Parameters:
yprArray- Array which will be filled with {yaw, pitch, roll} in degrees.
-
getIMU
Get the instantiated IMU object.
-