AP_NavEKF3_PosVelFusion.cpp 75 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635
  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_RangeFinder/RangeFinder_Backend.h>
  8. #include <AP_GPS/AP_GPS.h>
  9. #include <AP_Baro/AP_Baro.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 NavEKF3_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,4,5);
  23. zeroCols(P,4,5);
  24. if (PV_AidingMode != AID_ABSOLUTE) {
  25. stateStruct.velocity.zero();
  26. // set the variances using the measurement noise parameter
  27. P[5][5] = P[4][4] = sq(frontend->_gpsHorizVelNoise);
  28. } else {
  29. // reset horizontal velocity states to the GPS velocity if available
  30. if ((imuSampleTime_ms - lastTimeGpsReceived_ms < 250 && velResetSource == DEFAULT) || velResetSource == GPS) {
  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[5][5] = P[4][4] = 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[5][5] = P[4][4] = 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. // clear reset data source preference
  62. velResetSource = DEFAULT;
  63. }
  64. // resets position states to last GPS measurement or to zero if in constant position mode
  65. void NavEKF3_core::ResetPosition(void)
  66. {
  67. // Store the position before the reset so that we can record the reset delta
  68. posResetNE.x = stateStruct.position.x;
  69. posResetNE.y = stateStruct.position.y;
  70. // reset the corresponding covariances
  71. zeroRows(P,7,8);
  72. zeroCols(P,7,8);
  73. if (PV_AidingMode != AID_ABSOLUTE) {
  74. // reset all position state history to the last known position
  75. stateStruct.position.x = lastKnownPositionNE.x;
  76. stateStruct.position.y = lastKnownPositionNE.y;
  77. // set the variances using the position measurement noise parameter
  78. P[7][7] = P[8][8] = sq(frontend->_gpsHorizPosNoise);
  79. } else {
  80. // Use GPS data as first preference if fresh data is available
  81. if ((imuSampleTime_ms - lastTimeGpsReceived_ms < 250 && posResetSource == DEFAULT) || posResetSource == GPS) {
  82. // record the ID of the GPS for the data we are using for the reset
  83. last_gps_idx = gpsDataNew.sensor_idx;
  84. // write to state vector and compensate for offset between last GPS measurement and the EKF time horizon
  85. stateStruct.position.x = gpsDataNew.pos.x + 0.001f*gpsDataNew.vel.x*(float(imuDataDelayed.time_ms) - float(gpsDataNew.time_ms));
  86. stateStruct.position.y = gpsDataNew.pos.y + 0.001f*gpsDataNew.vel.y*(float(imuDataDelayed.time_ms) - float(gpsDataNew.time_ms));
  87. // set the variances using the position measurement noise parameter
  88. P[7][7] = P[8][8] = sq(MAX(gpsPosAccuracy,frontend->_gpsHorizPosNoise));
  89. // clear the timeout flags and counters
  90. posTimeout = false;
  91. lastPosPassTime_ms = imuSampleTime_ms;
  92. } else if ((imuSampleTime_ms - rngBcnLast3DmeasTime_ms < 250 && posResetSource == DEFAULT) || posResetSource == RNGBCN) {
  93. // use the range beacon data as a second preference
  94. stateStruct.position.x = receiverPos.x;
  95. stateStruct.position.y = receiverPos.y;
  96. // set the variances from the beacon alignment filter
  97. P[7][7] = receiverPosCov[0][0];
  98. P[8][8] = receiverPosCov[1][1];
  99. // clear the timeout flags and counters
  100. rngBcnTimeout = false;
  101. lastRngBcnPassTime_ms = imuSampleTime_ms;
  102. }
  103. }
  104. for (uint8_t i=0; i<imu_buffer_length; i++) {
  105. storedOutput[i].position.x = stateStruct.position.x;
  106. storedOutput[i].position.y = stateStruct.position.y;
  107. }
  108. outputDataNew.position.x = stateStruct.position.x;
  109. outputDataNew.position.y = stateStruct.position.y;
  110. outputDataDelayed.position.x = stateStruct.position.x;
  111. outputDataDelayed.position.y = stateStruct.position.y;
  112. // Calculate the position jump due to the reset
  113. posResetNE.x = stateStruct.position.x - posResetNE.x;
  114. posResetNE.y = stateStruct.position.y - posResetNE.y;
  115. // store the time of the reset
  116. lastPosReset_ms = imuSampleTime_ms;
  117. // clear reset source preference
  118. posResetSource = DEFAULT;
  119. }
  120. // reset the vertical position state using the last height measurement
  121. void NavEKF3_core::ResetHeight(void)
  122. {
  123. // Store the position before the reset so that we can record the reset delta
  124. posResetD = stateStruct.position.z;
  125. // write to the state vector
  126. stateStruct.position.z = -hgtMea;
  127. outputDataNew.position.z = stateStruct.position.z;
  128. outputDataDelayed.position.z = stateStruct.position.z;
  129. // reset the terrain state height
  130. if (onGround) {
  131. // assume vehicle is sitting on the ground
  132. terrainState = stateStruct.position.z + rngOnGnd;
  133. } else {
  134. // can make no assumption other than vehicle is not below ground level
  135. terrainState = MAX(stateStruct.position.z + rngOnGnd , terrainState);
  136. }
  137. for (uint8_t i=0; i<imu_buffer_length; i++) {
  138. storedOutput[i].position.z = stateStruct.position.z;
  139. }
  140. // Calculate the position jump due to the reset
  141. posResetD = stateStruct.position.z - posResetD;
  142. // store the time of the reset
  143. lastPosResetD_ms = imuSampleTime_ms;
  144. // clear the timeout flags and counters
  145. hgtTimeout = false;
  146. lastHgtPassTime_ms = imuSampleTime_ms;
  147. // reset the corresponding covariances
  148. zeroRows(P,9,9);
  149. zeroCols(P,9,9);
  150. // set the variances to the measurement variance
  151. P[9][9] = posDownObsNoise;
  152. // Reset the vertical velocity state using GPS vertical velocity if we are airborne
  153. // Check that GPS vertical velocity data is available and can be used
  154. if (inFlight && !gpsNotAvailable && frontend->_fusionModeGPS == 0 && !frontend->inhibitGpsVertVelUse) {
  155. stateStruct.velocity.z = gpsDataNew.vel.z;
  156. } else if (onGround) {
  157. stateStruct.velocity.z = 0.0f;
  158. }
  159. for (uint8_t i=0; i<imu_buffer_length; i++) {
  160. storedOutput[i].velocity.z = stateStruct.velocity.z;
  161. }
  162. outputDataNew.velocity.z = stateStruct.velocity.z;
  163. outputDataDelayed.velocity.z = stateStruct.velocity.z;
  164. // reset the corresponding covariances
  165. zeroRows(P,6,6);
  166. zeroCols(P,6,6);
  167. // set the variances to the measurement variance
  168. P[6][6] = sq(frontend->_gpsVertVelNoise);
  169. }
  170. // Zero the EKF height datum
  171. // Return true if the height datum reset has been performed
  172. bool NavEKF3_core::resetHeightDatum(void)
  173. {
  174. if (activeHgtSource == HGT_SOURCE_RNG || !onGround) {
  175. // only allow resets when on the ground.
  176. // If using using rangefinder for height then never perform a
  177. // reset of the height datum
  178. return false;
  179. }
  180. // record the old height estimate
  181. float oldHgt = -stateStruct.position.z;
  182. // reset the barometer so that it reads zero at the current height
  183. AP::baro().update_calibration();
  184. // reset the height state
  185. stateStruct.position.z = 0.0f;
  186. // adjust the height of the EKF origin so that the origin plus baro height before and after the reset is the same
  187. if (validOrigin) {
  188. if (!gpsGoodToAlign) {
  189. // if we don't have GPS lock then we shouldn't be doing a
  190. // resetHeightDatum, but if we do then the best option is
  191. // to maintain the old error
  192. EKF_origin.alt += (int32_t)(100.0f * oldHgt);
  193. } else {
  194. // if we have a good GPS lock then reset to the GPS
  195. // altitude. This ensures the reported AMSL alt from
  196. // getLLH() is equal to GPS altitude, while also ensuring
  197. // that the relative alt is zero
  198. EKF_origin.alt = AP::gps().location().alt;
  199. }
  200. ekfGpsRefHgt = (double)0.01 * (double)EKF_origin.alt;
  201. }
  202. // set the terrain state to zero (on ground). The adjustment for
  203. // frame height will get added in the later constraints
  204. terrainState = 0;
  205. return true;
  206. }
  207. /********************************************************
  208. * FUSE MEASURED_DATA *
  209. ********************************************************/
  210. // select fusion of velocity, position and height measurements
  211. void NavEKF3_core::SelectVelPosFusion()
  212. {
  213. // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
  214. // If so, don't fuse measurements on this time step to reduce frame over-runs
  215. // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
  216. if (magFusePerformed && dtIMUavg < 0.005f && !posVelFusionDelayed) {
  217. posVelFusionDelayed = true;
  218. return;
  219. } else {
  220. posVelFusionDelayed = false;
  221. }
  222. // read GPS data from the sensor and check for new data in the buffer
  223. readGpsData();
  224. gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms);
  225. // Determine if we need to fuse position and velocity data on this time step
  226. if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE) {
  227. // correct GPS data for position offset of antenna phase centre relative to the IMU
  228. Vector3f posOffsetBody = AP::gps().get_antenna_offset(gpsDataDelayed.sensor_idx) - accelPosOffset;
  229. if (!posOffsetBody.is_zero()) {
  230. if (fuseVelData) {
  231. // TODO use a filtered angular rate with a group delay that matches the GPS delay
  232. Vector3f angRate = imuDataDelayed.delAng * (1.0f/imuDataDelayed.delAngDT);
  233. Vector3f velOffsetBody = angRate % posOffsetBody;
  234. Vector3f velOffsetEarth = prevTnb.mul_transpose(velOffsetBody);
  235. gpsDataDelayed.vel -= velOffsetEarth;
  236. }
  237. Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
  238. gpsDataDelayed.pos.x -= posOffsetEarth.x;
  239. gpsDataDelayed.pos.y -= posOffsetEarth.y;
  240. gpsDataDelayed.hgt += posOffsetEarth.z;
  241. }
  242. // Don't fuse velocity data if GPS doesn't support it
  243. if (frontend->_fusionModeGPS <= 1) {
  244. fuseVelData = true;
  245. } else {
  246. fuseVelData = false;
  247. }
  248. fusePosData = true;
  249. } else {
  250. fuseVelData = false;
  251. fusePosData = false;
  252. }
  253. // we have GPS data to fuse and a request to align the yaw using the GPS course
  254. if (gpsYawResetRequest) {
  255. realignYawGPS();
  256. }
  257. // Select height data to be fused from the available baro, range finder and GPS sources
  258. selectHeightForFusion();
  259. // if we are using GPS, check for a change in receiver and reset position and height
  260. if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE && gpsDataDelayed.sensor_idx != last_gps_idx) {
  261. // record the ID of the GPS that we are using for the reset
  262. last_gps_idx = gpsDataDelayed.sensor_idx;
  263. // Store the position before the reset so that we can record the reset delta
  264. posResetNE.x = stateStruct.position.x;
  265. posResetNE.y = stateStruct.position.y;
  266. // Set the position states to the position from the new GPS
  267. stateStruct.position.x = gpsDataNew.pos.x;
  268. stateStruct.position.y = gpsDataNew.pos.y;
  269. // Calculate the position offset due to the reset
  270. posResetNE.x = stateStruct.position.x - posResetNE.x;
  271. posResetNE.y = stateStruct.position.y - posResetNE.y;
  272. // Add the offset to the output observer states
  273. for (uint8_t i=0; i<imu_buffer_length; i++) {
  274. storedOutput[i].position.x += posResetNE.x;
  275. storedOutput[i].position.y += posResetNE.y;
  276. }
  277. outputDataNew.position.x += posResetNE.x;
  278. outputDataNew.position.y += posResetNE.y;
  279. outputDataDelayed.position.x += posResetNE.x;
  280. outputDataDelayed.position.y += posResetNE.y;
  281. // store the time of the reset
  282. lastPosReset_ms = imuSampleTime_ms;
  283. // If we are alseo using GPS as the height reference, reset the height
  284. if (activeHgtSource == HGT_SOURCE_GPS) {
  285. // Store the position before the reset so that we can record the reset delta
  286. posResetD = stateStruct.position.z;
  287. // write to the state vector
  288. stateStruct.position.z = -hgtMea;
  289. // Calculate the position jump due to the reset
  290. posResetD = stateStruct.position.z - posResetD;
  291. // Add the offset to the output observer states
  292. outputDataNew.position.z += posResetD;
  293. outputDataDelayed.position.z += posResetD;
  294. for (uint8_t i=0; i<imu_buffer_length; i++) {
  295. storedOutput[i].position.z += posResetD;
  296. }
  297. // store the time of the reset
  298. lastPosResetD_ms = imuSampleTime_ms;
  299. }
  300. }
  301. // If we are operating without any aiding, fuse in the last known position
  302. // to constrain tilt drift. This assumes a non-manoeuvring vehicle
  303. // Do this to coincide with the height fusion
  304. if (fuseHgtData && PV_AidingMode == AID_NONE) {
  305. gpsDataDelayed.vel.zero();
  306. gpsDataDelayed.pos.x = lastKnownPositionNE.x;
  307. gpsDataDelayed.pos.y = lastKnownPositionNE.y;
  308. fusePosData = true;
  309. fuseVelData = false;
  310. }
  311. // perform fusion
  312. if (fuseVelData || fusePosData || fuseHgtData) {
  313. FuseVelPosNED();
  314. // clear the flags to prevent repeated fusion of the same data
  315. fuseVelData = false;
  316. fuseHgtData = false;
  317. fusePosData = false;
  318. }
  319. }
  320. // fuse selected position, velocity and height measurements
  321. void NavEKF3_core::FuseVelPosNED()
  322. {
  323. // start performance timer
  324. hal.util->perf_begin(_perf_FuseVelPosNED);
  325. // health is set bad until test passed
  326. velHealth = false;
  327. posHealth = false;
  328. hgtHealth = false;
  329. // declare variables used to check measurement errors
  330. Vector3f velInnov;
  331. // declare variables used to control access to arrays
  332. bool fuseData[6] = {false,false,false,false,false,false};
  333. uint8_t stateIndex;
  334. uint8_t obsIndex;
  335. // declare variables used by state and covariance update calculations
  336. Vector6 R_OBS; // Measurement variances used for fusion
  337. Vector6 R_OBS_DATA_CHECKS; // Measurement variances used for data checks only
  338. Vector6 observation;
  339. float SK;
  340. // perform sequential fusion of GPS measurements. This assumes that the
  341. // errors in the different velocity and position components are
  342. // uncorrelated which is not true, however in the absence of covariance
  343. // data from the GPS receiver it is the only assumption we can make
  344. // so we might as well take advantage of the computational efficiencies
  345. // associated with sequential fusion
  346. if (fuseVelData || fusePosData || fuseHgtData) {
  347. // form the observation vector
  348. observation[0] = gpsDataDelayed.vel.x;
  349. observation[1] = gpsDataDelayed.vel.y;
  350. observation[2] = gpsDataDelayed.vel.z;
  351. observation[3] = gpsDataDelayed.pos.x;
  352. observation[4] = gpsDataDelayed.pos.y;
  353. observation[5] = -hgtMea;
  354. // calculate additional error in GPS position caused by manoeuvring
  355. float posErr = frontend->gpsPosVarAccScale * accNavMag;
  356. // estimate the GPS Velocity, GPS horiz position and height measurement variances.
  357. // Use different errors if operating without external aiding using an assumed position or velocity of zero
  358. if (PV_AidingMode == AID_NONE) {
  359. if (tiltAlignComplete && motorsArmed) {
  360. // This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate
  361. R_OBS[0] = sq(constrain_float(frontend->_noaidHorizNoise, 0.5f, 50.0f));
  362. } else {
  363. // Use a smaller value to give faster initial alignment
  364. R_OBS[0] = sq(0.5f);
  365. }
  366. R_OBS[1] = R_OBS[0];
  367. R_OBS[2] = R_OBS[0];
  368. R_OBS[3] = R_OBS[0];
  369. R_OBS[4] = R_OBS[0];
  370. for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
  371. } else {
  372. if (gpsSpdAccuracy > 0.0f) {
  373. // use GPS receivers reported speed accuracy if available and floor at value set by GPS velocity noise parameter
  374. R_OBS[0] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsHorizVelNoise, 50.0f));
  375. R_OBS[2] = sq(constrain_float(gpsSpdAccuracy, frontend->_gpsVertVelNoise, 50.0f));
  376. } else {
  377. // calculate additional error in GPS velocity caused by manoeuvring
  378. R_OBS[0] = sq(constrain_float(frontend->_gpsHorizVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsNEVelVarAccScale * accNavMag);
  379. R_OBS[2] = sq(constrain_float(frontend->_gpsVertVelNoise, 0.05f, 5.0f)) + sq(frontend->gpsDVelVarAccScale * accNavMag);
  380. }
  381. R_OBS[1] = R_OBS[0];
  382. // Use GPS reported position accuracy if available and floor at value set by GPS position noise parameter
  383. if (gpsPosAccuracy > 0.0f) {
  384. R_OBS[3] = sq(constrain_float(gpsPosAccuracy, frontend->_gpsHorizPosNoise, 100.0f));
  385. } else {
  386. R_OBS[3] = sq(constrain_float(frontend->_gpsHorizPosNoise, 0.1f, 10.0f)) + sq(posErr);
  387. }
  388. R_OBS[4] = R_OBS[3];
  389. // For data integrity checks we use the same measurement variances as used to calculate the Kalman gains for all measurements except GPS horizontal velocity
  390. // 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 performance
  391. // plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
  392. 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);
  393. }
  394. R_OBS[5] = posDownObsNoise;
  395. for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
  396. // if vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
  397. // innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
  398. // the accelerometers and we should disable the GPS and barometer innovation consistency checks.
  399. if (useGpsVertVel && fuseVelData && (frontend->_altSource != 2)) {
  400. // calculate innovations for height and vertical GPS vel measurements
  401. float hgtErr = stateStruct.position.z - observation[5];
  402. float velDErr = stateStruct.velocity.z - observation[2];
  403. // check if they are the same sign and both more than 3-sigma out of bounds
  404. if ((hgtErr*velDErr > 0.0f) && (sq(hgtErr) > 9.0f * (P[9][9] + R_OBS_DATA_CHECKS[5])) && (sq(velDErr) > 9.0f * (P[6][6] + R_OBS_DATA_CHECKS[2]))) {
  405. badIMUdata = true;
  406. } else {
  407. badIMUdata = false;
  408. }
  409. }
  410. // calculate innovations and check GPS data validity using an innovation consistency check
  411. // test position measurements
  412. if (fusePosData) {
  413. // test horizontal position measurements
  414. innovVelPos[3] = stateStruct.position.x - observation[3];
  415. innovVelPos[4] = stateStruct.position.y - observation[4];
  416. varInnovVelPos[3] = P[7][7] + R_OBS_DATA_CHECKS[3];
  417. varInnovVelPos[4] = P[8][8] + R_OBS_DATA_CHECKS[4];
  418. // apply an innovation consistency threshold test, but don't fail if bad IMU data
  419. float maxPosInnov2 = sq(MAX(0.01f * (float)frontend->_gpsPosInnovGate, 1.0f))*(varInnovVelPos[3] + varInnovVelPos[4]);
  420. posTestRatio = (sq(innovVelPos[3]) + sq(innovVelPos[4])) / maxPosInnov2;
  421. posHealth = ((posTestRatio < 1.0f) || badIMUdata);
  422. // use position data if healthy or timed out
  423. if (PV_AidingMode == AID_NONE) {
  424. posHealth = true;
  425. lastPosPassTime_ms = imuSampleTime_ms;
  426. } else if (posHealth || posTimeout) {
  427. posHealth = true;
  428. lastPosPassTime_ms = imuSampleTime_ms;
  429. // if timed out or outside the specified uncertainty radius, reset to the GPS
  430. if (posTimeout || ((P[8][8] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
  431. // reset the position to the current GPS position
  432. ResetPosition();
  433. // reset the velocity to the GPS velocity
  434. ResetVelocity();
  435. // don't fuse GPS data on this time step
  436. fusePosData = false;
  437. fuseVelData = false;
  438. // Reset the position variances and corresponding covariances to a value that will pass the checks
  439. zeroRows(P,7,8);
  440. zeroCols(P,7,8);
  441. P[7][7] = sq(float(0.5f*frontend->_gpsGlitchRadiusMax));
  442. P[8][8] = P[7][7];
  443. // Reset the normalised innovation to avoid failing the bad fusion tests
  444. posTestRatio = 0.0f;
  445. velTestRatio = 0.0f;
  446. }
  447. } else {
  448. posHealth = false;
  449. }
  450. }
  451. // test velocity measurements
  452. if (fuseVelData) {
  453. // test velocity measurements
  454. uint8_t imax = 2;
  455. // Don't fuse vertical velocity observations if inhibited by the user or if we are using synthetic data
  456. if (frontend->_fusionModeGPS > 0 || PV_AidingMode != AID_ABSOLUTE || frontend->inhibitGpsVertVelUse) {
  457. imax = 1;
  458. }
  459. float innovVelSumSq = 0; // sum of squares of velocity innovations
  460. float varVelSum = 0; // sum of velocity innovation variances
  461. for (uint8_t i = 0; i<=imax; i++) {
  462. // velocity states start at index 4
  463. stateIndex = i + 4;
  464. // calculate innovations using blended and single IMU predicted states
  465. velInnov[i] = stateStruct.velocity[i] - observation[i]; // blended
  466. // calculate innovation variance
  467. varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS_DATA_CHECKS[i];
  468. // sum the innovation and innovation variances
  469. innovVelSumSq += sq(velInnov[i]);
  470. varVelSum += varInnovVelPos[i];
  471. }
  472. // apply an innovation consistency threshold test, but don't fail if bad IMU data
  473. // calculate the test ratio
  474. velTestRatio = innovVelSumSq / (varVelSum * sq(MAX(0.01f * (float)frontend->_gpsVelInnovGate, 1.0f)));
  475. // fail if the ratio is greater than 1
  476. velHealth = ((velTestRatio < 1.0f) || badIMUdata);
  477. // use velocity data if healthy, timed out, or in constant position mode
  478. if (velHealth || velTimeout) {
  479. velHealth = true;
  480. // restart the timeout count
  481. lastVelPassTime_ms = imuSampleTime_ms;
  482. // If we are doing full aiding and velocity fusion times out, reset to the GPS velocity
  483. if (PV_AidingMode == AID_ABSOLUTE && velTimeout) {
  484. // reset the velocity to the GPS velocity
  485. ResetVelocity();
  486. // don't fuse GPS velocity data on this time step
  487. fuseVelData = false;
  488. // Reset the normalised innovation to avoid failing the bad fusion tests
  489. velTestRatio = 0.0f;
  490. }
  491. } else {
  492. velHealth = false;
  493. }
  494. }
  495. // test height measurements
  496. if (fuseHgtData) {
  497. // calculate height innovations
  498. innovVelPos[5] = stateStruct.position.z - observation[5];
  499. varInnovVelPos[5] = P[9][9] + R_OBS_DATA_CHECKS[5];
  500. // calculate the innovation consistency test ratio
  501. hgtTestRatio = sq(innovVelPos[5]) / (sq(MAX(0.01f * (float)frontend->_hgtInnovGate, 1.0f)) * varInnovVelPos[5]);
  502. // when on ground we accept a larger test ratio to allow
  503. // the filter to handle large switch on IMU bias errors
  504. // without rejecting the height sensor
  505. const float maxTestRatio = (PV_AidingMode == AID_NONE && onGround)? 3.0 : 1.0;
  506. // fail if the ratio is > 1, but don't fail if bad IMU data
  507. hgtHealth = ((hgtTestRatio < maxTestRatio) || badIMUdata);
  508. // Fuse height data if healthy or timed out or in constant position mode
  509. if (hgtHealth || hgtTimeout) {
  510. // Calculate a filtered value to be used by pre-flight health checks
  511. // 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
  512. if (onGround) {
  513. float dtBaro = (imuSampleTime_ms - lastHgtPassTime_ms)*1.0e-3f;
  514. const float hgtInnovFiltTC = 2.0f;
  515. float alpha = constrain_float(dtBaro/(dtBaro+hgtInnovFiltTC),0.0f,1.0f);
  516. hgtInnovFiltState += (innovVelPos[5]-hgtInnovFiltState)*alpha;
  517. } else {
  518. hgtInnovFiltState = 0.0f;
  519. }
  520. // if timed out, reset the height
  521. if (hgtTimeout) {
  522. ResetHeight();
  523. }
  524. // If we have got this far then declare the height data as healthy and reset the timeout counter
  525. hgtHealth = true;
  526. lastHgtPassTime_ms = imuSampleTime_ms;
  527. }
  528. }
  529. // set range for sequential fusion of velocity and position measurements depending on which data is available and its health
  530. if (fuseVelData && velHealth) {
  531. fuseData[0] = true;
  532. fuseData[1] = true;
  533. if (useGpsVertVel) {
  534. fuseData[2] = true;
  535. }
  536. }
  537. if (fusePosData && posHealth) {
  538. fuseData[3] = true;
  539. fuseData[4] = true;
  540. }
  541. if (fuseHgtData && hgtHealth) {
  542. fuseData[5] = true;
  543. }
  544. // fuse measurements sequentially
  545. for (obsIndex=0; obsIndex<=5; obsIndex++) {
  546. if (fuseData[obsIndex]) {
  547. stateIndex = 4 + obsIndex;
  548. // calculate the measurement innovation, using states from a different time coordinate if fusing height data
  549. // adjust scaling on GPS measurement noise variances if not enough satellites
  550. if (obsIndex <= 2)
  551. {
  552. innovVelPos[obsIndex] = stateStruct.velocity[obsIndex] - observation[obsIndex];
  553. R_OBS[obsIndex] *= sq(gpsNoiseScaler);
  554. }
  555. else if (obsIndex == 3 || obsIndex == 4) {
  556. innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - observation[obsIndex];
  557. R_OBS[obsIndex] *= sq(gpsNoiseScaler);
  558. } else if (obsIndex == 5) {
  559. innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - observation[obsIndex];
  560. const float gndMaxBaroErr = 4.0f;
  561. const float gndBaroInnovFloor = -0.5f;
  562. if(getTouchdownExpected() && activeHgtSource == HGT_SOURCE_BARO) {
  563. // when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
  564. // constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
  565. // this function looks like this:
  566. // |/
  567. //---------|---------
  568. // ____/|
  569. // / |
  570. // / |
  571. innovVelPos[5] += constrain_float(-innovVelPos[5]+gndBaroInnovFloor, 0.0f, gndBaroInnovFloor+gndMaxBaroErr);
  572. }
  573. }
  574. // calculate the Kalman gain and calculate innovation variances
  575. varInnovVelPos[obsIndex] = P[stateIndex][stateIndex] + R_OBS[obsIndex];
  576. SK = 1.0f/varInnovVelPos[obsIndex];
  577. for (uint8_t i= 0; i<=9; i++) {
  578. Kfusion[i] = P[i][stateIndex]*SK;
  579. }
  580. // inhibit delta angle bias state estmation by setting Kalman gains to zero
  581. if (!inhibitDelAngBiasStates) {
  582. for (uint8_t i = 10; i<=12; i++) {
  583. Kfusion[i] = P[i][stateIndex]*SK;
  584. }
  585. } else {
  586. // zero indexes 10 to 12 = 3*4 bytes
  587. memset(&Kfusion[10], 0, 12);
  588. }
  589. // inhibit delta velocity bias state estimation by setting Kalman gains to zero
  590. if (!inhibitDelVelBiasStates) {
  591. for (uint8_t i = 13; i<=15; i++) {
  592. Kfusion[i] = P[i][stateIndex]*SK;
  593. }
  594. } else {
  595. // zero indexes 13 to 15 = 3*4 bytes
  596. memset(&Kfusion[13], 0, 12);
  597. }
  598. // inhibit magnetic field state estimation by setting Kalman gains to zero
  599. if (!inhibitMagStates) {
  600. for (uint8_t i = 16; i<=21; i++) {
  601. Kfusion[i] = P[i][stateIndex]*SK;
  602. }
  603. } else {
  604. // zero indexes 16 to 21 = 6*4 bytes
  605. memset(&Kfusion[16], 0, 24);
  606. }
  607. // inhibit wind state estimation by setting Kalman gains to zero
  608. if (!inhibitWindStates) {
  609. Kfusion[22] = P[22][stateIndex]*SK;
  610. Kfusion[23] = P[23][stateIndex]*SK;
  611. } else {
  612. // zero indexes 22 to 23 = 2*4 bytes
  613. memset(&Kfusion[22], 0, 8);
  614. }
  615. // update the covariance - take advantage of direct observation of a single state at index = stateIndex to reduce computations
  616. // this is a numerically optimised implementation of standard equation P = (I - K*H)*P;
  617. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  618. for (uint8_t j= 0; j<=stateIndexLim; j++)
  619. {
  620. KHP[i][j] = Kfusion[i] * P[stateIndex][j];
  621. }
  622. }
  623. // Check that we are not going to drive any variances negative and skip the update if so
  624. bool healthyFusion = true;
  625. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  626. if (KHP[i][i] > P[i][i]) {
  627. healthyFusion = false;
  628. }
  629. }
  630. if (healthyFusion) {
  631. // update the covariance matrix
  632. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  633. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  634. P[i][j] = P[i][j] - KHP[i][j];
  635. }
  636. }
  637. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  638. ForceSymmetry();
  639. ConstrainVariances();
  640. // update states and renormalise the quaternions
  641. for (uint8_t i = 0; i<=stateIndexLim; i++) {
  642. statesArray[i] = statesArray[i] - Kfusion[i] * innovVelPos[obsIndex];
  643. }
  644. stateStruct.quat.normalize();
  645. // record good fusion status
  646. if (obsIndex == 0) {
  647. faultStatus.bad_nvel = false;
  648. } else if (obsIndex == 1) {
  649. faultStatus.bad_evel = false;
  650. } else if (obsIndex == 2) {
  651. faultStatus.bad_dvel = false;
  652. } else if (obsIndex == 3) {
  653. faultStatus.bad_npos = false;
  654. } else if (obsIndex == 4) {
  655. faultStatus.bad_epos = false;
  656. } else if (obsIndex == 5) {
  657. faultStatus.bad_dpos = false;
  658. }
  659. } else {
  660. // record bad fusion status
  661. if (obsIndex == 0) {
  662. faultStatus.bad_nvel = true;
  663. } else if (obsIndex == 1) {
  664. faultStatus.bad_evel = true;
  665. } else if (obsIndex == 2) {
  666. faultStatus.bad_dvel = true;
  667. } else if (obsIndex == 3) {
  668. faultStatus.bad_npos = true;
  669. } else if (obsIndex == 4) {
  670. faultStatus.bad_epos = true;
  671. } else if (obsIndex == 5) {
  672. faultStatus.bad_dpos = true;
  673. }
  674. }
  675. }
  676. }
  677. }
  678. // stop performance timer
  679. hal.util->perf_end(_perf_FuseVelPosNED);
  680. }
  681. /********************************************************
  682. * MISC FUNCTIONS *
  683. ********************************************************/
  684. // select the height measurement to be fused from the available baro, range finder and GPS sources
  685. void NavEKF3_core::selectHeightForFusion()
  686. {
  687. // Read range finder data and check for new data in the buffer
  688. // This data is used by both height and optical flow fusion processing
  689. readRangeFinder();
  690. rangeDataToFuse = storedRange.recall(rangeDataDelayed,imuDataDelayed.time_ms);
  691. // correct range data for the body frame position offset relative to the IMU
  692. // the corrected reading is the reading that would have been taken if the sensor was
  693. // co-located with the IMU
  694. if (rangeDataToFuse) {
  695. AP_RangeFinder_Backend *sensor = frontend->_rng.get_backend(rangeDataDelayed.sensor_idx);
  696. if (sensor != nullptr) {
  697. Vector3f posOffsetBody = sensor->get_pos_offset() - accelPosOffset;
  698. if (!posOffsetBody.is_zero()) {
  699. Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
  700. rangeDataDelayed.rng += posOffsetEarth.z / prevTnb.c.z;
  701. }
  702. }
  703. }
  704. // read baro height data from the sensor and check for new data in the buffer
  705. readBaroData();
  706. baroDataToFuse = storedBaro.recall(baroDataDelayed, imuDataDelayed.time_ms);
  707. // select height source
  708. if (((frontend->_useRngSwHgt > 0) && (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
  709. if (frontend->_altSource == 1) {
  710. // always use range finder
  711. activeHgtSource = HGT_SOURCE_RNG;
  712. } else {
  713. // determine if we are above or below the height switch region
  714. float rangeMaxUse = 1e-4f * (float)frontend->_rng.max_distance_cm_orient(ROTATION_PITCH_270) * (float)frontend->_useRngSwHgt;
  715. bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse;
  716. bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse;
  717. // If the terrain height is consistent and we are moving slowly, then it can be
  718. // used as a height reference in combination with a range finder
  719. // apply a hysteresis to the speed check to prevent rapid switching
  720. bool dontTrustTerrain, trustTerrain;
  721. if (filterStatus.flags.horiz_vel) {
  722. // We can use the velocity estimate
  723. float horizSpeed = norm(stateStruct.velocity.x, stateStruct.velocity.y);
  724. dontTrustTerrain = (horizSpeed > frontend->_useRngSwSpd) || !terrainHgtStable;
  725. float trust_spd_trigger = MAX((frontend->_useRngSwSpd - 1.0f),(frontend->_useRngSwSpd * 0.5f));
  726. trustTerrain = (horizSpeed < trust_spd_trigger) && terrainHgtStable;
  727. } else {
  728. // We can't use the velocity estimate
  729. dontTrustTerrain = !terrainHgtStable;
  730. trustTerrain = terrainHgtStable;
  731. }
  732. /*
  733. * Switch between range finder and primary height source using height above ground and speed thresholds with
  734. * hysteresis to avoid rapid switching. Using range finder for height requires a consistent terrain height
  735. * which cannot be assumed if the vehicle is moving horizontally.
  736. */
  737. if ((aboveUpperSwHgt || dontTrustTerrain) && (activeHgtSource == HGT_SOURCE_RNG)) {
  738. // cannot trust terrain or range finder so stop using range finder height
  739. if (frontend->_altSource == 0) {
  740. activeHgtSource = HGT_SOURCE_BARO;
  741. } else if (frontend->_altSource == 2) {
  742. activeHgtSource = HGT_SOURCE_GPS;
  743. }
  744. } else if (belowLowerSwHgt && trustTerrain && (activeHgtSource != HGT_SOURCE_RNG)) {
  745. // reliable terrain and range finder so start using range finder height
  746. activeHgtSource = HGT_SOURCE_RNG;
  747. }
  748. }
  749. } else if ((frontend->_altSource == 2) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) < 500) && validOrigin && gpsAccuracyGood) {
  750. activeHgtSource = HGT_SOURCE_GPS;
  751. } else if ((frontend->_altSource == 3) && validOrigin && rngBcnGoodToAlign) {
  752. activeHgtSource = HGT_SOURCE_BCN;
  753. } else {
  754. activeHgtSource = HGT_SOURCE_BARO;
  755. }
  756. // Use Baro alt as a fallback if we lose range finder or GPS
  757. bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500));
  758. bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000));
  759. if (lostRngHgt || lostGpsHgt) {
  760. activeHgtSource = HGT_SOURCE_BARO;
  761. }
  762. // if there is new baro data to fuse, calculate filtered baro data required by other processes
  763. if (baroDataToFuse) {
  764. // calculate offset to baro data that enables us to switch to Baro height use during operation
  765. if (activeHgtSource != HGT_SOURCE_BARO) {
  766. calcFiltBaroOffset();
  767. }
  768. // filtered baro data used to provide a reference for takeoff
  769. // it is is reset to last height measurement on disarming in performArmingChecks()
  770. if (!getTakeoffExpected()) {
  771. const float gndHgtFiltTC = 0.5f;
  772. const float dtBaro = frontend->hgtAvg_ms*1.0e-3f;
  773. float alpha = constrain_float(dtBaro / (dtBaro+gndHgtFiltTC),0.0f,1.0f);
  774. meaHgtAtTakeOff += (baroDataDelayed.hgt-meaHgtAtTakeOff)*alpha;
  775. }
  776. }
  777. // If we are not using GPS as the primary height sensor, correct EKF origin height so that
  778. // combined local NED position height and origin height remains consistent with the GPS altitude
  779. // This also enables the GPS height to be used as a backup height source
  780. if (gpsDataToFuse &&
  781. (((frontend->_originHgtMode & (1 << 0)) && (activeHgtSource == HGT_SOURCE_BARO)) ||
  782. ((frontend->_originHgtMode & (1 << 1)) && (activeHgtSource == HGT_SOURCE_RNG)))
  783. ) {
  784. correctEkfOriginHeight();
  785. }
  786. // Select the height measurement source
  787. if (rangeDataToFuse && (activeHgtSource == HGT_SOURCE_RNG)) {
  788. // using range finder data
  789. // correct for tilt using a flat earth model
  790. if (prevTnb.c.z >= 0.7) {
  791. // calculate height above ground
  792. hgtMea = MAX(rangeDataDelayed.rng * prevTnb.c.z, rngOnGnd);
  793. // correct for terrain position relative to datum
  794. hgtMea -= terrainState;
  795. // enable fusion
  796. fuseHgtData = true;
  797. // set the observation noise
  798. posDownObsNoise = sq(constrain_float(frontend->_rngNoise, 0.1f, 10.0f));
  799. // add uncertainty created by terrain gradient and vehicle tilt
  800. posDownObsNoise += sq(rangeDataDelayed.rng * frontend->_terrGradMax) * MAX(0.0f , (1.0f - sq(prevTnb.c.z)));
  801. } else {
  802. // disable fusion if tilted too far
  803. fuseHgtData = false;
  804. }
  805. } else if (gpsDataToFuse && (activeHgtSource == HGT_SOURCE_GPS)) {
  806. // using GPS data
  807. hgtMea = gpsDataDelayed.hgt;
  808. // enable fusion
  809. fuseHgtData = true;
  810. // set the observation noise using receiver reported accuracy or the horizontal noise scaled for typical VDOP/HDOP ratio
  811. if (gpsHgtAccuracy > 0.0f) {
  812. posDownObsNoise = sq(constrain_float(gpsHgtAccuracy, 1.5f * frontend->_gpsHorizPosNoise, 100.0f));
  813. } else {
  814. posDownObsNoise = sq(constrain_float(1.5f * frontend->_gpsHorizPosNoise, 0.1f, 10.0f));
  815. }
  816. } else if (baroDataToFuse && (activeHgtSource == HGT_SOURCE_BARO)) {
  817. // using Baro data
  818. hgtMea = baroDataDelayed.hgt - baroHgtOffset;
  819. // enable fusion
  820. fuseHgtData = true;
  821. // set the observation noise
  822. posDownObsNoise = sq(constrain_float(frontend->_baroAltNoise, 0.1f, 10.0f));
  823. // reduce weighting (increase observation noise) on baro if we are likely to be in ground effect
  824. if (getTakeoffExpected() || getTouchdownExpected()) {
  825. posDownObsNoise *= frontend->gndEffectBaroScaler;
  826. }
  827. // If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
  828. // This prevents negative baro disturbances due to copter downwash corrupting the EKF altitude during initial ascent
  829. if (motorsArmed && getTakeoffExpected()) {
  830. hgtMea = MAX(hgtMea, meaHgtAtTakeOff);
  831. }
  832. } else {
  833. fuseHgtData = false;
  834. }
  835. // If we haven't fused height data for a while, then declare the height data as being timed out
  836. // set timeout period based on whether we have vertical GPS velocity available to constrain drift
  837. hgtRetryTime_ms = (useGpsVertVel && !velTimeout) ? frontend->hgtRetryTimeMode0_ms : frontend->hgtRetryTimeMode12_ms;
  838. if (imuSampleTime_ms - lastHgtPassTime_ms > hgtRetryTime_ms) {
  839. hgtTimeout = true;
  840. } else {
  841. hgtTimeout = false;
  842. }
  843. }
  844. /*
  845. * Fuse body frame velocity measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
  846. * The script file used to generate these and other equations in this filter can be found here:
  847. * https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
  848. */
  849. void NavEKF3_core::FuseBodyVel()
  850. {
  851. Vector24 H_VEL;
  852. Vector3f bodyVelPred;
  853. // Copy required states to local variable names
  854. float q0 = stateStruct.quat[0];
  855. float q1 = stateStruct.quat[1];
  856. float q2 = stateStruct.quat[2];
  857. float q3 = stateStruct.quat[3];
  858. float vn = stateStruct.velocity.x;
  859. float ve = stateStruct.velocity.y;
  860. float vd = stateStruct.velocity.z;
  861. // Fuse X, Y and Z axis measurements sequentially assuming observation errors are uncorrelated
  862. for (uint8_t obsIndex=0; obsIndex<=2; obsIndex++) {
  863. // calculate relative velocity in sensor frame including the relative motion due to rotation
  864. bodyVelPred = (prevTnb * stateStruct.velocity);
  865. // correct sensor offset body frame position offset relative to IMU
  866. Vector3f posOffsetBody = (*bodyOdmDataDelayed.body_offset) - accelPosOffset;
  867. // correct prediction for relative motion due to rotation
  868. // note - % operator overloaded for cross product
  869. if (imuDataDelayed.delAngDT > 0.001f) {
  870. bodyVelPred += (imuDataDelayed.delAng * (1.0f / imuDataDelayed.delAngDT)) % posOffsetBody;
  871. }
  872. // calculate observation jacobians and Kalman gains
  873. if (obsIndex == 0) {
  874. // calculate X axis observation Jacobian
  875. H_VEL[0] = q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f;
  876. H_VEL[1] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
  877. H_VEL[2] = q0*vd*-2.0f+q1*ve*2.0f-q2*vn*2.0f;
  878. H_VEL[3] = q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f;
  879. H_VEL[4] = q0*q0+q1*q1-q2*q2-q3*q3;
  880. H_VEL[5] = q0*q3*2.0f+q1*q2*2.0f;
  881. H_VEL[6] = q0*q2*-2.0f+q1*q3*2.0f;
  882. for (uint8_t index = 7; index < 24; index++) {
  883. H_VEL[index] = 0.0f;
  884. }
  885. // calculate intermediate expressions for X axis Kalman gains
  886. float R_VEL = sq(bodyOdmDataDelayed.velErr);
  887. float t2 = q0*q3*2.0f;
  888. float t3 = q1*q2*2.0f;
  889. float t4 = t2+t3;
  890. float t5 = q0*q0;
  891. float t6 = q1*q1;
  892. float t7 = q2*q2;
  893. float t8 = q3*q3;
  894. float t9 = t5+t6-t7-t8;
  895. float t10 = q0*q2*2.0f;
  896. float t25 = q1*q3*2.0f;
  897. float t11 = t10-t25;
  898. float t12 = q3*ve*2.0f;
  899. float t13 = q0*vn*2.0f;
  900. float t26 = q2*vd*2.0f;
  901. float t14 = t12+t13-t26;
  902. float t15 = q3*vd*2.0f;
  903. float t16 = q2*ve*2.0f;
  904. float t17 = q1*vn*2.0f;
  905. float t18 = t15+t16+t17;
  906. float t19 = q0*vd*2.0f;
  907. float t20 = q2*vn*2.0f;
  908. float t27 = q1*ve*2.0f;
  909. float t21 = t19+t20-t27;
  910. float t22 = q1*vd*2.0f;
  911. float t23 = q0*ve*2.0f;
  912. float t28 = q3*vn*2.0f;
  913. float t24 = t22+t23-t28;
  914. float t29 = P[0][0]*t14;
  915. float t30 = P[1][1]*t18;
  916. float t31 = P[4][5]*t9;
  917. float t32 = P[5][5]*t4;
  918. float t33 = P[0][5]*t14;
  919. float t34 = P[1][5]*t18;
  920. float t35 = P[3][5]*t24;
  921. float t79 = P[6][5]*t11;
  922. float t80 = P[2][5]*t21;
  923. float t36 = t31+t32+t33+t34+t35-t79-t80;
  924. float t37 = t4*t36;
  925. float t38 = P[4][6]*t9;
  926. float t39 = P[5][6]*t4;
  927. float t40 = P[0][6]*t14;
  928. float t41 = P[1][6]*t18;
  929. float t42 = P[3][6]*t24;
  930. float t81 = P[6][6]*t11;
  931. float t82 = P[2][6]*t21;
  932. float t43 = t38+t39+t40+t41+t42-t81-t82;
  933. float t44 = P[4][0]*t9;
  934. float t45 = P[5][0]*t4;
  935. float t46 = P[1][0]*t18;
  936. float t47 = P[3][0]*t24;
  937. float t84 = P[6][0]*t11;
  938. float t85 = P[2][0]*t21;
  939. float t48 = t29+t44+t45+t46+t47-t84-t85;
  940. float t49 = t14*t48;
  941. float t50 = P[4][1]*t9;
  942. float t51 = P[5][1]*t4;
  943. float t52 = P[0][1]*t14;
  944. float t53 = P[3][1]*t24;
  945. float t86 = P[6][1]*t11;
  946. float t87 = P[2][1]*t21;
  947. float t54 = t30+t50+t51+t52+t53-t86-t87;
  948. float t55 = t18*t54;
  949. float t56 = P[4][2]*t9;
  950. float t57 = P[5][2]*t4;
  951. float t58 = P[0][2]*t14;
  952. float t59 = P[1][2]*t18;
  953. float t60 = P[3][2]*t24;
  954. float t78 = P[2][2]*t21;
  955. float t88 = P[6][2]*t11;
  956. float t61 = t56+t57+t58+t59+t60-t78-t88;
  957. float t62 = P[4][3]*t9;
  958. float t63 = P[5][3]*t4;
  959. float t64 = P[0][3]*t14;
  960. float t65 = P[1][3]*t18;
  961. float t66 = P[3][3]*t24;
  962. float t90 = P[6][3]*t11;
  963. float t91 = P[2][3]*t21;
  964. float t67 = t62+t63+t64+t65+t66-t90-t91;
  965. float t68 = t24*t67;
  966. float t69 = P[4][4]*t9;
  967. float t70 = P[5][4]*t4;
  968. float t71 = P[0][4]*t14;
  969. float t72 = P[1][4]*t18;
  970. float t73 = P[3][4]*t24;
  971. float t92 = P[6][4]*t11;
  972. float t93 = P[2][4]*t21;
  973. float t74 = t69+t70+t71+t72+t73-t92-t93;
  974. float t75 = t9*t74;
  975. float t83 = t11*t43;
  976. float t89 = t21*t61;
  977. float t76 = R_VEL+t37+t49+t55+t68+t75-t83-t89;
  978. float t77;
  979. // calculate innovation variance for X axis observation and protect against a badly conditioned calculation
  980. if (t76 > R_VEL) {
  981. t77 = 1.0f/t76;
  982. faultStatus.bad_xvel = false;
  983. } else {
  984. t76 = R_VEL;
  985. t77 = 1.0f/R_VEL;
  986. faultStatus.bad_xvel = true;
  987. return;
  988. }
  989. varInnovBodyVel[0] = t77;
  990. // calculate innovation for X axis observation
  991. innovBodyVel[0] = bodyVelPred.x - bodyOdmDataDelayed.vel.x;
  992. // calculate Kalman gains for X-axis observation
  993. Kfusion[0] = t77*(t29+P[0][5]*t4+P[0][4]*t9-P[0][6]*t11+P[0][1]*t18-P[0][2]*t21+P[0][3]*t24);
  994. Kfusion[1] = t77*(t30+P[1][5]*t4+P[1][4]*t9+P[1][0]*t14-P[1][6]*t11-P[1][2]*t21+P[1][3]*t24);
  995. Kfusion[2] = t77*(-t78+P[2][5]*t4+P[2][4]*t9+P[2][0]*t14-P[2][6]*t11+P[2][1]*t18+P[2][3]*t24);
  996. Kfusion[3] = t77*(t66+P[3][5]*t4+P[3][4]*t9+P[3][0]*t14-P[3][6]*t11+P[3][1]*t18-P[3][2]*t21);
  997. Kfusion[4] = t77*(t69+P[4][5]*t4+P[4][0]*t14-P[4][6]*t11+P[4][1]*t18-P[4][2]*t21+P[4][3]*t24);
  998. Kfusion[5] = t77*(t32+P[5][4]*t9+P[5][0]*t14-P[5][6]*t11+P[5][1]*t18-P[5][2]*t21+P[5][3]*t24);
  999. Kfusion[6] = t77*(-t81+P[6][5]*t4+P[6][4]*t9+P[6][0]*t14+P[6][1]*t18-P[6][2]*t21+P[6][3]*t24);
  1000. Kfusion[7] = t77*(P[7][5]*t4+P[7][4]*t9+P[7][0]*t14-P[7][6]*t11+P[7][1]*t18-P[7][2]*t21+P[7][3]*t24);
  1001. Kfusion[8] = t77*(P[8][5]*t4+P[8][4]*t9+P[8][0]*t14-P[8][6]*t11+P[8][1]*t18-P[8][2]*t21+P[8][3]*t24);
  1002. Kfusion[9] = t77*(P[9][5]*t4+P[9][4]*t9+P[9][0]*t14-P[9][6]*t11+P[9][1]*t18-P[9][2]*t21+P[9][3]*t24);
  1003. if (!inhibitDelAngBiasStates) {
  1004. Kfusion[10] = t77*(P[10][5]*t4+P[10][4]*t9+P[10][0]*t14-P[10][6]*t11+P[10][1]*t18-P[10][2]*t21+P[10][3]*t24);
  1005. Kfusion[11] = t77*(P[11][5]*t4+P[11][4]*t9+P[11][0]*t14-P[11][6]*t11+P[11][1]*t18-P[11][2]*t21+P[11][3]*t24);
  1006. Kfusion[12] = t77*(P[12][5]*t4+P[12][4]*t9+P[12][0]*t14-P[12][6]*t11+P[12][1]*t18-P[12][2]*t21+P[12][3]*t24);
  1007. } else {
  1008. // zero indexes 10 to 12 = 3*4 bytes
  1009. memset(&Kfusion[10], 0, 12);
  1010. }
  1011. if (!inhibitDelVelBiasStates) {
  1012. Kfusion[13] = t77*(P[13][5]*t4+P[13][4]*t9+P[13][0]*t14-P[13][6]*t11+P[13][1]*t18-P[13][2]*t21+P[13][3]*t24);
  1013. Kfusion[14] = t77*(P[14][5]*t4+P[14][4]*t9+P[14][0]*t14-P[14][6]*t11+P[14][1]*t18-P[14][2]*t21+P[14][3]*t24);
  1014. Kfusion[15] = t77*(P[15][5]*t4+P[15][4]*t9+P[15][0]*t14-P[15][6]*t11+P[15][1]*t18-P[15][2]*t21+P[15][3]*t24);
  1015. } else {
  1016. // zero indexes 13 to 15 = 3*4 bytes
  1017. memset(&Kfusion[13], 0, 12);
  1018. }
  1019. if (!inhibitMagStates) {
  1020. Kfusion[16] = t77*(P[16][5]*t4+P[16][4]*t9+P[16][0]*t14-P[16][6]*t11+P[16][1]*t18-P[16][2]*t21+P[16][3]*t24);
  1021. Kfusion[17] = t77*(P[17][5]*t4+P[17][4]*t9+P[17][0]*t14-P[17][6]*t11+P[17][1]*t18-P[17][2]*t21+P[17][3]*t24);
  1022. Kfusion[18] = t77*(P[18][5]*t4+P[18][4]*t9+P[18][0]*t14-P[18][6]*t11+P[18][1]*t18-P[18][2]*t21+P[18][3]*t24);
  1023. Kfusion[19] = t77*(P[19][5]*t4+P[19][4]*t9+P[19][0]*t14-P[19][6]*t11+P[19][1]*t18-P[19][2]*t21+P[19][3]*t24);
  1024. Kfusion[20] = t77*(P[20][5]*t4+P[20][4]*t9+P[20][0]*t14-P[20][6]*t11+P[20][1]*t18-P[20][2]*t21+P[20][3]*t24);
  1025. Kfusion[21] = t77*(P[21][5]*t4+P[21][4]*t9+P[21][0]*t14-P[21][6]*t11+P[21][1]*t18-P[21][2]*t21+P[21][3]*t24);
  1026. } else {
  1027. // zero indexes 16 to 21 = 6*4 bytes
  1028. memset(&Kfusion[16], 0, 24);
  1029. }
  1030. if (!inhibitWindStates) {
  1031. Kfusion[22] = t77*(P[22][5]*t4+P[22][4]*t9+P[22][0]*t14-P[22][6]*t11+P[22][1]*t18-P[22][2]*t21+P[22][3]*t24);
  1032. Kfusion[23] = t77*(P[23][5]*t4+P[23][4]*t9+P[23][0]*t14-P[23][6]*t11+P[23][1]*t18-P[23][2]*t21+P[23][3]*t24);
  1033. } else {
  1034. // zero indexes 22 to 23 = 2*4 bytes
  1035. memset(&Kfusion[22], 0, 8);
  1036. }
  1037. } else if (obsIndex == 1) {
  1038. // calculate Y axis observation Jacobian
  1039. H_VEL[0] = q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f;
  1040. H_VEL[1] = q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f;
  1041. H_VEL[2] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
  1042. H_VEL[3] = q2*vd*2.0f-q3*ve*2.0f-q0*vn*2.0f;
  1043. H_VEL[4] = q0*q3*-2.0f+q1*q2*2.0f;
  1044. H_VEL[5] = q0*q0-q1*q1+q2*q2-q3*q3;
  1045. H_VEL[6] = q0*q1*2.0f+q2*q3*2.0f;
  1046. for (uint8_t index = 7; index < 24; index++) {
  1047. H_VEL[index] = 0.0f;
  1048. }
  1049. // calculate intermediate expressions for Y axis Kalman gains
  1050. float R_VEL = sq(bodyOdmDataDelayed.velErr);
  1051. float t2 = q0*q3*2.0f;
  1052. float t9 = q1*q2*2.0f;
  1053. float t3 = t2-t9;
  1054. float t4 = q0*q0;
  1055. float t5 = q1*q1;
  1056. float t6 = q2*q2;
  1057. float t7 = q3*q3;
  1058. float t8 = t4-t5+t6-t7;
  1059. float t10 = q0*q1*2.0f;
  1060. float t11 = q2*q3*2.0f;
  1061. float t12 = t10+t11;
  1062. float t13 = q1*vd*2.0f;
  1063. float t14 = q0*ve*2.0f;
  1064. float t26 = q3*vn*2.0f;
  1065. float t15 = t13+t14-t26;
  1066. float t16 = q0*vd*2.0f;
  1067. float t17 = q2*vn*2.0f;
  1068. float t27 = q1*ve*2.0f;
  1069. float t18 = t16+t17-t27;
  1070. float t19 = q3*vd*2.0f;
  1071. float t20 = q2*ve*2.0f;
  1072. float t21 = q1*vn*2.0f;
  1073. float t22 = t19+t20+t21;
  1074. float t23 = q3*ve*2.0f;
  1075. float t24 = q0*vn*2.0f;
  1076. float t28 = q2*vd*2.0f;
  1077. float t25 = t23+t24-t28;
  1078. float t29 = P[0][0]*t15;
  1079. float t30 = P[1][1]*t18;
  1080. float t31 = P[5][4]*t8;
  1081. float t32 = P[6][4]*t12;
  1082. float t33 = P[0][4]*t15;
  1083. float t34 = P[1][4]*t18;
  1084. float t35 = P[2][4]*t22;
  1085. float t78 = P[4][4]*t3;
  1086. float t79 = P[3][4]*t25;
  1087. float t36 = t31+t32+t33+t34+t35-t78-t79;
  1088. float t37 = P[5][6]*t8;
  1089. float t38 = P[6][6]*t12;
  1090. float t39 = P[0][6]*t15;
  1091. float t40 = P[1][6]*t18;
  1092. float t41 = P[2][6]*t22;
  1093. float t81 = P[4][6]*t3;
  1094. float t82 = P[3][6]*t25;
  1095. float t42 = t37+t38+t39+t40+t41-t81-t82;
  1096. float t43 = t12*t42;
  1097. float t44 = P[5][0]*t8;
  1098. float t45 = P[6][0]*t12;
  1099. float t46 = P[1][0]*t18;
  1100. float t47 = P[2][0]*t22;
  1101. float t83 = P[4][0]*t3;
  1102. float t84 = P[3][0]*t25;
  1103. float t48 = t29+t44+t45+t46+t47-t83-t84;
  1104. float t49 = t15*t48;
  1105. float t50 = P[5][1]*t8;
  1106. float t51 = P[6][1]*t12;
  1107. float t52 = P[0][1]*t15;
  1108. float t53 = P[2][1]*t22;
  1109. float t85 = P[4][1]*t3;
  1110. float t86 = P[3][1]*t25;
  1111. float t54 = t30+t50+t51+t52+t53-t85-t86;
  1112. float t55 = t18*t54;
  1113. float t56 = P[5][2]*t8;
  1114. float t57 = P[6][2]*t12;
  1115. float t58 = P[0][2]*t15;
  1116. float t59 = P[1][2]*t18;
  1117. float t60 = P[2][2]*t22;
  1118. float t87 = P[4][2]*t3;
  1119. float t88 = P[3][2]*t25;
  1120. float t61 = t56+t57+t58+t59+t60-t87-t88;
  1121. float t62 = t22*t61;
  1122. float t63 = P[5][3]*t8;
  1123. float t64 = P[6][3]*t12;
  1124. float t65 = P[0][3]*t15;
  1125. float t66 = P[1][3]*t18;
  1126. float t67 = P[2][3]*t22;
  1127. float t89 = P[4][3]*t3;
  1128. float t90 = P[3][3]*t25;
  1129. float t68 = t63+t64+t65+t66+t67-t89-t90;
  1130. float t69 = P[5][5]*t8;
  1131. float t70 = P[6][5]*t12;
  1132. float t71 = P[0][5]*t15;
  1133. float t72 = P[1][5]*t18;
  1134. float t73 = P[2][5]*t22;
  1135. float t92 = P[4][5]*t3;
  1136. float t93 = P[3][5]*t25;
  1137. float t74 = t69+t70+t71+t72+t73-t92-t93;
  1138. float t75 = t8*t74;
  1139. float t80 = t3*t36;
  1140. float t91 = t25*t68;
  1141. float t76 = R_VEL+t43+t49+t55+t62+t75-t80-t91;
  1142. float t77;
  1143. // calculate innovation variance for Y axis observation and protect against a badly conditioned calculation
  1144. if (t76 > R_VEL) {
  1145. t77 = 1.0f/t76;
  1146. faultStatus.bad_yvel = false;
  1147. } else {
  1148. t76 = R_VEL;
  1149. t77 = 1.0f/R_VEL;
  1150. faultStatus.bad_yvel = true;
  1151. return;
  1152. }
  1153. varInnovBodyVel[1] = t77;
  1154. // calculate innovation for Y axis observation
  1155. innovBodyVel[1] = bodyVelPred.y - bodyOdmDataDelayed.vel.y;
  1156. // calculate Kalman gains for Y-axis observation
  1157. Kfusion[0] = t77*(t29-P[0][4]*t3+P[0][5]*t8+P[0][6]*t12+P[0][1]*t18+P[0][2]*t22-P[0][3]*t25);
  1158. Kfusion[1] = t77*(t30-P[1][4]*t3+P[1][5]*t8+P[1][0]*t15+P[1][6]*t12+P[1][2]*t22-P[1][3]*t25);
  1159. Kfusion[2] = t77*(t60-P[2][4]*t3+P[2][5]*t8+P[2][0]*t15+P[2][6]*t12+P[2][1]*t18-P[2][3]*t25);
  1160. Kfusion[3] = t77*(-t90-P[3][4]*t3+P[3][5]*t8+P[3][0]*t15+P[3][6]*t12+P[3][1]*t18+P[3][2]*t22);
  1161. Kfusion[4] = t77*(-t78+P[4][5]*t8+P[4][0]*t15+P[4][6]*t12+P[4][1]*t18+P[4][2]*t22-P[4][3]*t25);
  1162. Kfusion[5] = t77*(t69-P[5][4]*t3+P[5][0]*t15+P[5][6]*t12+P[5][1]*t18+P[5][2]*t22-P[5][3]*t25);
  1163. Kfusion[6] = t77*(t38-P[6][4]*t3+P[6][5]*t8+P[6][0]*t15+P[6][1]*t18+P[6][2]*t22-P[6][3]*t25);
  1164. Kfusion[7] = t77*(-P[7][4]*t3+P[7][5]*t8+P[7][0]*t15+P[7][6]*t12+P[7][1]*t18+P[7][2]*t22-P[7][3]*t25);
  1165. Kfusion[8] = t77*(-P[8][4]*t3+P[8][5]*t8+P[8][0]*t15+P[8][6]*t12+P[8][1]*t18+P[8][2]*t22-P[8][3]*t25);
  1166. Kfusion[9] = t77*(-P[9][4]*t3+P[9][5]*t8+P[9][0]*t15+P[9][6]*t12+P[9][1]*t18+P[9][2]*t22-P[9][3]*t25);
  1167. if (!inhibitDelAngBiasStates) {
  1168. Kfusion[10] = t77*(-P[10][4]*t3+P[10][5]*t8+P[10][0]*t15+P[10][6]*t12+P[10][1]*t18+P[10][2]*t22-P[10][3]*t25);
  1169. Kfusion[11] = t77*(-P[11][4]*t3+P[11][5]*t8+P[11][0]*t15+P[11][6]*t12+P[11][1]*t18+P[11][2]*t22-P[11][3]*t25);
  1170. Kfusion[12] = t77*(-P[12][4]*t3+P[12][5]*t8+P[12][0]*t15+P[12][6]*t12+P[12][1]*t18+P[12][2]*t22-P[12][3]*t25);
  1171. } else {
  1172. // zero indexes 10 to 12 = 3*4 bytes
  1173. memset(&Kfusion[10], 0, 12);
  1174. }
  1175. if (!inhibitDelVelBiasStates) {
  1176. Kfusion[13] = t77*(-P[13][4]*t3+P[13][5]*t8+P[13][0]*t15+P[13][6]*t12+P[13][1]*t18+P[13][2]*t22-P[13][3]*t25);
  1177. Kfusion[14] = t77*(-P[14][4]*t3+P[14][5]*t8+P[14][0]*t15+P[14][6]*t12+P[14][1]*t18+P[14][2]*t22-P[14][3]*t25);
  1178. Kfusion[15] = t77*(-P[15][4]*t3+P[15][5]*t8+P[15][0]*t15+P[15][6]*t12+P[15][1]*t18+P[15][2]*t22-P[15][3]*t25);
  1179. } else {
  1180. // zero indexes 13 to 15 = 3*4 bytes
  1181. memset(&Kfusion[13], 0, 12);
  1182. }
  1183. if (!inhibitMagStates) {
  1184. Kfusion[16] = t77*(-P[16][4]*t3+P[16][5]*t8+P[16][0]*t15+P[16][6]*t12+P[16][1]*t18+P[16][2]*t22-P[16][3]*t25);
  1185. Kfusion[17] = t77*(-P[17][4]*t3+P[17][5]*t8+P[17][0]*t15+P[17][6]*t12+P[17][1]*t18+P[17][2]*t22-P[17][3]*t25);
  1186. Kfusion[18] = t77*(-P[18][4]*t3+P[18][5]*t8+P[18][0]*t15+P[18][6]*t12+P[18][1]*t18+P[18][2]*t22-P[18][3]*t25);
  1187. Kfusion[19] = t77*(-P[19][4]*t3+P[19][5]*t8+P[19][0]*t15+P[19][6]*t12+P[19][1]*t18+P[19][2]*t22-P[19][3]*t25);
  1188. Kfusion[20] = t77*(-P[20][4]*t3+P[20][5]*t8+P[20][0]*t15+P[20][6]*t12+P[20][1]*t18+P[20][2]*t22-P[20][3]*t25);
  1189. Kfusion[21] = t77*(-P[21][4]*t3+P[21][5]*t8+P[21][0]*t15+P[21][6]*t12+P[21][1]*t18+P[21][2]*t22-P[21][3]*t25);
  1190. } else {
  1191. // zero indexes 16 to 21 = 6*4 bytes
  1192. memset(&Kfusion[16], 0, 24);
  1193. }
  1194. if (!inhibitWindStates) {
  1195. Kfusion[22] = t77*(-P[22][4]*t3+P[22][5]*t8+P[22][0]*t15+P[22][6]*t12+P[22][1]*t18+P[22][2]*t22-P[22][3]*t25);
  1196. Kfusion[23] = t77*(-P[23][4]*t3+P[23][5]*t8+P[23][0]*t15+P[23][6]*t12+P[23][1]*t18+P[23][2]*t22-P[23][3]*t25);
  1197. } else {
  1198. // zero indexes 22 to 23 = 2*4 bytes
  1199. memset(&Kfusion[22], 0, 8);
  1200. }
  1201. } else if (obsIndex == 2) {
  1202. // calculate Z axis observation Jacobian
  1203. H_VEL[0] = q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f;
  1204. H_VEL[1] = q1*vd*-2.0f-q0*ve*2.0f+q3*vn*2.0f;
  1205. H_VEL[2] = q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f;
  1206. H_VEL[3] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
  1207. H_VEL[4] = q0*q2*2.0f+q1*q3*2.0f;
  1208. H_VEL[5] = q0*q1*-2.0f+q2*q3*2.0f;
  1209. H_VEL[6] = q0*q0-q1*q1-q2*q2+q3*q3;
  1210. for (uint8_t index = 7; index < 24; index++) {
  1211. H_VEL[index] = 0.0f;
  1212. }
  1213. // calculate intermediate expressions for Z axis Kalman gains
  1214. float R_VEL = sq(bodyOdmDataDelayed.velErr);
  1215. float t2 = q0*q2*2.0f;
  1216. float t3 = q1*q3*2.0f;
  1217. float t4 = t2+t3;
  1218. float t5 = q0*q0;
  1219. float t6 = q1*q1;
  1220. float t7 = q2*q2;
  1221. float t8 = q3*q3;
  1222. float t9 = t5-t6-t7+t8;
  1223. float t10 = q0*q1*2.0f;
  1224. float t25 = q2*q3*2.0f;
  1225. float t11 = t10-t25;
  1226. float t12 = q0*vd*2.0f;
  1227. float t13 = q2*vn*2.0f;
  1228. float t26 = q1*ve*2.0f;
  1229. float t14 = t12+t13-t26;
  1230. float t15 = q1*vd*2.0f;
  1231. float t16 = q0*ve*2.0f;
  1232. float t27 = q3*vn*2.0f;
  1233. float t17 = t15+t16-t27;
  1234. float t18 = q3*ve*2.0f;
  1235. float t19 = q0*vn*2.0f;
  1236. float t28 = q2*vd*2.0f;
  1237. float t20 = t18+t19-t28;
  1238. float t21 = q3*vd*2.0f;
  1239. float t22 = q2*ve*2.0f;
  1240. float t23 = q1*vn*2.0f;
  1241. float t24 = t21+t22+t23;
  1242. float t29 = P[0][0]*t14;
  1243. float t30 = P[6][4]*t9;
  1244. float t31 = P[4][4]*t4;
  1245. float t32 = P[0][4]*t14;
  1246. float t33 = P[2][4]*t20;
  1247. float t34 = P[3][4]*t24;
  1248. float t78 = P[5][4]*t11;
  1249. float t79 = P[1][4]*t17;
  1250. float t35 = t30+t31+t32+t33+t34-t78-t79;
  1251. float t36 = t4*t35;
  1252. float t37 = P[6][5]*t9;
  1253. float t38 = P[4][5]*t4;
  1254. float t39 = P[0][5]*t14;
  1255. float t40 = P[2][5]*t20;
  1256. float t41 = P[3][5]*t24;
  1257. float t80 = P[5][5]*t11;
  1258. float t81 = P[1][5]*t17;
  1259. float t42 = t37+t38+t39+t40+t41-t80-t81;
  1260. float t43 = P[6][0]*t9;
  1261. float t44 = P[4][0]*t4;
  1262. float t45 = P[2][0]*t20;
  1263. float t46 = P[3][0]*t24;
  1264. float t83 = P[5][0]*t11;
  1265. float t84 = P[1][0]*t17;
  1266. float t47 = t29+t43+t44+t45+t46-t83-t84;
  1267. float t48 = t14*t47;
  1268. float t49 = P[6][1]*t9;
  1269. float t50 = P[4][1]*t4;
  1270. float t51 = P[0][1]*t14;
  1271. float t52 = P[2][1]*t20;
  1272. float t53 = P[3][1]*t24;
  1273. float t85 = P[5][1]*t11;
  1274. float t86 = P[1][1]*t17;
  1275. float t54 = t49+t50+t51+t52+t53-t85-t86;
  1276. float t55 = P[6][2]*t9;
  1277. float t56 = P[4][2]*t4;
  1278. float t57 = P[0][2]*t14;
  1279. float t58 = P[2][2]*t20;
  1280. float t59 = P[3][2]*t24;
  1281. float t88 = P[5][2]*t11;
  1282. float t89 = P[1][2]*t17;
  1283. float t60 = t55+t56+t57+t58+t59-t88-t89;
  1284. float t61 = t20*t60;
  1285. float t62 = P[6][3]*t9;
  1286. float t63 = P[4][3]*t4;
  1287. float t64 = P[0][3]*t14;
  1288. float t65 = P[2][3]*t20;
  1289. float t66 = P[3][3]*t24;
  1290. float t90 = P[5][3]*t11;
  1291. float t91 = P[1][3]*t17;
  1292. float t67 = t62+t63+t64+t65+t66-t90-t91;
  1293. float t68 = t24*t67;
  1294. float t69 = P[6][6]*t9;
  1295. float t70 = P[4][6]*t4;
  1296. float t71 = P[0][6]*t14;
  1297. float t72 = P[2][6]*t20;
  1298. float t73 = P[3][6]*t24;
  1299. float t92 = P[5][6]*t11;
  1300. float t93 = P[1][6]*t17;
  1301. float t74 = t69+t70+t71+t72+t73-t92-t93;
  1302. float t75 = t9*t74;
  1303. float t82 = t11*t42;
  1304. float t87 = t17*t54;
  1305. float t76 = R_VEL+t36+t48+t61+t68+t75-t82-t87;
  1306. float t77;
  1307. // calculate innovation variance for Z axis observation and protect against a badly conditioned calculation
  1308. if (t76 > R_VEL) {
  1309. t77 = 1.0f/t76;
  1310. faultStatus.bad_zvel = false;
  1311. } else {
  1312. t76 = R_VEL;
  1313. t77 = 1.0f/R_VEL;
  1314. faultStatus.bad_zvel = true;
  1315. return;
  1316. }
  1317. varInnovBodyVel[2] = t77;
  1318. // calculate innovation for Z axis observation
  1319. innovBodyVel[2] = bodyVelPred.z - bodyOdmDataDelayed.vel.z;
  1320. // calculate Kalman gains for X-axis observation
  1321. Kfusion[0] = t77*(t29+P[0][4]*t4+P[0][6]*t9-P[0][5]*t11-P[0][1]*t17+P[0][2]*t20+P[0][3]*t24);
  1322. Kfusion[1] = t77*(P[1][4]*t4+P[1][0]*t14+P[1][6]*t9-P[1][5]*t11-P[1][1]*t17+P[1][2]*t20+P[1][3]*t24);
  1323. Kfusion[2] = t77*(t58+P[2][4]*t4+P[2][0]*t14+P[2][6]*t9-P[2][5]*t11-P[2][1]*t17+P[2][3]*t24);
  1324. Kfusion[3] = t77*(t66+P[3][4]*t4+P[3][0]*t14+P[3][6]*t9-P[3][5]*t11-P[3][1]*t17+P[3][2]*t20);
  1325. Kfusion[4] = t77*(t31+P[4][0]*t14+P[4][6]*t9-P[4][5]*t11-P[4][1]*t17+P[4][2]*t20+P[4][3]*t24);
  1326. Kfusion[5] = t77*(-t80+P[5][4]*t4+P[5][0]*t14+P[5][6]*t9-P[5][1]*t17+P[5][2]*t20+P[5][3]*t24);
  1327. Kfusion[6] = t77*(t69+P[6][4]*t4+P[6][0]*t14-P[6][5]*t11-P[6][1]*t17+P[6][2]*t20+P[6][3]*t24);
  1328. Kfusion[7] = t77*(P[7][4]*t4+P[7][0]*t14+P[7][6]*t9-P[7][5]*t11-P[7][1]*t17+P[7][2]*t20+P[7][3]*t24);
  1329. Kfusion[8] = t77*(P[8][4]*t4+P[8][0]*t14+P[8][6]*t9-P[8][5]*t11-P[8][1]*t17+P[8][2]*t20+P[8][3]*t24);
  1330. Kfusion[9] = t77*(P[9][4]*t4+P[9][0]*t14+P[9][6]*t9-P[9][5]*t11-P[9][1]*t17+P[9][2]*t20+P[9][3]*t24);
  1331. if (!inhibitDelAngBiasStates) {
  1332. Kfusion[10] = t77*(P[10][4]*t4+P[10][0]*t14+P[10][6]*t9-P[10][5]*t11-P[10][1]*t17+P[10][2]*t20+P[10][3]*t24);
  1333. Kfusion[11] = t77*(P[11][4]*t4+P[11][0]*t14+P[11][6]*t9-P[11][5]*t11-P[11][1]*t17+P[11][2]*t20+P[11][3]*t24);
  1334. Kfusion[12] = t77*(P[12][4]*t4+P[12][0]*t14+P[12][6]*t9-P[12][5]*t11-P[12][1]*t17+P[12][2]*t20+P[12][3]*t24);
  1335. } else {
  1336. // zero indexes 10 to 12 = 3*4 bytes
  1337. memset(&Kfusion[10], 0, 12);
  1338. }
  1339. if (!inhibitDelVelBiasStates) {
  1340. Kfusion[13] = t77*(P[13][4]*t4+P[13][0]*t14+P[13][6]*t9-P[13][5]*t11-P[13][1]*t17+P[13][2]*t20+P[13][3]*t24);
  1341. Kfusion[14] = t77*(P[14][4]*t4+P[14][0]*t14+P[14][6]*t9-P[14][5]*t11-P[14][1]*t17+P[14][2]*t20+P[14][3]*t24);
  1342. Kfusion[15] = t77*(P[15][4]*t4+P[15][0]*t14+P[15][6]*t9-P[15][5]*t11-P[15][1]*t17+P[15][2]*t20+P[15][3]*t24);
  1343. } else {
  1344. // zero indexes 13 to 15 = 3*4 bytes
  1345. memset(&Kfusion[13], 0, 12);
  1346. }
  1347. if (!inhibitMagStates) {
  1348. Kfusion[16] = t77*(P[16][4]*t4+P[16][0]*t14+P[16][6]*t9-P[16][5]*t11-P[16][1]*t17+P[16][2]*t20+P[16][3]*t24);
  1349. Kfusion[17] = t77*(P[17][4]*t4+P[17][0]*t14+P[17][6]*t9-P[17][5]*t11-P[17][1]*t17+P[17][2]*t20+P[17][3]*t24);
  1350. Kfusion[18] = t77*(P[18][4]*t4+P[18][0]*t14+P[18][6]*t9-P[18][5]*t11-P[18][1]*t17+P[18][2]*t20+P[18][3]*t24);
  1351. Kfusion[19] = t77*(P[19][4]*t4+P[19][0]*t14+P[19][6]*t9-P[19][5]*t11-P[19][1]*t17+P[19][2]*t20+P[19][3]*t24);
  1352. Kfusion[20] = t77*(P[20][4]*t4+P[20][0]*t14+P[20][6]*t9-P[20][5]*t11-P[20][1]*t17+P[20][2]*t20+P[20][3]*t24);
  1353. Kfusion[21] = t77*(P[21][4]*t4+P[21][0]*t14+P[21][6]*t9-P[21][5]*t11-P[21][1]*t17+P[21][2]*t20+P[21][3]*t24);
  1354. } else {
  1355. // zero indexes 16 to 21 = 6*4 bytes
  1356. memset(&Kfusion[16], 0, 24);
  1357. }
  1358. if (!inhibitWindStates) {
  1359. Kfusion[22] = t77*(P[22][4]*t4+P[22][0]*t14+P[22][6]*t9-P[22][5]*t11-P[22][1]*t17+P[22][2]*t20+P[22][3]*t24);
  1360. Kfusion[23] = t77*(P[23][4]*t4+P[23][0]*t14+P[23][6]*t9-P[23][5]*t11-P[23][1]*t17+P[23][2]*t20+P[23][3]*t24);
  1361. } else {
  1362. // zero indexes 22 to 23 = 2*4 bytes
  1363. memset(&Kfusion[22], 0, 8);
  1364. }
  1365. } else {
  1366. return;
  1367. }
  1368. // calculate the innovation consistency test ratio
  1369. // TODO add tuning parameter for gate
  1370. bodyVelTestRatio[obsIndex] = sq(innovBodyVel[obsIndex]) / (sq(5.0f) * varInnovBodyVel[obsIndex]);
  1371. // Check the innovation for consistency and don't fuse if out of bounds
  1372. // TODO also apply angular velocity magnitude check
  1373. if ((bodyVelTestRatio[obsIndex]) < 1.0f) {
  1374. // record the last time observations were accepted for fusion
  1375. prevBodyVelFuseTime_ms = imuSampleTime_ms;
  1376. // notify first time only
  1377. if (!bodyVelFusionActive) {
  1378. bodyVelFusionActive = true;
  1379. gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u fusing odometry",(unsigned)imu_index);
  1380. }
  1381. // correct the covariance P = (I - K*H)*P
  1382. // take advantage of the empty columns in KH to reduce the
  1383. // number of operations
  1384. for (unsigned i = 0; i<=stateIndexLim; i++) {
  1385. for (unsigned j = 0; j<=6; j++) {
  1386. KH[i][j] = Kfusion[i] * H_VEL[j];
  1387. }
  1388. for (unsigned j = 7; j<=stateIndexLim; j++) {
  1389. KH[i][j] = 0.0f;
  1390. }
  1391. }
  1392. for (unsigned j = 0; j<=stateIndexLim; j++) {
  1393. for (unsigned i = 0; i<=stateIndexLim; i++) {
  1394. ftype res = 0;
  1395. res += KH[i][0] * P[0][j];
  1396. res += KH[i][1] * P[1][j];
  1397. res += KH[i][2] * P[2][j];
  1398. res += KH[i][3] * P[3][j];
  1399. res += KH[i][4] * P[4][j];
  1400. res += KH[i][5] * P[5][j];
  1401. res += KH[i][6] * P[6][j];
  1402. KHP[i][j] = res;
  1403. }
  1404. }
  1405. // Check that we are not going to drive any variances negative and skip the update if so
  1406. bool healthyFusion = true;
  1407. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  1408. if (KHP[i][i] > P[i][i]) {
  1409. healthyFusion = false;
  1410. }
  1411. }
  1412. if (healthyFusion) {
  1413. // update the covariance matrix
  1414. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  1415. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  1416. P[i][j] = P[i][j] - KHP[i][j];
  1417. }
  1418. }
  1419. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  1420. ForceSymmetry();
  1421. ConstrainVariances();
  1422. // correct the state vector
  1423. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  1424. statesArray[j] = statesArray[j] - Kfusion[j] * innovBodyVel[obsIndex];
  1425. }
  1426. stateStruct.quat.normalize();
  1427. } else {
  1428. // record bad axis
  1429. if (obsIndex == 0) {
  1430. faultStatus.bad_xvel = true;
  1431. } else if (obsIndex == 1) {
  1432. faultStatus.bad_yvel = true;
  1433. } else if (obsIndex == 2) {
  1434. faultStatus.bad_zvel = true;
  1435. }
  1436. }
  1437. }
  1438. }
  1439. }
  1440. // select fusion of body odometry measurements
  1441. void NavEKF3_core::SelectBodyOdomFusion()
  1442. {
  1443. // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
  1444. // If so, don't fuse measurements on this time step to reduce frame over-runs
  1445. // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
  1446. if (magFusePerformed && (dtIMUavg < 0.005f) && !bodyVelFusionDelayed) {
  1447. bodyVelFusionDelayed = true;
  1448. return;
  1449. } else {
  1450. bodyVelFusionDelayed = false;
  1451. }
  1452. // Check for data at the fusion time horizon
  1453. if (storedBodyOdm.recall(bodyOdmDataDelayed, imuDataDelayed.time_ms)) {
  1454. // start performance timer
  1455. hal.util->perf_begin(_perf_FuseBodyOdom);
  1456. usingWheelSensors = false;
  1457. // Fuse data into the main filter
  1458. FuseBodyVel();
  1459. // stop the performance timer
  1460. hal.util->perf_end(_perf_FuseBodyOdom);
  1461. } else if (storedWheelOdm.recall(wheelOdmDataDelayed, imuDataDelayed.time_ms)) {
  1462. // check if the delta time is too small to calculate a velocity
  1463. if (wheelOdmDataDelayed.delTime > EKF_TARGET_DT) {
  1464. // get the forward velocity
  1465. float fwdSpd = wheelOdmDataDelayed.delAng * wheelOdmDataDelayed.radius * (1.0f / wheelOdmDataDelayed.delTime);
  1466. // get the unit vector from the projection of the X axis onto the horizontal
  1467. Vector3f unitVec;
  1468. unitVec.x = prevTnb.a.x;
  1469. unitVec.y = prevTnb.a.y;
  1470. unitVec.z = 0.0f;
  1471. unitVec.normalize();
  1472. // multiply by forward speed to get velocity vector measured by wheel encoders
  1473. Vector3f velNED = unitVec * fwdSpd;
  1474. // This is a hack to enable use of the existing body frame velocity fusion method
  1475. // TODO write a dedicated observation model for wheel encoders
  1476. usingWheelSensors = true;
  1477. bodyOdmDataDelayed.vel = prevTnb * velNED;
  1478. bodyOdmDataDelayed.body_offset = wheelOdmDataDelayed.hub_offset;
  1479. bodyOdmDataDelayed.velErr = frontend->_wencOdmVelErr;
  1480. // Fuse data into the main filter
  1481. FuseBodyVel();
  1482. }
  1483. }
  1484. }