Copter: Autotune: Reduce default AGGR

This commit is contained in:
Leonard Hall 2024-02-23 14:34:07 +10:30 committed by Peter Barker
parent c47b3b8f03
commit 327fd034da

View File

@ -95,7 +95,7 @@ const AP_Param::GroupInfo AC_AutoTune_Multi::var_info[] = {
// @Description: Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
// @Range: 0.05 0.10
// @User: Standard
AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.1f),
AP_GROUPINFO("AGGR", 2, AC_AutoTune_Multi, aggressiveness, 0.075f),
// @Param: MIN_D
// @DisplayName: AutoTune minimum D