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:
Andrew Tridgell 2018-09-14 07:31:33 +10:00
parent 58a363c643
commit 820b2386c0

View File

@ -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