From a1508b58c189575bdd5dad7f876b722d77a162b8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 Jun 2017 13:17:31 +1000 Subject: [PATCH] AP_NavEKF3: use AHRS likely flying state this sets inFlight when AHRS has indicated flying for 5s --- libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp index bcf920459b..351329f3bc 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp @@ -367,11 +367,11 @@ void NavEKF3_core::detectFlight() inFlight = true; } - // If more than 15 seconds armed since exiting on-ground, then we definitely are flying - if ((imuSampleTime_ms - timeAtArming_ms) > 15000) { + // If more than 5 seconds since likely_flying was set + // true, then set inFlight true + if (_ahrs->get_time_flying_ms() > 5000) { inFlight = true; } - } }