Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Sponsored by ARK] Bidirectional DShot #23863

Merged
merged 27 commits into from
Mar 12, 2025

Conversation

dakejahl
Copy link
Contributor

@dakejahl dakejahl commented Oct 29, 2024

First of all a big thank you to @julianoes for the initial implementation. This implementation differs in that it uses up to 4 DMA channels for Capture Compare input on all 4 channels of the first timer. The limitation to a single timer is due to the limited available DMA channels on most boards (4 without PX4IO on ARKV6X) This will work down to 1 DMA channel by only capturing the input from a single timer channel.

Implementation
If Bidirectional DShot is not enabled the implementation is the same as it was before. Timers will be configured for DShot mode if the timer supports Burst Mode and if there is enough DMA channels available (1 DMA per timer). If Bidirectional Dshot is enabled, only the first timer will be configured for DShot due to DMA channel limitations. Burst mode uses 1 DMA, and CaptureCompare mode uses 4 (re-using the DMA used during Burst). An hrt callback is used to process the eRPM frames since DShot frames have predictable timing but unpredictable pulse count. This webpage was a useful resource.

Further discussion
Initially I wanted to support bidirectional dshot on all timers with DMA simultaneously. This requires triggering each timer (burst/captcomp) sequentially so that we can reuse the available DMA channels between the timers.

Timer1 Burst (1DMA) --> Timer1 CaptComp (x4 DMA) --> Timer2 Burst (1 DMA) --> Timer2 CaptComp (x4 DMA)

I made it pretty far with this implementation but decide to scrap it because I kept running into race conditions and this development has already taken quite some time. I think it is still possible to do, but is out of scope of this PR. The code is structured in a way that should allow fairly easy extensibility to support this in the future.

Issues
An issue I found but am not fixing here is that DShot.cpp configures all of the channels on timers that have DShot enabled. This results in a pulse train on every channel output on that timer, regardless of if the output function is enabled. The fix is not super easy as it requires extra logic in order to properly initialize the timer channels for burst mode, since the enabled outputs need to be sequential. This is the current implementations behavior so I am leaving it as I found it.

Targets Tested
ARKV6X with 4 DMA channels
ARKV6X with 2 DMA channels
CubeOrange with 4 DMA channels

Screenshots
image
image

@dakejahl dakejahl force-pushed the dev/bidirectional_dshot_single_timer branch 2 times, most recently from e4681c4 to 16dc6d4 Compare October 29, 2024 22:58
@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-sync-q-a-oct-30-2024/42184/1

@julianoes
Copy link
Contributor

Thanks for your work @dakejahl. I'll review and test this on the Holybro 6Xs as well as Cubes tomorrow.

@julianoes
Copy link
Contributor

@dakejahl This implementation differs in that it uses up to 4 DMA channels for Capture Compare input on all 4 channels of the first timer.

Do I remember it right that I did the capture round robin style, so one channel per output pulse. Is that what you mean with this?

And so if I understand you right, we need 4 DMA channels to enable this? Which means that we need to disable DMA for serial ports or sensors to enable this, right?

And what are the steps to enable this? It's not on by default, right?

@dakejahl
Copy link
Contributor Author

dakejahl commented Oct 30, 2024

@julianoes your impl was doing round robin using a single DMA and reading from the burst register. You were re-using the 1 DMA from the burst output for the input capture.

And so if I understand you right, we need 4 DMA channels to enable this? Which means that we need to disable DMA for serial ports or sensors to enable this, right?

The init logic determines if DMA is available for each channel, so this will work with only 1 DMA (the 1 used for burst output anyway). If there are more DMA available, then great, but they are not strictly required as the channel will be marked in the captcomp_channels field. For example on the ARKV6X jetson carrier and basic carrier we do not have a PX4IO, so this leaves us with 4 DMA, so it works out of the box with all 4 channels. If the ARKV6X was paired with a carrier with PX4IO, then we would only have 2 DMA available and only Timer1 Ch1 and Ch2 would be used for CaptComp. I tested simulating having a PX4IO by adding some test code to allocate 2 extra DMA channels during init, and the driver worked as expected by only capturing on Ch1 and Ch2.

And what are the steps to enable this? It's not on by default, right?

DSHOT_BIDIR_EN parameter enables this, it is disabled by default

@julianoes
Copy link
Contributor

and the driver worked as expected by only capturing on Ch1 and Ch2.

