Class Pigeon2

java.lang.Object
com.ctre.phoenix.sensors.BasePigeon
com.ctre.phoenix.sensors.Pigeon2
Direct Known Subclasses:
WPI_Pigeon2

@Deprecated(since="2024",
            forRemoval=true)
public class Pigeon2
extends BasePigeon
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.
 
 // Example usage of a Pigeon 2
 Pigeon2 pigeon = new Pigeon2(0); // creates a new Pigeon2 with ID 0

 Pigeon2Configuration config = new Pigeon2Configuration();
 // set mount pose as rolled 90 degrees counter-clockwise
 config.MountPoseYaw = 0;
 config.MountPosePitch = 0;
 config.MountPoseRoll = 90;
 pigeon.configAllSettings(config);

 System.out.println(pigeon.getYaw()); // prints the yaw of the Pigeon
 System.out.println(pigeon.getPitch()); // prints the pitch of the Pigeon
 System.out.println(pigeon.getRoll()); // prints the roll of the Pigeon

 double gravityVec[] = new double[3];
 pigeon.getGravityVector(gravityVec); // gets the gravity vector of the Pigeon 2

 ErrorCode error = pigeon.getLastError(); // gets the last error generated by the Pigeon
 Pigeon2_Faults faults = new Pigeon2_Faults();
 ErrorCode faultsError = pigeon.getFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated
 
 
  • Constructor Details

    • Pigeon2

      public Pigeon2​(int deviceNumber, String canbus)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Create a Pigeon object that communicates with Pigeon on CAN Bus.
      Parameters:
      deviceNumber - CAN Device Id of Pigeon [0,62]
      canbus - Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number
    • Pigeon2

      public Pigeon2​(int deviceNumber)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Create a Pigeon object that communicates with Pigeon on CAN Bus.
      Parameters:
      deviceNumber - CAN Device Id of Pigeon [0,62]
  • Method Details

    • configMountPose

      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the Mount Pose using the primary axis. This is useful if the Pigeon 2.0 is mounted straight, and you only need to describe what axis is forward and what axis is up.
      Parameters:
      forward - Axis that points forward from the robot
      up - Axis that points up from the robot
      Returns:
      OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
    • configMountPose

      public ErrorCode configMountPose​(Pigeon2.AxisDirection forward, Pigeon2.AxisDirection up, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the Mount Pose using the primary axis. This is useful if the Pigeon 2.0 is mounted straight, and you only need to describe what axis is forward and what axis is up.
      Parameters:
      forward - Axis that points forward from the robot
      up - Axis that points up from the robot
      timeoutMs - Config timeout in milliseconds.
      Returns:
      OK if successful, InvalidParamValue if both forward and up are of the same primary axis, otherwise config return.
    • configMountPose

      public ErrorCode configMountPose​(double yaw, double pitch, double roll, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose of the Pigeon2.

      This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current orientation, referenced from the robot's point of view.

      This is only necessary if the Pigeon2 is mounted at an exotic angle near the gimbal lock point or not forward.

      If the pigeon is relatively flat and pointed forward, this is not needed.

      Examples:

      If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw, 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.

      If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it pitched 90 degrees clockwise.

      Parameters:
      yaw - Yaw angle needed to reach the current orientation in degrees.
      pitch - Pitch angle needed to reach the current orientation in degrees.
      roll - Roll angle needed to reach the current orientation in degrees.
      timeoutMs - Config timeout in milliseconds.
      Returns:
      Worst error code of all config sets.
    • configMountPose

      public ErrorCode configMountPose​(double yaw, double pitch, double roll)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose of the Pigeon2.

      This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current orientation, referenced from the robot's point of view.

      This is only necessary if the Pigeon2 is mounted at an exotic angle near the gimbal lock point or not forward.

      If the pigeon is relatively flat and pointed forward, this is not needed.

      Examples:

      If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw, 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.

      If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it pitched 90 degrees clockwise.

      Parameters:
      yaw - Yaw angle needed to reach the current orientation in degrees.
      pitch - Pitch angle needed to reach the current orientation in degrees.
      roll - Roll angle needed to reach the current orientation in degrees.
      Returns:
      Worst error code of all config sets.
    • configMountPoseYaw

      public ErrorCode configMountPoseYaw​(double yaw, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose Yaw of the Pigeon2. See configMountPose(double, double, double, int)
      Parameters:
      yaw - Yaw angle needed to reach the current orientation in degrees.
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode of configSet
    • configMountPoseYaw

      public ErrorCode configMountPoseYaw​(double yaw)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose Yaw of the Pigeon2. See configMountPose(double, double, double)
      Parameters:
      yaw - Yaw angle needed to reach the current orientation in degrees.
      Returns:
      ErrorCode of configSet
    • configMountPosePitch

      public ErrorCode configMountPosePitch​(double pitch, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose Pitch of the Pigeon2. See configMountPose(double, double, double, int)
      Parameters:
      pitch - Pitch angle needed to reach the current orientation in degrees.
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode of configSet
    • configMountPosePitch

      public ErrorCode configMountPosePitch​(double pitch)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose Pitch of the Pigeon2. See configMountPose(double, double, double)
      Parameters:
      pitch - Pitch angle needed to reach the current orientation in degrees.
      Returns:
      ErrorCode of configSet
    • configMountPoseRoll

      public ErrorCode configMountPoseRoll​(double roll, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose Roll of the Pigeon2. See configMountPose(double, double, double, int)
      Parameters:
      roll - Roll angle needed to reach the current orientation in degrees.
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode of configSet
    • configMountPoseRoll

      public ErrorCode configMountPoseRoll​(double roll)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configure the mounting pose Roll of the Pigeon2. See configMountPose(double, double, double)
      Parameters:
      roll - Roll angle needed to reach the current orientation in degrees.
      Returns:
      ErrorCode of configSet
    • configXAxisGyroError

      public ErrorCode configXAxisGyroError​(double err, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures the X Axis Gyroscope Error for 1 rotation
      Parameters:
      err - Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode fo configSet
    • configXAxisGyroError

      public ErrorCode configXAxisGyroError​(double err)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures the X Axis Gyroscope Error for 1 rotation
      Parameters:
      err - Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
      Returns:
      ErrorCode fo configSet
    • configYAxisGyroError

      public ErrorCode configYAxisGyroError​(double err, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures the Y Axis Gyroscope Error for 1 rotation
      Parameters:
      err - Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode fo configSet
    • configYAxisGyroError

      public ErrorCode configYAxisGyroError​(double err)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures the Y Axis Gyroscope Error for 1 rotation
      Parameters:
      err - Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
      Returns:
      ErrorCode fo configSet
    • configZAxisGyroError

      public ErrorCode configZAxisGyroError​(double err, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures the Z Axis Gyroscope Error for 1 rotation
      Parameters:
      err - Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode fo configSet
    • configZAxisGyroError

      public ErrorCode configZAxisGyroError​(double err)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures the Z Axis Gyroscope Error for 1 rotation
      Parameters:
      err - Degrees that Pigeon 2.0 overshot after 1 rotation (i.e. overshot 1 degree is 1; undershot by 3 degrees is -3)
      Returns:
      ErrorCode fo configSet
    • configEnableCompass

      public ErrorCode configEnableCompass​(boolean enable, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use
      Parameters:
      enable - Boolean to enable/disable magnetometer fusion
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode Status of the config response
    • configEnableCompass

      public ErrorCode configEnableCompass​(boolean enable)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Enables the magnetometer fusion for Pigeon2. This is **not** recommended for FRC use
      Parameters:
      enable - Boolean to enable/disable magnetometer fusion
      Returns:
      ErrorCode Status of the config response
    • configDisableTemperatureCompensation

      public ErrorCode configDisableTemperatureCompensation​(boolean disable, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Disables temperature compensation from Pigeon2.
      Parameters:
      disable - Boolean to disable/enable temperature compensation
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode Status of the config response
    • configDisableTemperatureCompensation

      public ErrorCode configDisableTemperatureCompensation​(boolean disable)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Disables temperature compensation from Pigeon2.
      Parameters:
      disable - Boolean to disable/enable temperature compensation
      Returns:
      ErrorCode Status of the config response
    • configDisableNoMotionCalibration

      public ErrorCode configDisableNoMotionCalibration​(boolean disable, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Disables the no-motion calibration from Pigeon2
      Parameters:
      disable - Boolean to disable/enable no-motion calibration
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode Status of the config response
    • configDisableNoMotionCalibration

      public ErrorCode configDisableNoMotionCalibration​(boolean disable)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Disables the no-motion calibration from Pigeon2
      Parameters:
      disable - Boolean to disable/enable no-motion calibration
      Returns:
      ErrorCode Status of the config response
    • zeroGyroBiasNow

      public ErrorCode zeroGyroBiasNow​(int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Performs an offset calibration on gyro bias
      Parameters:
      timeoutMs - Config timeout in milliseconds.
      Returns:
      ErrorCode Status of the config response
    • zeroGyroBiasNow

      Deprecated, for removal: This API element is subject to removal in a future version.
      Performs an offset calibration on gyro bias
      Returns:
      ErrorCode Status of the config response
    • configAllSettings

      public ErrorCode configAllSettings​(Pigeon2Configuration settings, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures all persistent settings.
      Parameters:
      allConfigs - Object with all of the persistant settings
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configAllSettings

      Deprecated, for removal: This API element is subject to removal in a future version.
      Configures all persistent settings.
      Parameters:
      allConfigs - Object with all of the persistant settings
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getGravityVector

      public ErrorCode getGravityVector​(double[] gravVector)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Get the Gravity Vector. This provides a vector that points toward ground. This is useful for applications like an arm, where the z-value of the gravity vector corresponds to the feed-forward needed to hold the arm steady. The gravity vector is calculated after the mount pose, so if the pigeon is where it was mounted, the gravity vector is {0, 0, 1}.
      Parameters:
      gravVector - Pass in a double array of size 3 to get the gravity vector
      Returns:
      Errorcode of getter
    • getFaults

      public ErrorCode getFaults​(Pigeon2_Faults toFill)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Gets the fault status
      Parameters:
      toFill - Container for fault statuses.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getStickyFaults

      Deprecated, for removal: This API element is subject to removal in a future version.
      Gets the sticky fault status
      Parameters:
      toFill - Container for sticky fault statuses.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getAllConfigs

      public void getAllConfigs​(Pigeon2Configuration allConfigs, int timeoutMs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Gets all persistant settings.
      Parameters:
      allConfigs - Object with all of the persistant settings
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
    • getAllConfigs

      public void getAllConfigs​(Pigeon2Configuration allConfigs)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Gets all persistant settings.
      Parameters:
      allConfigs - Object with all of the persistant settings