mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_SteerController: lower the default STEER2SRV_D
This commit is contained in:
parent
a1cbcc5e23
commit
98b4ed1522
@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_SteerController::var_info[] PROGMEM = {
|
|||||||
// @Range: 0 0.1
|
// @Range: 0 0.1
|
||||||
// @Increment: 0.01
|
// @Increment: 0.01
|
||||||
// @User: User
|
// @User: User
|
||||||
AP_GROUPINFO("D", 4, AP_SteerController, _K_D, 0.02f),
|
AP_GROUPINFO("D", 4, AP_SteerController, _K_D, 0.005f),
|
||||||
|
|
||||||
// @Param: IMAX
|
// @Param: IMAX
|
||||||
// @DisplayName: Integrator limit
|
// @DisplayName: Integrator limit
|
||||||
|
Loading…
Reference in New Issue
Block a user