Class PigeonSwerve
- java.lang.Object
-
- frc.robot.subsystems.swervedrive2.swervelib.imu.SwerveIMU
-
- frc.robot.subsystems.swervedrive2.swervelib.imu.PigeonSwerve
-
public class PigeonSwerve extends SwerveIMU
SwerveIMU interface for the Pigeon.
-
-
Field Summary
Fields Modifier and Type Field Description (package private) com.ctre.phoenix.sensors.WPI_PigeonIMUimu
-
Constructor Summary
Constructors Constructor Description PigeonSwerve(int canid)Generate the SwerveIMU for pigeon.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidclearStickyFaults()Clear sticky faults on IMU.voidfactoryDefault()Reset IMU to factory default.ObjectgetIMU()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.
-
-
-
Method Detail
-
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.
-
-