mirror of https://github.com/ArduPilot/ardupilot
APM_Control: halve the default pitch D term for planes
this is based on feedback from the 3.9.1 release
This commit is contained in:
parent
2d3942222b
commit
3ab7fe348a
|
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
|
|||
// @Range: 0 0.1
|
||||
// @Increment: 0.01
|
||||
// @User: User
|
||||
AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.08f),
|
||||
AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.04f),
|
||||
|
||||
// @Param: I
|
||||
// @DisplayName: Integrator Gain
|
||||
|
|
Loading…
Reference in New Issue