From d8dab7b5c7c74c0b4e16cc839b97e717c87ee078 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Mon, 10 Jun 2013 21:34:32 +1000 Subject: [PATCH] APM_Control: Pitch Control - Reduced the speed below which the integrator is locked This is to allow for slow speed flare manoeuvres in FBW modes --- libraries/APM_Control/AP_PitchController.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 7d395b4057..c2f520b268 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -171,7 +171,7 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab // Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs 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)) { + if (dt > 0 && aspeed > 0.5f*float(aspd_min)) { 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