Skip to content

Conversation

@dakejahl
Copy link
Contributor

Summary

Major refactoring of the DShot driver adding Extended DShot Telemetry (EDT) support, ESC EEPROM read/write, and significant robustness improvements to bidirectional DShot decoding.

Key Changes

Extended DShot Telemetry (EDT)

  • HAL-level support for EDT frames interleaved with eRPM data (temperature, voltage, current)
  • New DSHOT_BIDIR_EDT parameter to enable EDT mode
  • New up_bdshot_get_extended_telemetry() API for retrieving EDT values by type
  • Improved status reporting/formatting via CLI dshot status

ESC EEPROM Architecture

  • New ESCSettingsInterface abstract base class for firmware-agnostic ESC settings handling
  • AM32Settings implementation with full 48-byte EEPROM structure support
  • New uORB messages: esc_eeprom_read and esc_eeprom_write with selective byte write masking
  • MAVLink ESC_EEPROM stream for bidirectional EEPROM access via GCS

BDShot Robustness Improvements

  • Adaptive per-channel timing calibration handles ESC oscillator variation
  • New convert_edge_intervals_to_bitstream() with flexible frame validation (18-24 bits)
  • Online/offline detection with 200-count hysteresis to prevent spurious state changes
  • Multi-timer BDShot support with sequential timer processing architecture. Allows multiple timers to use BDShot by triggering the Burst/Capture sequentially. This also means we only need 1 DMA to support BDShot across all timers.

DShot Driver Refactoring

  • Clean State enum (Armed/Disarmed) replacing scattered boolean flags
  • Unified telemetry handling via DShotCommon.h with standardized EscData structure
  • Separated serial and BDShot telemetry processing paths
  • ESC programming state machine for EEPROM operations
  • New vehicle command handler for MAV_CMD_ESC_REQUEST_EEPROM

Other Changes

  • New DSHOT_ESC_TYPE parameter for ESC firmware identification
  • BDShot150/300/600 added as distinct PWM output modes
  • Improved ESC health checking: only reports offline ESCs that are actually configured as motors
  • New isMotor() helper in mixer_module for motor output detection
  • Tools/bdshot_analyzer.py: Saleae timing analysis tool for BDShot signal debugging

Testing Notes

  • Requires BDShot-capable ESCs for EDT testing
  • AM32 firmware ESCs required for EEPROM functionality
  • MAVLink development dialect required for ESC_EEPROM messages

Parameters

DSHOT_ESC_TYPE=1 (for AM32, for ESC settings testing)
DSHOT_BIDIR_EDT=1 (for EDT testing)


DShot Sequential Timer triggering timing analysis

Timing analysis script for use with Saleae to validate sequential bdshot trigger timing.

python Tools/bdshot_analyzer.py ~Downloads/digital.csv --dshot-rate 300 --loop-rate 800
bdshot_timing

ESC_EEPROM Support in QGC

New UI in QGC for configuring AM32 ESCs. Feature branch is still WIP https://github.com/dakejahl/qgroundcontrol/pull/3/changes

am32_qgc_new

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-dev-call-jan-14-2026-team-sync-and-community-q-a/48289/1

@github-actions
Copy link

