mirror of https://github.com/ArduPilot/ardupilot
APM_Control: changed default I gain for roll/pitch controllers to non-zero
too many people are still not tuning. At least this will give them a chance to get their aircraft back in a cross-wind
This commit is contained in:
parent
0d7ec0fbfe
commit
3b6c732b3b
|
@ -57,7 +57,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
|
|||
// @Range: 0 0.5
|
||||
// @Increment: 0.05
|
||||
// @User: User
|
||||
AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.0f),
|
||||
AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.04f),
|
||||
|
||||
// @Param: RMAX_UP
|
||||
// @DisplayName: Pitch up max rate
|
||||
|
|
|
@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
|
|||
// @Range: 0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: User
|
||||
AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.0f),
|
||||
AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.04f),
|
||||
|
||||
// @Param: RMAX
|
||||
// @DisplayName: Maximum Roll Rate
|
||||
|
|
Loading…
Reference in New Issue