Package swervelib.imu

Class Pigeon2Swerve

java.lang.Object
swervelib.imu.SwerveIMU
swervelib.imu.Pigeon2Swerve

public class Pigeon2Swerve extends SwerveIMU
SwerveIMU interface for the Pigeon2
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    (package private) com.ctre.phoenix.sensors.WPI_Pigeon2
    Pigeon2 IMU device.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Pigeon2Swerve(int canid)
    Generate the SwerveIMU for pigeon.
    Pigeon2Swerve(int canid, String canbus)
    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_Pigeon2 imu
      Pigeon2 IMU device.
  • Constructor Details

    • Pigeon2Swerve

      public Pigeon2Swerve(int canid, String canbus)
      Generate the SwerveIMU for pigeon.
      Parameters:
      canid - CAN ID for the pigeon
      canbus - CAN Bus name the pigeon resides on.
    • Pigeon2Swerve

      public Pigeon2Swerve(int canid)
      Generate the SwerveIMU for pigeon.
      Parameters:
      canid - CAN ID for the pigeon
  • 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.