mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: suppress the throttle in auto-throttle modes after parachute release
This commit is contained in:
parent
9affddcaa3
commit
d20b86b95e
@ -558,6 +558,12 @@ void Plane::flap_slew_limit(int8_t &last_value, int8_t &new_value)
|
||||
*/
|
||||
bool Plane::suppress_throttle(void)
|
||||
{
|
||||
if (auto_throttle_mode && parachute.released()) {
|
||||
// throttle always suppressed in auto-throttle modes after parachute release
|
||||
throttle_suppressed = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
if (!throttle_suppressed) {
|
||||
// we've previously met a condition for unsupressing the throttle
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user