Browse Source

Plane: update isFlying() landing check

When we are landing a sink_rate < -0.2f means the vehicle is climbing,
which should never happen during an approach for any supported landing
type (slope or deepstall), and on hard impacts with the ground its
common for the vehicle altitude to be projected to low and climb back to
the correct altitude slowly (but at a higher rate). This changes the
check to only consider sinks while on approach as acceptable.
master
Michael du Breuil 7 years ago committed by Tom Pittenger
parent
commit
bd32b5deb7
  1. 2
      ArduPlane/is_flying.cpp

2
ArduPlane/is_flying.cpp

@ -90,7 +90,7 @@ void Plane::update_is_flying_5Hz(void) @@ -90,7 +90,7 @@ void Plane::update_is_flying_5Hz(void)
break;
case AP_Vehicle::FixedWing::FLIGHT_LAND:
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) {
if (landing.is_on_approach() && auto_state.sink_rate > 0.2f) {
is_flying_bool = true;
}
break;

Loading…
Cancel
Save