Class WPI_Pigeon2

All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj.interfaces.Gyro, AutoCloseable

public class WPI_Pigeon2 extends Pigeon2 implements edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj.interfaces.Gyro
  • Constructor Details

    • WPI_Pigeon2

      public WPI_Pigeon2(int deviceNumber, String canbus)
      Constructor for Pigeon 2.
      Parameters:
      deviceNumber - device ID of Pigeon 2
      canbus - Name of the CANbus; can be a CANivore device name or serial number. Pass in nothing or "rio" to use the roboRIO.
    • WPI_Pigeon2

      public WPI_Pigeon2(int deviceNumber)
      Constructor for Pigeon 2.
      Parameters:
      deviceNumber - device ID of Pigeon 2
  • Method Details

    • close

      public void close()
      Specified by:
      close in interface AutoCloseable
    • calibrate

      public void calibrate()
      This function does nothing, it exists to satisfy the WPILib Gyro interface. Pigeon does calibration on boot and any one-time calibrations (like temperature) are done via Phoenix Tuner.
      Specified by:
      calibrate in interface edu.wpi.first.wpilibj.interfaces.Gyro
    • reset

      public void reset()
      Description copied from interface: edu.wpi.first.wpilibj.interfaces.Gyro
      Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is significant drift in the gyro and it needs to be recalibrated after it has been running.
      Specified by:
      reset in interface edu.wpi.first.wpilibj.interfaces.Gyro
    • getAngle

      public double getAngle()
      Description copied from interface: edu.wpi.first.wpilibj.interfaces.Gyro
      Return the heading of the robot in degrees.

      The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

      The angle is expected to increase as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.

      This heading is based on integration of the returned rate from the gyro.

      Specified by:
      getAngle in interface edu.wpi.first.wpilibj.interfaces.Gyro
      Returns:
      the current heading of the robot in degrees.
    • getRate

      public double getRate()
      Description copied from interface: edu.wpi.first.wpilibj.interfaces.Gyro
      Return the rate of rotation of the gyro.

      The rate is based on the most recent reading of the gyro analog value

      The rate is expected to be positive as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.

      Specified by:
      getRate in interface edu.wpi.first.wpilibj.interfaces.Gyro
      Returns:
      the current rate in degrees per second
    • getRotation2d

      public edu.wpi.first.math.geometry.Rotation2d getRotation2d()
      Description copied from interface: edu.wpi.first.wpilibj.interfaces.Gyro
      Return the heading of the robot as a Rotation2d.

      The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.

      The angle is expected to increase as the gyro turns counterclockwise when looked at from the top. It needs to follow the NWU axis convention.

      This heading is based on integration of the returned rate from the gyro.

      Specified by:
      getRotation2d in interface edu.wpi.first.wpilibj.interfaces.Gyro
      Returns:
      the current heading of the robot as a Rotation2d.
    • initSendable

      public void initSendable(edu.wpi.first.util.sendable.SendableBuilder builder)
      Description copied from interface: edu.wpi.first.util.sendable.Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface edu.wpi.first.util.sendable.Sendable
      Parameters:
      builder - sendable builder