From 6fe07e5702c0a0aca2b91e2f6d539fce277d9a26 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Aug 2018 17:01:56 +1000 Subject: [PATCH] APM_Control: raised default PID gains for roll/pitch --- libraries/APM_Control/AP_PitchController.cpp | 6 +++--- libraries/APM_Control/AP_RollController.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 3d60ce729d..ee186039c4 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = { // @Range: 0.1 3.0 // @Increment: 0.1 // @User: User - AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 0.6f), + AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 1.0f), // @Param: D // @DisplayName: Damping Gain @@ -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.02f), + AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.08f), // @Param: I // @DisplayName: Integrator Gain @@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = { // @Range: 0 0.5 // @Increment: 0.05 // @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 // @DisplayName: Pitch up max rate diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 0aa2dada91..9861490522 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { // @Range: 0.1 4.0 // @Increment: 0.1 // @User: User - AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.6f), + AP_GROUPINFO("P", 1, AP_RollController, gains.P, 1.0f), // @Param: D // @DisplayName: Damping Gain @@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { // @Range: 0 0.1 // @Increment: 0.01 // @User: User - AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.02f), + AP_GROUPINFO("D", 2, AP_RollController, gains.D, 0.08f), // @Param: I // @DisplayName: Integrator Gain @@ -54,7 +54,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { // @Range: 0 1.0 // @Increment: 0.05 // @User: User - AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.1f), + AP_GROUPINFO("I", 3, AP_RollController, gains.I, 0.3f), // @Param: RMAX // @DisplayName: Maximum Roll Rate