Files
PX4-Autopilot/msg/EscReport.msg
Jacob Dahl f00e46f618 feat(dshot): Extended Telemetry and EEPROM support
Overhauls the DShot driver with per-timer BDShot selection, multi-timer                                                                                                                                  
sequential capture, Extended DShot Telemetry (EDT), and AM32 ESC EEPROM                                                                                                                                  
read/write via MAVLink. Expands ESC support from 8 to 12 channels.                                                                                                                                       
                                                                                                                                                                                                   
BDShot:                                                                                                                                                                                                  
- Per-timer BDShot protocol selection via actuator config UI                                                                                                                                             
- Multi-timer sequential burst/capture on any DMA-capable timer                                                                                                                                          
- Adaptive per-channel GCR bitstream decoding                                                                                                                                                            
- Per-channel online/offline detection with hysteresis                                                                                                                                                   
                                                                                                                                                                                                   
Extended DShot Telemetry (EDT):                                                                                                                                                                          
- Temperature, voltage, current from BDShot frames (no serial wire)                                                                                                                                      
- New DSHOT_BIDIR_EDT parameter                                                                                                                                     
- EDT data merged with serial telemetry when both available                                                                                                                                              
                                                                                                                                                                                                   
AM32 EEPROM:                                                                                                                                                                                             
- Read/write AM32 ESC settings via MAVLink ESC_EEPROM message                                                                                                                                            
- ESCSettingsInterface abstraction for future ESC firmware types                                                                                                                                         
- New DSHOT_ESC_TYPE parameter                                                                                                                                                                           
                                                                                                                                                                                                   
Other changes:                                                                                                                                                                                           
- Per-motor pole count params DSHOT_MOT_POL1–12 (replaces MOT_POLE_COUNT)                                                                                                                              
- EscStatus/EscReport expanded to 12 ESCs with uint16 bitmasks                                                                                                                                           
- Numerous bounds-check, overflow, and concurrency fixes                                                                                                                                                 
- Updated DShot documentation
2026-03-17 16:38:33 -08:00

32 lines
1.6 KiB
Plaintext

uint64 timestamp # [us] Time since system start
uint32 esc_errorcount # [-] Number of reported errors by ESC - if supported
int32 esc_rpm # [rpm] Motor RPM, negative for reverse rotation - if supported
float32 esc_voltage # [V] Voltage measured from current ESC - if supported
float32 esc_current # [A] Current measured from current ESC - if supported
float32 esc_temperature # [degC] Temperature measured from current ESC - if supported
uint8 esc_address # [-] Address of current ESC (in most cases 1-12 / must be set by driver)
int16 motor_temperature # [degC] Temperature measured from current motor - if supported
uint8 esc_state # [-] State of ESC - depend on Vendor
uint8 actuator_function # [-] Actuator output function (one of Motor1...MotorN)
uint8 ACTUATOR_FUNCTION_MOTOR1 = 101
uint8 ACTUATOR_FUNCTION_MOTOR_MAX = 112 # output_functions.yaml Motor.start + Motor.count - 1
uint16 failures # [@enum FAILURE] Bitmask to indicate the internal ESC faults
int8 esc_power # [%] [@range 0,100] Applied power (negative values reserved)
uint8 FAILURE_OVER_CURRENT = 0 # (1 << 0)
uint8 FAILURE_OVER_VOLTAGE = 1 # (1 << 1)
uint8 FAILURE_MOTOR_OVER_TEMPERATURE = 2 # (1 << 2)
uint8 FAILURE_OVER_RPM = 3 # (1 << 3)
uint8 FAILURE_INCONSISTENT_CMD = 4 # (1 << 4) Set if ESC received an inconsistent command (i.e out of boundaries)
uint8 FAILURE_MOTOR_STUCK = 5 # (1 << 5)
uint8 FAILURE_GENERIC = 6 # (1 << 6)
uint8 FAILURE_MOTOR_WARN_TEMPERATURE = 7 # (1 << 7)
uint8 FAILURE_WARN_ESC_TEMPERATURE = 8 # (1 << 8)
uint8 FAILURE_OVER_ESC_TEMPERATURE = 9 # (1 << 9)
uint8 ESC_FAILURE_COUNT = 10 # Counter - keep it as last element!