mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
6ea568d72a
commit
d8dab7b5c7
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue