feat(dshot): Extended Telemetry and EEPROM support#26263
Conversation
|
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 |
🔎 FLASH Analysispx4_fmu-v5x [Total VM Diff: 8392 byte (0.4 %)]px4_fmu-v6x [Total VM Diff: 8452 byte (0.42 %)]Updated: 2026-03-17T23:37:43 |
|
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! |
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. |
There was a problem hiding this comment.
need uint8_t in dshot_motor_data_set for imxrt in https://github.com/PX4/PX4-Autopilot/pull/26263/files#diff-ee11cd0da359496d5246d1e4759d08dee22fa735d4c4aed71afe1547eb55d56fR616
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.
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. |
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 |
|
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) |
|
Having some trouble getting ESC_EEPROM stream to show up in QGC / mavsdk. FC: imxrt based / V6X-RT 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)? |
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. |
If you can't use the telemetry wire on your drone/esc setup you can also flash this |
Thanks for the pointer, will give this a spin. Was hoping to avoid external configurators =>> might end up with CAN ESCs instead. |
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? |
|
@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. |
7e0038b to
73052cc
Compare
|
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) |
|
@dakejahl Oh, ok I'm starting to understand. Let me think about it. |
|
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 |
|
Testing 4 outputs over 2 timers on CubeOrange: @dakejahl any idea why Ch2 is showing errors? |
|
And here is a test on just the first 4 motor outputs on the Holybro Kakute H743-Wing: |
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.
Prevent out-of-bounds access on timer_io_channels[] when channel index exceeds MAX_TIMER_IO_CHANNELS.
|
I see the |
|
You can use the QGC Actuators page to change motor direction |

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
Extended DShot Telemetry (EDT)
DSHOT_BIDIR_EDTparameter (replacesDSHOT_BIDIR_EN)AM32 ESC EEPROM Support
ESC_EEPROMmessage)ESCSettingsInterfaceabstraction for future ESC firmware typesDSHOT_ESC_TYPEparameterDriver Refactoring
DSHOT_MOT_POL1–DSHOT_MOT_POL12(replaces globalMOT_POLE_COUNT)EscDatastruct (DShotCommon.h)Parameter Changes
DSHOT_BIDIR_ENDSHOT_BIDIR_EDT(now controls EDT; BDShot enabled per-timer)MOT_POLE_COUNTDSHOT_MOT_POL1–DSHOT_MOT_POL12DSHOT_ESC_TYPETesting