Class Pigeon2Swerve


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

      • imu

        com.ctre.phoenix.sensors.WPI_Pigeon2 imu
        Pigeon2 IMU device.
    • Constructor Detail

      • 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 Detail

      • 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.