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

Implement ESC Minimum RPM Check Before Takeoff #27696

Open
wants to merge 6 commits into
base: master
Choose a base branch
from

Conversation

loki077
Copy link
Contributor

@loki077 loki077 commented Jul 30, 2024

This PR introduces a code implementation to perform an ESC minimum RPM check before takeoff. The purpose of this check is to ensure that motors are properly spooling before takeoff, leveraging ESC telemetry when available. This aims to prevent flights with undetected motor failures.

Initially, I considered integrating this check with a Pre-ARM check (#26832), but it was highlighted that a similar method already exists in Copter (#21499).

With assistance from @peterbarker found a different method to generalise the check into AP_motors.

This code is still a work in progress and needs further discussion during dev call if this is the right approach.

@loki077
Copy link
Contributor Author

loki077 commented Jul 30, 2024

@Pradeep-Carbonix @robertlong13 FYI

@peterbarker
Copy link
Contributor

@WickedShell and @magicrub have had ideas on this sort of thing before.

... and it's @andyp1per 's code we're co-opting

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Jul 30, 2024
@rmackay9
Copy link
Contributor

thanks for this, I'm not sure that architecturally we should be putting this down in the motors library. This check depends on other subsystems so I think it naturally belongs higher

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

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

maybe this common code should go in AP_Vehicle?

@@ -1926,6 +1941,10 @@ void QuadPlane::update_throttle_hover()
*/
void QuadPlane::motors_output(bool run_rate_controller)
{
#if HAL_WITH_ESC_TELEM
motors->takeoff_check(takeoff_rpm_min, takeoff_rpm_max, false);
Copy link
Contributor

Choose a reason for hiding this comment

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

the land_complete false is a problem, and means this doesn't work at all.
We need this to only impact automatic takeoff, not manual takeoff or a back transition. If we lose RPM monitoring on a motor we must not fail to spool up on back transition

Copy link
Contributor

Choose a reason for hiding this comment

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

can use in_vtol_takeoff()

// @Description: Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check
// @Range: 0 10000
// @User: Standard
AP_GROUPINFO("TKOFF_RPM_MIN", 39, QuadPlane, takeoff_rpm_min, 0),
Copy link
Contributor

Choose a reason for hiding this comment

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

a blank line between params helps readability

@@ -612,6 +612,11 @@ class QuadPlane
// AHRS alt for land abort and package place, meters
float land_descend_start_alt;

// support for blocking takeoff until RPMs reach parameter-defined
// minimum levels:
AP_Float takeoff_rpm_min;
Copy link
Contributor

Choose a reason for hiding this comment

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

these are AP_Int16 in copter, we should make them the same type in plane

@@ -612,6 +612,11 @@ class QuadPlane
// AHRS alt for land abort and package place, meters
float land_descend_start_alt;

// support for blocking takeoff until RPMs reach parameter-defined
// minimum levels:
AP_Float takeoff_rpm_min;
Copy link
Contributor

Choose a reason for hiding this comment

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

needs #if HAL_WITH_ESC_TELEM around these

@@ -1926,6 +1941,11 @@ void QuadPlane::update_throttle_hover()
*/
void QuadPlane::motors_output(bool run_rate_controller)
{
#if HAL_WITH_ESC_TELEM
Copy link
Contributor

Choose a reason for hiding this comment

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

I'd much rather have this in QuadPlane::takeoff_controller(), and operate just like the existing check for tiltrotor.fully_up()
I don't think it should apply to manually piloted takeoffs
I don't think we should be calling set_spoolup_block() at all in quadplanes, we can just delay takeoff, and print a message as to why it is delayed

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants