phoenix6.hardware.core.core_pigeon2#

Module Contents#

class phoenix6.hardware.core.core_pigeon2.CorePigeon2(device_id: int, canbus: str = '')#

Bases: phoenix6.hardware.parent_device.ParentDevice

Constructs a new Pigeon 2 sensor object.

Parameters:
  • device_id (int) – ID of the device, as configured in Phoenix Tuner.

  • canbus (str, optional) –

    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

property sim_state: phoenix6.sim.pigeon2_sim_state.Pigeon2SimState#

Get the simulation state for this device.

This function reuses an allocated simulation state object, so it is safe to call this function multiple times in a robot loop.

Returns:

Simulation state

Return type:

Pigeon2SimState

get_version_major() phoenix6.status_signal.StatusSignal[int]#

App Major Version number.

  • Minimum Value: 0

  • Maximum Value: 255

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

VersionMajor Status Signal Object

Return type:

StatusSignal[int]

get_version_minor() phoenix6.status_signal.StatusSignal[int]#

App Minor Version number.

  • Minimum Value: 0

  • Maximum Value: 255

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

VersionMinor Status Signal Object

Return type:

StatusSignal[int]

get_version_bugfix() phoenix6.status_signal.StatusSignal[int]#

App Bugfix Version number.

  • Minimum Value: 0

  • Maximum Value: 255

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

VersionBugfix Status Signal Object

Return type:

StatusSignal[int]

get_version_build() phoenix6.status_signal.StatusSignal[int]#

App Build Version number.

  • Minimum Value: 0

  • Maximum Value: 255

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

VersionBuild Status Signal Object

Return type:

StatusSignal[int]

get_version() phoenix6.status_signal.StatusSignal[int]#

Full Version. The format is a four byte value.

Full Version of firmware in device. The format is a four byte value.

  • Minimum Value: 0

  • Maximum Value: 4294967295

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Version Status Signal Object

Return type:

StatusSignal[int]

get_fault_field() phoenix6.status_signal.StatusSignal[int]#

Integer representing all faults

This returns the fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetFault_*() methods instead.

  • Minimum Value: 0

  • Maximum Value: 16777215

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

FaultField Status Signal Object

Return type:

StatusSignal[int]

get_sticky_fault_field() phoenix6.status_signal.StatusSignal[int]#

Integer representing all sticky faults

This returns the persistent “sticky” fault flags reported by the device. These are device specific and are not used directly in typical applications. Use the signal specific GetStickyFault_*() methods instead.

  • Minimum Value: 0

  • Maximum Value: 16777215

  • Default Value: 0

  • Units:

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFaultField Status Signal Object

Return type:

StatusSignal[int]

get_yaw() phoenix6.status_signal.StatusSignal[phoenix6.units.degree]#

Current reported yaw of the Pigeon2.

  • Minimum Value: -368640.0

  • Maximum Value: 368639.99725341797

  • Default Value: 0

  • Units: deg

Default Rates:
  • CAN 2.0: 100.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

Yaw Status Signal Object

Return type:

StatusSignal[degree]

get_pitch() phoenix6.status_signal.StatusSignal[phoenix6.units.degree]#

Current reported pitch of the Pigeon2.

  • Minimum Value: -90.0

  • Maximum Value: 89.9560546875

  • Default Value: 0

  • Units: deg

Default Rates:
  • CAN 2.0: 100.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

Pitch Status Signal Object

Return type:

StatusSignal[degree]

get_roll() phoenix6.status_signal.StatusSignal[phoenix6.units.degree]#

Current reported roll of the Pigeon2.

  • Minimum Value: -180.0

  • Maximum Value: 179.9560546875

  • Default Value: 0

  • Units: deg

Default Rates:
  • CAN 2.0: 100.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

Roll Status Signal Object

Return type:

StatusSignal[degree]

get_quat_w() phoenix6.status_signal.StatusSignal[float]#

The W component of the reported Quaternion.

  • Minimum Value: -1.0001220852154804

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 50.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

QuatW Status Signal Object

Return type:

StatusSignal[float]

get_quat_x() phoenix6.status_signal.StatusSignal[float]#

The X component of the reported Quaternion.

  • Minimum Value: -1.0001220852154804

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 50.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

QuatX Status Signal Object

Return type:

StatusSignal[float]

get_quat_y() phoenix6.status_signal.StatusSignal[float]#

The Y component of the reported Quaternion.

  • Minimum Value: -1.0001220852154804

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 50.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

QuatY Status Signal Object

Return type:

