mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Copter: Autotune: Reduce default AGGR
This commit is contained in:
parent
c47b3b8f03
commit
327fd034da
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user