AP_NavEKF2_Control.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_NavEKF2.h"
  3. #include "AP_NavEKF2_core.h"
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <AP_Vehicle/AP_Vehicle.h>
  6. #include <GCS_MAVLink/GCS.h>
  7. #include <AP_GPS/AP_GPS.h>
  8. #include <stdio.h>
  9. extern const AP_HAL::HAL& hal;
  10. // Control filter mode transitions
  11. void NavEKF2_core::controlFilterModes()
  12. {
  13. // Determine motor arm status
  14. prevMotorsArmed = motorsArmed;
  15. motorsArmed = hal.util->get_soft_armed();
  16. if (motorsArmed && !prevMotorsArmed) {
  17. // set the time at which we arm to assist with checks
  18. timeAtArming_ms = imuSampleTime_ms;
  19. }
  20. // Detect if we are in flight on or ground
  21. detectFlight();
  22. // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
  23. // avoid unnecessary operations
  24. setWindMagStateLearningMode();
  25. // Check the alignmnent status of the tilt and yaw attitude
  26. // Used during initial bootstrap alignment of the filter
  27. checkAttitudeAlignmentStatus();
  28. // Set the type of inertial navigation aiding used
  29. setAidingMode();
  30. }
  31. /*
  32. return effective value for _magCal for this core
  33. */
  34. uint8_t NavEKF2_core::effective_magCal(void) const
  35. {
  36. // force use of simple magnetic heading fusion for specified cores
  37. if (frontend->_magMask & core_index) {
  38. return 2;
  39. } else {
  40. return frontend->_magCal;
  41. }
  42. }
  43. // Determine if learning of wind and magnetic field will be enabled and set corresponding indexing limits to
  44. // avoid unnecessary operations
  45. void NavEKF2_core::setWindMagStateLearningMode()
  46. {
  47. // If we are on ground, or in constant position mode, or don't have the right vehicle and sensing to estimate wind, inhibit wind states
  48. bool setWindInhibit = (!useAirspeed() && !assume_zero_sideslip()) || onGround || (PV_AidingMode == AID_NONE);
  49. if (!inhibitWindStates && setWindInhibit) {
  50. inhibitWindStates = true;
  51. } else if (inhibitWindStates && !setWindInhibit) {
  52. inhibitWindStates = false;
  53. // set states and variances
  54. if (yawAlignComplete && useAirspeed()) {
  55. // if we have airspeed and a valid heading, set the wind states to the reciprocal of the vehicle heading
  56. // which assumes the vehicle has launched into the wind
  57. Vector3f tempEuler;
  58. stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
  59. float windSpeed = sqrtf(sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y)) - tasDataDelayed.tas;
  60. stateStruct.wind_vel.x = windSpeed * cosf(tempEuler.z);
  61. stateStruct.wind_vel.y = windSpeed * sinf(tempEuler.z);
  62. // set the wind sate variances to the measurement uncertainty
  63. for (uint8_t index=22; index<=23; index++) {
  64. P[index][index] = sq(constrain_float(frontend->_easNoise, 0.5f, 5.0f) * constrain_float(_ahrs->get_EAS2TAS(), 0.9f, 10.0f));
  65. }
  66. } else {
  67. // set the variances using a typical wind speed
  68. for (uint8_t index=22; index<=23; index++) {
  69. P[index][index] = sq(5.0f);
  70. }
  71. }
  72. }
  73. // determine if the vehicle is manoeuvring
  74. if (accNavMagHoriz > 0.5f) {
  75. manoeuvring = true;
  76. } else {
  77. manoeuvring = false;
  78. }
  79. // Determine if learning of magnetic field states has been requested by the user
  80. uint8_t magCal = effective_magCal();
  81. bool magCalRequested =
  82. ((magCal == 0) && inFlight) || // when flying
  83. ((magCal == 1) && manoeuvring) || // when manoeuvring
  84. ((magCal == 3) && finalInflightYawInit && finalInflightMagInit) || // when initial in-air yaw and mag field reset is complete
  85. (magCal == 4); // all the time
  86. // Deny mag calibration request if we aren't using the compass, it has been inhibited by the user,
  87. // we do not have an absolute position reference or are on the ground (unless explicitly requested by the user)
  88. bool magCalDenied = !use_compass() || (magCal == 2) || (onGround && magCal != 4);
  89. // Inhibit the magnetic field calibration if not requested or denied
  90. bool setMagInhibit = !magCalRequested || magCalDenied;
  91. if (!inhibitMagStates && setMagInhibit) {
  92. inhibitMagStates = true;
  93. } else if (inhibitMagStates && !setMagInhibit) {
  94. inhibitMagStates = false;
  95. if (magFieldLearned) {
  96. // if we have already learned the field states, then retain the learned variances
  97. P[16][16] = earthMagFieldVar.x;
  98. P[17][17] = earthMagFieldVar.y;
  99. P[18][18] = earthMagFieldVar.z;
  100. P[19][19] = bodyMagFieldVar.x;
  101. P[20][20] = bodyMagFieldVar.y;
  102. P[21][21] = bodyMagFieldVar.z;
  103. } else {
  104. // set the variances equal to the observation variances
  105. for (uint8_t index=18; index<=21; index++) {
  106. P[index][index] = sq(frontend->_magNoise);
  107. }
  108. // set the NE earth magnetic field states using the published declination
  109. // and set the corresponding variances and covariances
  110. alignMagStateDeclination();
  111. }
  112. // request a reset of the yaw and magnetic field states if not done before
  113. if (!magStateInitComplete || (!finalInflightMagInit && inFlight)) {
  114. magYawResetRequest = true;
  115. }
  116. }
  117. // If on ground we clear the flag indicating that the magnetic field in-flight initialisation has been completed
  118. // because we want it re-done for each takeoff
  119. if (onGround) {
  120. finalInflightYawInit = false;
  121. finalInflightMagInit = false;
  122. }
  123. // Adjust the indexing limits used to address the covariance, states and other EKF arrays to avoid unnecessary operations
  124. // if we are not using those states
  125. if (inhibitMagStates && inhibitWindStates) {
  126. stateIndexLim = 15;
  127. } else if (inhibitWindStates) {
  128. stateIndexLim = 21;
  129. } else {
  130. stateIndexLim = 23;
  131. }
  132. }
  133. // Set inertial navigation aiding mode
  134. void NavEKF2_core::setAidingMode()
  135. {
  136. // Save the previous status so we can detect when it has changed
  137. PV_AidingModePrev = PV_AidingMode;
  138. // Determine if we should change aiding mode
  139. switch (PV_AidingMode) {
  140. case AID_NONE: {
  141. // Don't allow filter to start position or velocity aiding until the tilt and yaw alignment is complete
  142. // and IMU gyro bias estimates have stabilised
  143. bool filterIsStable = tiltAlignComplete && yawAlignComplete && checkGyroCalStatus();
  144. // If GPS usage has been prohiited then we use flow aiding provided optical flow data is present
  145. // GPS aiding is the preferred option unless excluded by the user
  146. bool canUseGPS = ((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && filterIsStable && !gpsInhibit);
  147. bool canUseRangeBeacon = readyToUseRangeBeacon() && filterIsStable;
  148. bool canUseExtNav = readyToUseExtNav();
  149. if(canUseGPS || canUseRangeBeacon || canUseExtNav) {
  150. PV_AidingMode = AID_ABSOLUTE;
  151. } else if (optFlowDataPresent() && (frontend->_flowUse == FLOW_USE_NAV) && filterIsStable) {
  152. PV_AidingMode = AID_RELATIVE;
  153. }
  154. }
  155. break;
  156. case AID_RELATIVE: {
  157. // Check if the optical flow sensor has timed out
  158. bool flowSensorTimeout = ((imuSampleTime_ms - flowValidMeaTime_ms) > 5000);
  159. // Check if the fusion has timed out (flow measurements have been rejected for too long)
  160. bool flowFusionTimeout = ((imuSampleTime_ms - prevFlowFuseTime_ms) > 5000);
  161. // Enable switch to absolute position mode if GPS is available
  162. // If GPS is not available and flow fusion has timed out, then fall-back to no-aiding
  163. if((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && !gpsInhibit) {
  164. PV_AidingMode = AID_ABSOLUTE;
  165. } else if (flowSensorTimeout || flowFusionTimeout) {
  166. PV_AidingMode = AID_NONE;
  167. }
  168. }
  169. break;
  170. case AID_ABSOLUTE: {
  171. // Find the minimum time without data required to trigger any check
  172. uint16_t minTestTime_ms = MIN(frontend->tiltDriftTimeMax_ms, MIN(frontend->posRetryTimeNoVel_ms,frontend->posRetryTimeUseVel_ms));
  173. // Check if optical flow data is being used
  174. bool optFlowUsed = (imuSampleTime_ms - prevFlowFuseTime_ms <= minTestTime_ms);
  175. // Check if airspeed data is being used
  176. bool airSpdUsed = (imuSampleTime_ms - lastTasPassTime_ms <= minTestTime_ms);
  177. // Check if range beacon data is being used
  178. bool rngBcnUsed = (imuSampleTime_ms - lastRngBcnPassTime_ms <= minTestTime_ms);
  179. // Check if GPS is being used
  180. bool posUsed = (imuSampleTime_ms - lastPosPassTime_ms <= minTestTime_ms);
  181. bool gpsVelUsed = (imuSampleTime_ms - lastVelPassTime_ms <= minTestTime_ms);
  182. // Check if attitude drift has been constrained by a measurement source
  183. bool attAiding = posUsed || gpsVelUsed || optFlowUsed || airSpdUsed || rngBcnUsed;
  184. // check if velocity drift has been constrained by a measurement source
  185. bool velAiding = gpsVelUsed || airSpdUsed || optFlowUsed;
  186. // check if position drift has been constrained by a measurement source
  187. bool posAiding = posUsed || rngBcnUsed;
  188. // Check if the loss of attitude aiding has become critical
  189. bool attAidLossCritical = false;
  190. if (!attAiding) {
  191. attAidLossCritical = (imuSampleTime_ms - prevFlowFuseTime_ms > frontend->tiltDriftTimeMax_ms) &&
  192. (imuSampleTime_ms - lastTasPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
  193. (imuSampleTime_ms - lastRngBcnPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
  194. (imuSampleTime_ms - lastPosPassTime_ms > frontend->tiltDriftTimeMax_ms) &&
  195. (imuSampleTime_ms - lastVelPassTime_ms > frontend->tiltDriftTimeMax_ms);
  196. }
  197. // Check if the loss of position accuracy has become critical
  198. bool posAidLossCritical = false;
  199. if (!posAiding ) {
  200. uint16_t maxLossTime_ms;
  201. if (!velAiding) {
  202. maxLossTime_ms = frontend->posRetryTimeNoVel_ms;
  203. } else {
  204. maxLossTime_ms = frontend->posRetryTimeUseVel_ms;
  205. }
  206. posAidLossCritical = (imuSampleTime_ms - lastRngBcnPassTime_ms > maxLossTime_ms) &&
  207. (imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
  208. }
  209. if (attAidLossCritical) {
  210. // if the loss of attitude data is critical, then put the filter into a constant position mode
  211. PV_AidingMode = AID_NONE;
  212. posTimeout = true;
  213. velTimeout = true;
  214. rngBcnTimeout = true;
  215. tasTimeout = true;
  216. gpsNotAvailable = true;
  217. } else if (posAidLossCritical) {
  218. // if the loss of position is critical, declare all sources of position aiding as being timed out
  219. posTimeout = true;
  220. velTimeout = true;
  221. rngBcnTimeout = true;
  222. gpsNotAvailable = true;
  223. }
  224. break;
  225. }
  226. }
  227. // check to see if we are starting or stopping aiding and set states and modes as required
  228. if (PV_AidingMode != PV_AidingModePrev) {
  229. // set various usage modes based on the condition when we start aiding. These are then held until aiding is stopped.
  230. switch (PV_AidingMode) {
  231. case AID_NONE:
  232. // We have ceased aiding
  233. gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u has stopped aiding",(unsigned)imu_index);
  234. // When not aiding, estimate orientation & height fusing synthetic constant position and zero velocity measurement to constrain tilt errors
  235. posTimeout = true;
  236. velTimeout = true;
  237. // Reset the normalised innovation to avoid false failing bad fusion tests
  238. velTestRatio = 0.0f;
  239. posTestRatio = 0.0f;
  240. // store the current position to be used to keep reporting the last known position
  241. lastKnownPositionNE.x = stateStruct.position.x;
  242. lastKnownPositionNE.y = stateStruct.position.y;
  243. // initialise filtered altitude used to provide a takeoff reference to current baro on disarm
  244. // this reduces the time required for the baro noise filter to settle before the filtered baro data can be used
  245. meaHgtAtTakeOff = baroDataDelayed.hgt;
  246. // reset the vertical position state to faster recover from baro errors experienced during touchdown
  247. stateStruct.position.z = -meaHgtAtTakeOff;
  248. break;
  249. case AID_RELATIVE:
  250. // We have commenced aiding, but GPS usage has been prohibited so use optical flow only
  251. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using optical flow",(unsigned)imu_index);
  252. posTimeout = true;
  253. velTimeout = true;
  254. // Reset the last valid flow measurement time
  255. flowValidMeaTime_ms = imuSampleTime_ms;
  256. // Reset the last valid flow fusion time
  257. prevFlowFuseTime_ms = imuSampleTime_ms;
  258. break;
  259. case AID_ABSOLUTE: {
  260. bool canUseGPS = ((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && !gpsInhibit);
  261. bool canUseRangeBeacon = readyToUseRangeBeacon();
  262. bool canUseExtNav = readyToUseExtNav();
  263. // We have commenced aiding and GPS usage is allowed
  264. if (canUseGPS) {
  265. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using GPS",(unsigned)imu_index);
  266. }
  267. posTimeout = false;
  268. velTimeout = false;
  269. // We have commenced aiding and range beacon usage is allowed
  270. if (canUseRangeBeacon) {
  271. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using range beacons",(unsigned)imu_index);
  272. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial pos NE = %3.1f,%3.1f (m)",(unsigned)imu_index,(double)receiverPos.x,(double)receiverPos.y);
  273. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial beacon pos D offset = %3.1f (m)",(unsigned)imu_index,(double)bcnPosOffset);
  274. }
  275. // We have commenced aiding and external nav usage is allowed
  276. if (canUseExtNav) {
  277. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using external nav data",(unsigned)imu_index);
  278. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial pos NED = %3.1f,%3.1f,%3.1f (m)",(unsigned)imu_index,(double)extNavDataDelayed.pos.x,(double)extNavDataDelayed.pos.y,(double)extNavDataDelayed.pos.z);
  279. // handle yaw reset as special case
  280. extNavYawResetRequest = true;
  281. controlMagYawReset();
  282. // handle height reset as special case
  283. hgtMea = -extNavDataDelayed.pos.z;
  284. posDownObsNoise = sq(constrain_float(extNavDataDelayed.posErr, 0.1f, 10.0f));
  285. ResetHeight();
  286. }
  287. // reset the last fusion accepted times to prevent unwanted activation of timeout logic
  288. lastPosPassTime_ms = imuSampleTime_ms;
  289. lastVelPassTime_ms = imuSampleTime_ms;
  290. lastRngBcnPassTime_ms = imuSampleTime_ms;
  291. }
  292. break;
  293. }
  294. // Always reset the position and velocity when changing mode
  295. ResetVelocity();
  296. ResetPosition();
  297. }
  298. }
  299. // Check the tilt and yaw alignmnent status
  300. // Used during initial bootstrap alignment of the filter
  301. void NavEKF2_core::checkAttitudeAlignmentStatus()
  302. {
  303. // Check for tilt convergence - used during initial alignment
  304. float alpha = 1.0f*imuDataDelayed.delAngDT;
  305. float temp=tiltErrVec.length();
  306. tiltErrFilt = alpha*temp + (1.0f-alpha)*tiltErrFilt;
  307. if (tiltErrFilt < 0.005f && !tiltAlignComplete) {
  308. tiltAlignComplete = true;
  309. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u tilt alignment complete",(unsigned)imu_index);
  310. }
  311. // submit yaw and magnetic field reset requests depending on whether we have compass data
  312. if (tiltAlignComplete && !yawAlignComplete) {
  313. if (use_compass()) {
  314. magYawResetRequest = true;
  315. gpsYawResetRequest = false;
  316. } else {
  317. magYawResetRequest = false;
  318. gpsYawResetRequest = true;
  319. }
  320. }
  321. }
  322. // return true if we should use the airspeed sensor
  323. bool NavEKF2_core::useAirspeed(void) const
  324. {
  325. return _ahrs->airspeed_sensor_enabled();
  326. }
  327. // return true if we should use the range finder sensor
  328. bool NavEKF2_core::useRngFinder(void) const
  329. {
  330. // TO-DO add code to set this based in setting of optical flow use parameter and presence of sensor
  331. return true;
  332. }
  333. // return true if optical flow data is available
  334. bool NavEKF2_core::optFlowDataPresent(void) const
  335. {
  336. return (imuSampleTime_ms - flowMeaTime_ms < 200);
  337. }
  338. // return true if the filter to be ready to use gps
  339. bool NavEKF2_core::readyToUseGPS(void) const
  340. {
  341. return validOrigin && tiltAlignComplete && yawAlignComplete && gpsGoodToAlign && (frontend->_fusionModeGPS != 3) && gpsDataToFuse;
  342. }
  343. // return true if the filter to be ready to use the beacon range measurements
  344. bool NavEKF2_core::readyToUseRangeBeacon(void) const
  345. {
  346. return tiltAlignComplete && yawAlignComplete && rngBcnGoodToAlign && rngBcnDataToFuse;
  347. }
  348. // return true if the filter to be ready to use external nav data
  349. bool NavEKF2_core::readyToUseExtNav(void) const
  350. {
  351. return tiltAlignComplete && extNavDataToFuse;
  352. }
  353. // return true if we should use the compass
  354. bool NavEKF2_core::use_compass(void) const
  355. {
  356. return _ahrs->get_compass() && _ahrs->get_compass()->use_for_yaw(magSelectIndex) && !allMagSensorsFailed;
  357. }
  358. /*
  359. should we assume zero sideslip?
  360. */
  361. bool NavEKF2_core::assume_zero_sideslip(void) const
  362. {
  363. // we don't assume zero sideslip for ground vehicles as EKF could
  364. // be quite sensitive to a rapid spin of the ground vehicle if
  365. // traction is lost
  366. return _ahrs->get_fly_forward() && _ahrs->get_vehicle_class() != AHRS_VEHICLE_GROUND;
  367. }
  368. // set the LLH location of the filters NED origin
  369. bool NavEKF2_core::setOriginLLH(const Location &loc)
  370. {
  371. if (PV_AidingMode == AID_ABSOLUTE && !extNavUsedForPos) {
  372. return false;
  373. }
  374. EKF_origin = loc;
  375. ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
  376. // define Earth rotation vector in the NED navigation frame at the origin
  377. calcEarthRateNED(earthRateNED, loc.lat);
  378. validOrigin = true;
  379. return true;
  380. }
  381. // Set the NED origin to be used until the next filter reset
  382. void NavEKF2_core::setOrigin(const Location &loc)
  383. {
  384. EKF_origin = loc;
  385. // if flying, correct for height change from takeoff so that the origin is at field elevation
  386. if (inFlight) {
  387. EKF_origin.alt += (int32_t)(100.0f * stateStruct.position.z);
  388. }
  389. ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
  390. // define Earth rotation vector in the NED navigation frame at the origin
  391. calcEarthRateNED(earthRateNED, EKF_origin.lat);
  392. validOrigin = true;
  393. gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u origin set",(unsigned)imu_index);
  394. // put origin in frontend as well to ensure it stays in sync between lanes
  395. frontend->common_EKF_origin = EKF_origin;
  396. frontend->common_origin_valid = true;
  397. }
  398. // record a yaw reset event
  399. void NavEKF2_core::recordYawReset()
  400. {
  401. yawAlignComplete = true;
  402. if (inFlight) {
  403. finalInflightYawInit = true;
  404. }
  405. }
  406. // return true and set the class variable true if the delta angle bias has been learned
  407. bool NavEKF2_core::checkGyroCalStatus(void)
  408. {
  409. // check delta angle bias variances
  410. const float delAngBiasVarMax = sq(radians(0.15f * dtEkfAvg));
  411. delAngBiasLearned = (P[9][9] <= delAngBiasVarMax) &&
  412. (P[10][10] <= delAngBiasVarMax) &&
  413. (P[11][11] <= delAngBiasVarMax);
  414. return delAngBiasLearned;
  415. }
  416. // Commands the EKF to not use GPS.
  417. // This command must be sent prior to arming
  418. // This command is forgotten by the EKF each time the vehicle disarms
  419. // Returns 0 if command rejected
  420. // Returns 1 if attitude, vertical velocity and vertical position will be provided
  421. // Returns 2 if attitude, 3D-velocity, vertical position and relative horizontal position will be provided
  422. uint8_t NavEKF2_core::setInhibitGPS(void)
  423. {
  424. if((PV_AidingMode == AID_ABSOLUTE) && motorsArmed) {
  425. return 0;
  426. } else {
  427. gpsInhibit = true;
  428. return 1;
  429. }
  430. // option 2 is not yet implemented as it requires a deeper integration of optical flow and GPS operation
  431. }
  432. // Update the filter status
  433. void NavEKF2_core::updateFilterStatus(void)
  434. {
  435. // init return value
  436. filterStatus.value = 0;
  437. bool doingFlowNav = (PV_AidingMode == AID_RELATIVE) && flowDataValid;
  438. bool doingWindRelNav = !tasTimeout && assume_zero_sideslip();
  439. bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE);
  440. bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout;
  441. bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
  442. bool optFlowNavPossible = flowDataValid && delAngBiasLearned;
  443. bool gpsNavPossible = !gpsNotAvailable && gpsGoodToAlign && delAngBiasLearned;
  444. bool filterHealthy = healthy() && tiltAlignComplete && (yawAlignComplete || (!use_compass() && (PV_AidingMode == AID_NONE)));
  445. // If GPS height usage is specified, height is considered to be inaccurate until the GPS passes all checks
  446. bool hgtNotAccurate = (frontend->_altSource == 2) && !validOrigin;
  447. // set individual flags
  448. filterStatus.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check)
  449. filterStatus.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid
  450. filterStatus.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid
  451. filterStatus.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav) && filterHealthy; // relative horizontal position estimate valid
  452. filterStatus.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid
  453. filterStatus.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid
  454. filterStatus.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid
  455. filterStatus.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode
  456. filterStatus.flags.pred_horiz_pos_rel = ((optFlowNavPossible || gpsNavPossible) && filterHealthy) || filterStatus.flags.horiz_pos_rel; // we should be able to estimate a relative position when we enter flight mode
  457. filterStatus.flags.pred_horiz_pos_abs = (gpsNavPossible && filterHealthy) || filterStatus.flags.horiz_pos_abs; // we should be able to estimate an absolute position when we enter flight mode
  458. filterStatus.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
  459. filterStatus.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
  460. filterStatus.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
  461. filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE);
  462. filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && !extNavUsedForPos; // GPS glitching is affecting navigation accuracy
  463. filterStatus.flags.gps_quality_good = gpsGoodToAlign;
  464. }