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
This commit is contained in:
Jacob Dahl
2026-03-17 16:38:33 -08:00
committed by GitHub
parent c9ee06ff17
commit f00e46f618
48 changed files with 2997 additions and 1692 deletions

View File

@@ -69,6 +69,8 @@ set(msg_files
DistanceSensorModeChangeRequest.msg
DronecanNodeStatus.msg
Ekf2Timestamps.msg
EscEepromRead.msg
EscEepromWrite.msg
EscReport.msg
EscStatus.msg
EstimatorAidSource1d.msg

7
msg/EscEepromRead.msg Normal file
View File

@@ -0,0 +1,7 @@
uint64 timestamp # [us] Time since system start
uint8 firmware # [-] ESC firmware type (see ESC_FIRMWARE enum in MAVLink)
uint8 index # [-] Index of the ESC (0 = ESC1, 1 = ESC2, etc.)
uint16 length # [-] Length of valid data
uint8[48] data # [-] Raw ESC EEPROM data
uint8 ORB_QUEUE_LENGTH = 8 # To support 8 queued up responses

8
msg/EscEepromWrite.msg Normal file
View File

@@ -0,0 +1,8 @@
uint64 timestamp # [us] Time since system start
uint8 firmware # [-] ESC firmware type (see ESC_FIRMWARE enum in MAVLink)
uint8 index # [-] Index of the ESC (0 = ESC1, 1 = ESC2, etc, 255 = All)
uint16 length # [-] Length of valid data
uint8[48] data # [-] Raw ESC EEPROM data
uint32[2] write_mask # [-] Bitmask indicating which bytes in the data array should be written (max 48 values)
uint8 ORB_QUEUE_LENGTH = 8 # To support 8 queued up requests

View File

@@ -1,30 +1,31 @@
uint64 timestamp # time since system start (microseconds)
uint32 esc_errorcount # Number of reported errors by ESC - if supported
int32 esc_rpm # Motor RPM, negative for reverse rotation [RPM] - if supported
float32 esc_voltage # Voltage measured from current ESC [V] - if supported
float32 esc_current # Current measured from current ESC [A] - if supported
float32 esc_temperature # Temperature measured from current ESC [degC] - if supported
int16 motor_temperature # Temperature measured from current motor [degC] - if supported
uint8 esc_address # Address of current ESC (in most cases 1-8 / must be set by driver)
uint8 esc_cmdcount # Counter of number of commands
uint64 timestamp # [us] Time since system start
uint8 esc_state # State of ESC - depend on Vendor
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 # 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 # Bitmask to indicate the internal ESC faults
int8 esc_power # Applied power 0-100 in % (negative values reserved)
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!
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!

View File

@@ -1,28 +1,32 @@
uint64 timestamp # time since system start (microseconds)
uint8 CONNECTED_ESC_MAX = 8 # The number of ESCs supported. Current (Q2/2013) we support 8 ESCs
uint64 timestamp # [us] Time since system start
uint8 CONNECTED_ESC_MAX = 12 # The number of ESCs supported (Motor1-Motor12)
uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC
uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC
uint8 ESC_CONNECTION_TYPE_ONESHOT = 2 # One Shot PPM
uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C
uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus
uint8 ESC_CONNECTION_TYPE_DSHOT = 5 # DShot
uint8 ESC_CONNECTION_TYPE_PPM = 0 # Traditional PPM ESC
uint8 ESC_CONNECTION_TYPE_SERIAL = 1 # Serial Bus connected ESC
uint8 ESC_CONNECTION_TYPE_ONESHOT = 2 # One Shot PPM
uint8 ESC_CONNECTION_TYPE_I2C = 3 # I2C
uint8 ESC_CONNECTION_TYPE_CAN = 4 # CAN-Bus
uint8 ESC_CONNECTION_TYPE_DSHOT = 5 # DShot
uint16 counter # incremented by the writing thread everytime new data is stored
uint16 counter # [-] Incremented by the writing thread everytime new data is stored
uint8 esc_count # number of connected ESCs
uint8 esc_connectiontype # how ESCs connected to the system
uint8 esc_count # [-] Number of connected ESCs
uint8 esc_connectiontype # [@enum ESC_CONNECTION_TYPE] How ESCs connected to the system
uint8 esc_online_flags # Bitmask indicating which ESC is online/offline
# esc_online_flags bit 0 : Set to 1 if ESC0 is online
# esc_online_flags bit 1 : Set to 1 if ESC1 is online
# esc_online_flags bit 2 : Set to 1 if ESC2 is online
# esc_online_flags bit 3 : Set to 1 if ESC3 is online
# esc_online_flags bit 4 : Set to 1 if ESC4 is online
# esc_online_flags bit 5 : Set to 1 if ESC5 is online
# esc_online_flags bit 6 : Set to 1 if ESC6 is online
# esc_online_flags bit 7 : Set to 1 if ESC7 is online
uint16 esc_online_flags # Bitmask indicating which ESC is online/offline (in motor order)
# esc_online_flags bit 0 : Set to 1 if Motor1 is online
# esc_online_flags bit 1 : Set to 1 if Motor2 is online
# esc_online_flags bit 2 : Set to 1 if Motor3 is online
# esc_online_flags bit 3 : Set to 1 if Motor4 is online
# esc_online_flags bit 4 : Set to 1 if Motor5 is online
# esc_online_flags bit 5 : Set to 1 if Motor6 is online
# esc_online_flags bit 6 : Set to 1 if Motor7 is online
# esc_online_flags bit 7 : Set to 1 if Motor8 is online
# esc_online_flags bit 8 : Set to 1 if Motor9 is online
# esc_online_flags bit 9 : Set to 1 if Motor10 is online
# esc_online_flags bit 10: Set to 1 if Motor11 is online
# esc_online_flags bit 11: Set to 1 if Motor12 is online
uint8 esc_armed_flags # Bitmask indicating which ESC is armed. For ESC's where the arming state is not known (returned by the ESC), the arming bits should always be set.
uint16 esc_armed_flags # [-] Bitmask indicating which ESC is armed (in motor order)
EscReport[8] esc
EscReport[12] esc

View File

@@ -80,6 +80,7 @@ uint16 VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION = 283 # Command to ask information
uint16 VEHICLE_CMD_MISSION_START = 300 # Start running a mission. |first_item: the first mission item to run|last_item: the last mission item to run (after this item is run, the mission ends)|
uint16 VEHICLE_CMD_ACTUATOR_TEST = 310 # Actuator testing command. |[@range -1,1] value|[s] timeout|Unused|Unused|output function|
uint16 VEHICLE_CMD_CONFIGURE_ACTUATOR = 311 # Actuator configuration command. |configuration|Unused|Unused|Unused|output function|
uint16 VEHICLE_CMD_ESC_REQUEST_EEPROM = 312 # Request EEPROM data from an ESC. |ESC Index|Firmware Type|Unused|Unused|Unused|
uint16 VEHICLE_CMD_COMPONENT_ARM_DISARM = 400 # Arms / Disarms a component. |1 to arm, 0 to disarm.
uint16 VEHICLE_CMD_RUN_PREARM_CHECKS = 401 # Instructs a target system to run pre-arm checks.
uint16 VEHICLE_CMD_INJECT_FAILURE = 420 # Inject artificial failure for testing purposes.
@@ -129,6 +130,13 @@ uint8 VEHICLE_ROI_LOCATION = 3 # Point toward fixed location.
uint8 VEHICLE_ROI_TARGET = 4 # Point toward target.
uint8 VEHICLE_ROI_ENUM_END = 5
uint8 ACTUATOR_CONFIGURATION_NONE = 0 # Do nothing.
uint8 ACTUATOR_CONFIGURATION_BEEP = 1 # Command the actuator to beep now.
uint8 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2 # Permanently set the actuator (ESC) to 3D mode (reversible thrust).
uint8 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3 # Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust).
uint8 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4 # Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise).
uint8 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5 # Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1).
uint8 PARACHUTE_ACTION_DISABLE = 0
uint8 PARACHUTE_ACTION_ENABLE = 1
uint8 PARACHUTE_ACTION_RELEASE = 2