mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
APM_Control: prevent bad init of FF in autotune
This commit is contained in:
parent
cb4a770d38
commit
91856b1d8c
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user