phoenix6.hardware.core.core_cancoder#

Module Contents#

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

Bases: phoenix6.hardware.parent_device.ParentDevice

Constructs a new CANcoder 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.cancoder_sim_state.CANcoderSimState#

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:

CANcoderSimState

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_velocity() phoenix6.status_signal.StatusSignal[phoenix6.units.rotations_per_second]#

Velocity of the device.

  • Minimum Value: -512.0

  • Maximum Value: 511.998046875

  • Default Value: 0

  • Units: rotations per second

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:

Velocity Status Signal Object

Return type:

StatusSignal[rotations_per_second]

get_position() phoenix6.status_signal.StatusSignal[phoenix6.units.rotation]#

Position of the device. This is initialized to the absolute position on boot.

  • Minimum Value: -16384.0

  • Maximum Value: 16383.999755859375

  • Default Value: 0

  • Units: rotations

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:

Position Status Signal Object

Return type:

StatusSignal[rotation]

get_absolute_position() phoenix6.status_signal.StatusSignal[phoenix6.units.rotation]#

Absolute Position of the device. The possible range is documented below; however, the exact expected range is determined by the AbsoluteSensorRange. This position is only affected by the MagnetSensor configs.

  • Minimum Value: -0.5

  • Maximum Value: 0.999755859375

  • Default Value: 0

  • Units: rotations

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:

AbsolutePosition Status Signal Object

Return type:

StatusSignal[rotation]

get_unfiltered_velocity() phoenix6.status_signal.StatusSignal[phoenix6.units.rotations_per_second]#

The unfiltered velocity reported by CANcoder.

This is the unfiltered velocity reported by CANcoder. This signal does not use the fusing algorithm.

  • Minimum Value: -8000.0

  • Maximum Value: 7999.755859375

  • Default Value: 0

  • Units: rotations per second

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:

UnfilteredVelocity Status Signal Object

Return type:

StatusSignal[rotations_per_second]

get_position_since_boot() phoenix6.status_signal.StatusSignal[phoenix6.units.rotation]#

The relative position reported by the CANcoder since boot.

This is the total displacement reported by CANcoder since power up. This signal is relative and is not influenced by the fusing algorithm.

  • Minimum Value: -16384.0

  • Maximum Value: 16383.999755859375

  • Default Value: 0

  • Units: rotations

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:

PositionSinceBoot Status Signal Object

Return type:

StatusSignal[rotation]

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

Measured supply voltage to the CANcoder.

  • Minimum Value: 4

  • Maximum Value: 16.75

  • Default Value: 4

  • 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_magnet_health() phoenix6.status_signal.StatusSignal[phoenix6.signals.spn_enums.MagnetHealthValue]#

Magnet health as measured by CANcoder.

Magnet health as measured by CANcoder. Red indicates too close or too far, Orange is adequate but with reduced accuracy, green is ideal. Invalid means the accuracy cannot be determined.

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:

MagnetHealth Status Signal Object

Return type:

StatusSignal[MagnetHealthValue]

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_bad_magnet() phoenix6.status_signal.StatusSignal[bool]#

The magnet distance is not correct or magnet is missing

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

Fault_BadMagnet Status Signal Object

Return type:

StatusSignal[bool]

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

The magnet distance is not correct or magnet is missing

  • Default Value: False

Default Rates:
  • CAN: 4.0 Hz

This refreshes and returns a cached StatusSignal object.

Returns:

StickyFault_BadMagnet 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_position(new_value: phoenix6.units.rotation, timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Sets the current position of the device.

Parameters:
  • new_value (rotation) – Value to set to. Units are in rotations.

  • 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_bad_magnet(timeout_seconds: phoenix6.units.second = 0.05) phoenix6.status_signal.StatusCode#

Clear sticky fault: The magnet distance is not correct or magnet is missing

Parameters:

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

Returns:

StatusCode of the set command

Return type:

StatusCode