mirror of https://github.com/ArduPilot/ardupilot
Copter: disable hover throttle learn in standby mode
This commit is contained in:
parent
c7a9fb3c9c
commit
c0cf814d3e
|
@ -9,7 +9,7 @@
|
|||
void Copter::update_throttle_hover()
|
||||
{
|
||||
// if not armed or landed exit
|
||||
if (!motors->armed() || ap.land_complete) {
|
||||
if (!motors->armed() || ap.land_complete || standby_active) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
// crash_check is disabled
|
||||
// thrust_loss_check is disabled
|
||||
// parachute_check is disabled
|
||||
// hover throttle learn is disabled
|
||||
// and landing detection is disabled.
|
||||
void Copter::standby_update()
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue