diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index e22282bcd7..28364501b6 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -28,7 +28,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = { // @Param: P // @DisplayName: Proportional Gain // @Description: This is the gain from pitch angle to elevator. This gain works the same way as PTCH2SRV_P in the old PID controller and can be set to the same value. - // @Range: 0.1 1.0 + // @Range: 0.1 2.0 // @Increment: 0.1 // @User: User AP_GROUPINFO("P", 1, AP_PitchController, _K_P, 0.4f), diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index a68619d908..670963005a 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = { // @Param: P // @DisplayName: Proportional Gain // @Description: This is the gain from bank angle to aileron. This gain works the same way as the P term in the old PID (RLL2SRV_P) and can be set to the same value. - // @Range: 0.1 1.0 + // @Range: 0.1 2.0 // @Increment: 0.1 // @User: User AP_GROUPINFO("P", 1, AP_RollController, _K_P, 0.4f),