StatusSignal[float]

get_quat_z() phoenix6.status_signal.StatusSignal[float]#

The Z component of the reported Quaternion.

  • Minimum Value: -1.0001220852154804

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 50.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

QuatZ Status Signal Object

Return type:

StatusSignal[float]

get_gravity_vector_x() phoenix6.status_signal.StatusSignal[float]#

The X component of the gravity vector.

This is the X component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes “Down” is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.

  • Minimum Value: -1.000030518509476

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

GravityVectorX Status Signal Object

Return type:

StatusSignal[float]

get_gravity_vector_y() phoenix6.status_signal.StatusSignal[float]#

The Y component of the gravity vector.

This is the X component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes “Down” is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.

  • Minimum Value: -1.000030518509476

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

GravityVectorY Status Signal Object

Return type:

StatusSignal[float]

get_gravity_vector_z() phoenix6.status_signal.StatusSignal[float]#

The Z component of the gravity vector.

This is the Z component of the reported gravity-vector. The gravity vector is not the acceleration experienced by the Pigeon2, rather it is where the Pigeon2 believes “Down” is. This can be used for mechanisms that are linearly related to gravity, such as an arm pivoting about a point, as the contribution of gravity to the arm is directly proportional to the contribution of gravity about one of these primary axis.

  • Minimum Value: -1.000030518509476

  • Maximum Value: 1.0

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

GravityVectorZ Status Signal Object

Return type:

StatusSignal[float]

get_temperature() phoenix6.status_signal.StatusSignal[phoenix6.units.celsius]#

Temperature of the Pigeon 2.

  • Minimum Value: -128.0

  • Maximum Value: 127.99609375

  • Default Value: 0

  • Units: ℃

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

Temperature Status Signal Object

Return type:

StatusSignal[celsius]

get_no_motion_enabled() phoenix6.status_signal.StatusSignal[bool]#

Whether the no-motion calibration feature is enabled.

  • Default Value: 0

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

NoMotionEnabled Status Signal Object

Return type:

StatusSignal[bool]

get_no_motion_count() phoenix6.status_signal.StatusSignal[float]#

The number of times a no-motion event occurred, wraps at 15.

  • Minimum Value: 0

  • Maximum Value: 15

  • Default Value: 0

  • Units:

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

NoMotionCount Status Signal Object

Return type:

StatusSignal[float]

get_temperature_compensation_disabled() phoenix6.status_signal.StatusSignal[bool]#

Whether the temperature-compensation feature is disabled.

  • Default Value: 0

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

TemperatureCompensationDisabled Status Signal Object

Return type:

StatusSignal[bool]

get_up_time() phoenix6.status_signal.StatusSignal[phoenix6.units.second]#

How long the Pigeon 2’s been up in seconds, caps at 255 seconds.

  • Minimum Value: 0

  • Maximum Value: 255

  • Default Value: 0

  • Units: s

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

UpTime Status Signal Object

Return type:

StatusSignal[second]

get_accum_gyro_x() phoenix6.status_signal.StatusSignal[phoenix6.units.degree]#

The accumulated gyro about the X axis without any sensor fusing.

  • Minimum Value: -23040.0

  • Maximum Value: 23039.9560546875

  • Default Value: 0

  • Units: deg

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AccumGyroX Status Signal Object

Return type:

StatusSignal[degree]

get_accum_gyro_y() phoenix6.status_signal.StatusSignal[phoenix6.units.degree]#

The accumulated gyro about the Y axis without any sensor fusing.

  • Minimum Value: -23040.0

  • Maximum Value: 23039.9560546875

  • Default Value: 0

  • Units: deg

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AccumGyroY Status Signal Object

Return type:

StatusSignal[degree]

get_accum_gyro_z() phoenix6.status_signal.StatusSignal[phoenix6.units.degree]#

The accumulated gyro about the Z axis without any sensor fusing.

  • Minimum Value: -23040.0

  • Maximum Value: 23039.9560546875

  • Default Value: 0

  • Units: deg

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AccumGyroZ Status Signal Object

Return type:

StatusSignal[degree]

get_angular_velocity_x_world() phoenix6.status_signal.StatusSignal[phoenix6.units.degrees_per_second]#

Angular Velocity world X

This is the X component of the angular velocity with respect to the world frame and is mount-calibrated.

  • Minimum Value: -2048.0

  • Maximum Value: 2047.99609375

  • Default Value: 0

  • Units: dps

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AngularVelocityXWorld Status Signal Object

Return type:

StatusSignal[degrees_per_second]

