[Sponsored by ARK] Bidirectional DShot#23863
Conversation
e4681c4 to
16dc6d4
Compare
|
This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there: |
|
Thanks for your work @dakejahl. I'll review and test this on the Holybro 6Xs as well as Cubes tomorrow. |
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? |
|
@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.
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
DSHOT_BIDIR_EN parameter enables this, it is disabled by default |
Aha! So then you only have feedback for part of the ESCs essentially?
Thanks, of course! 🤦♂️ |
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. |
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 ... |
Could you please provide me with some advice on how to solve this? @dakejahl |
@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. |
|
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). |
|
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%. |
|
@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. |
Got it, thank you very much! Looking forward to seeing your progress in development. |
|
@jgw365 can you test again? I pushed a commit which fixes a bug I introduced when trying to fix the F1 compilation |
|
Alright I've implemented and tested round robin @julianoes |
Co-authored-by: Julian Oes <[email protected]>
PetervdPerk-NXP
left a comment
There was a problem hiding this comment.
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?
|
The KakuteF7 flash is overflowing. @julianoes can we free up some flash on this board? |
The Kakute F7 has only 1 MB of flash and flash based params, so there is just not much space for anything.
6c94ef4
|
Just tested on a Pi6X Flow. https://review.px4.io/plot_app?log=dfb9eec1-a23a-48e0-a8e9-65e08fe2d9d0 |
|
Glad to see this come in 🎉 |
|
This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there: |
|
@dakejahl Can we have an update to https://docs.px4.io/main/en/peripherals/dshot.html ? |
* Bidirectional DShot Co-authored-by: Julian Oes <[email protected]> * f4/f1 support, not supported * fix f1 build target * sanity check timer_channel value, fix CCxNP ifdef, debug stuff * removed debug code, added define for H7 HAVE_GTIM_CCXNP * round robin sampling for less than 4 DMA * unlimited esc_status logging * dshot: fix formatting * dshot: add define for number of DMA channels to use This allows individual boards to override the number of DShot channels and hence avoid round robin capture of the RPM feedback. * ARK: enable 4 DMA channels for DShot on 6X * dshot: publish when all channels are updated This slows down the ESC_STATUS publication in the case of round robin capture. E.g. for 800 Hz output with one DMA channel, the ESC_STATUS is now published at 200 Hz. * dshot: avoid duplicate publications for bidir and telem Instead of publishing both bidirectional dshot updates as well as telemetry updates, we now combine the data from both streams, and publish whenever we get RPM updates, as the latter arrives with higher rate, e.g. 200 Hz with round robin, or faster otherwise. When combining the data, we take RPM from bidirectional dshot, and the rest from telemetry. When we have only one of the two, either telemetry or bidirectional dshot, we just publish that one. * boards: add ark fpv and pi6x BOARD_DMA_NUM_DSHOT_CHANNELS * dshot: turn off debug build --------- Co-authored-by: Julian Oes <[email protected]> Co-authored-by: alexklimaj <[email protected]>







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