github-actions bot commented Jan 14, 2026

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 8396 byte (0.4 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.3% +6.27Ki  +0.3% +6.27Ki    .text
 -99.4% +1.34Ki -99.4% +1.34Ki    [86 Others]
  +0.8% +1.29Ki  +0.8% +1.29Ki    [section .text]
  [NEW]    +924  [NEW]    +924    DShot::select_next_command()
  +129%    +680  +129%    +680    capture_complete_callback
  +391%    +672  +391%    +672    DShot::print_status()
  [NEW]    +384  [NEW]    +384    DShot::process_bdshot_telemetry()
  [NEW]    +372  [NEW]    +372    DShot::process_serial_telemetry()
   +73%    +360   +73%    +360    DShot::DShot()
  [NEW]    +324  [NEW]    +324    DShot::handle_configure_actuator()
  [NEW]    +304  [NEW]    +304    DShotTelemetry::parseCommandResponse()
 +22e2%    +302 +22e2%    +302    DShot::mixerChanged()
  [NEW]    +262  [NEW]    +262    DShot::consume_esc_data()
  [NEW]    +260  [NEW]    +260    DShotTelemetry::decodeTelemetryResponse()
  +165%    +244  +165%    +244    up_bdshot_status
  [NEW]    +184  [NEW]    +184    DShot::initialize_dshot()
  [DEL]    -186  [DEL]    -186    DShot::handle_new_bdshot_erpm()
  [DEL]    -220  [DEL]    -220    DShot::handle_new_telemetry_data()
 -64.1%    -236 -64.1%    -236    DShot::handle_vehicle_commands()
  [DEL]    -264  [DEL]    -264    DShotTelemetry::update()
  [DEL]    -284  [DEL]    -284    DShot::enable_dshot_outputs()
 -71.9%    -348 -71.9%    -348    DShot::print_usage()
[ = ]       0  +2.2% +1.88Ki    .bss
  [ = ]       0  +400%   +1024    dshot_capture_buffer
  [ = ]       0  +500%    +180    _erpms
  [ = ]       0  [NEW]    +160    _cc_calls
  [ = ]       0  [NEW]    +144    _edt_curr
  [ = ]       0  [NEW]    +144    _edt_temp
  [ = ]       0  [NEW]    +144    _edt_volt
  [ = ]       0  +258%     +49    [section .bss]
  [ = ]       0  [NEW]     +36    _consecutive_failures
  [ = ]       0  [NEW]     +36    _consecutive_successes
  [ = ]       0  +125%     +20    read_fail_crc
  [ = ]       0  +100%     +20    read_ok
  [ = ]       0  [NEW]     +12    _bdshot_capture_supported
  [ = ]       0  [NEW]     +12    _bdshot_processed
  [ = ]       0  +100%     +10    [6 Others]
  [ = ]       0  [NEW]      +9    _bdshot_online
  [ = ]       0  [NEW]      +8    AM32Settings::_esc_eeprom_read_pub
  [ = ]       0  [DEL]     -12    _erpms_ready
  [ = ]       0 -75.0%     -12    g_dma_perf
  [ = ]       0  [DEL]     -16    read_fail_nibble
  [ = ]       0  [DEL]     -16    read_fail_zero
  [ = ]       0  [DEL]     -32    _cc_call
+1.1%     +48  +1.1%     +48    .data
  [NEW]     +36  [NEW]     +36    _base_interval
  [NEW]      +8  [NEW]      +8    _bdshot_cycle_complete
  [NEW]      +4  [NEW]      +4    _bdshot_channel_mask
+1.0%      +4  +1.0%      +4    .init_section
+0.2% +3.61Ki  [ = ]       0    .debug_abbrev
+0.2%    +280  [ = ]       0    .debug_aranges
+0.2%    +856  [ = ]       0    .debug_frame
+0.2% +51.4Ki  [ = ]       0    .debug_info
+0.2% +10.1Ki  [ = ]       0    .debug_line
  +250%      +5  [ = ]       0    [Unmapped]
  +0.2% +10.1Ki  [ = ]       0    [section .debug_line]
+0.2% +5.53Ki  [ = ]       0    .debug_loclists
+0.2%    +934  [ = ]       0    .debug_rnglists
  [DEL]      -1  [ = ]       0    [Unmapped]
  +0.2%    +935  [ = ]       0    [section .debug_rnglists]
+0.1% +4.86Ki  [ = ]       0    .debug_str
+0.4%      +1  [ = ]       0    .shstrtab
+0.2% +1.29Ki  [ = ]       0    .strtab
  [NEW]     +19  [ = ]       0    AM32Settings
  [NEW]     +44  [ = ]       0    AM32Settings::AM32Settings()
  [NEW]     +43  [ = ]       0    AM32Settings::decodeInfoResponse()
  [NEW]     +45  [ = ]       0    AM32Settings::getExpectedResponseSize()
  [NEW]     +36  [ = ]       0    AM32Settings::publish_latest()
  [NEW]     +66  [ = ]       0    AM32Settings::~AM32Settings()
  [DEL]     -11  [ = ]       0    CSWTCH.154
  [DEL]     -12  [ = ]       0    CSWTCH.2711
  [NEW]     +12  [ = ]       0    CSWTCH.2712
  [DEL]     -10  [ = ]       0    CSWTCH.30
  [NEW]     +10  [ = ]       0    CSWTCH.31
  [DEL]     -24  [ = ]       0    CSWTCH.3459
  [DEL]     -24  [ = ]       0    CSWTCH.3460
  [NEW]     +24  [ = ]       0    CSWTCH.3461
  [NEW]     +24  [ = ]       0    CSWTCH.3462
  [DEL]     -10  [ = ]       0    CSWTCH.62
  [NEW]     +37  [ = ]       0    DShot::calculate_output_value()
  [NEW]     +56  [ = ]       0    DShot::consume_esc_data()
  [DEL]     -34  [ = ]       0    DShot::enable_dshot_outputs()
  [NEW]     +30  [ = ]       0    DShot::esc_armed_mask()
 -96.2%   +1002  [ = ]       0    [69 Others]
+0.3% +1.61Ki  [ = ]       0    .symtab
  [NEW]     +32  [ = ]       0    AM32Settings
  [NEW]     +64  [ = ]       0    AM32Settings::AM32Settings()
  [NEW]     +48  [ = ]       0    AM32Settings::_esc_eeprom_read_pub
  [NEW]     +64  [ = ]       0    AM32Settings::decodeInfoResponse()
  [NEW]     +32  [ = ]       0    AM32Settings::getExpectedResponseSize()
  [NEW]     +48  [ = ]       0    AM32Settings::publish_latest()
  [NEW]     +80  [ = ]       0    AM32Settings::~AM32Settings()
  [DEL]     -32  [ = ]       0    CSWTCH.154
  [DEL]     -32  [ = ]       0    CSWTCH.2711
  [NEW]     +32  [ = ]       0    CSWTCH.2712
  [DEL]     -32  [ = ]       0    CSWTCH.30
  [NEW]     +32  [ = ]       0    CSWTCH.31
  [DEL]     -48  [ = ]       0    CSWTCH.3459
  [DEL]     -48  [ = ]       0    CSWTCH.3460
  [NEW]     +48  [ = ]       0    CSWTCH.3461
  [NEW]     +48  [ = ]       0    CSWTCH.3462
  [DEL]     -48  [ = ]       0    CSWTCH.62
 -25.0%     -16  [ = ]       0    DShot::DShot()
  [NEW]     +32  [ = ]       0    DShot::calculate_output_value()
  [NEW]     +32  [ = ]       0    DShot::consume_esc_data()
 -61.9% +1.28Ki  [ = ]       0    [86 Others]
 +19% +1.72Ki  [ = ]       0    [Unmapped]
+0.2% +88.4Ki  +0.4% +8.20Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 8428 byte (0.41 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.3% +6.32Ki  +0.3% +6.32Ki    .text
 -99.3% +1.39Ki -99.3% +1.39Ki    [85 Others]
  +0.8% +1.28Ki  +0.8% +1.28Ki    [section .text]
  [NEW]    +924  [NEW]    +924    DShot::select_next_command()
  +129%    +680  +129%    +680    capture_complete_callback
  +391%    +672  +391%    +672    DShot::print_status()
  [NEW]    +384  [NEW]    +384    DShot::process_bdshot_telemetry()
  [NEW]    +372  [NEW]    +372    DShot::process_serial_telemetry()
   +73%    +360   +73%    +360    DShot::DShot()
  [NEW]    +324  [NEW]    +324    DShot::handle_configure_actuator()
  [NEW]    +304  [NEW]    +304    DShotTelemetry::parseCommandResponse()
 +22e2%    +302 +22e2%    +302    DShot::mixerChanged()
  [NEW]    +262  [NEW]    +262    DShot::consume_esc_data()
  [NEW]    +260  [NEW]    +260    DShotTelemetry::decodeTelemetryResponse()
  +165%    +244  +165%    +244    up_bdshot_status
  [NEW]    +184  [NEW]    +184    DShot::initialize_dshot()
  [DEL]    -186  [DEL]    -186    DShot::handle_new_bdshot_erpm()
  [DEL]    -220  [DEL]    -220    DShot::handle_new_telemetry_data()
 -64.1%    -236 -64.1%    -236    DShot::handle_vehicle_commands()
  [DEL]    -264  [DEL]    -264    DShotTelemetry::update()
  [DEL]    -284  [DEL]    -284    DShot::enable_dshot_outputs()
 -71.9%    -348 -71.9%    -348    DShot::print_usage()
[ = ]       0  +2.0% +1.88Ki    .bss
  [ = ]       0  +400%   +1024    dshot_capture_buffer
  [ = ]       0  +500%    +180    _erpms
  [ = ]       0  [NEW]    +160    _cc_calls
  [ = ]       0  [NEW]    +144    _edt_curr
  [ = ]       0  [NEW]    +144    _edt_temp
  [ = ]       0  [NEW]    +144    _edt_volt
  [ = ]       0  [NEW]     +36    _consecutive_failures
  [ = ]       0  [NEW]     +36    _consecutive_successes
  [ = ]       0   +67%     +32    [section .bss]
  [ = ]       0  +125%     +20    read_fail_crc
  [ = ]       0  +100%     +20    read_ok
  [ = ]       0  [NEW]     +12    _bdshot_capture_supported
  [ = ]       0  [NEW]     +12    _bdshot_processed
  [ = ]       0  [NEW]      +9    _bdshot_online
  [ = ]       0  [NEW]      +8    AM32Settings::_esc_eeprom_read_pub
  [ = ]       0  +200%      +8    _dshot_frequency
  [ = ]       0 -12.5%      +7    [6 Others]
  [ = ]       0  [DEL]     -12    _erpms_ready
  [ = ]       0  [DEL]     -16    read_fail_nibble
  [ = ]       0  [DEL]     -16    read_fail_zero
  [ = ]       0  [DEL]     -32    _cc_call
+0.7%     +32  +0.7%     +32    .data
  [NEW]     +36  [NEW]     +36    _base_interval
   +13%     +12   +13%     +12    g_spi1dev
  [NEW]      +8  [NEW]      +8    _bdshot_cycle_complete
  [NEW]      +4  [NEW]      +4    _bdshot_channel_mask
  [DEL]     -28  [DEL]     -28    [section .data]
+1.1%      +4  +1.1%      +4    .init_section
+0.2% +3.61Ki  [ = ]       0    .debug_abbrev
+0.2%    +280  [ = ]       0    .debug_aranges
+0.2%    +876  [ = ]       0    .debug_frame
+0.2% +51.1Ki  [ = ]       0    .debug_info
+0.2% +10.1Ki  [ = ]       0    .debug_line
  [NEW]      +6  [ = ]       0    [Unmapped]
  +0.2% +10.1Ki  [ = ]       0    [section .debug_line]
+0.2% +5.61Ki  [ = ]       0    .debug_loclists
+0.2%    +949  [ = ]       0    .debug_rnglists
  [NEW]      +2  [ = ]       0    [Unmapped]
  +0.2%    +947  [ = ]       0    [section .debug_rnglists]
+0.1% +4.85Ki  [ = ]       0    .debug_str
-0.4%      -1  [ = ]       0    .shstrtab
+0.2% +1.30Ki  [ = ]       0    .strtab
  [NEW]     +19  [ = ]       0    AM32Settings
  [NEW]     +44  [ = ]       0    AM32Settings::AM32Settings()
  [NEW]     +43  [ = ]       0    AM32Settings::decodeInfoResponse()
  [NEW]     +45  [ = ]       0    AM32Settings::getExpectedResponseSize()
  [NEW]     +36  [ = ]       0    AM32Settings::publish_latest()
  [NEW]     +66  [ = ]       0    AM32Settings::~AM32Settings()
  [DEL]     -11  [ = ]       0    CSWTCH.154
  [DEL]     -12  [ = ]       0    CSWTCH.2711
  [NEW]     +12  [ = ]       0    CSWTCH.2712
  [DEL]     -10  [ = ]       0    CSWTCH.30
  [NEW]     +10  [ = ]       0    CSWTCH.31
  [DEL]     -24  [ = ]       0    CSWTCH.3459
  [DEL]     -24  [ = ]       0    CSWTCH.3460
  [NEW]     +24  [ = ]       0    CSWTCH.3461
  [NEW]     +24  [ = ]       0    CSWTCH.3462
  [NEW]     +37  [ = ]       0    DShot::calculate_output_value()
  [NEW]     +56  [ = ]       0    DShot::consume_esc_data()
  [DEL]     -34  [ = ]       0    DShot::enable_dshot_outputs()
  [NEW]     +30  [ = ]       0    DShot::esc_armed_mask()
  [NEW]     +59  [ = ]       0    DShot::handle_configure_actuator()
 -96.3%    +943  [ = ]       0    [66 Others]
+0.3% +1.61Ki  [ = ]       0    .symtab
  [NEW]     +32  [ = ]       0    AM32Settings
  [NEW]     +64  [ = ]       0    AM32Settings::AM32Settings()
  [NEW]     +48  [ = ]       0    AM32Settings::_esc_eeprom_read_pub
  [NEW]     +64  [ = ]       0    AM32Settings::decodeInfoResponse()
  [NEW]     +32  [ = ]       0    AM32Settings::getExpectedResponseSize()
  [NEW]     +48  [ = ]       0    AM32Settings::publish_latest()
  [NEW]     +80  [ = ]       0    AM32Settings::~AM32Settings()
  [DEL]     -32  [ = ]       0    CSWTCH.154
  [DEL]     -32  [ = ]       0    CSWTCH.2711
  [NEW]     +32  [ = ]       0    CSWTCH.2712
  [DEL]     -32  [ = ]       0    CSWTCH.30
  [NEW]     +32  [ = ]       0    CSWTCH.31
  [DEL]     -48  [ = ]       0    CSWTCH.3459
  [DEL]     -48  [ = ]       0    CSWTCH.3460
  [NEW]     +48  [ = ]       0    CSWTCH.3461
  [NEW]     +48  [ = ]       0    CSWTCH.3462
 -60.0%     -48  [ = ]       0    CSWTCH.63
 -25.0%     -16  [ = ]       0    DShot::DShot()
  [NEW]     +32  [ = ]       0    DShot::calculate_output_value()
  [NEW]     +32  [ = ]       0    DShot::consume_esc_data()
 -54.2% +1.28Ki  [ = ]       0    [79 Others]
-20.0%     -32  [ = ]       0    [ELF Program Headers]
-33.9% -2.29Ki  [ = ]       0    [Unmapped]
+0.2% +84.2Ki  +0.4% +8.23Ki    TOTAL

Updated: 2026-01-28T06:35:08

@mrpollo mrpollo requested a review from Igor-Misic January 14, 2026 16:21
@mrpollo
Copy link
Contributor

mrpollo commented Jan 14, 2026

Reviewers maybe we should coordinate and split the review so its faster and easier on everyone, please coordinate on the maintainer channel on discord so we can get this moving!

@julianoes
Copy link
Contributor

Multi-timer BDShot support with sequential timer processing architecture. Allows multiple timers to use BDShot by triggering the Burst/Capture sequentially. This also means we only need 1 DMA to support BDShot across all timers.

How much latency does this introduce? And why not do it in parallel per timer? For the boards that I recently worked with there seemed enough DMA channels available anyway.

Copy link
Contributor

@erkki erkki left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@dakejahl
Copy link
Contributor Author

How much latency does this introduce?

See above plot from the bdshot_analyzer.py. The inter channel gap mean is 78us and the max is 138us. This is negligible in the context of 800Hz control loop. For comparison, a 4KHz control loop rate is 250us intervals. The IMU_GYRO_RATEMAX param only goes as high as 2KHz.

And why not do it in parallel per timer? For the boards that I recently worked with there seemed enough DMA channels available anyway.

There is a race condition. Both timers finish burst complete at about the same time. The callback which sets up capture for the first timer takes too long. By the time the capture is set up for the second timer, the response frame has already started. So the second timer capture/compare consistently misses the first part of the response.

@julianoes
Copy link
Contributor

the max is 138us.

That's with 8 outputs or 4? And At fastest DShot 600 I assume?

@dakejahl
Copy link
Contributor Author

the max is 138us.

That's with 8 outputs or 4? And At fastest DShot 600 I assume?

It's with 2 timers and dshot300. The "inter channel gap" is the time delta between Timer1 capture complete and Timer2 burst start.

It doesn't matter if it's dshot150/300/600, the time delta is composed of the delay in hrt_call_after(&_cc_calls[timer_index], delay, capture_complete_callback, arg) and the setup time for configuring and triggering the next timer.

@julianoes
Copy link
Contributor

But wouldn't the capture complete be later/slower depending on the DShot variant. I guess I'm still confused.

@dakejahl
Copy link
Contributor Author

dakejahl commented Jan 15, 2026

But wouldn't the capture complete be later/slower depending on the DShot variant. I guess I'm still confused.

DShot150 frame length is twice as long as DShot300 (~100us vs ~50us). Same goes for capture (~70u vs ~140us). At DShot150 you can expect a 240us delta between Timer1_Burst and Timer2_Burst. This is negligible for motor control. The interval between Timer1_Burst_N and Timer1_Burst_N+1 and Timer2_Burst_N and Timer2_Burst_N+1 is consistent and within the min/max as show in the image above (Channel A/B Frame Intervals)

@erkki
Copy link
Contributor

erkki commented Jan 16, 2026

Having some trouble getting ESC_EEPROM stream to show up in QGC / mavsdk.

FC: imxrt based / V6X-RT
ESC: AM32 TEKKO32 2.17
Serial telemetry is not enabled.

Tested with both EDT enabled and EDT disabled (although EDT seems to be not implemented for imxrt currently: https://github.com/PX4/PX4-Autopilot/pull/26263/files#diff-ee11cd0da359496d5246d1e4759d08dee22fa735d4c4aed71afe1547eb55d56fR534).

Is the understanding correct that ESC_EEPROM / ESC settings should show up fine with standard BDSHOT telemetry (without EDT, without serial telemetry)?

@dakejahl
Copy link
Contributor Author

Is the understanding correct that ESC_EEPROM / ESC settings should show up fine with standard BDSHOT telemetry (without EDT, without serial telemetry)?

You need serial telemetry because that's how the ESC settings are sent. The settings are requested from one ESC at a time via .dshot command and sent over the serial line. You don't need EDT. Also set DSHOT_ESC_TYPE=1 for AM32.

@PetervdPerk-NXP
Copy link
Member

PetervdPerk-NXP commented Jan 16, 2026

Having some trouble getting ESC_EEPROM stream to show up in QGC / mavsdk.

FC: imxrt based / V6X-RT ESC: AM32 TEKKO32 2.17 Serial telemetry is not enabled.

Tested with both EDT enabled and EDT disabled (although EDT seems to be not implemented for imxrt currently: https://github.com/PX4/PX4-Autopilot/pull/26263/files#diff-ee11cd0da359496d5246d1e4759d08dee22fa735d4c4aed71afe1547eb55d56fR534).

Is the understanding correct that ESC_EEPROM / ESC settings should show up fine with standard BDSHOT telemetry (without EDT, without serial telemetry)?

If you can't use the telemetry wire on your drone/esc setup you can also flash this esc_passhrough app which implements the 4-Way Interface to USB passthrough on the V6X-RT and then you can use the AM32 web configurator directly without serial telemetry, also this allows you to flash the ESC's.

@erkki
Copy link
Contributor

erkki commented Jan 16, 2026

Having some trouble getting ESC_EEPROM stream to show up in QGC / mavsdk.
FC: imxrt based / V6X-RT ESC: AM32 TEKKO32 2.17 Serial telemetry is not enabled.
Tested with both EDT enabled and EDT disabled (although EDT seems to be not implemented for imxrt currently: https://github.com/PX4/PX4-Autopilot/pull/26263/files#diff-ee11cd0da359496d5246d1e4759d08dee22fa735d4c4aed71afe1547eb55d56fR534).
Is the understanding correct that ESC_EEPROM / ESC settings should show up fine with standard BDSHOT telemetry (without EDT, without serial telemetry)?

If you can't use the telemetry wire on your drone/esc setup you can also flash this esc_passhrough app which implements the 4-Way Interface to USB passthrough on the V6X-RT and then you can use the AM32 web configurator directly without serial telemetry, also this allows you to flash the ESC's.

Thanks for the pointer, will give this a spin.

Was hoping to avoid external configurators =>> might end up with CAN ESCs instead.

@julianoes
Copy link
Contributor

@dakejahl

This is negligible for motor control.

Is it? That was definitely not my assumption based on the fact that people fly 1kHz or 2kHz loops, just to get the gyro loop response time down.

@dakejahl
Copy link
Contributor Author

@dakejahl

This is negligible for motor control.

Is it? That was definitely not my assumption based on the fact that people fly 1kHz or 2kHz loops, just to get the gyro loop response time down.

I mean the devil is in the details. If you are trying to run 2kHz loop rate, dshot150, and using 3+ timers then yes you're going to have problems. Not every combination can be perfectly supported, I think we should optimize for the 99% case. I think the 99% case looks like 800Hz to 2kHz, 1 to 2 timers, and dshot300 or dshot600. Another thing to consider is most people running high loop rates are likely flying freestyle quads, and these should have all 4 motors on the first timer (I know not all do... but the hardware designer should think about these things)

Alternatively we can try to fix the race condition by optimizing timer reconfiguration time and maybe even stagger the bursts ever so slightly rather than stagger them sequentially.

@julianoes what would you suggest? Or what is your preference?

@julianoes
Copy link
Contributor

@dakejahl do I understand correctly that we have to make a trade-off either in response latency, so how quickly the burst ends up on the wire, or whether we can get the RPM feedback of all motors or only one channel per timer per round? If so, then I would strongly lead towards having no latency to the motor output and RPM feedback at a slower rate.

@dakejahl
Copy link
Contributor Author

dakejahl commented Jan 21, 2026

The core issue is that when you burst both timers at the same time the telemetry response frame also comes at the same time. There is only 30us between burst complete and the response frame being received. It takes longer than 30us to setup capture-compare on the first timer (because of all the timer code overhead). This means by the time the capture-compare setup for the second timer takes place, we've already missed some of the response frame bits. On this branch it's 100% error rate. On your other branch it's 10-20% error rate. Triggering the timer burst sequentially (or even just staggering them by 5-10us) solves the problem. Triggering sequentially comes with the added benefit of reducing the required number of available DMA streams, with the tradeoff of added latency from output calculation to on-the-wire for each timer after the first (+75us nominal)

@julianoes
Copy link
Contributor

@dakejahl Oh, ok I'm starting to understand. Let me think about it.

@dakejahl
Copy link
Contributor Author

dakejahl commented Jan 21, 2026

I've updated the implementation to trigger the timers simultaneously with a 10us stagger between them to solve the issue described in the previous comment.

Scope shot from this latest commit, using GPIO to measure the time (15.44us) it takes to configure the timer for capture-compare. There is a 22us delay between triggering Timer1 Burst and Timer2 Burst.
Screenshot from 2026-01-20 17-51-15

dshot status

INFO  [arch_dshot] Output 0: read 648501, failed CRC 2
INFO  [arch_dshot] Output 1: read 648490, failed CRC 13
INFO  [arch_dshot] Output 2: read 648494, failed CRC 10
INFO  [arch_dshot] Output 3: read 648493, failed CRC 10
INFO  [arch_dshot] Output 4: read 648498, failed CRC 5
INFO  [arch_dshot] Output 5: read 648498, failed CRC 6
INFO  [arch_dshot] Output 6: read 648497, failed CRC 7
INFO  [arch_dshot] Output 7: read 648503, failed CRC 1

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-dev-call-jan-21-2026-team-sync-and-community-q-a/48330/2

@alexcekay alexcekay self-requested a review January 21, 2026 17:04
@julianoes
Copy link
Contributor

Testing 4 outputs over 2 timers on CubeOrange:

nsh> dshot status
----------------------------------------------------------------
INFO  [dshot] DShot Driver Status
----------------------------------------------------------------
INFO  [dshot] Configuration:
INFO  [dshot]   Output Mask:        0x33 (4 channels)
INFO  [dshot]   BDShot Telemetry:   Enabled
INFO  [dshot]   Serial Telemetry:   Disabled
INFO  [dshot]   Extended DShot:     Disabled
INFO  [dshot]   ESC Type:           Unknown (0)
INFO  [dshot]   Motor Poles:        14
INFO  [dshot]   3D Mode:            Disabled
----------------------------------------------------------------
INFO  [dshot] Telemetry Status:
INFO  [dshot]   Ch   Motor  BDShot   Serial   BDShot Err   Serial Err
INFO  [dshot]   1    1      Online   -        0            0
INFO  [dshot]   2    2      Online   -        634          0
INFO  [dshot]   5    3      Online   -        0            0
INFO  [dshot]   6    4      Online   -        0            0
----------------------------------------------------------------
INFO  [dshot] Bidirectional DShot Hardware:
INFO  [arch_dshot] dshot driver stats:
INFO  [arch_dshot] BDShot channel mask: 0x33
----------------------------------------------------------------
INFO  [dshot] Mixer Information:
INFO  [mixer_module] Param prefix: PWM_AUX
control latency: 93286 events, 24708022us elapsed, 264.86us avg, min 253us max 504us 7.154us rms
INFO  [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 109, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 1: func: 102, value: 109, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 2: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 3: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 4: func: 103, value: 109, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 5: func: 104, value: 109, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
----------------------------------------------------------------
INFO  [dshot] Performance Counters:
dshot: cycle: 93373 events, 4994525us elapsed, 53.49us avg, min 47us max 1380us 5.727us rms
dshot: bdshot success: 44904 events
dshot: bdshot error: 0 events
----------------------------------------------------------------

@dakejahl any idea why Ch2 is showing errors?

@julianoes
Copy link
Contributor

And here is a test on just the first 4 motor outputs on the Holybro Kakute H743-Wing:

INFO  [dshot] DShot Driver Status
----------------------------------------------------------------
INFO  [dshot] Configuration:
INFO  [dshot]   Output Mask:        0x0f (4 channels)
INFO  [dshot]   BDShot Telemetry:   Enabled
INFO  [dshot]   Serial Telemetry:   Disabled
INFO  [dshot]   Extended DShot:     Disabled
INFO  [dshot]   ESC Type:           Unknown (0)
INFO  [dshot]   Motor Poles:        14
INFO  [dshot]   3D Mode:            Disabled
----------------------------------------------------------------
INFO  [dshot] Telemetry Status:
INFO  [dshot]   Ch   Motor  BDShot   Serial   BDShot Err   Serial Err  
INFO  [dshot]   1    1      Online   -        0            0           
INFO  [dshot]   2    2      Online   -        0            0           
INFO  [dshot]   3    3      Online   -        0            0           
INFO  [dshot]   4    4      Online   -        0            0           
----------------------------------------------------------------
INFO  [dshot] Bidirectional DShot Hardware:
INFO  [arch_dshot] dshot driver stats:
INFO  [arch_dshot] BDShot channel mask: 0x f
----------------------------------------------------------------
INFO  [dshot] Mixer Information:
INFO  [mixer_module] Param prefix: PWM_MAIN
control latency: 18334 events, 5547390us elapsed, 302.57us avg, min 111us max 21437us 440.658us rms
INFO  [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 1: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
WARN  [arch_dshot] Cycle not complete, check system jitter!
Channel 2: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 3: func: 104, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
WARN  [arch_dshot] Cycle not complete, check system jitter!
Channel 4: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 5: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 6: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 7: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 8: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 9: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
WARN  [arch_dshot] Cycle not complete, check system jitter!
Channel 10: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 11: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
WARN  [arch_dshot] Cycle not complete, check system jitter!
Channel 12: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 13: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
WARN  [arch_dshot] Cycle not complete, check system jitter!
----------------------------------------------------------------
INFO  [dshot] Performance Counters:
dshot: cycle: 18519 events, 855547us elapsed, 46.20us avg, min 32us max 21336us 368.107us rms
dshot: bdshot success: 3638 events
WARN  [arch_dshot] Cycle not complete, check system jitter!
dshot: bdshot error: 0 events
----------------------------------------------------------------
nsh> WARN  [arch_dshot] Cycle not complete, check system jitter!

@dakejahl
Copy link
Contributor Author

dakejahl commented Jan 28, 2026

Screenshot from 2026-01-27 19-37-05 Screenshot from 2026-01-27 19-36-54
nsh> dshot status
----------------------------------------------------------------
INFO  [dshot] DShot Driver Status
----------------------------------------------------------------
INFO  [dshot] Configuration:
INFO  [dshot]   Output Mask:        0xff (8 timers)
INFO  [dshot]   BDShot Telemetry:   Enabled
INFO  [dshot]   Serial Telemetry:   Enabled
INFO  [dshot]     Device: /dev/ttyS3
INFO  [dshot]   Extended DShot:     Enabled
INFO  [dshot]   ESC Type:           AM32 (1)
INFO  [dshot]   Motor Poles:        14
INFO  [dshot]   3D Mode:            Disabled
----------------------------------------------------------------
INFO  [dshot] Telemetry Status:
INFO  [dshot]   Ch   Motor  BDShot   Serial   BDShot Err   Serial Err  
INFO  [dshot]   1    1      Online   Online   15           0           
INFO  [dshot]   2    2      Online   Online   77           0           
INFO  [dshot]   3    3      Online   Online   74           0           
INFO  [dshot]   4    4      Online   Online   77           0           
INFO  [dshot]   5    5      Online   Online   76           0           
INFO  [dshot]   6    6      Online   Online   68           0           
INFO  [dshot]   7    7      Online   Online   71           0           
INFO  [dshot]   8    8      Online   Online   68           0           
INFO  [dshot]   EDT Requested Mask (motor order): 0xff
INFO  [dshot]   Settings Requested Mask (motor order): 0xff
----------------------------------------------------------------
INFO  [dshot] Bidirectional DShot Hardware:
INFO  [arch_dshot] dshot driver stats:
INFO  [arch_dshot] BDShot channel mask: 0xff
INFO  [arch_dshot] Timer 0: enabled=1 init=1 bidir=1 cap_ch=3
INFO  [arch_dshot] Timer 1: enabled=1 init=1 bidir=1 cap_ch=0
INFO  [arch_dshot] Output 0: read_ok 56902, fail_crc 15
INFO  [arch_dshot] Output 1: read_ok 56840, fail_crc 77
INFO  [arch_dshot] Output 2: read_ok 56843, fail_crc 74
INFO  [arch_dshot] Output 3: read_ok 56840, fail_crc 77
INFO  [arch_dshot] Output 4: read_ok 56841, fail_crc 76
INFO  [arch_dshot] Output 5: read_ok 56850, fail_crc 68
INFO  [arch_dshot] Output 6: read_ok 56847, fail_crc 71
INFO  [arch_dshot] Output 7: read_ok 56849, fail_crc 68
INFO  [arch_dshot] BDShot EDT rates
INFO  [arch_dshot] Ch0:  eRPM: 201Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 6.22Hz
INFO  [arch_dshot] Ch1:  eRPM: 201Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 6.22Hz
INFO  [arch_dshot] Ch2:  eRPM: 199Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 6.50Hz
INFO  [arch_dshot] Ch3:  eRPM: 198Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 6.50Hz
INFO  [arch_dshot] Ch4:  eRPM: 192Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 5.74Hz
INFO  [arch_dshot] Ch5:  eRPM: 198Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 6.10Hz
INFO  [arch_dshot] Ch6:  eRPM: 201Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 5.74Hz
INFO  [arch_dshot] Ch7:  eRPM: 195Hz  Temp: 0.97Hz  Volt: 0.97Hz  Curr: 6.10Hz
----------------------------------------------------------------
INFO  [dshot] Serial Telemetry Stats:
INFO  [dshot] Number of successful ESC frames: 111962
INFO  [dshot] Number of timeouts: 0
INFO  [dshot] Number of CRC errors: 0
----------------------------------------------------------------
INFO  [dshot] Mixer Information:
INFO  [mixer_module] Param prefix: PWM_MAIN
control latency: 228329 events, 74504860us elapsed, 326.30us avg, min 248us max 754us 13.789us rms
INFO  [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 1: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 2: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 3: func: 104, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 4: func: 105, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 5: func: 106, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 6: func: 107, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 7: func: 108, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 8: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
----------------------------------------------------------------
INFO  [dshot] Performance Counters:
dshot: cycle: 228449 events, 35329926us elapsed, 154.65us avg, min 70us max 856us 44.106us rms
dshot: bdshot success: 56597 events
dshot: bdshot error: 0 events
dshot: telem success: 111770 events
dshot: telem error: 0 events
dshot: telem timeout: 0 events
dshot: telem all sampled: 13976 events
----------------------------------------------------------------

Looking good!

Copy link
Contributor

@hamishwillee hamishwillee left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm going to assume docs will magically appear at some point. Happy to help.

dakejahl and others added 4 commits January 27, 2026 21:26
This makes it consistent with the 12 motor output functions.
For some boards, we can have DShot on 12 to 14 timer channels, so we
need to support up to 16 to have them covered.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

8 participants