get_angular_velocity_y_world() phoenix6.status_signal.StatusSignal[phoenix6.units.degrees_per_second]#

Angular Velocity Quaternion Y Component

This is the Y component of the angular velocity with respect to the world frame and is mount-calibrated.

  • Minimum Value: -2048.0

  • Maximum Value: 2047.99609375

  • Default Value: 0

  • Units: dps

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AngularVelocityYWorld Status Signal Object

Return type:

StatusSignal[degrees_per_second]

get_angular_velocity_z_world() phoenix6.status_signal.StatusSignal[phoenix6.units.degrees_per_second]#

Angular Velocity Quaternion Z Component

This is the Z component of the angular velocity with respect to the world frame and is mount-calibrated.

  • Minimum Value: -2048.0

  • Maximum Value: 2047.99609375

  • Default Value: 0

  • Units: dps

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AngularVelocityZWorld Status Signal Object

Return type:

StatusSignal[degrees_per_second]

get_acceleration_x() phoenix6.status_signal.StatusSignal[phoenix6.units.g]#

The acceleration measured by Pigeon2 in the X direction.

This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.

  • Minimum Value: -2.0

  • Maximum Value: 1.99993896484375

  • Default Value: 0

  • Units: g

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AccelerationX Status Signal Object

Return type:

StatusSignal[g]

get_acceleration_y() phoenix6.status_signal.StatusSignal[phoenix6.units.g]#

The acceleration measured by Pigeon2 in the Y direction.

This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.

  • Minimum Value: -2.0

  • Maximum Value: 1.99993896484375

  • Default Value: 0

  • Units: g

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AccelerationY Status Signal Object

Return type:

StatusSignal[g]

get_acceleration_z() phoenix6.status_signal.StatusSignal[phoenix6.units.g]#

The acceleration measured by Pigeon2 in the Z direction.

This value includes the acceleration due to gravity. If this is undesirable, get the gravity vector and subtract out the contribution in this direction.

  • Minimum Value: -2.0

  • Maximum Value: 1.99993896484375

  • Default Value: 0

  • Units: g

Default Rates:
  • CAN 2.0: 10.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

AccelerationZ Status Signal Object

Return type:

StatusSignal[g]

get_supply_voltage() phoenix6.status_signal.StatusSignal[phoenix6.units.volt]#

Measured supply voltage to the Pigeon2.

  • Minimum Value: 0.0

  • Maximum Value: 31.99951171875

  • Default Value: 0

  • Units: V

Default Rates:
  • CAN 2.0: 4.0 Hz

  • CAN FD: 100.0 Hz (TimeSynced with Pro)

This refreshes and returns a cached StatusSignal object.

Returns:

SupplyVoltage Status Signal Object

Return type:

StatusSignal[volt]

get_angular_velocity_x_device() phoenix6.status_signal.StatusSignal[phoenix6.units.degrees_per_second]#

The angular velocity (ω) of the Pigeon 2 about the device’s X axis.

This value is not mount-calibrated

  • Minimum Value: -1998.048780487805

  • Maximum Value: 1997.987804878049

  • Default Value: 0

  • Units: dps

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

AngularVelocityXDevice Status Signal Object

Return type:

StatusSignal[degrees_per_second]

get_angular_velocity_y_device() phoenix6.status_signal.StatusSignal[phoenix6.units.degrees_per_second]#

The angular velocity (ω) of the Pigeon 2 about the device’s Y axis.

This value is not mount-calibrated

  • Minimum Value: -1998.048780487805

  • Maximum Value: 1997.987804878049

  • Default Value: 0

  • Units: dps

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

AngularVelocityYDevice Status Signal Object

Return type:

StatusSignal[degrees_per_second]

get_angular_velocity_z_device() phoenix6.status_signal.StatusSignal[phoenix6.units.degrees_per_second]#

The angular velocity (ω) of the Pigeon 2 about the device’s Z axis.

This value is not mount-calibrated

  • Minimum Value: -1998.048780487805

  • Maximum Value: 1997.987804878049

  • Default Value: 0

  • Units: dps

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

AngularVelocityZDevice Status Signal Object

Return type:

StatusSignal[degrees_per_second]

get_magnetic_field_x() phoenix6.status_signal.StatusSignal[phoenix6.units.microtesla]#

The biased magnitude of the magnetic field measured by the Pigeon 2 in the X direction. This is only valid after performing a magnetometer calibration.

  • Minimum Value: -19660.8

  • Maximum Value: 19660.2

  • Default Value: 0

  • Units: uT

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

