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

Disarm PWM ESCs before reboot #24290

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open

Disarm PWM ESCs before reboot #24290

wants to merge 1 commit into from

Conversation

alexcekay
Copy link
Member

@alexcekay alexcekay commented Feb 4, 2025

Solved Problem

Rebooting can be dangerous when using PWM, as depending on how fast the system reboots a valid PWM pulse can be created. This can happen due to the following reason:

  • 'reboot' is called, which stops the PWM output, so the PWM signal is LOW.
  • During the reboot, the FMU is off and the PWM signal is floating. ESCs have a pullup, so the PWM signal is HIGH.
  • After the reboot is finished, the PWM output is initialized to LOW.

Screenshot from 2025-02-04 10-39-32

Solution

  • Disarm the PWM ESCs after reboot/hardfault/assertion, by pulling the PWM PINs low for 400ms

Changelog Entry

For release notes:

Feature Disarm PWM ESCs before reboot/shutdown on v5x/v6x

Test coverage

  • Tested on the bench

Copy link

github-actions bot commented Feb 4, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 8 byte (0 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%      +8  +0.0%      +8    .text
  +0.0%      +5  +0.0%      +5    [section .text]
  +0.2%      +3  +0.2%      +3    ../../src/systemcmds/ver/ver.cpp
+0.0%     +73  [ = ]       0    .debug_abbrev
  +2.2%     +17  [ = ]       0    ../../boards/px4/fmu-v5x/src/init.cpp
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -8  [ = ]       0    .debug_aranges
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -2  [ = ]       0    .debug_info
  +0.0%      +2  [ = ]       0    ../../boards/px4/fmu-v5x/src/init.cpp
  -0.2%      -4  [ = ]       0    ../../src/lib/version/version.c
-0.0%     -23  [ = ]       0    .debug_line
  +0.1%      +2  [ = ]       0    ../../boards/px4/fmu-v5x/src/init.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -8  [ = ]       0    .debug_ranges
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
-0.1%      -8  [ = ]       0    [Unmapped]
+0.0%     +32  +0.0%      +8    TOTAL

px4_fmu-v6x [Total VM Diff: 16 byte (0 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%     +16  +0.0%     +16    .text
  +0.0%     +13  +0.0%     +13    [section .text]
  +0.2%      +3  +0.2%      +3    ../../src/systemcmds/ver/ver.cpp
+0.0%     +73  [ = ]       0    .debug_abbrev
  +2.2%     +17  [ = ]       0    ../../boards/px4/fmu-v6x/src/init.cpp
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -8  [ = ]       0    .debug_aranges
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -2  [ = ]       0    .debug_info
  +0.0%      +2  [ = ]       0    ../../boards/px4/fmu-v6x/src/init.cpp
  -0.2%      -4  [ = ]       0    ../../src/lib/version/version.c
-0.0%     -23  [ = ]       0    .debug_line
  +0.1%      +2  [ = ]       0    ../../boards/px4/fmu-v6x/src/init.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -8  [ = ]       0    .debug_ranges
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
-0.0%     -16  [ = ]       0    [Unmapped]
+0.0%     +32  +0.0%     +16    TOTAL

Updated: 2025-02-05T16:04:21

@alexcekay alexcekay force-pushed the pr-esc-disarm branch 2 times, most recently from 017151e to 83bce44 Compare February 4, 2025 13:17
@alexcekay alexcekay marked this pull request as ready for review February 4, 2025 14:07
@alexcekay alexcekay requested a review from dagar February 4, 2025 14:17
@dagar
Copy link
Member

dagar commented Feb 5, 2025

  1. What about the px4io (that's in most fmu-v5x/v6x flight controllers)
  2. What about other boards? (we should apply the fix everywhere everywhere)
  3. Would it instead make sense to solve this via shutdown hooks in the output modules?
    • eg drivers/pwm_out could first send the disarm values, then clear the line, and only then allow the system to actually reboot?
    • likewise for drivers/px4io, drivers/dshot, perhaps uavcan, etc

EDIT: I kind of like option 3 to first send disarm, but we'd probably still want the low level board reset timing as well.

if (status >= 0) {
up_mdelay(6);
up_mdelay(400);
Copy link
Member

Choose a reason for hiding this comment

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

Why 400 milliseconds? Wouldn't even 20 milliseconds be sufficient for almost all real usage?

Copy link
Member Author

@alexcekay alexcekay Feb 5, 2025

Choose a reason for hiding this comment

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

I have the threshold from: boards/px4/fmu-v3/src/init.c, where there is an up_mdelay(400);
After some experiments with a APD F3X I set the threshold to 100ms as this avoided it from spinning. Lower values caused it to still spin.

@alexcekay
Copy link
Member Author

alexcekay commented Feb 5, 2025

Hi @dagar,

Would it instead make sense to solve this via shutdown hooks in the output modules?

I actually solved it first via the shutdown hook. The problem with that solution is, that it does not solve the issue for any kind of unexpected resets. For example when the board gets resetted via a hard fault, the motor would still spin up.
At one point I had both options in there (disarm via hardfault + low level init as now), but this felt unneeded and the delays added up.

What about other boards? (we should apply the fix everywhere everywhere)

Rolled it out to all boards that did not already have a higher threshold defined.

What about the px4io (that's in most fmu-v5x/v6x flight controllers)

I did have a look at the px4io. The reset behavior is different in the sense, that the ESC can't pull up the PWM Pins of the IO to 3.3V during reset due to electrical characteristics of the STM32F1, which results in a voltage of ~1.1V on the PWM signal during reset. So I don't see a direct problem, can however add a similar logic in another PR.

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.

2 participants