BasePigeon

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

Bases: CANBusAddressable

Pigeon IMU Class. Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).

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

addYaw(angleDeg: float, timeoutMs: int = 0) int

Atomically add to the Yaw register.

Parameters:
  • angleDeg – Degrees to add to the Yaw register.

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

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

Clears the Sticky Faults

Returns:

Error Code generated by function. 0 indicates no error.

configAllSettings(allConfigs: phoenix5._ctre.sensors.BasePigeonConfiguration, 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.

configFactoryDefault(timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Configures all persistent settings to defaults.

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:

Error Code generated by function. 0 indicates no error.

configGetCustomParam(paramIndex: int, timeoutMs: int = 0) int

Gets the value of a custom parameter. This is for arbitrary use.

Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.

Parameters:
  • paramIndex – Index of custom parameter. [0-1]

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

Value of the custom param.

configGetParameter(*args, **kwargs)

Overloaded function.

  1. configGetParameter(self: phoenix5._ctre.sensors.BasePigeon, param: phoenix5._ctre.ParamEnum, ordinal: int, timeoutMs: int = 0) -> float

Gets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.

Parameters:
  • param – Parameter enumeration.

  • ordinal – Ordinal of parameter.

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

Value of parameter.

  1. configGetParameter(self: phoenix5._ctre.sensors.BasePigeon, param: phoenix5._ctre.ParamEnum, valueToSend: int, ordinal: int, timeoutMs: int) -> tuple[phoenix5._ctre.ErrorCode, int, int]

Gets a parameter by passing an int by reference

Parameters:
  • param – Parameter enumeration

  • valueToSend – Value to send to parameter

  • valueReceived – Reference to integer to receive

  • subValue – SubValue of parameter

  • ordinal – Ordinal of parameter

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

configSetCustomParam(newValue: int, paramIndex: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the value of a custom parameter. This is for arbitrary use.

Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.

Parameters:
  • newValue – Value for custom parameter.

  • paramIndex – Index of custom parameter. [0-1]

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

configSetParameter(param: phoenix5._ctre.ParamEnum, value: float, subValue: int, ordinal: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.

Parameters:
  • param – Parameter enumeration.

  • value – Value of parameter.

  • subValue – Subvalue for parameter. Maximum value of 255.

  • ordinal – Ordinal of parameter.

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

static destroyAllBasePigeons() None

Destructs all pigeon objects

get6dQuaternion() tuple[phoenix5._ctre.ErrorCode, Annotated[list[float], FixedSize(4)]]

Get 6d Quaternion data.

Parameters:

wxyz – Array to fill with quaternion data w[0], x[1], y[2], z[3]

Returns:

The last ErrorCode generated.

getAbsoluteCompassHeading() float

Get the absolute compass heading.

Returns:

compass heading [0,360) degrees.

getAccumGyro() tuple[int, Annotated[list[float], FixedSize(3)]]

Get AccumGyro data. AccumGyro is the integrated gyro value on each axis.

Parameters:

xyz_deg – Array to fill with x[0], y[1], and z[2] AccumGyro data

Returns:

The last ErrorCode generated.

getAllConfigs(allConfigs: phoenix5._ctre.sensors.BasePigeonConfiguration, 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.

getBiasedAccelerometer() tuple[int, Annotated[list[int], FixedSize(3)]]

Get Biased Accelerometer data.

Parameters:

ba_xyz – Array to fill with x[0], y[1], and z[2] data. These are in fixed point notation Q2.14. eg. 16384 = 1G

Returns:

The last ErrorCode generated.

getBiasedMagnetometer() tuple[int, Annotated[list[int], FixedSize(3)]]

Get Biased Magnetometer data.

Parameters:

bm_xyz – Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.

Returns:

The last ErrorCode generated.

getCompassFieldStrength() float

Gets the compass’ measured magnetic field strength.

Returns:

field strength in Microteslas (uT).

getCompassHeading() float

Get the continuous compass heading.

Returns:

continuous compass heading [-23040, 23040) degrees. Use SetCompassHeading to modify the wrap-around portion.

getFirmVers() int
Returns:

firmware version of Pigeon

getFirmwareVersion() int

Gets the firmware version of the device.

Returns:

param holds the firmware version of the device. Device must be powered cycled at least once.

getLastError() phoenix5._ctre.ErrorCode

Call GetLastError() generated by this object. Not all functions return an error code but can potentially report errors.

This function can be used to retrieve those error codes.

Returns:

The last ErrorCode generated.

getPitch() float

Get the pitch from the Pigeon

Returns:

Pitch

getRawGyro() tuple[int, Annotated[list[float], FixedSize(3)]]

Get Raw Gyro data.

Parameters:

xyz_dps – Array to fill with x[0], y[1], and z[2] data in degrees per second.

Returns:

The last ErrorCode generated.

getRawMagnetometer() tuple[int, Annotated[list[int], FixedSize(3)]]

Get Raw Magnetometer data.

Parameters:

rm_xyz – Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.

Returns:

The last ErrorCode generated.

getResetCount() int
Returns:

number of times Pigeon Reset

getResetFlags() int
Returns:

Reset flags for Pigeon

getRoll() float

Get the roll from the Pigeon

Returns:

Roll

getSimCollection() phoenix5._ctre.sensors.BasePigeonSimCollection
Returns:

object that can set simulation inputs.

getStatusFramePeriod(frame: phoenix5._ctre.sensors.PigeonIMU_StatusFrame, timeoutMs: int = 0) int

Gets the period of the given status frame.

Parameters:
  • frame – Frame to get the period of.

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

Period of the given status frame.

getTemp() float

Gets the temperature of the pigeon.

Returns:

Temperature in (‘C)

getUpTime() int

Gets the current Pigeon uptime.

Returns:

How long has Pigeon been running in whole seconds. Value caps at 255.

getYaw() float

Get the yaw from the Pigeon

Returns:

Yaw

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

Get Yaw, Pitch, and Roll data.

Parameters:

ypr – Array to fill with yaw[0], pitch[1], and roll[2] data. * Yaw is within [-368,640, +368,640] degrees. * Pitch is within [-90,+90] degrees. * Roll is within [-90,+90] degrees.

Returns:

The last ErrorCode generated.

hasResetOccurred() bool
Returns:

true iff a reset has occurred since last call.

setAccumZAngle(angleDeg: float, timeoutMs: int = 0) int

Sets the AccumZAngle.

Parameters:
  • angleDeg – Degrees to set AccumZAngle to.

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

setControlFramePeriod(frame: phoenix5._ctre.sensors.PigeonIMU_ControlFrame, periodMs: int) phoenix5._ctre.ErrorCode

Sets the period of the given control frame.

Parameters:
  • frame – Frame whose period is to be changed.

  • periodMs – Period in ms for the given frame.

Returns:

Error Code generated by function. 0 indicates no error.

setStatusFramePeriod(statusFrame: phoenix5._ctre.sensors.PigeonIMU_StatusFrame, periodMs: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the period of the given status frame.

Parameters:
  • statusFrame – Frame whose period is to be changed.

  • periodMs – Period in ms for the given frame.

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

setYaw(angleDeg: float, timeoutMs: int = 0) int

Sets the Yaw register to the specified value.

Parameters:
  • angleDeg – Degree of Yaw [+/- 368,640 degrees]

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

setYawToCompass(timeoutMs: int = 0) int

Sets the Yaw register to match the current compass value.

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:

Error Code generated by function. 0 indicates no error.