MagneticFieldX Status Signal Object

Return type:

StatusSignal[microtesla]

get_magnetic_field_y() phoenix6.status_signal.StatusSignal[phoenix6.units.microtesla]#

The biased magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. This is only valid after performing a magnetometer calibration.

  • Minimum Value: -19660.8

  • Maximum Value: 19660.2

  • Default Value: 0

  • Units: uT

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

MagneticFieldY Status Signal Object

Return type:

StatusSignal[microtesla]

get_magnetic_field_z() phoenix6.status_signal.StatusSignal[phoenix6.units.microtesla]#

The biased magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. This is only valid after performing a magnetometer calibration.

  • Minimum Value: -19660.8

  • Maximum Value: 19660.2

  • Default Value: 0

  • Units: uT

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

MagneticFieldZ Status Signal Object

Return type:

StatusSignal[microtesla]

get_raw_magnetic_field_x() phoenix6.status_signal.StatusSignal[phoenix6.units.microtesla]#

The raw magnitude of the magnetic field measured by the Pigeon 2 in the X direction. This is only valid after performing a magnetometer calibration.

  • Minimum Value: -19660.8

  • Maximum Value: 19660.2

  • Default Value: 0

  • Units: uT

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

RawMagneticFieldX Status Signal Object

Return type:

StatusSignal[microtesla]

get_raw_magnetic_field_y() phoenix6.status_signal.StatusSignal[phoenix6.units.microtesla]#

The raw magnitude of the magnetic field measured by the Pigeon 2 in the Y direction. This is only valid after performing a magnetometer calibration.

  • Minimum Value: -19660.8

  • Maximum Value: 19660.2

  • Default Value: 0

  • Units: uT

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

RawMagneticFieldY Status Signal Object

Return type:

StatusSignal[microtesla]

get_raw_magnetic_field_z() phoenix6.status_signal.StatusSignal[phoenix6.units.microtesla]#

The raw magnitude of the magnetic field measured by the Pigeon 2 in the Z direction. This is only valid after performing a magnetometer calibration.

  • Minimum Value: -19660.8

  • Maximum Value: 19660.2

  • Default Value: 0

  • Units: uT

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

RawMagneticFieldZ Status Signal Object

Return type:

StatusSignal[microtesla]

get_is_pro_licensed() phoenix6.status_signal.StatusSignal[bool]#

Whether the device is Phoenix Pro licensed.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

IsProLicensed Status Signal Object

Return type:

StatusSignal[bool]

get_fault_hardware() phoenix6.status_signal.StatusSignal[bool]#

Hardware fault occurred

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_Hardware Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_hardware() phoenix6.status_signal.StatusSignal[bool]#

Hardware fault occurred

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_Hardware Status Signal Object

Return type:

StatusSignal[bool]

get_fault_undervoltage() phoenix6.status_signal.StatusSignal[bool]#

Device supply voltage dropped to near brownout levels

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_Undervoltage Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_undervoltage() phoenix6.status_signal.StatusSignal[bool]#

Device supply voltage dropped to near brownout levels

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_Undervoltage Status Signal Object

Return type:

StatusSignal[bool]

get_fault_boot_during_enable() phoenix6.status_signal.StatusSignal[bool]#

Device boot while detecting the enable signal

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_BootDuringEnable Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_boot_during_enable() phoenix6.status_signal.StatusSignal[bool]#

Device boot while detecting the enable signal

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_BootDuringEnable Status Signal Object

Return type:

StatusSignal[bool]

get_fault_unlicensed_feature_in_use() phoenix6.status_signal.StatusSignal[bool]#

An unlicensed feature is in use, device may not behave as expected.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_UnlicensedFeatureInUse Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_unlicensed_feature_in_use() phoenix6.status_signal.StatusSignal[bool]#

An unlicensed feature is in use, device may not behave as expected.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_UnlicensedFeatureInUse Status Signal Object

Return type:

StatusSignal[bool]

get_fault_bootup_accelerometer() phoenix6.status_signal.StatusSignal[bool]#

Bootup checks failed: Accelerometer

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_BootupAccelerometer Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_bootup_accelerometer() phoenix6.status_signal.StatusSignal[bool]#

Bootup checks failed: Accelerometer

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_BootupAccelerometer Status Signal Object

Return type:

StatusSignal[bool]

get_fault_bootup_gyroscope() phoenix6.status_signal.StatusSignal[bool]#

Bootup checks failed: Gyroscope

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_BootupGyroscope Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_bootup_gyroscope() phoenix6.status_signal.StatusSignal[bool]#

