APM_Control: prevent bad init of FF in autotune

This commit is contained in:
Andrew Tridgell 2021-04-11 08:30:10 +10:00
parent cb4a770d38
commit 91856b1d8c

View File

@ -117,7 +117,7 @@ void AP_AutoTune::start(void)
last_save_ms = now;
restore = last_save = get_gains(current);
current = restore = last_save = get_gains(current);
// do first update of rmax and tau now
update_rmax();