APM_Control: raise default IMAX to 3000

on the first flight users often need more I gain to overcome poor
choices for the P gain
This commit is contained in:
Andrew Tridgell 2015-02-19 16:15:33 +11:00
parent cd2898b149
commit ec70042d25
2 changed files with 4 additions and 4 deletions

View File

@ -87,11 +87,11 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
// @Param: IMAX
// @DisplayName: Integrator limit
// @Description: This limits the number of centi-degrees of elevator over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 degrees, so the default value represents a 1/3rd of the total control throw which is adequate for most aircraft unless they are severely out of trim or have very limited elevator control effectiveness.
// @Description: This limits the number of centi-degrees of elevator over which the integrator will operate. At the default setting of 3000 centi-degrees, the integrator will be limited to +- 30 degrees of servo travel. The maximum servo deflection is +- 45 degrees, so the default value represents a 2/3rd of the total control throw which is adequate for most aircraft unless they are severely out of trim or have very limited elevator control effectiveness.
// @Range: 0 4500
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("IMAX", 7, AP_PitchController, gains.imax, 1500),
AP_GROUPINFO("IMAX", 7, AP_PitchController, gains.imax, 3000),
AP_GROUPEND
};

View File

@ -69,11 +69,11 @@ const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
// @Param: IMAX
// @DisplayName: Integrator limit
// @Description: This limits the number of degrees of aileron in centi-degrees over which the integrator will operate. At the default setting of 1500 centi-degrees, the integrator will be limited to +- 15 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 1/3rd of the total control throw which is adequate unless the aircraft is severely out of trim.
// @Description: This limits the number of degrees of aileron in centi-degrees over which the integrator will operate. At the default setting of 3000 centi-degrees, the integrator will be limited to +- 30 degrees of servo travel. The maximum servo deflection is +- 45 centi-degrees, so the default value represents a 2/3rd of the total control throw which is adequate unless the aircraft is severely out of trim.
// @Range: 0 4500
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("IMAX", 5, AP_RollController, gains.imax, 1500),
AP_GROUPINFO("IMAX", 5, AP_RollController, gains.imax, 3000),
AP_GROUPEND
};