Skip to content

Commit

Permalink
APM_Control: Allow autotune level 0 to actually reach the lowest entr…
Browse files Browse the repository at this point in the history
…ies of the autotune level table
  • Loading branch information
WickedShell authored and tridge committed Oct 31, 2023
1 parent 2be4c0e commit f1b6a7d
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/APM_Control/AP_AutoTune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit f1b6a7d

Please sign in to comment.