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

[WIP] initial bidirectional dshot support #20749

Closed
wants to merge 13 commits into from
Closed

Conversation

dagar
Copy link
Member

@dagar dagar commented Dec 12, 2022

Opening a pull request with @julianoes initial work to increase visibility (a lot of people are interested in this). #19861

TODO:

  • parameter to explicitly enable? In some circumstances can we try to do it automatically?
  • dynamic notch filter with bidirectional RPM feedback test/review/iterate (probably as a follow on later)
  • coexist with dshot telemetry?
  • more tightly integrate dshot feedback with system (preflight checks, in flight failures, etc)

@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012, 2017 PX4 Development Team. All rights reserved.
* Copyright (C) 2012, 2017, 2022 PX4 Development Team. All rights reserved.
Copy link
Member Author

Choose a reason for hiding this comment

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

Suggested change
* Copyright (C) 2012, 2017, 2022 PX4 Development Team. All rights reserved.
* Copyright (C) 2012-2022 PX4 Development Team. All rights reserved.

esc_status_s &esc_status = _esc_status_pub.get();
esc_status = {};
_esc_status_pub.update();
up_dshot_set_erpm_callback(&DShot::erpm_trampoline, this);
Copy link
Member Author

Choose a reason for hiding this comment

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

TODO: review logging and publication

I think it should be sufficient to let the lower level dshot driver capture (and store) the eRPM feedback (with timestamp) and leave it to the dshot module to handle populating esc_status and publishing. We could schedule the work item to run sooner if desired.

Copy link
Contributor

Choose a reason for hiding this comment

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

Right, or we just publish every time right after we send out the new motor commands. That way, we won't have the very latest result but that shouldn't matter too much as the numbers come in with a delay anyway because we retrieve the results round-robin style.

@julianoes
Copy link
Contributor

Thanks @dagar, I'm planning to get back to this soon.

@amrathod
Copy link

Hi, I tried building this for a Pixracer and get the following error:
image

@dagar
Copy link
Member Author

dagar commented Dec 14, 2022

Hi, I tried building this for a Pixracer and get the following error: image

Is this pixracer (stm32f4) or pixracer pro (stm32h7)?

@amrathod
Copy link

Hi, I tried building this for a Pixracer and get the following error: image

Is this pixracer (stm32f4) or pixracer pro (stm32h7)?

Actually i am building on my pc using 'make px4_fmu-v4_default'. My intention is to then flash it onto a pixracer pro using QGC.

@julianoes
Copy link
Contributor

I'm picking this back up. I just rebased on top of main, and it still works, so that's a start.

@julianoes
Copy link
Contributor

@amrathod this won't work for the Pixracer. The current work is only for STM32H7 based flight controllers.

@spencerfolk
Copy link

@julianoes Any update on this feature merging into main soon?

@julianoes
Copy link
Contributor

Still on my todo list yes.

@ugupta62
Copy link

Hi, I just wanted to let you guys know that I built this pr on mro-pixracer pro and I can see the esc_info and status in mavlink console of QGC, however, the motors don't arm. I tried to see if the motor spins through QGC, but it doesn't respond.

@julianoes
Copy link
Contributor

@dagar I've just rebased this and added a param to explicitly enable bidirectional dshot.

I think the next step is to figure out how to generalize the timer configuration for boards other than 6X or come up with a way to define the dshot timer and channel defines in the board config.

@spencerfolk
Copy link

@julianoes thanks so much for all your work on this. Have you been able to ascertain how fast the erpm is publishing for each motor?

@julianoes
Copy link
Contributor

@spencerfolk

Have you been able to ascertain how fast the erpm is publishing for each motor?

So it's reading the erpm feedback round robin style, so if you send out dshot at 800 Hz, you would get feedback at 200 Hz for a quad, or 100 Hz for an octo. However, I need to do a bit more testing and verification to check if that's working like it should.

@julianoes julianoes force-pushed the pr-bidirectional-dshot branch 2 times, most recently from e7171cb to 647bd84 Compare April 27, 2023 00:48
@julianoes
Copy link
Contributor

@spencerfolk I had a look at how much of the feedback we fail to parse. In the current state on the bench at 800 Hz gyro rate I get these numbers:

dshot status
INFO  [dshot] Outputs initialized: yes
INFO  [dshot] Outputs used: 0xf
INFO  [dshot] Outputs on: yes
dshot: cycle: 212628 events, 5424551us elapsed, 25.51us avg, min 22us max 60us 1.409us rms
dshot: sent: 212632 events
dshot: received: 53161 events
dshot: parse_error: 19906 events
INFO  [mixer_module] Param prefix: PWM_AUX
control latency: 212656 events, 71066701us elapsed, 334.19us avg, min 151us max 5449us 277.998us rms
INFO  [mixer_module] Switched to rate_ctrl work queue
Channel Configuration:
Channel 0: func: 101, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 1: func: 102, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 2: func: 103, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
Channel 3: func: 104, 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
Channel 8: func:   0, value: 0, failsafe: 0, disarmed: 0, min: 109, max: 1999
INFO  [arch_dshot] dshot driver stats: 192865 read, 0 failed nibble, 0 failed CRC, 19913 invalid/zero

