Browse Source

AP_NavEKF2: use AHRS likely flying state

this sets inFlight when AHRS has indicated flying for 5s
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
cbffc29f0b
  1. 6
      libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp

6
libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp

@ -368,11 +368,11 @@ void NavEKF2_core::detectFlight() @@ -368,11 +368,11 @@ void NavEKF2_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…
Cancel
Save