Pigeon2

class phoenix5.sensors.Pigeon2(deviceNumber: int, canbus: str = '')

Bases: BasePigeon

Pigeon 2 Class. Class supports communicating over CANbus.

{@code
// Example usage of a Pigeon 2
Pigeon2 pigeon{0}; // creates a new Pigeon2 with ID 0

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

std::cout << pigeon.GetYaw() << std::endl; // prints the yaw of the Pigeon
std::cout << pigeon.GetPitch() << std::endl; // prints the pitch of the Pigeon
std::cout << pigeon.GetRoll() << std::endl; // prints the roll of the Pigeon

double gravityVec[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;
ErrorCode faultsError = pigeon.GetFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated
}

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.

Deprecated:

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.

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

configAllSettings(settings: phoenix5._ctre.sensors.Pigeon2Configuration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

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.

configDisableNoMotionCalibration(disable: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Disables the no-motion calibration from Pigeon2

Parameters:
  • disable – Boolean to disable/enable no-motion calibration

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

ErrorCode Status of the config response

configDisableTemperatureCompensation(disable: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Disables temperature compensation from Pigeon2.

Parameters:
  • disable – Boolean to disable/enable temperature compensation

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

ErrorCode Status of the config response

configEnableCompass(enable: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Enables the magnetometer fusion for Pigeon2. This is not recommended for FRC use

Parameters:
  • enable – Boolean to enable/disable magnetometer fusion

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

ErrorCode Status of the config response

configMountPose(*args, **kwargs)

Overloaded function.

  1. configMountPose(self: phoenix5._ctre.sensors.Pigeon2, forward: phoenix5._ctre.sensors.AxisDirection, up: phoenix5._ctre.sensors.AxisDirection, timeoutMs: int = 50) -> phoenix5._ctre.ErrorCode

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.

  1. configMountPose(self: phoenix5._ctre.sensors.Pigeon2, yaw: float, pitch: float, roll: float, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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.

configMountPosePitch(pitch: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configure the mounting pose Pitch of the Pigeon2. See configMountPose()

Parameters:
  • pitch – Pitch angle needed to reach the current orientation in degrees.

  • timeoutMs – Config timeout in milliseconds.

Returns:

ErrorCode of configSet

configMountPoseRoll(roll: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configure the mounting pose Roll of the Pigeon2. See configMountPose()

Parameters:
  • roll – Roll angle needed to reach the current orientation in degrees.

  • timeoutMs – Config timeout in milliseconds.

Returns:

ErrorCode of configSet

configMountPoseYaw(yaw: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configure the mounting pose Yaw of the Pigeon2. See configMountPose()

Parameters:
  • yaw – Yaw angle needed to reach the current orientation in degrees.

  • timeoutMs – Config timeout in milliseconds.

Returns:

ErrorCode of configSet

configXAxisGyroError(err: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

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

configYAxisGyroError(err: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

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

configZAxisGyroError(err: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

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

getAllConfigs(allConfigs: phoenix5._ctre.sensors.Pigeon2Configuration, timeoutMs: int = 50) None

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.

getFaults(toFill: phoenix5._ctre.sensors.Pigeon2_Faults) phoenix5._ctre.ErrorCode

Gets the fault status

Parameters:

toFill – Container for fault statuses.

Returns:

Error Code generated by function. 0 indicates no error.

getGravityVector() tuple[phoenix5._ctre.ErrorCode, Annotated[list[float], FixedSize(3)]]

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

getStickyFaults(toFill: phoenix5._ctre.sensors.Pigeon2_StickyFaults) phoenix5._ctre.ErrorCode

Gets the sticky fault status

Parameters:

toFill – Container for sticky fault statuses.

Returns:

Error Code generated by function. 0 indicates no error.

zeroGyroBiasNow(timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Performs an offset calibration on gyro bias

Parameters:

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:

ErrorCode Status of the config response