ArduPlane: Only run is_flying landing checks when in landing stage

This commit is contained in:
Michael du Breuil 2017-11-02 15:12:07 -07:00 committed by Andrew Tridgell
parent 338d745de1
commit 83decd1370

View File

@ -70,10 +70,6 @@ void Plane::update_is_flying_5Hz(void)
crash_state.impact_detected = false;
}
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) {
is_flying_bool = true;
}
switch (flight_stage)
{
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF:
@ -93,6 +89,12 @@ void Plane::update_is_flying_5Hz(void)
// TODO: detect ground impacts
break;
case AP_Vehicle::FixedWing::FLIGHT_LAND:
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) {
is_flying_bool = true;
}
break;
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND:
if (auto_state.sink_rate < -0.5f) {
// steep climb