Copter: disable hover throttle learn in standby mode

This commit is contained in:
Iampete1 2021-05-18 00:17:08 +01:00 committed by Randy Mackay
parent c7a9fb3c9c
commit c0cf814d3e
2 changed files with 2 additions and 1 deletions

View File

@ -9,7 +9,7 @@
void Copter::update_throttle_hover() void Copter::update_throttle_hover()
{ {
// if not armed or landed exit // if not armed or landed exit
if (!motors->armed() || ap.land_complete) { if (!motors->armed() || ap.land_complete || standby_active) {
return; return;
} }

View File

@ -9,6 +9,7 @@
// crash_check is disabled // crash_check is disabled
// thrust_loss_check is disabled // thrust_loss_check is disabled
// parachute_check is disabled // parachute_check is disabled
// hover throttle learn is disabled
// and landing detection is disabled. // and landing detection is disabled.
void Copter::standby_update() void Copter::standby_update()
{ {