Class WPI_Pigeon2

All Implemented Interfaces:
Sendable, AutoCloseable

@Deprecated(since="2024",
            forRemoval=true)
public class WPI_Pigeon2
extends Pigeon2
implements Sendable, AutoCloseable
Deprecated, for removal: This API element is subject to removal in a future version.
This device's Phoenix 5 API is deprecated for removal in the 2025 season. Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API. A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.

If the Phoenix 5 API must be used for this device, the device must have 22.X firmware. This firmware is available in Tuner X after selecting Phoenix 5 in the firmware year dropdown.

Pigeon 2 Class. Class supports communicating over CANbus.
  • Constructor Details

    • WPI_Pigeon2

      public WPI_Pigeon2​(int deviceNumber, String canbus)
      Deprecated, for removal: This API element is subject to removal in a future version.
      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)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Constructor for Pigeon 2.
      Parameters:
      deviceNumber - device ID of Pigeon 2
  • Method Details

    • close

      public void close()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Specified by:
      close in interface AutoCloseable
    • reset

      public void reset()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Resets the Pigeon 2 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.

    • getAngle

      public double getAngle()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the heading of the robot in degrees.

      The angle increases as the Pigeon 2 turns clockwise when looked at from the top. This follows the NED axis convention.

      The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.

      Returns:
      The current heading of the robot in degrees
    • getRate

      public double getRate()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the rate of rotation of the Pigeon 2.

      The rate is positive as the Pigeon 2 turns clockwise when looked at from the top.

      Returns:
      The current rate in degrees per second
    • getRotation2d

      Deprecated, for removal: This API element is subject to removal in a future version.
      Returns the heading of the robot as a Rotation2d.

      The angle increases as the Pigeon 2 turns counterclockwise when looked at from the top. This follows the NWU axis convention.

      The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.

      Returns:
      The current heading of the robot as a Rotation2d
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Specified by:
      initSendable in interface Sendable