APM_Control: increase available range for roll and pitch

This commit is contained in:
Andrew Tridgell 2014-08-16 18:07:13 +10:00
parent fb867f3a06
commit 8f3dad0d1c
2 changed files with 2 additions and 2 deletions

View File

@ -38,7 +38,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 2.0
// @Range: 0.1 3.0
// @Increment: 0.1
// @User: User
AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 0.4f),

View File

@ -37,7 +37,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 2.0
// @Range: 0.1 4.0
// @Increment: 0.1
// @User: User
AP_GROUPINFO("P", 1, AP_RollController, gains.P, 0.4f),