Browse Source

Copter: only allow autotuning when flying

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
bbc4cb263f
  1. 4
      ArduCopter/ArduCopter.pde

4
ArduCopter/ArduCopter.pde

@ -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
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();
}

Loading…
Cancel
Save