AP_NavEKF2_PosVelFusion.cpp 45 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974
  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 <AP_RangeFinder/RangeFinder_Backend.h>
  7. #include <AP_GPS/AP_GPS.h>
  8. #include <AP_Baro/AP_Baro.h>
  9. #include <stdio.h>
  10. extern const AP_HAL::HAL& hal;
  11. /********************************************************
  12. * RESET FUNCTIONS *
  13. ********************************************************/
  14. // Reset velocity states to last GPS measurement if available or to zero if in constant position mode or if PV aiding is not absolute
  15. // Do not reset vertical velocity using GPS as there is baro alt available to constrain drift
  16. void NavEKF2_core::ResetVelocity(void)
  17. {
  18. // Store the position before the reset so that we can record the reset delta
  19. velResetNE.x = stateStruct.velocity.x;
  20. velResetNE.y = stateStruct.velocity.y;
  21. // reset the corresponding covariances
  22. zeroRows(P,3,4);
  23. zeroCols(P,3,4);
  24. if (PV_AidingMode != AID_ABSOLUTE) {
  25. stateStruct.velocity.zero();
  26. // set the variances using the measurement noise parameter
  27. P[4][4] = P[3][3] = sq(frontend->_gpsHorizVelNoise);
  28. } else {
  29. // reset horizontal velocity states to the GPS velocity if available
  30. if (imuSampleTime_ms - lastTimeGpsReceived_ms < 250) {
  31. stateStruct.velocity.x = gpsDataNew.vel.x;
  32. stateStruct.velocity.y = gpsDataNew.vel.y;
  33. // set the variances using the reported GPS speed accuracy
  34. P[4][4] = P[3][3] = sq(MAX(frontend->_gpsHorizVelNoise,gpsSpdAccuracy));
  35. // clear the timeout flags and counters
  36. velTimeout = false;
  37. lastVelPassTime_ms = imuSampleTime_ms;
  38. } else {
  39. stateStruct.velocity.x = 0.0f;
  40. stateStruct.velocity.y = 0.0f;
  41. // set the variances using the likely speed range
  42. P[4][4] = P[3][3] = sq(25.0f);
  43. // clear the timeout flags and counters
  44. velTimeout = false;
  45. lastVelPassTime_ms = imuSampleTime_ms;
  46. }
  47. }
  48. for (uint8_t i=0; i<imu_buffer_length; i++) {
  49. storedOutput[i].velocity.x = stateStruct.velocity.x;
  50. storedOutput[i].velocity.y = stateStruct.velocity.y;
  51. }
  52. outputDataNew.velocity.x = stateStruct.velocity.x;
  53. outputDataNew.velocity.y = stateStruct.velocity.y;
  54. outputDataDelayed.velocity.x = stateStruct.velocity.x;
  55. outputDataDelayed.velocity.y = stateStruct.velocity.y;
  56. // Calculate the position jump due to the reset
  57. velResetNE.x = stateStruct.velocity.x - velResetNE.x;
  58. velResetNE.y = stateStruct.velocity.y - velResetNE.y;
  59. // store the time of the reset
  60. lastVelReset_ms = imuSampleTime_ms;
  61. }
  62. // resets position states to last GPS measurement or to zero if in constant position mode
  63. void NavEKF2_core::ResetPosition(void)
  64. {
  65. // Store the position before the reset so that we can record the reset delta
  66. posResetNE.x = stateStruct.position.x;
  67. posResetNE.y = stateStruct.position.y;
  68. // reset the corresponding covariances
  69. zeroRows(P,6,7);
  70. zeroCols(P,6,7);
  71. if (PV_AidingMode != AID_ABSOLUTE) {
  72. // reset all position state history to the last known position
  73. stateStruct.position.x = lastKnownPositionNE.x;
  74. stateStruct.position.y = lastKnownPositionNE.y;
  75. // set the variances using the position measurement noise parameter
  76. P[6][6] = P[7][7] = sq(frontend->_gpsHorizPosNoise);
  77. } else {
  78. // Use GPS data as first preference if fresh data is available
  79. if (imuSampleTime_ms - lastTimeGpsReceived_ms < 250) {
  80. // record the ID of the GPS for the data we are using for the reset
  81. last_gps_idx = gpsDataNew.sensor_idx;
  82. // write to state vector and compensate for offset between last GPS measurement and the EKF time horizon
  83. stateStruct.position.x = gpsDataNew.pos.x + 0.001f*gpsDataNew.vel.x*(float(imuDataDelayed.time_ms) - float(gpsDataNew.time_ms));
  84. stateStruct.position.y = gpsDataNew.pos.y + 0.001f*gpsDataNew.vel.y*(float(imuDataDelayed.time_ms) - float(gpsDataNew.time_ms));
  85. // set the variances using the position measurement noise parameter
  86. P[6][6] = P[7][7] = sq(MAX(gpsPosAccuracy,frontend->_gpsHorizPosNoise));
  87. // clear the timeout flags and counters
  88. posTimeout = false;
  89. lastPosPassTime_ms = imuSampleTime_ms;
  90. } else if (imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250) {
  91. // use the range beacon data as a second preference
  92. stateStruct.position.x = receiverPos.x;
  93. stateStruct.position.y = receiverPos.y;
  94. // set the variances from the beacon alignment filter
  95. P[6][6] = receiverPosCov[0][0];
  96. P[7][7] = receiverPosCov[1][1];
  97. // clear the timeout flags and counters
  98. rngBcnTimeout = false;
  99. lastRngBcnPassTime_ms = imuSampleTime_ms;
  100. } else if (imuSampleTime_ms - extNavDataDelayed.time_ms < 250) {
  101. // use the range beacon data as a second preference
  102. stateStruct.position.x = extNavDataDelayed.pos.x;
  103. stateStruct.position.y = extNavDataDelayed.pos.y;
  104. // set the variances from the beacon alignment filter
  105. P[7][7] = P[6][6] = sq(extNavDataDelayed.posErr);
  106. }
  107. }
  108. for (uint8_t i=0; i<imu_buffer_length; i++) {
  109. storedOutput[i].position.x = stateStruct.position.x;
  110. storedOutput[i].position.y = stateStruct.position.y;
  111. }
  112. outputDataNew.position.x = stateStruct.position.x;
  113. outputDataNew.position.y = stateStruct.position.y;
  114. outputDataDelayed.position.x = stateStruct.position.x;
  115. outputDataDelayed.position.y = stateStruct.position.y;
  116. // Calculate the position jump due to the reset
  117. posResetNE.x = stateStruct.position.x - posResetNE.x;
  118. posResetNE.y = stateStruct.position.y - posResetNE.y;
  119. // store the time of the reset
  120. lastPosReset_ms = imuSampleTime_ms;
  121. }
  122. // reset the vertical position state using the last height measurement
  123. void NavEKF2_core::ResetHeight(void)
  124. {
  125. // Store the position before the reset so that we can record the reset delta
  126. posResetD = stateStruct.position.z;
  127. // write to the state vector
  128. stateStruct.position.z = -hgtMea;
  129. outputDataNew.position.z = stateStruct.position.z;
  130. outputDataDelayed.position.z = stateStruct.position.z;
  131. // reset the terrain state height
  132. if (onGround) {
  133. // assume vehicle is sitting on the ground
  134. terrainState = stateStruct.position.z + rngOnGnd;
  135. } else {
  136. // can make no assumption other than vehicle is not below ground level
  137. terrainState = MAX(stateStruct.position.z + rngOnGnd , terrainState);
  138. }
  139. for (uint8_t i=0; i<imu_buffer_length; i++) {
  140. storedOutput[i].position.z = stateStruct.position.z;
  141. }
  142. // Calculate the position jump due to the reset
  143. posResetD = stateStruct.position.z - posResetD;
  144. // store the time of the reset
  145. lastPosResetD_ms = imuSampleTime_ms;
  146. // clear the timeout flags and counters
  147. hgtTimeout = false;
  148. lastHgtPassTime_ms = imuSampleTime_ms;
  149. // reset the corresponding covariances
  150. zeroRows(P,8,8);
  151. zeroCols(P,8,8);
  152. // set the variances to the measurement variance
  153. P[8][8] = posDownObsNoise;
  154. // Reset the vertical velocity state using GPS vertical velocity if we are airborne
  155. // Check that GPS vertical velocity data is available and can be used
  156. if (inFlight && !gpsNotAvailable && frontend->_fusionModeGPS == 0 && !frontend->inhibitGpsVertVelUse) {
  157. stateStruct.velocity.z = gpsDataNew.vel.z;
  158. } else if (onGround) {
  159. stateStruct.velocity.z = 0.0f;
  160. }
  161. for (uint8_t i=0; i<imu_buffer_length; i++) {
  162. storedOutput[i].velocity.z = stateStruct.velocity.z;
  163. }
  164. outputDataNew.velocity.z = stateStruct.velocity.z;
  165. outputDataDelayed.velocity.z = stateStruct.velocity.z;
  166. // reset the corresponding covariances
  167. zeroRows(P,5,5);
  168. zeroCols(P,5,5);
  169. // set the variances to the measurement variance
  170. P[5][5] = sq(frontend->_gpsVertVelNoise);
  171. }
  172. // Zero the EKF height datum
  173. // Return true if the height datum reset has been performed
  174. bool NavEKF2_core::resetHeightDatum(void)
  175. {
  176. if (activeHgtSource == HGT_SOURCE_RNG || !onGround) {
  177. // only allow resets when on the ground.
  178. // If using using rangefinder for height then never perform a
  179. // reset of the height datum
  180. return false;
  181. }
  182. // record the old height estimate
  183. float oldHgt = -stateStruct.position.z;
  184. // reset the barometer so that it reads zero at the current height
  185. AP::baro().update_calibration();
  186. // reset the height state
  187. stateStruct.position.z = 0.0f;
  188. // adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
  189. if (validOrigin) {
  190. if (!gpsGoodToAlign) {
  191. // if we don't have GPS lock then we shouldn't be doing a
  192. // resetHeightDatum, but if we do then the best option is
  193. // to maintain the old error
  194. EKF_origin.alt += (int32_t)(100.0f * oldHgt);
  195. } else {
  196. // if we have a good GPS lock then reset to the GPS
  197. // altitude. This ensures the reported AMSL alt from
  198. // getLLH() is equal to GPS altitude, while also ensuring
  199. // that the relative alt is zero
  200. EKF_origin.alt = AP::gps().location().alt;
  201. }
  202. ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
  203. }
  204. // set the terrain state to zero (on ground). The adjustment for
  205. // frame height will get added in the later constraints
  206. terrainState = 0;
  207. return true;
  208. }
  209. /********************************************************
  210. * FUSE MEASURED_DATA *
  211. ********************************************************/
  212. // select fusion of velocity, position and height measurements
  213. void NavEKF2_core::SelectVelPosFusion()
  214. {
  215. // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
  216. // If so, don't fuse measurements on this time step to reduce frame over-runs
  217. // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
  218. if (magFusePerformed && dtIMUavg < 0.005f && !posVelFusionDelayed) {
  219. posVelFusionDelayed = true;
  220. return;
  221. } else {
  222. posVelFusionDelayed = false;
  223. }
  224. // Check for data at the fusion time horizon
  225. extNavDataToFuse = storedExtNav.recall(extNavDataDelayed, imuDataDelayed.time_ms);
  226. // read GPS data from the sensor and check for new data in the buffer
  227. readGpsData();
  228. gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms);
  229. // Determine if we need to fuse position and velocity data on this time step
  230. if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE) {
  231. // set fusion request flags
  232. if (frontend->_fusionModeGPS <= 1) {
  233. fuseVelData = true;
  234. } else {
  235. fuseVelData = false;
  236. }
  237. fusePosData = true;
  238. extNavUsedForPos = false;
  239. // correct GPS data for position offset of antenna phase centre relative to the IMU
  240. Vector3f posOffsetBody = AP::gps().get_antenna_offset(gpsDataDelayed.sensor_idx) - accelPosOffset;
  241. if (!posOffsetBody.is_zero()) {
  242. // Don't fuse velocity data if GPS doesn't support it
  243. if (fuseVelData) {
  244. // TODO use a filtered angular rate with a group delay that matches the GPS delay
  245. Vector3f angRate = imuDataDelayed.delAng * (1.0f/imuDataDelayed.delAngDT);
  246. Vector3f velOffsetBody = angRate % posOffsetBody;
  247. Vector3f velOffsetEarth = prevTnb.mul_transpose(velOffsetBody);
  248. gpsDataDelayed.vel.x -= velOffsetEarth.x;
  249. gpsDataDelayed.vel.y -= velOffsetEarth.y;
  250. gpsDataDelayed.vel.z -= velOffsetEarth.z;
  251. }
  252. Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
  253. gpsDataDelayed.pos.x -= posOffsetEarth.x;
  254. gpsDataDelayed.pos.y -= posOffsetEarth.y;
  255. gpsDataDelayed.hgt += posOffsetEarth.z;
  256. }
  257. // copy corrected GPS data to observation vector
  258. if (fuseVelData) {
  259. velPosObs[0] = gpsDataDelayed.vel.x;
  260. velPosObs[1] = gpsDataDelayed.vel.y;
  261. velPosObs[2] = gpsDataDelayed.vel.z;
  262. }
  263. velPosObs[3] = gpsDataDelayed.pos.x;
  264. velPosObs[4] = gpsDataDelayed.pos.y;
  265. } else if (extNavDataToFuse && PV_AidingMode == AID_ABSOLUTE) {
  266. // This is a special case that uses and external nav system for position
  267. extNavUsedForPos = true;
  268. activeHgtSource = HGT_SOURCE_EV;
  269. fuseVelData = false;
  270. fuseHgtData = true;
  271. fusePosData = true;
  272. velPosObs[3] = extNavDataDelayed.pos.x;
  273. velPosObs[4] = extNavDataDelayed.pos.y;
  274. velPosObs[5] = extNavDataDelayed.pos.z;
  275. // if compass is disabled, also use it for yaw
  276. if (!use_compass()) {
  277. extNavUsedForYaw = true;
  278. if (!yawAlignComplete) {
  279. extNavYawResetRequest = true;
  280. magYawResetRequest = false;
  281. gpsYawResetRequest = false;
  282. controlMagYawReset();
  283. finalInflightYawInit = true;
  284. } else {
  285. fuseEulerYaw();
  286. }
  287. } else {
  288. extNavUsedForYaw = false;
  289. }
  290. } else {
  291. fuseVelData = false;
  292. fusePosData = false;
  293. }
  294. // we have GPS data to fuse and a request to align the yaw using the GPS course
  295. if (gpsYawResetRequest) {
  296. realignYawGPS();
  297. }
  298. // Select height data to be fused from the available baro, range finder and GPS sources
  299. selectHeightForFusion();
  300. // if we are using GPS, check for a change in receiver and reset position and height
  301. if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE && gpsDataDelayed.sensor_idx != last_gps_idx) {
  302. // record the ID of the GPS that we are using for the reset
  303. last_gps_idx = gpsDataDelayed.sensor_idx;
  304. // Store the position before the reset so that we can record the reset delta
  305. posResetNE.x = stateStruct.position.x;
  306. posResetNE.y = stateStruct.position.y;
  307. // Set the position states to the position from the new GPS
  308. stateStruct.position.x = gpsDataNew.pos.x;
  309. stateStruct.position.y = gpsDataNew.pos.y;
  310. // Calculate the position offset due to the reset
  311. posResetNE.x = stateStruct.position.x - posResetNE.x;
  312. posResetNE.y = stateStruct.position.y - posResetNE.y;
  313. // Add the offset to the output observer states
  314. for (uint8_t i=0; i<imu_buffer_length; i++) {
  315. storedOutput[i].position.x += posResetNE.x;
  316. storedOutput[i].position.y += posResetNE.y;
  317. }
  318. outputDataNew.position.x += posResetNE.x;
  319. outputDataNew.position.y += posResetNE.y;
  320. outputDataDelayed.position.x += posResetNE.x;
  321. outputDataDelayed.position.y += posResetNE.y;
  322. // store the time of the reset
  323. lastPosReset_ms = imuSampleTime_ms;
  324. // If we are also using GPS as the height reference, reset the height
  325. if (activeHgtSource == HGT_SOURCE_GPS) {
  326. // Store the position before the reset so that we can record the reset delta
  327. posResetD = stateStruct.position.z;
  328. // write to the state vector
  329. stateStruct.position.z = -hgtMea;
  330. // Calculate the position jump due to the reset
  331. posResetD = stateStruct.position.z - posResetD;
  332. // Add the offset to the output observer states
  333. outputDataNew.position.z += posResetD;
  334. outputDataDelayed.position.z += posResetD;
  335. for (uint8_t i=0; i<imu_buffer_length; i++) {
  336. storedOutput[i].position.z += posResetD;
  337. }
  338. // store the time of the reset
  339. lastPosResetD_ms = imuSampleTime_ms;
  340. }
  341. }
  342. // If we are operating without any aiding, fuse in the last known position
  343. // to constrain tilt drift. This assumes a non-manoeuvring vehicle
  344. // Do this to coincide with the height fusion
  345. if (fuseHgtData && PV_AidingMode == AID_NONE) {
  346. velPosObs[3] = lastKnownPositionNE.x;
  347. velPosObs[4] = lastKnownPositionNE.y;
  348. fusePosData = true;
  349. fuseVelData = false;
  350. }
  351. // perform fusion
  352. if (fuseVelData || fusePosData || fuseHgtData) {
  353. FuseVelPosNED();
  354. // clear the flags to prevent repeated fusion of the same data
  355. fuseVelData = false;
  356. fuseHgtData = false;
  357. fusePosData = false;
  358. }
  359. }
  360. // fuse selected position, velocity and height measurements
  361. void NavEKF2_core::FuseVelPosNED()
  362. {
  363. // start performance timer
  364. hal.util->perf_begin(_perf_FuseVelPosNED);
  365. // health is set bad until test passed
  366. velHealth = false;
  367. posHealth = false;
  368. hgtHealth = false;
  369. // declare variables used to check measurement errors
  370. Vector3f velInnov;
  371. // declare variables used to control access to arrays
  372. bool fuseData[6] = {false,false,false,false,false,false};
  373. uint8_t stateIndex;
  374. uint8_t obsIndex;
  375. // declare variables used by state and covariance update calculations
  376. Vector6 R_OBS; // Measurement variances used for fusion
  377. Vector6 R_OBS_DATA_CHECKS; // Measurement variances used for data checks only
  378. float SK;
  379. // perform sequential fusion of GPS measurements. This assumes that the
  380. // errors in the different velocity and position components are
  381. // uncorrelated which is not true, however in the absence of covariance
  382. // data from the GPS receiver it is the only assumption we can make
  383. // so we might as well take advantage of the computational efficiencies
  384. // associated with sequential fusion
  385. if (fuseVelData || fusePosData || fuseHgtData) {
  386. // calculate additional error in GPS position caused by manoeuvring
  387. float posErr = frontend->gpsPosVarAccScale * accNavMag;
  388. // estimate the GPS Velocity, GPS horiz position and height measurement variances.
  389. // Use different errors if operating without external aiding using an assumed position or velocity of zero
  390. if (PV_AidingMode == AID_NONE) {
  391. if (tiltAlignComplete && motorsArmed) {
  392. // This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate
  393. R_OBS[0] = sq(constrain_float(frontend->_noaidHorizNoise, 0.5f, 50.0f));
  394. } else {
  395. // Use a smaller value to give faster initial alignment
  396. R_OBS[0] = sq(0.5f);
  397. }
  398. R_OBS[1] = R_OBS[0];
  399. R_OBS[2] = R_OBS[0];
  400. R_OBS[3] = R_OBS[0];
  401. R_OBS[4] = R_OBS[0];
  402. for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
  403. } else {
  404. if (gpsSpdAccuracy > 0.0f) {
  405. // use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter
  406. R_OBS[0] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsHorizVelNoise, 50.0f));
  407. R_OBS[2] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsVertVelNoise, 50.0f));
  408. } else {
  409. // calculate additional error in GPS velocity caused by manoeuvring
  410. R_OBS[0] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
  411. R_OBS[2] = sq(constrain_float(frontend->_gpsVertVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsDVelVarAccScale * accNavMag);
  412. }
  413. R_OBS[1] = R_OBS[0];
  414. // Use GPS reported position accuracy if available and floor at value set by GPS position noise parameter
  415. if (gpsPosAccuracy > 0.0f) {
  416. R_OBS[3] = sq(constrain_float(gpsPosAccuracy, frontend->_gpsHorizPosNoise, 100.0f));
  417. } else if (extNavUsedForPos) {
  418. R_OBS[3] = sq(constrain_float(extNavDataDelayed.posErr, 0.01f, 10.0f));
  419. } else {
  420. R_OBS[3] = sq(constrain_float(frontend->_gpsHorizPosNoise, 0.1f, 10.0f)) + sq(posErr);
  421. }
  422. R_OBS[4] = R_OBS[3];
  423. // For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity
  424. // For horizontal GPS velocity we don't want the acceptance radius to increase with reported GPS accuracy so we use a value based on best GPS perfomrance
  425. // plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
  426. for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
  427. }
  428. R_OBS[5] = posDownObsNoise;
  429. for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
  430. // if vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
  431. // innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
  432. // the accelerometers and we should disable the GPS and barometer innovation consistency checks.
  433. if (useGpsVertVel && fuseVelData && (frontend->_altSource != 2)) {
  434. // calculate innovations for height and vertical GPS vel measurements
  435. float hgtErr = stateStruct.position.z - velPosObs[5];
  436. float velDErr = stateStruct.velocity.z - velPosObs[2];
  437. // check if they are the same sign and both more than 3-sigma out of bounds
  438. if ((hgtErr*velDErr > 0.0f) && (sq(hgtErr) > 9.0f * (P[8][8] + R_OBS_DATA_CHECKS[5])) && (sq(velDErr) > 9.0f * (P[5][5] + R_OBS_DATA_CHECKS[2]))) {
  439. badIMUdata = true;
  440. } else {
  441. badIMUdata = false;
  442. }
  443. }
  444. // calculate innovations and check GPS data validity using an innovation consistency check
  445. // test position measurements
  446. if (fusePosData) {
  447. // test horizontal position measurements
  448. innovVelPos[3] = stateStruct.position.x - velPosObs[3];
  449. innovVelPos[4] = stateStruct.position.y - velPosObs[4];
  450. varInnovVelPos[3] = P[6][6] + R_OBS_DATA_CHECKS[3];
  451. varInnovVelPos[4] = P[7][7] + R_OBS_DATA_CHECKS[4];
  452. // apply an innovation consistency threshold test, but don't fail if bad IMU data
  453. float maxPosInnov2 = sq(MAX(0.01f * (float)frontend->_gpsPosInnovGate, 1.0f))*(varInnovVelPos[3] + varInnovVelPos[4]);
  454. posTestRatio = (sq(innovVelPos[3]) + sq(innovVelPos[4])) / maxPosInnov2;
  455. posHealth = ((posTestRatio < 1.0f) || badIMUdata);
  456. // use position data if healthy or timed out
  457. if (PV_AidingMode == AID_NONE) {
  458. posHealth = true;
  459. lastPosPassTime_ms = imuSampleTime_ms;
  460. } else if (posHealth || posTimeout) {
  461. posHealth = true;
  462. lastPosPassTime_ms = imuSampleTime_ms;
  463. // if timed out or outside the specified uncertainty radius, reset to the GPS
  464. if (posTimeout || ((P[6][6] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
  465. // reset the position to the current GPS position
  466. ResetPosition();
  467. // reset the velocity to the GPS velocity
  468. ResetVelocity();
  469. // don't fuse GPS data on this time step
  470. fusePosData = false;
  471. fuseVelData = false;
  472. // Reset the position variances and corresponding covariances to a value that will pass the checks
  473. zeroRows(P,6,7);
  474. zeroCols(P,6,7);
  475. P[6][6] = sq(float(0.5f*frontend->_gpsGlitchRadiusMax));
  476. P[7][7] = P[6][6];
  477. // Reset the normalised innovation to avoid failing the bad fusion tests
  478. posTestRatio = 0.0f;
  479. velTestRatio = 0.0f;
  480. }
  481. } else {
  482. posHealth = false;
  483. }
  484. }
  485. // test velocity measurements
  486. if (fuseVelData) {
  487. // test velocity measurements
  488. uint8_t imax = 2;
  489. // Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data
  490. if (frontend->_fusionModeGPS > 0 || PV_AidingMode != AID_ABSOLUTE || frontend->inhibitGpsVertVelUse) {
  491. imax = 1;
  492. }
  493. float innovVelSumSq = 0; // sum of squares of velocity innovations
  494. float varVelSum = 0; // sum of velocity innovation variances
  495. for (uint8_t i = 0; i<=imax; i++) {
  496. // velocity states start at index 3
  497. stateIndex = i + 3;
  498. // calculate innovations using blended and single IMU predicted states
  499. velInnov[i] = stateStruct.velocity[i] - velPosObs[i]; // blended
  500. // calculate innovation variance
  501. varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS_DATA_CHECKS[i];
  502. // sum the innovation and innovation variances
  503. innovVelSumSq += sq(velInnov[i]);
  504. varVelSum += varInnovVelPos[i];
  505. }
  506. // apply an innovation consistency threshold test, but don't fail if bad IMU data
  507. // calculate the test ratio
  508. velTestRatio = innovVelSumSq / (varVelSum * sq(MAX(0.01f * (float)frontend->_gpsVelInnovGate, 1.0f)));
  509. // fail if the ratio is greater than 1
  510. velHealth = ((velTestRatio < 1.0f) || badIMUdata);
  511. // use velocity data if healthy, timed out, or in constant position mode
  512. if (velHealth || velTimeout) {
  513. velHealth = true;
  514. // restart the timeout count
  515. lastVelPassTime_ms = imuSampleTime_ms;
  516. // If we are doing full aiding and velocity fusion times out, reset to the GPS velocity
  517. if (PV_AidingMode == AID_ABSOLUTE && velTimeout) {
  518. // reset the velocity to the GPS velocity
  519. ResetVelocity();
  520. // don't fuse GPS velocity data on this time step
  521. fuseVelData = false;
  522. // Reset the normalised innovation to avoid failing the bad fusion tests
  523. velTestRatio = 0.0f;
  524. }
  525. } else {
  526. velHealth = false;
  527. }
  528. }
  529. // test height measurements
  530. if (fuseHgtData) {
  531. // calculate height innovations
  532. innovVelPos[5] = stateStruct.position.z - velPosObs[5];
  533. varInnovVelPos[5] = P[8][8] + R_OBS_DATA_CHECKS[5];
  534. // calculate the innovation consistency test ratio
  535. hgtTestRatio = sq(innovVelPos[5]) / (sq(MAX(0.01f * (float)frontend->_hgtInnovGate, 1.0f)) * varInnovVelPos[5]);
  536. // when on ground we accept a larger test ratio to allow
  537. // the filter to handle large switch on IMU bias errors
  538. // without rejecting the height sensor
  539. const float maxTestRatio = (PV_AidingMode == AID_NONE && onGround)? 3.0 : 1.0;
  540. // fail if the ratio is > maxTestRatio, but don't fail if bad IMU data
  541. hgtHealth = (hgtTestRatio < maxTestRatio) || badIMUdata;
  542. // Fuse height data if healthy or timed out or in constant position mode
  543. if (hgtHealth || hgtTimeout) {
  544. // Calculate a filtered value to be used by pre-flight health checks
  545. // We need to filter because wind gusts can generate significant baro noise and we want to be able to detect bias errors in the inertial solution
  546. if (onGround) {
  547. float dtBaro = (imuSampleTime_ms - lastHgtPassTime_ms)*1.0e-3f;
  548. const float hgtInnovFiltTC = 2.0f;
  549. float alpha = constrain_float(dtBaro/(dtBaro+hgtInnovFiltTC),0.0f,1.0f);
  550. hgtInnovFiltState += (innovVelPos[5]-hgtInnovFiltState)*alpha;
  551. } else {
  552. hgtInnovFiltState = 0.0f;
  553. }
  554. // if timed out, reset the height
  555. if (hgtTimeout) {
  556. ResetHeight();
  557. }
  558. // If we have got this far then declare the height data as healthy and reset the timeout counter
  559. hgtHealth = true;
  560. lastHgtPassTime_ms = imuSampleTime_ms;
  561. }
  562. }
  563. // set range for sequential fusion of velocity and position measurements depending on which data is available and its health
  564. if (fuseVelData && velHealth) {
  565. fuseData[0] = true;
  566. fuseData[1] = true;
  567. if (useGpsVertVel) {
  568. fuseData[2] = true;
  569. }
  570. tiltErrVec.zero();
  571. }
  572. if (fusePosData && posHealth) {
  573. fuseData[3] = true;
  574. fuseData[4] = true;
  575. tiltErrVec.zero();
  576. }
  577. if (fuseHgtData && hgtHealth) {
  578. fuseData[5] = true;
  579. }
  580. // fuse measurements sequentially
  581. for (obsIndex=0; obsIndex<=5; obsIndex++) {
  582. if (fuseData[obsIndex]) {
  583. stateIndex = 3 + obsIndex;
  584. // calculate the measurement innovation, using states from a different time coordinate if fusing height data
  585. // adjust scaling on GPS measurement noise variances if not enough satellites
  586. if (obsIndex <= 2)
  587. {
  588. innovVelPos[obsIndex] = stateStruct.velocity[obsIndex] - velPosObs[obsIndex];
  589. R_OBS[obsIndex] *= sq(gpsNoiseScaler);
  590. }
  591. else if (obsIndex == 3 || obsIndex == 4) {
  592. innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - velPosObs[obsIndex];
  593. R_OBS[obsIndex] *= sq(gpsNoiseScaler);
  594. } else if (obsIndex == 5) {
  595. innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - velPosObs[obsIndex];
  596. const float gndMaxBaroErr = 4.0f;
  597. const float gndBaroInnovFloor = -0.5f;
  598. if(getTouchdownExpected() && activeHgtSource == HGT_SOURCE_BARO) {
  599. // when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
  600. // constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
  601. // this function looks like this:
  602. // |/
  603. //---------|---------
  604. // ____/|
  605. // / |
  606. // / |
  607. innovVelPos[5] += constrain_float(-innovVelPos[5]+gndBaroInnovFloor, 0.0f, gndBaroInnovFloor+gndMaxBaroErr);
  608. }
  609. }
  610. // calculate the Kalman gain and calculate innovation variances
  611. varInnovVelPos[obsIndex] = P[stateIndex][stateIndex] + R_OBS[obsIndex];
  612. SK = 1.0f/varInnovVelPos[obsIndex];
  613. for (uint8_t i= 0; i<=15; i++) {
  614. Kfusion[i] = P[i][stateIndex]*SK;
  615. }
  616. // inhibit magnetic field state estimation by setting Kalman gains to zero
  617. if (!inhibitMagStates) {
  618. for (uint8_t i = 16; i<=21; i++) {
  619. Kfusion[i] = P[i][stateIndex]*SK;
  620. }
  621. } else {
  622. for (uint8_t i = 16; i<=21; i++) {
  623. Kfusion[i] = 0.0f;
  624. }
  625. }
  626. // inhibit wind state estimation by setting Kalman gains to zero
  627. if (!inhibitWindStates) {
  628. Kfusion[22] = P[22][stateIndex]*SK;
  629. Kfusion[23] = P[23][stateIndex]*SK;
  630. } else {
  631. Kfusion[22] = 0.0f;
  632. Kfusion[23] = 0.0f;
  633. }
  634. // update the covariance - take advantage of direct observation of a single state at index = stateIndex to reduce computations
  635. // this is a numerically optimised implementation of standard equation P = (I - K*H)*P;
  636. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  637. for (uint8_t j= 0; j<=stateIndexLim; j++)
  638. {
  639. KHP[i][j] = Kfusion[i] * P[stateIndex][j];
  640. }
  641. }
  642. // Check that we are not going to drive any variances negative and skip the update if so
  643. bool healthyFusion = true;
  644. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  645. if (KHP[i][i] > P[i][i]) {
  646. healthyFusion = false;
  647. }
  648. }
  649. if (healthyFusion) {
  650. // update the covariance matrix
  651. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  652. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  653. P[i][j] = P[i][j] - KHP[i][j];
  654. }
  655. }
  656. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  657. ForceSymmetry();
  658. ConstrainVariances();
  659. // update the states
  660. // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
  661. stateStruct.angErr.zero();
  662. // calculate state corrections and re-normalise the quaternions for states predicted using the blended IMU data
  663. for (uint8_t i = 0; i<=stateIndexLim; i++) {
  664. statesArray[i] = statesArray[i] - Kfusion[i] * innovVelPos[obsIndex];
  665. }
  666. // the first 3 states represent the angular misalignment vector. This is
  667. // is used to correct the estimated quaternion
  668. stateStruct.quat.rotate(stateStruct.angErr);
  669. // sum the attitude error from velocity and position fusion only
  670. // used as a metric for convergence monitoring
  671. if (obsIndex != 5) {
  672. tiltErrVec += stateStruct.angErr;
  673. }
  674. // record good fusion status
  675. if (obsIndex == 0) {
  676. faultStatus.bad_nvel = false;
  677. } else if (obsIndex == 1) {
  678. faultStatus.bad_evel = false;
  679. } else if (obsIndex == 2) {
  680. faultStatus.bad_dvel = false;
  681. } else if (obsIndex == 3) {
  682. faultStatus.bad_npos = false;
  683. } else if (obsIndex == 4) {
  684. faultStatus.bad_epos = false;
  685. } else if (obsIndex == 5) {
  686. faultStatus.bad_dpos = false;
  687. }
  688. } else {
  689. // record bad fusion status
  690. if (obsIndex == 0) {
  691. faultStatus.bad_nvel = true;
  692. } else if (obsIndex == 1) {
  693. faultStatus.bad_evel = true;
  694. } else if (obsIndex == 2) {
  695. faultStatus.bad_dvel = true;
  696. } else if (obsIndex == 3) {
  697. faultStatus.bad_npos = true;
  698. } else if (obsIndex == 4) {
  699. faultStatus.bad_epos = true;
  700. } else if (obsIndex == 5) {
  701. faultStatus.bad_dpos = true;
  702. }
  703. }
  704. }
  705. }
  706. }
  707. // stop performance timer
  708. hal.util->perf_end(_perf_FuseVelPosNED);
  709. }
  710. /********************************************************
  711. * MISC FUNCTIONS *
  712. ********************************************************/
  713. // select the height measurement to be fused from the available baro, range finder and GPS sources
  714. void NavEKF2_core::selectHeightForFusion()
  715. {
  716. // Read range finder data and check for new data in the buffer
  717. // This data is used by both height and optical flow fusion processing
  718. readRangeFinder();
  719. rangeDataToFuse = storedRange.recall(rangeDataDelayed,imuDataDelayed.time_ms);
  720. // correct range data for the body frame position offset relative to the IMU
  721. // the corrected reading is the reading that would have been taken if the sensor was
  722. // co-located with the IMU
  723. if (rangeDataToFuse) {
  724. AP_RangeFinder_Backend *sensor = frontend->_rng.get_backend(rangeDataDelayed.sensor_idx);
  725. if (sensor != nullptr) {
  726. Vector3f posOffsetBody = sensor->get_pos_offset() - accelPosOffset;
  727. if (!posOffsetBody.is_zero()) {
  728. Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
  729. rangeDataDelayed.rng += posOffsetEarth.z / prevTnb.c.z;
  730. }
  731. }
  732. }
  733. // read baro height data from the sensor and check for new data in the buffer
  734. readBaroData();
  735. baroDataToFuse = storedBaro.recall(baroDataDelayed, imuDataDelayed.time_ms);
  736. // select height source
  737. if (extNavUsedForPos) {
  738. // always use external vision as the height source if using for position.
  739. activeHgtSource = HGT_SOURCE_EV;
  740. } else if (((frontend->_useRngSwHgt > 0) && (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
  741. if (frontend->_altSource == 1) {
  742. // always use range finder
  743. activeHgtSource = HGT_SOURCE_RNG;
  744. } else {
  745. // determine if we are above or below the height switch region
  746. float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt;
  747. bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse;
  748. bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse;
  749. // If the terrain height is consistent and we are moving slowly, then it can be
  750. // used as a height reference in combination with a range finder
  751. // apply a hysteresis to the speed check to prevent rapid switching
  752. float horizSpeed = norm(stateStruct.velocity.x, stateStruct.velocity.y);
  753. bool dontTrustTerrain = ((horizSpeed > frontend->_useRngSwSpd) && filterStatus.flags.horiz_vel) || !terrainHgtStable;
  754. float trust_spd_trigger = MAX((frontend->_useRngSwSpd - 1.0f),(frontend->_useRngSwSpd * 0.5f));
  755. bool trustTerrain = (horizSpeed < trust_spd_trigger) && terrainHgtStable;
  756. /*
  757. * Switch between range finder and primary height source using height above ground and speed thresholds with
  758. * hysteresis to avoid rapid switching. Using range finder for height requires a consistent terrain height
  759. * which cannot be assumed if the vehicle is moving horizontally.
  760. */
  761. if ((aboveUpperSwHgt || dontTrustTerrain) && (activeHgtSource == HGT_SOURCE_RNG)) {
  762. // cannot trust terrain or range finder so stop using range finder height
  763. if (frontend->_altSource == 0) {
  764. activeHgtSource = HGT_SOURCE_BARO;
  765. } else if (frontend->_altSource == 2) {
  766. activeHgtSource = HGT_SOURCE_GPS;
  767. }
  768. } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) {
  769. // reliable terrain and range finder so start using range finder height
  770. activeHgtSource = HGT_SOURCE_RNG;
  771. }
  772. }
  773. } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) {
  774. activeHgtSource = HGT_SOURCE_GPS;
  775. } else if ((frontend->_altSource == 3) && validOrigin && rngBcnGoodToAlign) {
  776. activeHgtSource = HGT_SOURCE_BCN;
  777. } else {
  778. activeHgtSource = HGT_SOURCE_BARO;
  779. }
  780. // Use Baro alt as a fallback if we lose range finder, GPS or external nav
  781. bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500));
  782. bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000));
  783. bool lostExtNavHgt = ((activeHgtSource == HGT_SOURCE_EV) && ((imuSampleTime_ms - extNavMeasTime_ms) > 2000));
  784. if (lostRngHgt || lostGpsHgt || lostExtNavHgt) {
  785. activeHgtSource = HGT_SOURCE_BARO;
  786. }
  787. // if there is new baro data to fuse, calculate filtered baro data required by other processes
  788. if (baroDataToFuse) {
  789. // calculate offset to baro data that enables us to switch to Baro height use during operation
  790. if (activeHgtSource != HGT_SOURCE_BARO) {
  791. calcFiltBaroOffset();
  792. }
  793. // filtered baro data used to provide a reference for takeoff
  794. // it is is reset to last height measurement on disarming in performArmingChecks()
  795. if (!getTakeoffExpected()) {
  796. const float gndHgtFiltTC = 0.5f;
  797. const float dtBaro = frontend->hgtAvg_ms*1.0e-3f;
  798. float alpha = constrain_float(dtBaro / (dtBaro+gndHgtFiltTC),0.0f,1.0f);
  799. meaHgtAtTakeOff += (baroDataDelayed.hgt-meaHgtAtTakeOff)*alpha;
  800. }
  801. }
  802. // If we are not using GPS as the primary height sensor, correct EKF origin height so that
  803. // combined local NED position height and origin height remains consistent with the GPS altitude
  804. // This also enables the GPS height to be used as a backup height source
  805. if (gpsDataToFuse &&
  806. (((frontend->_originHgtMode & (1 << 0)) && (activeHgtSource == HGT_SOURCE_BARO)) ||
  807. ((frontend->_originHgtMode & (1 << 1)) && (activeHgtSource == HGT_SOURCE_RNG)))
  808. ) {
  809. correctEkfOriginHeight();
  810. }
  811. // Select the height measurement source
  812. if (extNavDataToFuse && (activeHgtSource == HGT_SOURCE_EV)) {
  813. hgtMea = -extNavDataDelayed.pos.z;
  814. posDownObsNoise = sq(constrain_float(extNavDataDelayed.posErr, 0.01f, 10.0f));
  815. } else if (rangeDataToFuse && (activeHgtSource == HGT_SOURCE_RNG)) {
  816. // using range finder data
  817. // correct for tilt using a flat earth model
  818. if (prevTnb.c.z >= 0.7) {
  819. // calculate height above ground
  820. hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd);
  821. // correct for terrain position relative to datum
  822. hgtMea -= terrainState;
  823. // enable fusion
  824. fuseHgtData = true;
  825. velPosObs[5] = -hgtMea;
  826. // set the observation noise
  827. posDownObsNoise = sq(constrain_float(frontend->_rngNoise, 0.1f, 10.0f));
  828. // add uncertainty created by terrain gradient and vehicle tilt
  829. posDownObsNoise += sq(rangeDataDelayed.rng * frontend->_terrGradMax) * MAX(0.0f , (1.0f - sq(prevTnb.c.z)));
  830. } else {
  831. // disable fusion if tilted too far
  832. fuseHgtData = false;
  833. }
  834. } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) {
  835. // using GPS data
  836. hgtMea = gpsDataDelayed.hgt;
  837. // enable fusion
  838. velPosObs[5] = -hgtMea;
  839. fuseHgtData = true;
  840. // set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio
  841. if (gpsHgtAccuracy > 0.0f) {
  842. posDownObsNoise = sq(constrain_float(gpsHgtAccuracy, 1.5f * frontend->_gpsHorizPosNoise, 100.0f));
  843. } else {
  844. posDownObsNoise = sq(constrain_float(1.5f * frontend->_gpsHorizPosNoise, 0.1f, 10.0f));
  845. }
  846. } else if (baroDataToFuse && (activeHgtSource == HGT_SOURCE_BARO)) {
  847. // using Baro data
  848. hgtMea = baroDataDelayed.hgt - baroHgtOffset;
  849. // enable fusion
  850. velPosObs[5] = -hgtMea;
  851. fuseHgtData = true;
  852. // set the observation noise
  853. posDownObsNoise = sq(constrain_float(frontend->_baroAltNoise, 0.1f, 10.0f));
  854. // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect
  855. if (getTakeoffExpected() || getTouchdownExpected()) {
  856. posDownObsNoise *= frontend->gndEffectBaroScaler;
  857. }
  858. // If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
  859. // This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
  860. if (motorsArmed && getTakeoffExpected()) {
  861. hgtMea = MAX(hgtMea, meaHgtAtTakeOff);
  862. }
  863. } else {
  864. fuseHgtData = false;
  865. }
  866. // If we haven't fused height data for a while, then declare the height data as being timed out
  867. // set timeout period based on whether we have vertical GPS velocity available to constrain drift
  868. hgtRetryTime_ms = (useGpsVertVel && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms;
  869. if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) {
  870. hgtTimeout = true;
  871. } else {
  872. hgtTimeout = false;
  873. }
  874. }