AC_AutoTune: fix restoring of original gains

current_gain_type was not being set when load_gains was called meaning subsequent calls to load_gains would fail if gain_type was GAIN_ORIGINAL
This commit is contained in:
Leonard Hall 2020-01-30 10:21:04 +09:00 committed by Andrew Tridgell
parent 6f76b2eacb
commit 8d08a5d4bd
2 changed files with 0 additions and 5 deletions

View File

@ -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();

View File

@ -170,7 +170,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