AC_AutoTune: add public reset method

This commit is contained in:
Peter Hall 2019-05-01 13:15:56 +01:00 committed by Andrew Tridgell
parent e4f6ffe719
commit a0d8c04f3e
2 changed files with 7 additions and 3 deletions

View File

@ -1215,9 +1215,7 @@ void AC_AutoTune::save_tuning_gains()
update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS);
Log_Write_Event(EVENT_AUTOTUNE_SAVEDGAINS);
// reset Autotune so that gains are not saved again and autotune can be run again.
mode = UNINITIALISED;
axes_completed = 0;
reset();
}
// update_gcs - send message to ground station

View File

@ -37,6 +37,12 @@ public:
// stop tune, reverting gains
void stop();
// reset Autotune so that gains are not saved again and autotune can be run again.
void reset() {
mode = UNINITIALISED;
axes_completed = 0;
}
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];