Bootup checks failed: Gyroscope

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_BootupGyroscope Status Signal Object

Return type:

StatusSignal[bool]

get_fault_bootup_magnetometer() phoenix6.status_signal.StatusSignal[bool]#

Bootup checks failed: Magnetometer

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_BootupMagnetometer Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_bootup_magnetometer() phoenix6.status_signal.StatusSignal[bool]#

Bootup checks failed: Magnetometer

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_BootupMagnetometer Status Signal Object

Return type:

StatusSignal[bool]

get_fault_boot_into_motion() phoenix6.status_signal.StatusSignal[bool]#

Motion Detected during bootup.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_BootIntoMotion Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_boot_into_motion() phoenix6.status_signal.StatusSignal[bool]#

Motion Detected during bootup.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_BootIntoMotion Status Signal Object

Return type:

StatusSignal[bool]

get_fault_data_acquired_late() phoenix6.status_signal.StatusSignal[bool]#

Motion stack data acquisition was slower than expected

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_DataAcquiredLate Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_data_acquired_late() phoenix6.status_signal.StatusSignal[bool]#

Motion stack data acquisition was slower than expected

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_DataAcquiredLate Status Signal Object

Return type:

StatusSignal[bool]

get_fault_loop_time_slow() phoenix6.status_signal.StatusSignal[bool]#

Motion stack loop time was slower than expected.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_LoopTimeSlow Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_loop_time_slow() phoenix6.status_signal.StatusSignal[bool]#

Motion stack loop time was slower than expected.

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_LoopTimeSlow Status Signal Object

Return type:

StatusSignal[bool]

get_fault_saturated_magnetometer() phoenix6.status_signal.StatusSignal[bool]#

Magnetometer values are saturated

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_SaturatedMagnetometer Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_saturated_magnetometer() phoenix6.status_signal.StatusSignal[bool]#

Magnetometer values are saturated

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_SaturatedMagnetometer Status Signal Object

Return type:

StatusSignal[bool]

get_fault_saturated_accelerometer() phoenix6.status_signal.StatusSignal[bool]#

Accelerometer values are saturated

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_SaturatedAccelerometer Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_saturated_accelerometer() phoenix6.status_signal.StatusSignal[bool]#

Accelerometer values are saturated

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_SaturatedAccelerometer Status Signal Object

Return type:

StatusSignal[bool]

get_fault_saturated_gyroscope() phoenix6.status_signal.StatusSignal[bool]#

Gyroscope values are saturated

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_SaturatedGyroscope Status Signal Object

Return type:

StatusSignal[bool]

get_sticky_fault_saturated_gyroscope() phoenix6.status_signal.StatusSignal[bool]#

Gyroscope values are saturated

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_SaturatedGyroscope Status Signal Object

Return type:

StatusSignal[bool]

set_control(request: phoenix6.hardware.parent_device.SupportsSendRequest) phoenix6.status_signal.StatusCode#

Control motor with generic control request object.

If control request is not supported by device, this request will fail with StatusCode NotSupported

Parameters:

request (SupportsSendRequest) – Control object to request of the device

Returns:

StatusCode of the request

Return type:

StatusCode

set_yaw(new_value: phoenix6.units.degree, timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

The yaw to set the Pigeon2 to right now.

Parameters:
  • new_value (degree) – Value to set to. Units are in deg.

  • timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_faults(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear the sticky faults in the device.

This typically has no impact on the device functionality. Instead, it just clears telemetry faults that are accessible via API and Tuner Self-Test.

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_hardware(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Hardware fault occurred

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_undervoltage(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Device supply voltage dropped to near brownout levels

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_boot_during_enable(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Device boot while detecting the enable signal

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_bootup_accelerometer(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Bootup checks failed: Accelerometer

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_bootup_gyroscope(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Bootup checks failed: Gyroscope

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_bootup_magnetometer(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Bootup checks failed: Magnetometer

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_boot_into_motion(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Motion Detected during bootup.

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_data_acquired_late(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Motion stack data acquisition was slower than expected

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_loop_time_slow(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Motion stack loop time was slower than expected.

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_saturated_magnetometer(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Magnetometer values are saturated

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_saturated_accelerometer(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Accelerometer values are saturated

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode

clear_sticky_fault_saturated_gyroscope(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: Gyroscope values are saturated

Parameters:

timeout_seconds (second) – Maximum time to wait up to in seconds.

Returns:

StatusCode of the set command

Return type:

StatusCode