Skip to content

feat(dshot): Extended Telemetry and EEPROM support#26263

Merged
dakejahl merged 217 commits intomainfrom
dev/dshot_stuff2
Mar 18, 2026
Merged

feat(dshot): Extended Telemetry and EEPROM support#26263
dakejahl merged 217 commits intomainfrom
dev/dshot_stuff2

Conversation

@dakejahl
Copy link
Copy Markdown
Contributor

@dakejahl dakejahl commented Jan 14, 2026

Summary

Major overhaul of the DShot driver adding bidirectional DShot improvements, Extended DShot Telemetry (EDT), and AM32 ESC EEPROM read/write support. BDShot is now selected per-timer via the actuator configuration UI, multi-timer sequential capture enables BDShot on any DMA-capable timer, and EDT provides temperature/voltage/current without a serial telemetry wire.

Bidirectional DShot Improvements

  • Per-timer BDShot selection (BDShot150/300/600 in actuator config)
  • Multi-timer sequential burst/capture — any timer with DMA can capture BDShot
  • Adaptive per-channel GCR bitstream decoding with flexible frame validation
  • Per-channel online/offline detection with hysteresis
  • Support for up to 16 DShot channels

Extended DShot Telemetry (EDT)

  • Temperature, voltage, current decoded from BDShot frames (no serial wire needed)
  • New DSHOT_BIDIR_EDT parameter (replaces DSHOT_BIDIR_EN)
  • EDT data merged with serial telemetry when both sources available

AM32 ESC EEPROM Support

  • Read/write AM32 EEPROM settings via MAVLink (ESC_EEPROM message)
  • ESCSettingsInterface abstraction for future ESC firmware types
  • Programming state machine for byte-level EEPROM writes
  • New DSHOT_ESC_TYPE parameter

Driver Refactoring

  • Per-motor pole count: DSHOT_MOT_POL1DSHOT_MOT_POL12 (replaces global MOT_POLE_COUNT)
  • Unified telemetry via EscData struct (DShotCommon.h)
  • Separated serial and BDShot telemetry processing paths
  • EscStatus expanded to 12 ESCs with uint16 bitmasks

Parameter Changes

Parameter Change
DSHOT_BIDIR_EN Renamed to DSHOT_BIDIR_EDT (now controls EDT; BDShot enabled per-timer)
MOT_POLE_COUNT Replaced by DSHOT_MOT_POL1DSHOT_MOT_POL12
DSHOT_ESC_TYPE New (0=Unknown, 1=AM32)

Testing

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

@DronecodeBot
Copy link
Copy Markdown

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
Copy Markdown

