From a0d8c04f3e63a47aaa22a4b6ff77bfd9d5c12da7 Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Wed, 1 May 2019 13:15:56 +0100 Subject: [PATCH] AC_AutoTune: add public reset method --- libraries/AC_AutoTune/AC_AutoTune.cpp | 4 +--- libraries/AC_AutoTune/AC_AutoTune.h | 6 ++++++ 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index fa1deb12c1..fbfaad5632 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -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 diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 754b776579..87ad7322b0 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -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[];