APM_Control: raised default PID gains for roll/pitch

This commit is contained in:
Andrew Tridgell 2018-08-17 17:01:56 +10:00
parent 5ba6f5a3a2
commit 6fe07e5702
2 changed files with 6 additions and 6 deletions

View File

@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @Range: 0.1 3.0 // @Range: 0.1 3.0
// @Increment: 0.1 // @Increment: 0.1
// @User: User // @User: User
AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 0.6f), AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 1.0f),
// @Param: D // @Param: D
// @DisplayName: Damping Gain // @DisplayName: Damping Gain
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @Range: 0 0.1 // @Range: 0 0.1
// @Increment: 0.01 // @Increment: 0.01
// @User: User // @User: User
AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.02f), AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.08f),
// @Param: I // @Param: I
// @DisplayName: Integrator Gain // @DisplayName: Integrator Gain
@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = {
// @Range: 0 0.5 // @Range: 0 0.5
// @Increment: 0.05 // @Increment: 0.05
// @User: User // @User: User
AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.15f), AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.3f),
// @Param: RMAX_UP // @Param: RMAX_UP
// @DisplayName: Pitch up max rate // @DisplayName: Pitch up max rate

View File

@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
// @Range: 0.1 4.0 // @Range: 0.1 4.0
// @Increment: 0.1 // @Increment: 0.1
// @User: User // @User: User
AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.6f), AP_GROUPINFO("P", 1, AP_RollController, gains.P, 1.0f),
// @Param: D // @Param: D
// @DisplayName: Damping Gain // @DisplayName: Damping Gain
@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
// @Range: 0 0.1 // @Range: 0 0.1
// @Increment: 0.01 // @Increment: 0.01
// @User: User // @User: User
AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.02f), AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.08f),
// @Param: I // @Param: I
// @DisplayName: Integrator Gain // @DisplayName: Integrator Gain
@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = {
// @Range: 0 1.0 // @Range: 0 1.0
// @Increment: 0.05 // @Increment: 0.05
// @User: User // @User: User
AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.1f), AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.3f),
// @Param: RMAX // @Param: RMAX
// @DisplayName: Maximum Roll Rate // @DisplayName: Maximum Roll Rate