APM_Control: use FF to increase but not reduce tau in autotune

if user wants a slow time constant we should not override
This commit is contained in:
Andrew Tridgell 2021-05-06 10:24:50 +10:00 committed by Peter Barker
parent 45d82887b3
commit cd43c0ecef

View File

@ -528,7 +528,7 @@ void AP_AutoTune::update_rmax(void)
if (level > 0 && is_positive(current.FF)) {
const float invtau = ((1.0f / target_tau) + (current.I / current.FF));
if (is_positive(invtau)) {
target_tau = 1.0f / invtau;
target_tau = MAX(target_tau,1.0f / invtau);
}
}