diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index f77b9875c6..bf6da7412e 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -907,7 +907,6 @@ void AC_AutoTune::backup_gains_and_initialise() // no axes are complete axes_completed = 0; - current_gain_type = GAIN_ORIGINAL; positive_direction = false; step = WAITING_FOR_LEVEL; step_start_time_ms = AP_HAL::millis(); @@ -1104,9 +1103,6 @@ void AC_AutoTune::load_twitch_gains() */ void AC_AutoTune::load_gains(enum GainType gain_type) { - if (current_gain_type == gain_type) { - return; - } switch (gain_type) { case GAIN_ORIGINAL: load_orig_gains(); diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 452e847816..aaa92a56ef 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -156,7 +156,6 @@ private: GAIN_INTRA_TEST = 2, GAIN_TUNED = 3, }; - enum GainType current_gain_type; void load_gains(enum GainType gain_type); TuneMode mode : 2; // see TuneMode for what modes are allowed