mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_NavEKF2: get_time_flying in vehicle
This commit is contained in:
parent
c870df0351
commit
2970334c0d
@ -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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user