AP_NavEKF3_Control.cpp 25 KB

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