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

Plane: Do not apply minimum throttle during SLT VTOL airbrake #28329

Merged
merged 2 commits into from
Oct 9, 2024

Conversation

Georacer
Copy link
Contributor

@Georacer Georacer commented Oct 7, 2024

Summary

This PR ensures that the bool SLT_Transition::active_frwd() check does not return true during a back-transition airbrake.

Details

The existing code would cause active_frwd() to return true during a back transition.
In turn, servos.cpp:553 would trigger:

#if HAL_QUADPLANE_ENABLED
    if (quadplane.in_frwd_transition()) {

and would set the minimum throttle to the forwards transition throttle: THR_TRIM or TKOFF_THR_MIN.

This would lead to undesired increase in airspeed and eventually altitude during the back transition.

The TECS minimum throttle can be used as a proxy to see the effect of that setting.
This is a snapshot during the airbrake phase.

Before:
image

After:
image

@Georacer Georacer changed the title Pr/bt no pusher Plane: Do not apply minimum throttle during SLT VTOL airbrake Oct 7, 2024
@tridge tridge merged commit 4352129 into ArduPilot:master Oct 9, 2024
68 checks passed
Comment on lines +4377 to +4379
return quadplane.assisted_flight && // We need to be in assisted flight...
((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)) // ... and a transition must be active...
&& !quadplane.in_vtol_airbrake(); // ... but not executing an QPOS_AIRBRAKE maneuver during an automated landing.
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
return quadplane.assisted_flight && // We need to be in assisted flight...
((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)) // ... and a transition must be active...
&& !quadplane.in_vtol_airbrake(); // ... but not executing an QPOS_AIRBRAKE maneuver during an automated landing.
// We need to be in assisted flight:
if (!quadplane.assisted_flight) {
return false;
}
if (!quadplane.in_vtol_airbrake()) {
// ... but not executing an QPOS_AIRBRAKE maneuver during an automated landing.
return false;
}
if (!((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)) {
return false;
}
return true;

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