This means about 10% of the measurements read invalid/zero.

@julianoes
Copy link
Contributor

I added the conversion from the period sent via dshot to RPM based on the pole count set via parameter, and this is starting to look usable.

For my bench setup I get 34000 RPM which might be about right given my motors are 2300kv * 15.2v = 34960.

There are still some spikes at high RPM that I don't understand though.

Note that the data below was captured with these topics increased in logger:

diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp
index 31ea1bad68..7b28698f3a 100644
--- a/src/modules/logger/logged_topics.cpp
+++ b/src/modules/logger/logged_topics.cpp
@@ -59,7 +59,7 @@ void LoggedTopics::add_default_topics()
        add_optional_topic("external_ins_attitude");
        add_optional_topic("external_ins_global_position");
        add_optional_topic("external_ins_local_position");
-       add_optional_topic("esc_status", 250);
+       add_optional_topic("esc_status", 10);
        add_topic("failure_detector_status", 100);
        add_topic("failsafe_flags");
        add_optional_topic("follow_target", 500);
@@ -131,7 +131,7 @@ void LoggedTopics::add_default_topics()
        add_topic("wind", 1000);
 
        // multi topics
-       add_optional_topic_multi("actuator_outputs", 100, 3);
+       add_optional_topic_multi("actuator_outputs", 10, 3);
        add_optional_topic_multi("airspeed_wind", 1000, 4);
        add_optional_topic_multi("control_allocator_status", 200, 2);
        add_optional_topic_multi("rate_ctrl_status", 200, 2);

2023-04-27_14-59

@steveturner
Copy link

On a ModalAI FCv1 with STM32 F7 the bidirectional dshot PR has a hardfault once the bidirectional param is enabled.
https://review.px4.io/plot_app?log=3f6aa20c-0bee-48ca-af3e-ea18504be1c5

Prior to it enabling it seemed OK, but dshot outputs do not work.

Previous changes worked on 1.13 with a DMA timer repurposed for the bidirectional dshot handling.

@julianoes
Copy link
Contributor

julianoes commented Apr 27, 2023

Oh, right, I don't think it would work on F7 in its current state. Only H7.

Previous changes worked on 1.13 with a DMA timer repurposed for the bidirectional dshot handling.

Interesting. I guess I can try to find out using another F7.

@amrathod
Copy link

amrathod commented May 1, 2023

Thank You @julianoes! I recently tested the bidirectional feedback on a pixracer pro, and verified the readings with a digital tachometer and the readings were close. I will post a log file within the week.

@henrykotze
Copy link

I am not familiar with dshot protocol, but do you foresee any changes that will be required in the mixer_module lib?

Currently working on bidirectional control for uavcan escs, such as for VESC, where their range is from -8191 to 8191 -> (max throtte in negative direction, max throttle in positive direction), but so far it seems I can only get this working by adjusting the mixer library.

In BeliHeli, we could set the zero throttle position to 1500 PWM, which allowed us to control the motor like a servo in v1.12.

This discussion should live in a different PR, but just mentioning here for now. Planning on PR those changes soon.

@julianoes
Copy link
Contributor

Thanks for the note @henrykotze. I assume the mixer overall might need some changes to support both directions but I'm not 100% sure.

Regarding bidirectional support and negative direction, I don't think it matters for the eRPM reported which is actually the period reported, and I think this period might always be positive for both directions.

@WshgL
Copy link

WshgL commented May 11, 2023

@julianoes Hello, thanks for your contribution. I try to use bi-directional dshot, when I use your original code, it works.

But when I try to add some of my own code in the firmware (Mainly publish the actuator_motors message by my code, that is replace the function of control_allocator), I encounter hard fault, indicating the bug at:
stm32_dmastart(dshot_handler[timer].dma_handle, bidirectional_dshot_enabled ? do_capture : NULL, NULL, false);

I removed the callback function do_capture and replace it to NULL, and it worked normally again.

This still includes a couple of hacks and debug statements.
This adds the param DSHOT_BIDIR_EN to enable bidirectional dshot.

Signed-off-by: Julian Oes <[email protected]>
This could potentially enable other H7 based platforms.

Signed-off-by: Julian Oes <[email protected]>
Otherwise we publish a lot of duplicate data for little gain.

Signed-off-by: Julian Oes <[email protected]>
This calculates the actual RPM from the period transmitted via dshot to
based on the pole count.

