Plane : APM_Control : Removed scaler incorrectly applied to the integrator path

This commit is contained in:
Paul Riseborough 2013-06-04 17:49:53 +10:00 committed by Andrew Tridgell
parent 181beb004d
commit 3ad35363be
2 changed files with 2 additions and 2 deletions

View File

@ -172,7 +172,7 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
if (!stabilize && ki_rate > 0) {
//only integrate if gain and time step are positive and airspeed above min value.
if (dt > 0 && aspeed > float(aspd_min)) {
float integrator_delta = rate_error * ki_rate * scaler * delta_time;
float integrator_delta = rate_error * ki_rate * delta_time;
if (_last_out < -45) {
// prevent the integrator from increasing if surface defln demand is above the upper limit
integrator_delta = max(integrator_delta , 0);

View File

@ -122,7 +122,7 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
if (!stabilize && ki_rate > 0) {
//only integrate if gain and time step are positive and airspeed above min value.
if (dt > 0 && aspeed > float(aspd_min)) {
float integrator_delta = rate_error * ki_rate * scaler * delta_time;
float integrator_delta = rate_error * ki_rate * delta_time;
// prevent the integrator from increasing if surface defln demand is above the upper limit
if (_last_out < -45) {
integrator_delta = max(integrator_delta , 0);