github-actions bot commented Jan 14, 2026

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 8392 byte (0.4 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.3% +6.25Ki  +0.3% +6.25Ki    .text
 -99.2% +1.83Ki -99.2% +1.83Ki    [125 Others]
  +0.7% +1.08Ki  +0.7% +1.08Ki    [section .text]
  [NEW]    +720  [NEW]    +720    DShot::select_next_command()
  +131%    +692  +131%    +692    capture_complete_callback
  +370%    +636  +370%    +636    DShot::print_status()
  [NEW]    +476  [NEW]    +476    DShot::process_bdshot_telemetry()
  [NEW]    +444  [NEW]    +444    DShot::process_serial_telemetry()
   +76%    +376   +76%    +376    DShot::DShot()
  [NEW]    +300  [NEW]    +300    DShot::handle_configure_actuator()
  [NEW]    +288  [NEW]    +288    DShotTelemetry::parseCommandResponse()
  [NEW]    +260  [NEW]    +260    DShotTelemetry::decodeTelemetryResponse()
  [NEW]    +234  [NEW]    +234    DShot::consume_esc_data()
  [NEW]    +196  [NEW]    +196    DShot::initialize_dshot()
  +132%    +196  +132%    +196    up_bdshot_status
   +45%    +192   +45%    +192    dma_burst_finished_callback
  [DEL]    -194  [DEL]    -194    DShot::handle_new_bdshot_erpm()
  [DEL]    -224  [DEL]    -224    DShot::handle_new_telemetry_data()
  [DEL]    -264  [DEL]    -264    DShotTelemetry::update()
 -75.0%    -276 -75.0%    -276    DShot::handle_vehicle_commands()
  [DEL]    -284  [DEL]    -284    DShot::enable_dshot_outputs()
 -71.9%    -348 -71.9%    -348    DShot::print_usage()
[ = ]       0  +2.1% +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 -93.6%     +33    [11 Others]
  [ = ]       0   +67%     +24    [section .bss]
  [ = ]       0  [NEW]     +22    DShot::_serial_port_path
  [ = ]       0  +125%     +20    read_fail_crc
  [ = ]       0  +125%     +20    read_ok
  [ = ]       0  [NEW]     +12    _bdshot_channel_mask
  [ = ]       0  [NEW]     +10    _bdshot_capture_supported
  [ = ]       0  [NEW]      +9    _bdshot_online
  [ = ]       0  [DEL]     -12    _erpms_ready
  [ = ]       0  [DEL]     -16    read_fail_nibble
  [ = ]       0  [DEL]     -16    read_fail_zero
  [ = ]       0  [DEL]     -22    DShot::_telemetry_device
  [ = ]       0  [DEL]     -32    _cc_call
+1.1%     +44  +1.1%     +44    .data
  [NEW]     +36  [NEW]     +36    _base_interval_x8
  [NEW]      +8  [NEW]      +8    _bdshot_cycle_complete
+0.2%     +24  +0.2%     +24    .ramfunc
  +0.6%      +8  +0.6%      +8    sensors::VehicleAngularVelocity::FilterAngularVelocity()
  +1.7%      +4  +1.7%      +4    param_get
  +1.4%      +4  +1.4%      +4    param_get_default_value
   +33%      +4   +33%      +4    param_get_index
  +9.1%      +4  +9.1%      +4    param_get_system_default_value
   +14%      +1   +14%      +1    ___ZNK3Ekf21updateAidSourceStatusI24estimator_aid_source3d_sN6matrix7Vector3IfEES4_EEvRT_RKyRKT1_RKT0_SE_SE_f.isra.0_veneer
 -12.5%      -1 -12.5%      -1    __nxsem_foreachholder.isra.0_veneer
+1.0%      +4  +1.0%      +4    .init_section
+0.2% +3.81Ki  [ = ]       0    .debug_abbrev
+0.2%    +296  [ = ]       0    .debug_aranges
+0.2%    +816  [ = ]       0    .debug_frame
+0.2% +69.1Ki  [ = ]       0    .debug_info
+0.2% +9.98Ki  [ = ]       0    .debug_line
  [DEL]      -4  [ = ]       0    [Unmapped]
  +0.2% +9.98Ki  [ = ]       0    [section .debug_line]
+0.1% +4.92Ki  [ = ]       0    .debug_loclists
+0.2%   +1019  [ = ]       0    .debug_rnglists
  [DEL]      -1  [ = ]       0    [Unmapped]
  +0.2%   +1020  [ = ]       0    [section .debug_rnglists]
+0.1% +3.90Ki  [ = ]       0    .debug_str
+0.8%      +2  [ = ]       0    .shstrtab
+0.2% +1.19Ki  [ = ]       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()
  [NEW]     +11  [ = ]       0    CSWTCH.154
  [NEW]     +11  [ = ]       0    CSWTCH.155
  [DEL]     -12  [ = ]       0    CSWTCH.1965
  [NEW]     +12  [ = ]       0    CSWTCH.1967
  [NEW]     +24  [ = ]       0    CSWTCH.3525
  [DEL]     -24  [ = ]       0    CSWTCH.3527
  [DEL]     -10  [ = ]       0    CSWTCH.62
  [NEW]     +30  [ = ]       0    DShot::_serial_port_path
  [DEL]     -30  [ = ]       0    DShot::_telemetry_device
  [NEW]     +37  [ = ]       0    DShot::calculate_output_value()
  [NEW]     +39  [ = ]       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.9%    +818  [ = ]       0    [72 Others]
+0.3% +1.48Ki  [ = ]       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()
 -50.0%     -32  [ = ]       0    CSWTCH.145
  [NEW]     +32  [ = ]       0    CSWTCH.154
  [NEW]     +32  [ = ]       0    CSWTCH.155
  [DEL]     -32  [ = ]       0    CSWTCH.1965
  [NEW]     +32  [ = ]       0    CSWTCH.1967
  [NEW]     +48  [ = ]       0    CSWTCH.3525
  [DEL]     -48  [ = ]       0    CSWTCH.3527
  [DEL]     -48  [ = ]       0    CSWTCH.62
  +200%     +32  [ = ]       0    ConstLayer::containedAsBitset()
 -33.3%     -16  [ = ]       0    ConstLayer::contains()
   +50%     +16  [ = ]       0    ConstLayer::store()
  [NEW]     +32  [ = ]       0    DShot::_serial_port_path
  [DEL]     -32  [ = ]       0    DShot::_telemetry_device
 -93.9% +1.11Ki  [ = ]       0    [112 Others]
 +22% +1.72Ki  [ = ]       0    [Unmapped]
+0.2%  +104Ki  +0.4% +8.20Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 8452 byte (0.42 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.3% +6.34Ki  +0.3% +6.34Ki    .text
 -99.1% +1.90Ki -99.1% +1.90Ki    [135 Others]
  +0.7% +1.10Ki  +0.7% +1.10Ki    [section .text]
  [NEW]    +720  [NEW]    +720    DShot::select_next_command()
  +131%    +692  +131%    +692    capture_complete_callback
  +370%    +636  +370%    +636    DShot::print_status()
  [NEW]    +476  [NEW]    +476    DShot::process_bdshot_telemetry()
  [NEW]    +444  [NEW]    +444    DShot::process_serial_telemetry()
   +76%    +376   +76%    +376    DShot::DShot()
  [NEW]    +300  [NEW]    +300    DShot::handle_configure_actuator()
  [NEW]    +288  [NEW]    +288    DShotTelemetry::parseCommandResponse()
  [NEW]    +260  [NEW]    +260    DShotTelemetry::decodeTelemetryResponse()
  [NEW]    +234  [NEW]    +234    DShot::consume_esc_data()
   +46%    +200   +46%    +200    dma_burst_finished_callback
  [NEW]    +196  [NEW]    +196    DShot::initialize_dshot()
  +132%    +196  +132%    +196    up_bdshot_status
  [DEL]    -194  [DEL]    -194    DShot::handle_new_bdshot_erpm()
  [DEL]    -224  [DEL]    -224    DShot::handle_new_telemetry_data()
  [DEL]    -264  [DEL]    -264    DShotTelemetry::update()
 -75.0%    -276 -75.0%    -276    DShot::handle_vehicle_commands()
  [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  +220%     +44    [section .bss]
  [ = ]       0  [NEW]     +36    _consecutive_failures
  [ = ]       0  [NEW]     +36    _consecutive_successes
  [ = ]       0  +325%     +34    [10 Others]
  [ = ]       0  [NEW]     +22    DShot::_serial_port_path
  [ = ]       0  +125%     +20    read_fail_crc
  [ = ]       0  +100%     +20    read_ok
  [ = ]       0  [NEW]     +12    _bdshot_channel_mask
  [ = ]       0  [NEW]     +10    _bdshot_capture_supported
  [ = ]       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]     -22    DShot::_telemetry_device
  [ = ]       0  [DEL]     -32    _cc_call
+0.7%     +32  +0.7%     +32    .data
  [NEW]     +36  [NEW]     +36    _base_interval_x8
   +17%     +16   +17%     +16    g_spi1dev
  [NEW]      +8  [NEW]      +8    _bdshot_cycle_complete
 -58.3%     -28 -58.3%     -28    [section .data]
+1.1%      +4  +1.1%      +4    .init_section
+0.2% +3.80Ki  [ = ]       0    .debug_abbrev
+0.2%    +296  [ = ]       0    .debug_aranges
+0.2%    +856  [ = ]       0    .debug_frame
+0.3% +68.0Ki  [ = ]       0    .debug_info
+0.2% +10.1Ki  [ = ]       0    .debug_line
+0.1% +4.68Ki  [ = ]       0    .debug_loclists
+0.2% +1.02Ki  [ = ]       0    .debug_rnglists
 -33.3%      -1  [ = ]       0    [Unmapped]
  +0.2% +1.02Ki  [ = ]       0    [section .debug_rnglists]
+0.1% +4.00Ki  [ = ]       0    .debug_str
-0.4%      -1  [ = ]       0    .shstrtab
+0.2% +1.20Ki  [ = ]       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()
  [NEW]     +11  [ = ]       0    CSWTCH.154
  [NEW]     +11  [ = ]       0    CSWTCH.155
  [DEL]     -12  [ = ]       0    CSWTCH.1965
  [NEW]     +12  [ = ]       0    CSWTCH.1967
  [NEW]     +24  [ = ]       0    CSWTCH.3525
  [DEL]     -24  [ = ]       0    CSWTCH.3527
  [NEW]     +30  [ = ]       0    DShot::_serial_port_path
  [DEL]     -30  [ = ]       0    DShot::_telemetry_device
  [NEW]     +37  [ = ]       0    DShot::calculate_output_value()
  [NEW]     +39  [ = ]       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()
  [NEW]     +59  [ = ]       0    DShot::handle_esc_request_eeprom()
 -97.4%    +760  [ = ]       0    [70 Others]
+0.3% +1.48Ki  [ = ]       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()
 -50.0%     -32  [ = ]       0    CSWTCH.145
  [NEW]     +32  [ = ]       0    CSWTCH.154
  [NEW]     +32  [ = ]       0    CSWTCH.155
  [DEL]     -32  [ = ]       0    CSWTCH.1965
  [NEW]     +32  [ = ]       0    CSWTCH.1967
  [NEW]     +48  [ = ]       0    CSWTCH.3525
  [DEL]     -48  [ = ]       0    CSWTCH.3527
 -60.0%     -48  [ = ]       0    CSWTCH.63
 -50.0%     -16  [ = ]       0    ConstLayer::containedAsBitset()
 -50.0%     -16  [ = ]       0    ConstLayer::contains()
   +50%     +16  [ = ]       0    ConstLayer::store()
  [NEW]     +32  [ = ]       0    DShot::_serial_port_path
  [DEL]     -32  [ = ]       0    DShot::_telemetry_device
 -93.4% +1.16Ki  [ = ]       0    [105 Others]
-34.9% -2.35Ki  [ = ]       0    [Unmapped]
+0.2% +99.4Ki  +0.4% +8.25Ki    TOTAL

Updated: 2026-03-17T23:37:43

@mrpollo mrpollo requested a review from Igor-Misic January 14, 2026 16:21
@mrpollo
Copy link
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
Contributor

the max is 138us.

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

@dakejahl
Copy link
Copy Markdown
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
Copy Markdown
Contributor

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

@dakejahl
Copy link
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
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
Copy Markdown
Contributor

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

@dakejahl
Copy link
Copy Markdown
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
Copy Markdown

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
Comment thread boards/ark/fpv/default.px4board Outdated
Comment thread platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c Outdated
Comment thread platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c Outdated
Comment thread platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c Outdated
Comment thread platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c Outdated
Comment thread src/drivers/dshot/esc/AM32Settings.h Outdated
Comment thread src/drivers/dshot/DShotCommon.h
Comment thread src/drivers/dshot/module.yaml Outdated
Comment thread src/modules/mavlink/streams/ESC_EEPROM.hpp Outdated
Comment thread src/modules/mavlink/streams/ESC_EEPROM.hpp Outdated
@julianoes
Copy link
Copy Markdown
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
Copy Markdown
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 added 11 commits March 13, 2026 16:58
The sentinel -1 init for _telemetry_motor_index created a deadlock:
set_next_telemetry_index() was only reachable from inside the
_telemetry_motor_index >= 0 branch, so the index never advanced from
-1 and no telemetry requests were ever sent.

Add a bootstrap path that calls set_next_telemetry_index() when the
index is -1 to select the first active motor.
Move the frame_us division out of dma_burst_finished_callback() into
up_dshot_init() since _dshot_frequency is constant after init.
Replace the _bdshot_processed[] volatile bool array (up to 16 reads per
cycle) and count_set_bits() comparison with a single uint16_t bitmask.
Rename up_bdshot_num_channels_ready() to up_bdshot_get_ready_mask() and
check with a direct mask comparison. Updated for both STM32 and NXP.
Cache count_set_bits(_output_mask) as _motor_count in mixerChanged()
instead of recomputing every updateOutputs() cycle. Use
__builtin_popcount() and remove the custom count_set_bits() from
DShotCommon.h.
Consolidates the repeated output-channel-to-motor-index mapping and
bounds-check pattern into a single inline method, used across 7 sites.
…hot()

Replace two separate if-chains (frequency mapping + bdshot check) with a
single switch that maps each config to its frequency and bdshot flag.
…me_esc_data()

Replace conditional &= accumulation with a direct expression:
"online unless a required source reports offline."
…otTelemetry

Replace 3 repeated reset-state blocks with a helper method, and replace
the manual byte-copy loop with memcpy.
_state was only set and consumed within updateOutputs(), never read
elsewhere. Replace with a local `armed` bool and simple if/else.
@tuupola
Copy link
Copy Markdown

tuupola commented Mar 17, 2026

I see the reverse, normal and beepx commands were removed? These were valuable when configuring a quad if you needed to change motor rotation direction.

nsh> dshot beep1 -m 1
nsh> dshot reverse -m 1
nsh> dshot save -m 1

@dakejahl
Copy link
Copy Markdown
Contributor Author

You can use the QGC Actuators page to change motor direction

@dakejahl dakejahl merged commit f00e46f into main Mar 18, 2026
84 checks passed
@dakejahl dakejahl deleted the dev/dshot_stuff2 branch March 18, 2026 00:38
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

10 participants