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

Open
wants to merge 3 commits into
base: main
Choose a base branch
from

Conversation

dakejahl
Copy link
Contributor

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.

TODO

  • Param for timer_index which selects the timer for bidirectional mode. Right now it is hardcoded to the first timer.
  • Test STM32F7 and fix build for F4/F1

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

Screenshots
image
image

Co-authored-by: Julian Oes <[email protected]>
@dakejahl dakejahl force-pushed the dev/bidirectional_dshot_single_timer branch 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
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.

4 participants