AP_Landing: Fix unconditional use of airspeed estimate, even when it was invalid

This commit is contained in:
Michael du Breuil 2019-03-12 02:44:45 -07:00 committed by Andrew Tridgell
parent 5571a84a49
commit 8e8ce6be35
1 changed files with 4 additions and 1 deletions

View File

@ -337,7 +337,10 @@ bool AP_Landing_Deepstall::override_servos(void)
// use the current airspeed to dictate the travel limits
float airspeed;
landing.ahrs.airspeed_estimate(&airspeed);
if (!landing.ahrs.airspeed_estimate(&airspeed)) {
airspeed = 0; // safely forces control to the deepstall steering since we don't have an estimate
}
// only allow the deepstall steering controller to run below the handoff airspeed
if (slew_progress >= 1.0f || airspeed <= handoff_airspeed) {