Skip to content

Conversation

@julianoes
Copy link
Contributor

@julianoes julianoes commented Nov 28, 2025

This extends DShot and Bidirectional DShot to more than one timer.

So far I have tested this on a CubeOrange with 6 outputs (AUX 1-4 on timer 1, AUX 5-6 on timer 4).

nsh> dshot status
INFO  [dshot] Outputs initialized: yes
INFO  [dshot] Outputs used: 0x3f
INFO  [dshot] Outputs on: yes
dshot: cycle: 41433 events, 1187949us elapsed, 28.67us avg, min 24us max 150us 2.546us rms
dshot: bdshot rpm: 20718 events
dshot: dshot telem: 0 events
INFO  [mixer_module] Param prefix: PWM_AUX
control latency: 41433 events, 9900016us elapsed, 238.94us avg, min 228us max 491us 7.134us 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: 317, 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: 430, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
Channel 5: func: 104, value: 676, failsafe: 0, disarmed: 0, min: 109, max: 1999, center: 65535
INFO  [arch_dshot] dshot driver stats:
INFO  [arch_dshot] Bidirectional DShot enabled on 2 timer(s)
INFO  [arch_dshot] Output 0: eRPM 172, read 19816, failed nibble 0, failed CRC 0, invalid/zero 902
INFO  [arch_dshot] Output 1: eRPM 426, read 19817, failed nibble 0, failed CRC 0, invalid/zero 902
INFO  [arch_dshot] Output 2: eRPM 0, read 0, failed nibble 0, failed CRC 0, invalid/zero 0
INFO  [arch_dshot] Output 3: eRPM 0, read 0, failed nibble 0, failed CRC 0, invalid/zero 0
INFO  [arch_dshot] Output 4: eRPM 581, read 19817, failed nibble 0, failed CRC 0, invalid/zero 903
INFO  [arch_dshot] Output 5: eRPM 845, read 19822, failed nibble 0, failed CRC 0, invalid/zero 902

@julianoes julianoes requested a review from dakejahl November 28, 2025 01:37
@github-actions
Copy link