Signed-off-by: Julian Oes <[email protected]>
@julianoes
Copy link
Contributor

Rebased and force-pushed. Still working on my bench.

@FHermisch
Copy link

Hi, based on the PR, I got bidirectional DShot running on an F4 (MambaF405MK2) with four channels in parallel (no round-robin needed). I did quite some heavy lifting on the code, but maybe I can help at some point on making the code more adaptable to other boards.

@julianoes
Copy link
Contributor

@FHermisch nice! Do you require 4 DMA channels for that, or just using one? Feel free to make a PR with your changes against this branch so we can have a look at it.

Somehow shifting the timer enable around made a big difference and got
rid of the spikes.

Signed-off-by: Julian Oes <[email protected]>
@FHermisch
Copy link

FHermisch commented May 19, 2023

@julianoes I use 2 DMA streams (DMA Request "UP") for writing out DSHOT data to two channels each in burst mode. Then I switch to using 4 DMA streams (DMA Request "CAPTURE") for reading-in the BiDi data. The code of the PR was running to slow on the F405 to be able to switch in time and be ready to capture the BiDi data, so I had to do low-level pushing of registers into the timers and the DMAs to be fast enough - sadly no code which can be directly integrated at the moment.
Things which took me quite some time:

  • the locking mechanism of Nuttx for the DMA streams: I was not able to free up one of the "UP" streams and take it again. Later I realized that the one stream/channel combination could also be used to capture one of the channels, so now I keep them and change the behaviour (e.g. from "UP" to "CaptComp Channel4").
  • register-width of the timers and FIFO: I disabled FIFO as I did not want to mingle around with it and I think they also throw me the "transfer complete" too early. Without FIFO the STM manual says one has to provide exactly the register width to the timers, but Timer3 on 405 uses 16bit and Timer2 on 405 uses 32bits
  • finding the proper sequence of disabling/ enabling of timer-channels, timers and DMAs

What helped me a lot:

  • toggling an LED as a DEBUG means and attaching an oscilloscope probe to the LED pin and another one to one of the DSHOT pins to see the timing issues
  • setting up everything from scratch an a Nucleo-Board (F401) and a single F030

I will compare the PR-Code with my code again and see if I find parts for which my solution will immediately help to find a proper generic solution for everyone.

@dongdongbh
Copy link

I just tested the Dshot code on px4_fmu-v6c and found that the data shows many spikes.

image

I checked the code and found that the spikes are mainly caused by failed reads. In case a read fails, e.g. due to a CRC error, the code returns zero. I changed the code to make it return the last read value instead, which resulted in the following data:

image

In addition to this, I found that this code can cause QGC to get stuck on the FC startup time after the user changes FC parameters. This seems to be because QGC is checking some FC status that is failing, which is causing QGC to get stuck. I'm not sure if this is caused by the Dshot code or an upstream problem.

@korigod
Copy link
Contributor

korigod commented Oct 6, 2023

I'm interested in this feature too, thank you @julianoes for working on this!

@dagar dagar self-assigned this Oct 18, 2023
@YouthKim
Copy link

YouthKim commented Nov 9, 2023

Has anyone successfully tested it on the holybro 6X flight controller? I tried multiple versions, but still failed. It always gives the following error: Motor output/control error.
I can see esc_status on the mavlink monitoring, but no data is detected and I can't arm the drone.
I'd appreciate any help you can offer me!

@julianoes
Copy link
Contributor

Has anyone successfully tested it on the holybro 6X flight controller?

That's what I used to develop this.

@YouthKim
Copy link

I tried it on two new holybro 6X flight controllers and a new holybro 6C flight controller, and the same problem always occurs.
I just turned on the bi-directional dshot function option, is that all that needed to do?
Could you provide me with the compiled 6x firmware( px4_fmu-v6x_default.px4) to help me find out what's wrong?

@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/trying-get-data-about-the-motor/36530/9

@jgw365
Copy link

jgw365 commented Oct 2, 2024

I just tested the Dshot code on px4_fmu-v6c and found that the data shows many spikes.

image

I checked the code and found that the spikes are mainly caused by failed reads. In case a read fails, e.g. due to a CRC error, the code returns zero. I changed the code to make it return the last read value instead, which resulted in the following data:

image

In addition to this, I found that this code can cause QGC to get stuck on the FC startup time after the user changes FC parameters. This seems to be because QGC is checking some FC status that is failing, which is causing QGC to get stuck. I'm not sure if this is caused by the Dshot code or an upstream problem.

Have you solved this problem?

@dakejahl
Copy link
Contributor

#23863 replaces

@dakejahl dakejahl closed this Oct 29, 2024
@julianoes julianoes deleted the pr-bidirectional-dshot branch October 30, 2024 02:25
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: ✅ Done
Development

Successfully merging this pull request may close these issues.