mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF3: use AHRS likely flying state
this sets inFlight when AHRS has indicated flying for 5s
This commit is contained in:
parent
cbffc29f0b
commit
a1508b58c1
@ -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;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user