github-actions bot commented Nov 28, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 1588 byte (0.07 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
[ = ]       0  +1.6% +1.38Ki    .bss
  [ = ]       0  +400%   +1024    dshot_capture_buffer
  [ = ]       0  [NEW]    +160    _cc_calls
  [ = ]       0  +400%     +64    read_fail_crc
  [ = ]       0  +400%     +64    read_fail_nibble
  [ = ]       0  +400%     +64    read_fail_zero
  [ = ]       0  +320%     +64    read_ok
  [ = ]       0 +11e2%     +11    _bidirectional
  [ = ]       0  [NEW]      +5    _bidi_timer_indices
  [ = ]       0  [NEW]      +3    _num_bidi_timers
  [ = ]       0  [DEL]     -19    [section .bss]
  [ = ]       0  [DEL]     -32    _cc_call
+0.0%    +176  +0.0%    +176    .text
   +18%     +76   +18%     +76    dma_burst_finished_callback
   +38%     +56   +38%     +56    up_bdshot_status
  +6.1%     +32  +6.1%     +32    capture_complete_callback
  [NEW]     +24  [NEW]     +24    CSWTCH.58
   +42%     +16   +42%     +16    DShot::update_num_motors()
  [NEW]     +12  [NEW]     +12    up_bdshot_set_active_channels
  -1.5%      -4  -1.5%      -4    build_gam_response()
  -0.6%      -4  -0.6%      -4    up_dshot_init
  -0.0%      -8  -0.0%      -8    [section .text]
  [DEL]     -24  [DEL]     -24    CSWTCH.62
+0.1%      +4  +0.1%      +4    .data
  [NEW]      +4  [NEW]      +4    _bdshot_active_channels
+0.0%     +65  [ = ]       0    .debug_abbrev
+0.0%      +8  [ = ]       0    .debug_aranges
+0.0%     +36  [ = ]       0    .debug_frame
+0.0%    +493  [ = ]       0    .debug_info
+0.0%    +126  [ = ]       0    .debug_line
  [DEL]      -1  [ = ]       0    [Unmapped]
  +0.0%    +127  [ = ]       0    [section .debug_line]
+0.0%    +171  [ = ]       0    .debug_loclists
+0.0%     +92  [ = ]       0    .debug_rnglists
+0.0%     +81  [ = ]       0    .debug_str
+0.0%     +92  [ = ]       0    .strtab
  [NEW]     +10  [ = ]       0    CSWTCH.58
  [DEL]     -10  [ = ]       0    CSWTCH.62
 -44.4%     -16  [ = ]       0    __sched_lock_veneer
   +59%     +16  [ = ]       0    __stm32_dmaresidual_veneer
  [NEW]     +24  [ = ]       0    _bdshot_active_channels
  [NEW]     +20  [ = ]       0    _bidi_timer_indices
  [DEL]      -9  [ = ]       0    _cc_call
  [NEW]     +10  [ = ]       0    _cc_calls
  [NEW]     +17  [ = ]       0    _num_bidi_timers
  [NEW]     +30  [ = ]       0    up_bdshot_set_active_channels
+0.0%    +144  [ = ]       0    .symtab
  [NEW]     +32  [ = ]       0    CSWTCH.58
  [DEL]     -48  [ = ]       0    CSWTCH.62
 -40.0%     -32  [ = ]       0    __sched_lock_veneer
   +67%     +32  [ = ]       0    __stm32_dmaresidual_veneer
  [NEW]     +32  [ = ]       0    _bdshot_active_channels
  [NEW]     +32  [ = ]       0    _bidi_timer_indices
 -33.3%     -16  [ = ]       0    _bidirectional
  [DEL]     -32  [ = ]       0    _cc_call
  [NEW]     +32  [ = ]       0    _cc_calls
  [NEW]     +48  [ = ]       0    _num_bidi_timers
   +50%     +16  [ = ]       0    read_fail_nibble
 -25.0%     -16  [ = ]       0    up_bdshot_channel_status
  [NEW]     +64  [ = ]       0    up_bdshot_set_active_channels
-1.6%    -176  [ = ]       0    [Unmapped]
+0.0% +1.28Ki  +0.1% +1.55Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 1656 byte (0.08 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
[ = ]       0  +1.5% +1.44Ki    .bss
  [ = ]       0  +400%   +1024    dshot_capture_buffer
  [ = ]       0  [NEW]    +160    _cc_calls
  [ = ]       0  +400%     +64    read_fail_crc
  [ = ]       0  +400%     +64    read_fail_nibble
  [ = ]       0  +400%     +64    read_fail_zero
  [ = ]       0  +320%     +64    read_ok
  [ = ]       0  +123%     +59    [section .bss]
  [ = ]       0  [NEW]      +5    _bidi_timer_indices
  [ = ]       0  [NEW]      +3    _num_bidi_timers
  [ = ]       0 -75.0%      -3    _bidirectional
  [ = ]       0  [DEL]     -32    _cc_call
+0.0%    +184  +0.0%    +184    .text
   +18%     +80   +18%     +80    dma_burst_finished_callback
   +38%     +56   +38%     +56    up_bdshot_status
  +6.1%     +32  +6.1%     +32    capture_complete_callback
  [NEW]     +24  [NEW]     +24    CSWTCH.59
   +42%     +16   +42%     +16    DShot::update_num_motors()
  [NEW]     +12  [NEW]     +12    up_bdshot_set_active_channels
  -0.6%      -4  -0.6%      -4    up_dshot_init
  -0.0%      -8  -0.0%      -8    [section .text]
 -50.0%     -24 -50.0%     -24    CSWTCH.63
+0.0%     +65  [ = ]       0    .debug_abbrev
+0.0%      +8  [ = ]       0    .debug_aranges
+0.0%     +36  [ = ]       0    .debug_frame
+0.0%    +477  [ = ]       0    .debug_info
+0.0%    +162  [ = ]       0    .debug_line
  +300%      +3  [ = ]       0    [Unmapped]
  +0.0%    +159  [ = ]       0    [section .debug_line]
+0.0%    +286  [ = ]       0    .debug_loclists
+0.0%     +97  [ = ]       0    .debug_rnglists
 -33.3%      -1  [ = ]       0    [Unmapped]
  +0.0%     +98  [ = ]       0    [section .debug_rnglists]
+0.0%     +81  [ = ]       0    .debug_str
+0.9%      +2  [ = ]       0    .shstrtab
+0.0%    +102  [ = ]       0    .strtab
  [NEW]     +10  [ = ]       0    CSWTCH.59
  [NEW]     +24  [ = ]       0    _bdshot_active_channels
  [NEW]     +20  [ = ]       0    _bidi_timer_indices
  [DEL]      -9  [ = ]       0    _cc_call
  [NEW]     +10  [ = ]       0    _cc_calls
  [NEW]     +17  [ = ]       0    _num_bidi_timers
  [NEW]     +30  [ = ]       0    up_bdshot_set_active_channels
+0.0%    +144  [ = ]       0    .symtab
  [NEW]     +32  [ = ]       0    CSWTCH.59
 -60.0%     -48  [ = ]       0    CSWTCH.63
  [NEW]     +32  [ = ]       0    _bdshot_active_channels
  [NEW]     +32  [ = ]       0    _bidi_timer_indices
 -33.3%     -16  [ = ]       0    _bidirectional
  [DEL]     -32  [ = ]       0    _cc_call
  [NEW]     +32  [ = ]       0    _cc_calls
  [NEW]     +48  [ = ]       0    _num_bidi_timers
   +50%     +16  [ = ]       0    read_fail_nibble
 -25.0%     -16  [ = ]       0    up_bdshot_channel_status
  [NEW]     +64  [ = ]       0    up_bdshot_set_active_channels
-2.6%    -184  [ = ]       0    [Unmapped]
+0.0% +1.43Ki  +0.1% +1.62Ki    TOTAL

Updated: 2025-12-02T17:43:45

@julianoes
Copy link
Contributor Author

Tested on Holybro Kakute H7 dualimu with 8 DShot outputs over 4 timers with 2 channels each, works as well!

@dirksavage88
Copy link
Contributor

Hey @julianoes we did something similar for the nxp tropic board

We should probably get a log with a multicopter using dshot across the different timers.

This extends dshot and bidir dshot to more than one timer.
This now shows the channels in output order rather than timer channel
order, and while at it, shows the actual eRPM read.
If there is no ESCs connected on a timer channel, we don't need to go
through it when doing the round robin eRPM read.
@julianoes julianoes force-pushed the pr-bidir-more-timer branch from 5ce65b4 to 2593b18 Compare December 2, 2025 17:34
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.

3 participants