Aha! So then you only have feedback for part of the ESCs essentially?

DSHOT_BIDIR_EN parameter enables this, it is disabled by default

Thanks, of course! 🤦‍♂️

@dakejahl
Copy link
Contributor Author

Aha! So then you only have feedback for part of the ESCs essentially?

yes exactly, you'd only have feedback from 1. This leads me to a question I have: is there a notch filter per ESC when using the gyro dynamic notch filter? (IMU_GYRO_DNF_EN). We could support round robin for the 1 - 3 DMA use case.

@julianoes
Copy link
Contributor

We could support round robin for the 1 - 3 DMA use case.

That's what I'm thinking, but I'm not aware how the dynamic notch filtering works.

@dakejahl
Copy link
Contributor Author

That's what I'm thinking, but I'm not aware how the dynamic notch filtering works.

I bet @dagar or @bresch knows. Is there a notch filter applied for each ESC? Is it worth it to round robin the ESC RPM if we don't have 4 DMA available?

It would be pretty easy to update the logic to round robin with the available DMA:

1 DMA: each channel is captured on every 4th measurement --> C x x x C x x x C x x x C ...
2 DMA: each channel is capture on every other measurement --> C x C x C x C x C x...
3 DMA: every third measurement is skipped --> C C C x C C C x C C C x C ...

@jgw365
Copy link

jgw365 commented Oct 31, 2024

截图 2024-10-31 20-19-57

The output of DShot in a px4_fmu-v6c board is fine, but I got incorrect eRPM data on channel 2 with 10% CRC errors, and the other channels can't be read. The code I used is an old PX4 with the DShot part of your code, and there are no warning errors.

@jgw365
Copy link

jgw365 commented Oct 31, 2024

截图 2024-10-31 20-19-57

The output of DShot in a px4_fmu-v6c board is fine, but I got incorrect eRPM data on channel 2 with 10% CRC errors, and the other channels can't be read. The code I used is an old PX4 with the DShot part of your code, and there are no warning errors.

Could you please provide me with some advice on how to solve this? @dakejahl

@jgw365
Copy link

jgw365 commented Oct 31, 2024

图片
The log records the RPM during arming.

@dakejahl
Copy link
Contributor Author

The code I used is an old PX4 with the DShot part of your code

@jgw365 I'm sorry but I really can't help you with a backport. Please test the PR as it is, and let me know if works on the fmu-v6c or not and we can go from there.

@jgw365
Copy link

jgw365 commented Nov 1, 2024

Okay, thank you a lot. I cloned your commit in the branch 'dev/bidirectional_dshot_single_timer' and used the command 'make px4_fmu-v6c upload' to upload it to my drone. After plugging in a battery, it seems that the channels are not connected correctly, but the motor output is functioning properly by the actuator test in QGroundControl (QGC).
截图 2024-11-01 10-26-56
图片
@dakejahl

@jgw365
Copy link

jgw365 commented Nov 1, 2024

A few weeks ago, I used julianoes‘ code from the branch 'pr-bidirectional-dshot'. I was able to achieve normal DShot ERPM; however, I noticed that there were many spikes caused by CRC errors, with a rate of about 10%.

@dakejahl
Copy link
Contributor Author

dakejahl commented Nov 5, 2024

@jgw365 it looks like it does indeed work. The fmu-v6x only has 2 DMA channels available so it's only capturing the eRPM from the first 2 channels. Please read the above comments discussing this. I might end up implementing round-robin for the less than 4 DMA cases such as this.

@jgw365
Copy link

jgw365 commented Nov 6, 2024

I might end up implementing round-robin for the less than 4 DMA cases such as this.

Got it, thank you very much! Looking forward to seeing your progress in development.

@julianoes julianoes self-requested a review November 12, 2024 21:41
@dakejahl
Copy link
Contributor Author

@jgw365 can you test again? I pushed a commit which fixes a bug I introduced when trying to fix the F1 compilation

@dakejahl
Copy link
Contributor Author

Alright I've implemented and tested round robin @julianoes

@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-sync-q-a-jan-15-2025/43274/1

@yzgarrard
Copy link

I'm working with a hexarotor controlled by a Pixhawk 6C mini. Currently, I'm using Ardupilot to obtain the motor RPM, but would rather use PX4 if possible.

Is this branch intended to work on a vehicle with more than four motors? I couldn't quite follow what was happening when there were varying numbers of DMA channels and timers, so I don't know what to expect if I run this branch.

