AP_NavEKF3: use AHRS likely flying state

this sets inFlight when AHRS has indicated flying for 5s
This commit is contained in:
Andrew Tridgell 2017-06-19 13:17:31 +10:00
parent cbffc29f0b
commit a1508b58c1
1 changed files with 3 additions and 3 deletions

View File

@ -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;
}
}
}