Copter: only save autotune gains if disarmed in autotue

This commit is contained in:
Peter Hall 2019-05-01 13:27:40 +01:00 committed by Andrew Tridgell
parent 0b1d392342
commit 3fe63d5bc0
3 changed files with 11 additions and 1 deletions

View File

@ -499,6 +499,7 @@ public:
void save_tuning_gains();
void stop();
void reset();
protected:

View File

@ -173,4 +173,9 @@ void Copter::ModeAutoTune::stop()
copter.autotune.stop();
}
void Copter::ModeAutoTune::reset()
{
copter.autotune.reset();
}
#endif // AUTOTUNE_ENABLED == ENABLED

View File

@ -266,7 +266,11 @@ void Copter::init_disarm_motors()
#if AUTOTUNE_ENABLED == ENABLED
// save auto tuned parameters
mode_autotune.save_tuning_gains();
if (control_mode == AUTOTUNE) {;
mode_autotune.save_tuning_gains();
} else {
mode_autotune.reset();
}
#endif
// we are not in the air