Browse Source

Plane: only save gains if disarmed in autotune

master
Peter Hall 6 years ago committed by Andrew Tridgell
parent
commit
0b1d392342
  1. 6
      ArduPlane/system.cpp

6
ArduPlane/system.cpp

@ -502,7 +502,11 @@ bool Plane::disarm_motors(void) @@ -502,7 +502,11 @@ bool Plane::disarm_motors(void)
#if QAUTOTUNE_ENABLED
//save qautotune gains if enabled and success
quadplane.qautotune.save_tuning_gains();
if (control_mode == &mode_qautotune) {
quadplane.qautotune.save_tuning_gains();
} else {
quadplane.qautotune.reset();
}
#endif
return true;

Loading…
Cancel
Save