APM_Control: Allow autotune level 0 to actually reach the lowest entries of the autotune level table

This commit is contained in:
Michael du Breuil 2023-10-28 13:51:03 -07:00 committed by Andrew Tridgell
parent 2be4c0e3f5
commit f1b6a7d586
1 changed files with 1 additions and 1 deletions

View File

@ -556,7 +556,7 @@ void AP_AutoTune::update_rmax(void)
if (level == 0) {
// this level means to keep current values of RMAX and TCONST
target_rmax = constrain_float(current.rmax_pos, 75, 720);
target_rmax = constrain_float(current.rmax_pos, 20, 720);
target_tau = constrain_float(current.tau, 0.1, 2);
} else {
target_rmax = tuning_table[level-1].rmax;