From bbc4cb263f3cd1d8169acb035f889865dd26ba56 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 21 Oct 2013 17:58:10 +0900 Subject: [PATCH] Copter: only allow autotuning when flying --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 37140e6168..7328c40c10 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1591,8 +1591,8 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode) #if AUTOTUNE == ENABLED case ROLL_PITCH_AUTOTUNE: - // only enter autotune mode from stabilized roll-pitch mode - if (roll_pitch_mode == ROLL_PITCH_STABLE) { + // only enter autotune mode from stabilized roll-pitch mode when armed and flying + if (roll_pitch_mode == ROLL_PITCH_STABLE && motors.armed() && !ap.land_complete) { // auto_tune_start returns true if it wants the roll-pitch mode changed to autotune roll_pitch_initialised = auto_tune_start(); }