AP_SteerController: lower the default STEER2SRV_D

This commit is contained in:
Andrew Tridgell 2013-09-16 08:26:29 +10:00
parent a1cbcc5e23
commit 98b4ed1522
1 changed files with 1 additions and 1 deletions

View File

@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] PROGMEM = {
// @Range: 0 0.1
// @Increment: 0.01
// @User: User
AP_GROUPINFO("D", 4, AP_SteerController, _K_D, 0.02f),
AP_GROUPINFO("D", 4, AP_SteerController, _K_D, 0.005f),
// @Param: IMAX
// @DisplayName: Integrator limit