mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Landing: Fix unconditional use of airspeed estimate, even when it was invalid
This commit is contained in:
parent
5571a84a49
commit
8e8ce6be35
@ -337,7 +337,10 @@ bool AP_Landing_Deepstall::override_servos(void)
|
|||||||
|
|
||||||
// use the current airspeed to dictate the travel limits
|
// use the current airspeed to dictate the travel limits
|
||||||
float airspeed;
|
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
|
// only allow the deepstall steering controller to run below the handoff airspeed
|
||||||
if (slew_progress >= 1.0f || airspeed <= handoff_airspeed) {
|
if (slew_progress >= 1.0f || airspeed <= handoff_airspeed) {
|
||||||
|
Loading…
Reference in New Issue
Block a user