Skip to content
Snippets Groups Projects
Commit bbc4cb26 authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter: only allow autotuning when flying

parent cd5b24bf
No related branches found
No related tags found
No related merge requests found
...@@ -1591,8 +1591,8 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode) ...@@ -1591,8 +1591,8 @@ bool set_roll_pitch_mode(uint8_t new_roll_pitch_mode)
#if AUTOTUNE == ENABLED #if AUTOTUNE == ENABLED
case ROLL_PITCH_AUTOTUNE: case ROLL_PITCH_AUTOTUNE:
// only enter autotune mode from stabilized roll-pitch mode // only enter autotune mode from stabilized roll-pitch mode when armed and flying
if (roll_pitch_mode == ROLL_PITCH_STABLE) { 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 // auto_tune_start returns true if it wants the roll-pitch mode changed to autotune
roll_pitch_initialised = auto_tune_start(); roll_pitch_initialised = auto_tune_start();
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment