mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Fix failure to disarm after landing in strong winds
This commit is contained in:
parent
6d6ec44d59
commit
a1bde16abd
@ -48,8 +48,9 @@ void Plane::update_is_flying_5Hz(void)
|
|||||||
// we've flown before, remove GPS constraints temporarily and only use airspeed
|
// we've flown before, remove GPS constraints temporarily and only use airspeed
|
||||||
is_flying_bool = airspeed_movement; // moving through the air
|
is_flying_bool = airspeed_movement; // moving through the air
|
||||||
} else {
|
} else {
|
||||||
// we've never flown yet, require good GPS movement
|
// Because ahrs.airspeed_estimate can return a continued high value after landing if flying in
|
||||||
is_flying_bool = airspeed_movement || // moving through the air
|
// strong winds above stall speed it is necessary to include the IMU based movement check.
|
||||||
|
is_flying_bool = (airspeed_movement && !AP::ins().is_still()) || // moving through the air
|
||||||
gps_confirmed_movement; // locked and we're moving
|
gps_confirmed_movement; // locked and we're moving
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user