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

Default motor PWM configuration #21513

Merged
merged 10 commits into from
Jul 10, 2023
Merged

Default motor PWM configuration #21513

merged 10 commits into from
Jul 10, 2023

Conversation

MaEtUgR
Copy link
Member

@MaEtUgR MaEtUgR commented Apr 26, 2023

Solved Problem

PWM configuration parameters for ESCs have ambiguous meanings depending on the use case and have to manually be adjusted according to the context that the allocator already has.

Fixes #21506

Solution

  • Default to PWM 1000us for disarmed (servos still have 1500us)
    PWM 900us is out of spec of any ESC I know and they all stop the motor with 1000us
  • Default to a range of PWM 1100us - 1900us for motors
    This is the most compatible range I can think of with any ESC I worked with. Some have a lower limit of 1050us or 1075us but all turn the motor with 1100us. Some stop the range at 1925us or 1940us but all of them have the range not yet ended with 1900us. The idea is that the conservative defaults work reliably out of the box. If a user carefully follows the steps and e.g. experimentally finds out the exact PWM limits for all ESCs in use they can still configure that. From looking at logs I see that most users don't do that.
  • Fixed wings deliberately turn off the forward motors if they are commanded to produce zero thrust.
  • StandardVTOL do the same as fixed wings when not hovering
  • Tailsitter can now stop motor in fast forward flight, bench and simulation tested
  • Tiltrotor simulation test
  • Rover ackermann & differential simulation tested only
  • Boat simulation test
  • Submarine simulation test

Changelog Entry

For release notes:

Attention: Default disarmed PWM was changed from 900us to 1000us!
Improvement: Default motor PWM limits minimum 1100 maximum 1900
Documentation: https://docs.px4.io/main/en/advanced_config/esc_calibration.html

Documentation improvement pending: PX4/PX4-user_guide#2599

Alternatives

I also thought about keeping the ambiguity of PWM configuration and adding some magic again to change it automatically but just for multicopters in one way and for fixed wings the other way. But I think that's not the right solution because it will cause more confusion and corner cases and explicit configuration and use.

Test coverage

  • I tested this on a quadcopter with PWM ESCs both configured as multirotor, fixed-wing and StandardVTOL with 1 or more pushers. It behaves as I expect in these cases.
  • What's still missing are the VTOL cases. I think I can figure out standard VTOL but might need some help with Tiltrotor, let's see. EDIT: See above what I covered.

Context

1.14 release has only the new actuator configuration now and I want to make sure we get these PWM problems out of the way from the beginning since many people will switch and reconfigure the actuators once.

@MaEtUgR MaEtUgR requested a review from sfuhrer April 26, 2023 12:49
@MaEtUgR MaEtUgR self-assigned this Apr 26, 2023
@MaEtUgR MaEtUgR changed the title Maetugr/multicopter pwm Default motor PWM configuration Apr 26, 2023
@junwoo091400 junwoo091400 added the Drivers 🔧 Sensors, Actuators, etc label Apr 26, 2023
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Apr 26, 2023

StandardVTOL now works as expected. Other VTOL cases 👀
It looks like a tailsitter was not even capable to turn off the motor before judging by this comment:

// update stopped motors //TODO: add option to switch off certain motors in FW

Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

Thanks for this push, I think it makes sense to align all this.

I didn't yet have time to in depth go through it in detail, but maybe answering my couple of questions already is enough for me to get a better understanding.