@dakejahl
Copy link
Contributor Author

@yzgarrard It only works on the first timer. If you take a look at the fmu-v6x/src/timer_config.cpp you will see the first is Timer1 and maps to the first 4 motor channels. So only motors 1 - 4 will work with bidir dshot.

@aminballoon
Copy link

@dakejahl So does it have solution to set more timer for BDShot ? [6,8 motors]

@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-sync-q-a-jan-22-2025/43384/3

@mrpollo
Copy link
Contributor

mrpollo commented Jan 22, 2025

We discussed this on the Jan 22 call, we want to get this in, and will be looking into the best way to do it.

Copy link
Member

@PetervdPerk-NXP PetervdPerk-NXP left a comment

Choose a reason for hiding this comment

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

Let's merge it as is.
I don't have to time to test on real hardware, but I doubt will regress.

@dk7xe you've got time to test main when this pr is in?

AlexKlimaj
AlexKlimaj previously approved these changes Feb 26, 2025
@dakejahl
Copy link
Contributor Author

The KakuteF7 flash is overflowing. @julianoes can we free up some flash on this board?

AlexKlimaj and others added 3 commits February 27, 2025 17:11
The Kakute F7 has only 1 MB of flash and flash based params, so there is
just not much space for anything.
@julianoes julianoes dismissed stale reviews from AlexKlimaj and PetervdPerk-NXP via 6c94ef4 March 11, 2025 21:20
@AlexKlimaj
Copy link
Member

Just tested on a Pi6X Flow.

https://review.px4.io/plot_app?log=dfb9eec1-a23a-48e0-a8e9-65e08fe2d9d0
https://review.px4.io/plot_app?log=77918b00-d3db-450f-9542-fcc780d9fafc

image
image

nsh> dshot status
INFO  [dshot] Outputs initialized: yes
INFO  [dshot] Outputs used: 0xf
INFO  [dshot] Outputs on: yes
dshot: cycle: 73533 events, 2031002us elapsed, 27.62us avg, min 22us max 67us 5.343us rms
INFO  [mixer_module] Param prefix: PWM_MAIN
control latency: 73538 events, 14249343us elapsed, 193.77us avg, min 176us max 248us 11.217us rms
INFO  [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 1: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 2: func: 104, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 3: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 4: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 5: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 6: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 7: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
INFO  [dshot] telemetry on: /dev/ttyS2
INFO  [dshot] Number of successful ESC frames: 110336
INFO  [dshot] Number of timeouts: 18
INFO  [dshot] Number of CRC errors: 0
INFO  [arch_dshot] dshot driver stats:
INFO  [arch_dshot] Bidirectional DShot enabled
INFO  [arch_dshot] Available DMA: 4
INFO  [arch_dshot] Timer 0, Channel 0: read 220793, failed nibble 1, failed CRC 0, invalid/zero 368
INFO  [arch_dshot] Timer 0, Channel 1: read 220795, failed nibble 0, failed CRC 0, invalid/zero 369
INFO  [arch_dshot] Timer 0, Channel 2: read 220798, failed nibble 0, failed CRC 0, invalid/zero 369
INFO  [arch_dshot] Timer 0, Channel 3: read 220800, failed nibble 0, failed CRC 0, invalid/zero 371
nsh> 
nsh> uorb top

update: 1s, topics: 135, total publications: 16806, 1736.5 kB/s
TOPIC NAME                          INST #SUB RATE #Q SIZE
actuator_armed                         0   17    2  1   16 
actuator_motors                        0    6  802  1   72 
actuator_outputs                       0    3  802  1   80 
battery_status                         0    9   10  1  168 
can_interface_status                   0    1    9  1   40 
can_interface_status                   1    1    9  1   40 
config_overrides                       0    1    2  4   16 
control_allocator_status               0    3  162  1   56 
cpuload                                0    5    2  1   16 
distance_sensor                        0    5   44  1   56 
ekf2_timestamps                        0    1  201  1   24 
esc_status                             0    8  802  1  336 

@AlexKlimaj AlexKlimaj merged commit 543851d into PX4:main Mar 12, 2025
56 of 58 checks passed
@mrpollo
Copy link
Contributor

mrpollo commented Mar 12, 2025

Glad to see this come in 🎉

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Status: Done
Status: Done
Development

Successfully merging this pull request may close these issues.