Plane: Added APM_Control integrator limits to table used to covert old PID values

This commit is contained in:
Paul Riseborough 2013-06-22 21:08:37 +10:00 committed by Andrew Tridgell
parent 147856e73c
commit 2204b30e66
4 changed files with 8 additions and 6 deletions

View File

@ -849,10 +849,12 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
{ Parameters::k_param_pidServoRoll, 0, AP_PARAM_FLOAT, "RLL2SRV_P" },
{ Parameters::k_param_pidServoRoll, 1, AP_PARAM_FLOAT, "RLL2SRV_I" },
{ Parameters::k_param_pidServoRoll, 2, AP_PARAM_FLOAT, "RLL2SRV_D" },
{ Parameters::k_param_pidServoRoll, 3, AP_PARAM_FLOAT, "RLL2SRV_IMAX" },
{ Parameters::k_param_pidServoPitch, 0, AP_PARAM_FLOAT, "PTCH2SRV_P" },
{ Parameters::k_param_pidServoPitch, 1, AP_PARAM_FLOAT, "PTCH2SRV_I" },
{ Parameters::k_param_pidServoPitch, 2, AP_PARAM_FLOAT, "PTCH2SRV_D" },
{ Parameters::k_param_pidServoPitch, 3, AP_PARAM_FLOAT, "PTCH2SRV_IMAX" },
};
static void load_parameters(void)

View File

@ -195,7 +195,7 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
}
// Scale the integration limit
float intLimScaled = float(_imax) / scaler;
float intLimScaled = _imax * 0.01f / scaler;
// Constrain the integrator state
_integrator = constrain_float(_integrator, -intLimScaled, intLimScaled);

View File

@ -145,7 +145,7 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
}
// Scale the integration limit
float intLimScaled = float(_imax) / scaler;
float intLimScaled = _imax * 0.01f / scaler;
// Constrain the integrator state
_integrator = constrain_float(_integrator, -intLimScaled, intLimScaled);

View File

@ -47,11 +47,11 @@ const AP_Param::GroupInfo AP_YawController::var_info[] PROGMEM = {
// @Param: IMAX
// @DisplayName: Integrator limit
// @Description: This limits the number of degrees of rudder over which the integrator will operate. At the default setting of 15 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 rudder control effectiveness.
// @Range: 0 45
// @Description: This limits the number of centi-degrees of rudder 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 rudder control effectiveness.
// @Range: 0 4500
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("IMAX", 4, AP_YawController, _imax, 15),
AP_GROUPINFO("IMAX", 4, AP_YawController, _imax, 1500),
AP_GROUPEND
};
@ -128,7 +128,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool stabilize, int16_t as
}
// Scale the integration limit
float intLimScaled = float(_imax) / (_K_D * scaler * scaler);
float intLimScaled = _imax * 0.01f / (_K_D * scaler * scaler);
// Constrain the integrator state
_integrator = constrain_float(_integrator, -intLimScaled, intLimScaled);