const matrix::Vector<float, NUM_ACTUATORS> &actuator_max)
{
if (matrix_index == 0) {
// Stop front facing motors when they are commanded 0 thrust
Copy link
Contributor

Choose a reason for hiding this comment

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

Don't we just want to keep them at PWM_MIN? Stop for me is to, well, stop completely, which is what most VTOL pusher/pullers should be confiugred to do, but if one wants to have them always spinning that should be possible by increasing PWM_MIN to higher than 1000 right?

Copy link
Member Author

Choose a reason for hiding this comment

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

which is what most VTOL pusher/pullers should be confiugred to do

That's what I'm trying to solve that you have to configure PWM according to what the motor is supposed to do which is context the allocator has but you currently need to set manually.

if one wants to have them always spinning that should be possible by increasing PWM_MIN to higher than 1000 right?

It's possible and currently, every user has to manually set the PWM_MIN of any motor that should not stop spinning e.g. any multicopter motor to a higher value. Also consider this only works for PWM outputs and the special cases all have to be manually configured for any other interface. E.g. DSHOT pusher is not even possible because the functionality is captured manually in PWM configuration. Instead of re-adding some magic to guess which motor should not stop spinning without having the context I suggest configuring every motor to be the same way and the allocator to have the interface available to command a motor to stop depending on what it does. So in summary it's extending the VTOL motor start/stop interface to all cases a motor should start/stop.

break;

case FlightPhase::HOVER_FLIGHT:
case FlightPhase::TRANSITION_FF_TO_HF:
case FlightPhase::TRANSITION_HF_TO_FF:
_stopped_motors = 0;
_stopped_motors &= ~_mc_motors_mask;
Copy link
Contributor

Choose a reason for hiding this comment

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

Would this stop the pusher in hover? It's needed for pusher support.

Copy link
Member Author

@MaEtUgR MaEtUgR Apr 27, 2023

Choose a reason for hiding this comment

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

Would this stop the pusher in hover? It's needed for pusher support.

No, exactly, good question. That's what I took care of. It only enables and disables mc motors but the pusher is only off when it's commanded zero thrust. This can be extended to where the controller decides to always run it even if just idling but currently for 1.14, it just works again like it was.

@mrpollo
Copy link
Contributor

mrpollo commented Apr 28, 2023

Thanks for carrying this through the finish line before the release @MaEtUgR

carrying

@MaEtUgR MaEtUgR force-pushed the maetugr/multicopter-pwm branch 2 times, most recently from 1a56c49 to 75a80f1 Compare May 4, 2023 14:47
@MaEtUgR MaEtUgR marked this pull request as ready for review May 4, 2023 14:48
@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 4, 2023

ok, I went through all vehicle types including boat, uuv, tiltrotor in simulation and made sure it does what I expect:
Stop motors with <2% output command if they are not used for hovering. I also went through to make naming consistent and reduce duplication. It's in a reviewable state now.

As discussed with @bkueng the next step would be to allow the controller to decide which motors are turning off or not but we need to discuss the interface there and I didn't want to introduce that bigger change for 1.14 now.

Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

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

What I see makes sense to me. As discussed, let's though give this some testflying on all VTOL types early next week. That's something I anyway had planned to do to sign off the release.

const uint32_t motor_mask = (1u << actuator_idx);

if (stoppable_motors_mask & motor_mask) {
if (fabsf(actuator_sp(actuator_idx)) < .02f) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Can you drop a comment for the magic number 0.02? And/Or make it a constant?

@dagar
Copy link
Member

dagar commented May 9, 2023

Default to PWM 1000us for disarmed (servos still have 1500us)
PWM 900us is out of spec of any ESC I know and they all stop the motor with 1000us

I'm not sure, maybe we should skip this one until we fix PWM calibration.

@dagar dagar self-requested a review May 9, 2023 02:11
@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-maintainers-call-may-09-2023/32047/1

@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 10, 2023

Just rebased on main again since @sfuhrer and I go out to flight test the latest state of main including this.

@sfuhrer
Copy link
Contributor

sfuhrer commented May 11, 2023

Flight tested together with @MaEtUgR on a MC, FW, VTOL tailsitter, VTOL standard, VTOL tiltrotor.
logs:
VTOL tailsitter: https://review.px4.io/plot_app?log=bf5e796d-1fe0-44be-b04e-6ca1456422c4
VTOL standard: https://review.px4.io/plot_app?log=dd707948-f84a-449d-b90c-e748497b1cf2
FW: https://review.px4.io/plot_app?log=2e7daeca-9281-410c-9288-a154602d42a4

No issues around the new PWM logic as proposed in this Pr was found. All VTOLs switched off the motors not in use correctly. On one vehicle (the tiltrotor), the ESCs required a minimum PWM of 1150 to turn, and the ESC was not configurable. On all other vehicles the default range (1100-1900 for motors) was kept. I didn't check if the ESC response would have gone above 1900.

sfuhrer
sfuhrer previously approved these changes May 15, 2023
@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-maintainers-call-may-16-2023/32137/1

@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 23, 2023

For this one I'm looking into making sure all the PWM calibrations are always done with 2000us and then 1000us as the reference values which right now they are the configured PWM_MIN and PWM_MAX values which mostly leads to unexpected calibration results.

@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-maintainers-call-may-23-2023/32245/1

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jun 16, 2023

Now that #21711 is merged PWM outputs can consistently be calibrated on 1.14. So I:

I plan to merge this, inform users to recalibrate PWM/Oneshot ESCs also in the 1.14 release notes and if necessary update the documentation.

@mrpollo
Copy link
Contributor

mrpollo commented Jun 16, 2023

Let's make sure the release notes are calling out any user actions for upgrading

MaEtUgR added a commit to PX4/PX4-user_guide that referenced this pull request Jun 27, 2023
For the 1.14 release because we already changed the actuator
configuration and users will need to go through their setups I also
corrected the PWM calibration and the default PWM values.

See PX4/PX4-Autopilot#21711
and PX4/PX4-Autopilot#21513

This is the documentation change with it. And needs to be
referenced by the release notes.
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jun 27, 2023

Here's the documentation change for this mainly with the fixed PWM calibration (#21711): PX4/PX4-user_guide#2599

That's what we need to reference in the release notes. Something along the lines of:

Before updating to 1.14 remove all propellers from the vehicle and after the update go through the improved ESC calibration for PWM/OneShot ESCs: https://docs.px4.io/main/en/advanced_config/esc_calibration.html
and the new actuator configuration for all actuators: https://docs.px4.io/main/en/config/actuators.html

@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-maintainers-call-july-04-2023/32943/1

MaEtUgR added a commit to PX4/PX4-user_guide that referenced this pull request Jul 5, 2023
For the 1.14 release because we already changed the actuator
configuration and users will need to go through their setups I also
corrected the PWM calibration and the default PWM values.

See PX4/PX4-Autopilot#21711
and PX4/PX4-Autopilot#21513

This is the documentation change with it. And needs to be
referenced by the release notes.
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jul 6, 2023

I think PX4/PX4-user_guide#2599 should be ready now. So once the doc is available via URL we can merge this and notify + reference what should be done.

MaEtUgR added a commit to PX4/PX4-user_guide that referenced this pull request Jul 10, 2023
For the 1.14 release because we already changed the actuator
configuration and users will need to go through their setups I also
corrected the PWM calibration and the default PWM values.

See PX4/PX4-Autopilot#21711
and PX4/PX4-Autopilot#21513

This is the documentation change with it. And needs to be
referenced by the release notes.
@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jul 10, 2023

PWM calibration was fixed with #21711
Documentation for it is merged with PX4/PX4-user_guide#2599
I'm moving on with this PR.

@MaEtUgR MaEtUgR merged commit 02ab5e0 into main Jul 10, 2023
81 of 84 checks passed
@MaEtUgR MaEtUgR deleted the maetugr/multicopter-pwm branch July 10, 2023 16:58
@vincentpoont2
Copy link
Contributor

@MaEtUgR Does this apply to all Airframes?

@MaEtUgR
Copy link
Member Author

MaEtUgR commented Jul 11, 2023

Does this apply to all Airframes?

@vincentpoont2 This applies to all vehicle types and airframes that use one or more PWM or OneShot ESC to drive motors and are updated to 1.14 release candidate (not out yet, will suggest that today) or later (latest main with this pr). Fixed-wing and VTOL motors should be calibrated and configured the same way. The autopilot can now stop the motor by using the disarmed PWM automatically when required for these vehicle types.

@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/1-14-stable-holybro-x500-v2-motors-ramp-down/35326/5

@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/the-latest-firmware-for-cube-orange-issue/35341/15

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Drivers 🔧 Sensors, Actuators, etc
Projects
Status: Done
Development

Successfully merging this pull request may close these issues.

Tune PWM default values for multi-rotor to improve user experience
7 participants