AP_NavEKF2: get_time_flying in vehicle

This commit is contained in:
Peter Hall 2020-01-06 23:07:10 +00:00 committed by WickedShell
parent c870df0351
commit 2970334c0d
1 changed files with 2 additions and 1 deletions

View File

@ -388,7 +388,8 @@ void NavEKF2_core::detectFlight()
// If more than 5 seconds since likely_flying was set // If more than 5 seconds since likely_flying was set
// true, then set inFlight true // true, then set inFlight true
if (_ahrs->get_time_flying_ms() > 5000) { const AP_Vehicle *vehicle = AP::vehicle();
if (vehicle->get_time_flying_ms() > 5000) {
inFlight = true; inFlight = true;
} }
} }