phoenix6.hardware.core.core_candi
¶
Module Contents¶
- class phoenix6.hardware.core.core_candi.CoreCANdi(device_id: int, canbus: str | phoenix6.canbus.CANBus = '')¶
Bases:
phoenix6.hardware.parent_device.ParentDevice
Constructs a new CANdi object.
- Parameters:
device_id (int) – ID of the device, as configured in Phoenix Tuner.
canbus (str | CANBus, 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.candi_sim_state.CANdiSimState¶
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:
- get_version_major(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
VersionMajor Status Signal Object
- Return type:
StatusSignal[int]
- get_version_minor(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
VersionMinor Status Signal Object
- Return type:
StatusSignal[int]
- get_version_bugfix(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
VersionBugfix Status Signal Object
- Return type:
StatusSignal[int]
- get_version_build(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
VersionBuild Status Signal Object
- Return type:
StatusSignal[int]
- get_version(refresh: bool = True) phoenix6.status_signal.StatusSignal[int] ¶
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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Version Status Signal Object
- Return type:
StatusSignal[int]
- get_fault_field(refresh: bool = True) phoenix6.status_signal.StatusSignal[int] ¶
Integer representing all 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: 4294967295
Default Value: 0
Units:
- Default Rates:
CAN: 4.0 Hz
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
FaultField Status Signal Object
- Return type:
StatusSignal[int]
- get_sticky_fault_field(refresh: bool = True) phoenix6.status_signal.StatusSignal[int] ¶
Integer representing all (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: 4294967295
Default Value: 0
Units:
- Default Rates:
CAN: 4.0 Hz
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
StickyFaultField Status Signal Object
- Return type:
StatusSignal[int]
- get_is_pro_licensed(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
IsProLicensed Status Signal Object
- Return type:
StatusSignal[bool]
- get_s1_state(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.signals.spn_enums.S1StateValue] ¶
State of the Signal 1 input (S1IN).
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
S1State Status Signal Object
- Return type:
- get_s2_state(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.signals.spn_enums.S2StateValue] ¶
State of the Signal 2 input (S2IN).
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
S2State Status Signal Object
- Return type:
- get_quadrature_position(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.rotation] ¶
Position from a quadrature encoder sensor connected to both the S1IN and S2IN inputs.
Minimum Value: -16384.0
Maximum Value: 16383.999755859375
Default Value: 0
Units: rotations
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
QuadraturePosition Status Signal Object
- Return type:
StatusSignal[rotation]
- get_pwm1_rise_to_rise(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.microsecond] ¶
Measured rise to rise time of the PWM signal at the S1 input of CANdi.
Minimum Value: 0
Maximum Value: 131070
Default Value: 0
Units: us
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
PWM1RiseToRise Status Signal Object
- Return type:
StatusSignal[microsecond]
- get_pwm1_position(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.rotation] ¶
Measured position of the PWM sensor at the S1 input of CANdi.
Minimum Value: -16384.0
Maximum Value: 16383.999755859375
Default Value: 0
Units: rotations
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
PWM1Position Status Signal Object
- Return type:
StatusSignal[rotation]
- get_pwm1_velocity(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.rotations_per_second] ¶
Measured velocity of the PWM sensor at the S1 input of CANdi.
Minimum Value: -512.0
Maximum Value: 511.998046875
Default Value: 0
Units: rotations per second
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
PWM1Velocity Status Signal Object
- Return type:
StatusSignal[rotations_per_second]
- get_pwm2_rise_to_rise(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.microsecond] ¶
Measured rise to rise time of the PWM signal at the S2 input of CANdi.
Minimum Value: 0
Maximum Value: 131070
Default Value: 0
Units: us
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
PWM2RiseToRise Status Signal Object
- Return type:
StatusSignal[microsecond]
- get_pwm2_position(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.rotation] ¶
Measured position of the PWM sensor at the S2 input of CANdi.
Minimum Value: -16384.0
Maximum Value: 16383.999755859375
Default Value: 0
Units: rotations
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
PWM2Position Status Signal Object
- Return type:
StatusSignal[rotation]
- get_overcurrent(refresh: bool = True) phoenix6.status_signal.StatusSignal[bool] ¶
True when the CANdi is in overcurrent protection mode. This may be due to either overcurrent or a short-circuit.
Default Value: 0
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Overcurrent Status Signal Object
- Return type:
StatusSignal[bool]
- get_supply_voltage(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.volt] ¶
Measured supply voltage to the CANdi.
Minimum Value: 4.0
Maximum Value: 29.5
Default Value: 0
Units: V
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
SupplyVoltage Status Signal Object
- Return type:
StatusSignal[volt]
- get_output_current(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.ampere] ¶
Measured output current. This includes both Vbat and 5V output current.
Minimum Value: 0.0
Maximum Value: 0.51
Default Value: 0
Units: A
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
OutputCurrent Status Signal Object
- Return type:
StatusSignal[ampere]
- get_pwm2_velocity(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.rotations_per_second] ¶
Measured velocity of the PWM sensor at the S2 input of CANdi.
Minimum Value: -512.0
Maximum Value: 511.998046875
Default Value: 0
Units: rotations per second
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
PWM2Velocity Status Signal Object
- Return type:
StatusSignal[rotations_per_second]
- get_quadrature_velocity(refresh: bool = True) phoenix6.status_signal.StatusSignal[phoenix6.units.rotations_per_second] ¶
Velocity from a quadrature encoder sensor connected to both the S1IN and S2IN inputs.
Minimum Value: -512.0
Maximum Value: 511.998046875
Default Value: 0
Units: rotations per second
- Default Rates:
CAN 2.0: 20.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
QuadratureVelocity Status Signal Object
- Return type:
StatusSignal[rotations_per_second]
- get_s1_closed(refresh: bool = True) phoenix6.status_signal.StatusSignal[bool] ¶
True if the Signal 1 input (S1IN) matches the configured S1 Closed State.
Configure the S1 closed state in the Digitals configuration object to change when this is asserted.
Default Value: False
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
S1Closed Status Signal Object
- Return type:
StatusSignal[bool]
- get_s2_closed(refresh: bool = True) phoenix6.status_signal.StatusSignal[bool] ¶
True if the Signal 2 input (S2IN) matches the configured S2 Closed State.
Configure the S2 closed state in the Digitals configuration object to change when this is asserted.
Default Value: False
- Default Rates:
CAN 2.0: 100.0 Hz
CAN FD: 100.0 Hz (TimeSynced with Pro)
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
S2Closed Status Signal Object
- Return type:
StatusSignal[bool]
- get_fault_hardware(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Fault_Hardware Status Signal Object
- Return type:
StatusSignal[bool]
- get_sticky_fault_hardware(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
StickyFault_Hardware Status Signal Object
- Return type:
StatusSignal[bool]
- get_fault_undervoltage(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Fault_Undervoltage Status Signal Object
- Return type:
StatusSignal[bool]
- get_sticky_fault_undervoltage(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
StickyFault_Undervoltage Status Signal Object
- Return type:
StatusSignal[bool]
- get_fault_boot_during_enable(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Fault_BootDuringEnable Status Signal Object
- Return type:
StatusSignal[bool]
- get_sticky_fault_boot_during_enable(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
StickyFault_BootDuringEnable Status Signal Object
- Return type:
StatusSignal[bool]
- get_fault_unlicensed_feature_in_use(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Fault_UnlicensedFeatureInUse Status Signal Object
- Return type:
StatusSignal[bool]
- get_sticky_fault_unlicensed_feature_in_use(refresh: bool = True) 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.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
StickyFault_UnlicensedFeatureInUse Status Signal Object
- Return type:
StatusSignal[bool]
- get_fault_5_v(refresh: bool = True) phoenix6.status_signal.StatusSignal[bool] ¶
CANdi has detected a 5V fault. This may be due to overcurrent or a short-circuit.
Default Value: False
- Default Rates:
CAN: 4.0 Hz
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
Fault_5V Status Signal Object
- Return type:
StatusSignal[bool]
- get_sticky_fault_5_v(refresh: bool = True) phoenix6.status_signal.StatusSignal[bool] ¶
CANdi has detected a 5V fault. This may be due to overcurrent or a short-circuit.
Default Value: False
- Default Rates:
CAN: 4.0 Hz
This refreshes and returns a cached StatusSignal object.
- Parameters:
refresh (bool) – Whether to refresh the StatusSignal before returning it; defaults to true
- Returns:
StickyFault_5V Status Signal Object
- Return type:
StatusSignal[bool]
- set_control(request: phoenix6.hardware.parent_device.SupportsSendRequest) phoenix6.status_signal.StatusCode ¶
- set_quadrature_position(new_value: phoenix6.units.rotation, timeout_seconds: phoenix6.units.second = 0.1) phoenix6.status_signal.StatusCode ¶
Sets the position of the quadrature input.
- 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:
- clear_sticky_faults(timeout_seconds: phoenix6.units.second = 0.1) 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:
- clear_sticky_fault_hardware(timeout_seconds: phoenix6.units.second = 0.1) 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:
- clear_sticky_fault_undervoltage(timeout_seconds: phoenix6.units.second = 0.1) 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:
- clear_sticky_fault_boot_during_enable(timeout_seconds: phoenix6.units.second = 0.1) 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:
- clear_sticky_fault_unlicensed_feature_in_use(timeout_seconds: phoenix6.units.second = 0.1) phoenix6.status_signal.StatusCode ¶
Clear sticky fault: An unlicensed feature is in use, device may not behave as expected.
- Parameters:
timeout_seconds (second) – Maximum time to wait up to in seconds.
- Returns:
StatusCode of the set command
- Return type:
- clear_sticky_fault_5_v(timeout_seconds: phoenix6.units.second = 0.1) phoenix6.status_signal.StatusCode ¶
Clear sticky fault: CANdi has detected a 5V fault. This may be due to overcurrent or a short-circuit.
- Parameters:
timeout_seconds (second) – Maximum time to wait up to in seconds.
- Returns:
StatusCode of the set command
- Return type: