Package swervelib.imu

Class PigeonSwerve

java.lang.Object
swervelib.imu.SwerveIMU
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_PigeonIMU
    Pigeon v1 IMU device.
  • Constructor Summary

    Constructors
    Constructor
    Description
    PigeonSwerve(int canid)
    Generate the SwerveIMU for pigeon.
  • Method Summary

    Modifier and Type
    Method
    Description
    void
    Clear sticky faults on IMU.
    void
    Reset IMU to factory default.
    Get the instantiated IMU object.
    void
    getYawPitchRoll(double[] yprArray)
    Fetch the yaw/pitch/roll from the IMU, inverts them all if SwerveIMU is inverted.
    void
    setYaw(double yaw)
    Set the yaw in degrees.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • imu

      com.ctre.phoenix.sensors.WPI_PigeonIMU imu
      Pigeon 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:
      factoryDefault in class SwerveIMU
    • clearStickyFaults

      public void clearStickyFaults()
      Clear sticky faults on IMU.
      Specified by:
      clearStickyFaults in class SwerveIMU
    • setYaw

      public void setYaw(double yaw)
      Set the yaw in degrees.
      Specified by:
      setYaw in class SwerveIMU
      Parameters:
      yaw - Angle 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:
      getYawPitchRoll in class SwerveIMU
      Parameters:
      yprArray - Array which will be filled with {yaw, pitch, roll} in degrees.
    • getIMU

      public Object getIMU()
      Get the instantiated IMU object.
      Specified by:
      getIMU in class SwerveIMU
      Returns:
      IMU object.