Class Pigeon2

All Implemented Interfaces:
Sendable, AutoCloseable

public class Pigeon2
extends CorePigeon2
implements Sendable, AutoCloseable
  • Constructor Details

    • Pigeon2

      public Pigeon2​(int deviceId)
      Constructs a new Pigeon 2 sensor object.

      Constructs the device using the default CAN bus for the system:

      • "rio" on roboRIO
      • "can0" on Linux
      • "*" on Windows
      Parameters:
      deviceId - ID of the device, as configured in Phoenix Tuner.
    • Pigeon2

      public Pigeon2​(int deviceId, String canbus)
      Constructs a new Pigeon 2 sensor object.
      Parameters:
      deviceId - ID of the device, as configured in Phoenix Tuner.
      canbus - Name of the CAN bus this device is on. Possible CAN bus strings are:
      • "rio" for the native roboRIO CAN bus
      • CANivore name or serial number
      • SocketCAN interface (non-FRC Linux only)
      • "*" for any CANivore seen by the program
      • empty string (default) to select the default for the system:
        • "rio" on roboRIO
        • "can0" on Linux
        • "*" on Windows
  • Method Details

    • close

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

      public void reset()
      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()
      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()
      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

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

      Returns the orientation of the robot as a Rotation3d created from the quaternion signals.
      Returns:
      The current orientation of the robot as a Rotation3d
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Specified by:
      initSendable in interface Sendable