AP_NavEKF2_OptFlowFusion.cpp 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735
  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 <stdio.h>
  7. extern const AP_HAL::HAL& hal;
  8. /********************************************************
  9. * RESET FUNCTIONS *
  10. ********************************************************/
  11. /********************************************************
  12. * FUSE MEASURED_DATA *
  13. ********************************************************/
  14. // select fusion of optical flow measurements
  15. void NavEKF2_core::SelectFlowFusion()
  16. {
  17. // Check if the magnetometer has been fused on that time step and the filter is running at faster than 200 Hz
  18. // If so, don't fuse measurements on this time step to reduce frame over-runs
  19. // Only allow one time slip to prevent high rate magnetometer data preventing fusion of other measurements
  20. if (magFusePerformed && dtIMUavg < 0.005f && !optFlowFusionDelayed) {
  21. optFlowFusionDelayed = true;
  22. return;
  23. } else {
  24. optFlowFusionDelayed = false;
  25. }
  26. // start performance timer
  27. hal.util->perf_begin(_perf_FuseOptFlow);
  28. // Perform Data Checks
  29. // Check if the optical flow data is still valid
  30. flowDataValid = ((imuSampleTime_ms - flowValidMeaTime_ms) < 1000);
  31. // check is the terrain offset estimate is still valid - if we are using range finder as the main height reference, the ground is assumed to be at 0
  32. gndOffsetValid = ((imuSampleTime_ms - gndHgtValidTime_ms) < 5000) || (activeHgtSource == HGT_SOURCE_RNG);
  33. // Perform tilt check
  34. bool tiltOK = (prevTnb.c.z > frontend->DCM33FlowMin);
  35. // Constrain measurements to zero if takeoff is not detected and the height above ground
  36. // is insuffient to achieve acceptable focus. This allows the vehicle to be picked up
  37. // and carried to test optical flow operation
  38. if (!takeOffDetected && ((terrainState - stateStruct.position.z) < 0.5f)) {
  39. ofDataDelayed.flowRadXYcomp.zero();
  40. ofDataDelayed.flowRadXY.zero();
  41. flowDataValid = true;
  42. }
  43. // if have valid flow or range measurements, fuse data into a 1-state EKF to estimate terrain height
  44. if (((flowDataToFuse && (frontend->_flowUse == FLOW_USE_TERRAIN)) || rangeDataToFuse) && tiltOK) {
  45. // Estimate the terrain offset (runs a one state EKF)
  46. EstimateTerrainOffset();
  47. }
  48. // Fuse optical flow data into the main filter
  49. if (flowDataToFuse && tiltOK) {
  50. if (frontend->_flowUse == FLOW_USE_NAV) {
  51. // Set the flow noise used by the fusion processes
  52. R_LOS = sq(MAX(frontend->_flowNoise, 0.05f));
  53. // Fuse the optical flow X and Y axis data into the main filter sequentially
  54. FuseOptFlow();
  55. }
  56. // reset flag to indicate that no new flow data is available for fusion
  57. flowDataToFuse = false;
  58. }
  59. // stop the performance timer
  60. hal.util->perf_end(_perf_FuseOptFlow);
  61. }
  62. /*
  63. Estimation of terrain offset using a single state EKF
  64. The filter can fuse motion compensated optical flow rates and range finder measurements
  65. Equations generated using https://github.com/PX4/ecl/tree/master/EKF/matlab/scripts/Terrain%20Estimator
  66. */
  67. void NavEKF2_core::EstimateTerrainOffset()
  68. {
  69. // start performance timer
  70. hal.util->perf_begin(_perf_TerrainOffset);
  71. // horizontal velocity squared
  72. float velHorizSq = sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y);
  73. // don't fuse flow data if LOS rate is misaligned, without GPS, or insufficient velocity, as it is poorly observable
  74. // don't fuse flow data if it exceeds validity limits
  75. // don't update terrain offset if grpund is being used as the zero height datum in the main filter
  76. bool cantFuseFlowData = ((frontend->_flowUse != FLOW_USE_TERRAIN)
  77. || gpsNotAvailable
  78. || PV_AidingMode == AID_RELATIVE
  79. || velHorizSq < 25.0f
  80. || (MAX(ofDataDelayed.flowRadXY[0],ofDataDelayed.flowRadXY[1]) > frontend->_maxFlowRate));
  81. if ((!rangeDataToFuse && cantFuseFlowData) || (activeHgtSource == HGT_SOURCE_RNG)) {
  82. // skip update
  83. inhibitGndState = true;
  84. } else {
  85. inhibitGndState = false;
  86. // record the time we last updated the terrain offset state
  87. gndHgtValidTime_ms = imuSampleTime_ms;
  88. // propagate ground position state noise each time this is called using the difference in position since the last observations and an RMS gradient assumption
  89. // limit distance to prevent intialisation afer bad gps causing bad numerical conditioning
  90. float distanceTravelledSq = sq(stateStruct.position[0] - prevPosN) + sq(stateStruct.position[1] - prevPosE);
  91. distanceTravelledSq = MIN(distanceTravelledSq, 100.0f);
  92. prevPosN = stateStruct.position[0];
  93. prevPosE = stateStruct.position[1];
  94. // in addition to a terrain gradient error model, we also have the growth in uncertainty due to the copters vertical velocity
  95. float timeLapsed = MIN(0.001f * (imuSampleTime_ms - timeAtLastAuxEKF_ms), 1.0f);
  96. float Pincrement = (distanceTravelledSq * sq(frontend->_terrGradMax)) + sq(timeLapsed)*P[5][5];
  97. Popt += Pincrement;
  98. timeAtLastAuxEKF_ms = imuSampleTime_ms;
  99. // fuse range finder data
  100. if (rangeDataToFuse) {
  101. // predict range
  102. float predRngMeas = MAX((terrainState - stateStruct.position[2]),rngOnGnd) / prevTnb.c.z;
  103. // Copy required states to local variable names
  104. float q0 = stateStruct.quat[0]; // quaternion at optical flow measurement time
  105. float q1 = stateStruct.quat[1]; // quaternion at optical flow measurement time
  106. float q2 = stateStruct.quat[2]; // quaternion at optical flow measurement time
  107. float q3 = stateStruct.quat[3]; // quaternion at optical flow measurement time
  108. // Set range finder measurement noise variance. TODO make this a function of range and tilt to allow for sensor, alignment and AHRS errors
  109. float R_RNG = frontend->_rngNoise;
  110. // calculate Kalman gain
  111. float SK_RNG = sq(q0) - sq(q1) - sq(q2) + sq(q3);
  112. float K_RNG = Popt/(SK_RNG*(R_RNG + Popt/sq(SK_RNG)));
  113. // Calculate the innovation variance for data logging
  114. varInnovRng = (R_RNG + Popt/sq(SK_RNG));
  115. // constrain terrain height to be below the vehicle
  116. terrainState = MAX(terrainState, stateStruct.position[2] + rngOnGnd);
  117. // Calculate the measurement innovation
  118. innovRng = predRngMeas - rangeDataDelayed.rng;
  119. // calculate the innovation consistency test ratio
  120. auxRngTestRatio = sq(innovRng) / (sq(MAX(0.01f * (float)frontend->_rngInnovGate, 1.0f)) * varInnovRng);
  121. // Check the innovation test ratio and don't fuse if too large
  122. if (auxRngTestRatio < 1.0f) {
  123. // correct the state
  124. terrainState -= K_RNG * innovRng;
  125. // constrain the state
  126. terrainState = MAX(terrainState, stateStruct.position[2] + rngOnGnd);
  127. // correct the covariance
  128. Popt = Popt - sq(Popt)/(SK_RNG*(R_RNG + Popt/sq(SK_RNG))*(sq(q0) - sq(q1) - sq(q2) + sq(q3)));
  129. // prevent the state variance from becoming negative
  130. Popt = MAX(Popt,0.0f);
  131. }
  132. }
  133. if (!cantFuseFlowData) {
  134. Vector3f relVelSensor; // velocity of sensor relative to ground in sensor axes
  135. Vector2f losPred; // predicted optical flow angular rate measurement
  136. float q0 = stateStruct.quat[0]; // quaternion at optical flow measurement time
  137. float q1 = stateStruct.quat[1]; // quaternion at optical flow measurement time
  138. float q2 = stateStruct.quat[2]; // quaternion at optical flow measurement time
  139. float q3 = stateStruct.quat[3]; // quaternion at optical flow measurement time
  140. float K_OPT;
  141. float H_OPT;
  142. Vector2f auxFlowObsInnovVar;
  143. // predict range to centre of image
  144. float flowRngPred = MAX((terrainState - stateStruct.position.z),rngOnGnd) / prevTnb.c.z;
  145. // constrain terrain height to be below the vehicle
  146. terrainState = MAX(terrainState, stateStruct.position.z + rngOnGnd);
  147. // calculate relative velocity in sensor frame
  148. relVelSensor = prevTnb*stateStruct.velocity;
  149. // divide velocity by range, subtract body rates and apply scale factor to
  150. // get predicted sensed angular optical rates relative to X and Y sensor axes
  151. losPred.x = relVelSensor.y / flowRngPred;
  152. losPred.y = - relVelSensor.x / flowRngPred;
  153. // calculate innovations
  154. auxFlowObsInnov = losPred - ofDataDelayed.flowRadXYcomp;
  155. // calculate observation jacobians
  156. float t2 = q0*q0;
  157. float t3 = q1*q1;
  158. float t4 = q2*q2;
  159. float t5 = q3*q3;
  160. float t6 = stateStruct.position.z - terrainState;
  161. float t7 = 1.0f / (t6*t6);
  162. float t8 = q0*q3*2.0f;
  163. float t9 = t2-t3-t4+t5;
  164. // prevent the state variances from becoming badly conditioned
  165. Popt = MAX(Popt,1E-6f);
  166. // calculate observation noise variance from parameter
  167. float flow_noise_variance = sq(MAX(frontend->_flowNoise, 0.05f));
  168. // Fuse Y axis data
  169. // Calculate observation partial derivative
  170. H_OPT = t7*t9*(-stateStruct.velocity.z*(q0*q2*2.0-q1*q3*2.0)+stateStruct.velocity.x*(t2+t3-t4-t5)+stateStruct.velocity.y*(t8+q1*q2*2.0));
  171. // calculate innovation variance
  172. auxFlowObsInnovVar.y = H_OPT * Popt * H_OPT + flow_noise_variance;
  173. // calculate Kalman gain
  174. K_OPT = Popt * H_OPT / auxFlowObsInnovVar.y;
  175. // calculate the innovation consistency test ratio
  176. auxFlowTestRatio.y = sq(auxFlowObsInnov.y) / (sq(MAX(0.01f * (float)frontend->_flowInnovGate, 1.0f)) * auxFlowObsInnovVar.y);
  177. // don't fuse if optical flow data is outside valid range
  178. if (auxFlowTestRatio.y < 1.0f) {
  179. // correct the state
  180. terrainState -= K_OPT * auxFlowObsInnov.y;
  181. // constrain the state
  182. terrainState = MAX(terrainState, stateStruct.position.z + rngOnGnd);
  183. // update intermediate variables used when fusing the X axis
  184. t6 = stateStruct.position.z - terrainState;
  185. t7 = 1.0f / (t6*t6);
  186. // correct the covariance
  187. Popt = Popt - K_OPT * H_OPT * Popt;
  188. // prevent the state variances from becoming badly conditioned
  189. Popt = MAX(Popt,1E-6f);
  190. }
  191. // fuse X axis data
  192. H_OPT = -t7*t9*(stateStruct.velocity.z*(q0*q1*2.0+q2*q3*2.0)+stateStruct.velocity.y*(t2-t3+t4-t5)-stateStruct.velocity.x*(t8-q1*q2*2.0));
  193. // calculate innovation variances
  194. auxFlowObsInnovVar.x = H_OPT * Popt * H_OPT + flow_noise_variance;
  195. // calculate Kalman gain
  196. K_OPT = Popt * H_OPT / auxFlowObsInnovVar.x;
  197. // calculate the innovation consistency test ratio
  198. auxFlowTestRatio.x = sq(auxFlowObsInnov.x) / (sq(MAX(0.01f * (float)frontend->_flowInnovGate, 1.0f)) * auxFlowObsInnovVar.x);
  199. // don't fuse if optical flow data is outside valid range
  200. if (auxFlowTestRatio.x < 1.0f) {
  201. // correct the state
  202. terrainState -= K_OPT * auxFlowObsInnov.x;
  203. // constrain the state
  204. terrainState = MAX(terrainState, stateStruct.position.z + rngOnGnd);
  205. // correct the covariance
  206. Popt = Popt - K_OPT * H_OPT * Popt;
  207. // prevent the state variances from becoming badly conditioned
  208. Popt = MAX(Popt,1E-6f);
  209. }
  210. }
  211. }
  212. // stop the performance timer
  213. hal.util->perf_end(_perf_TerrainOffset);
  214. }
  215. /*
  216. * Fuse angular motion compensated optical flow rates using explicit algebraic equations generated with Matlab symbolic toolbox.
  217. * The script file used to generate these and other equations in this filter can be found here:
  218. * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
  219. * Requires a valid terrain height estimate.
  220. */
  221. void NavEKF2_core::FuseOptFlow()
  222. {
  223. Vector24 H_LOS;
  224. Vector3f relVelSensor;
  225. Vector14 SH_LOS;
  226. Vector2 losPred;
  227. // Copy required states to local variable names
  228. float q0 = stateStruct.quat[0];
  229. float q1 = stateStruct.quat[1];
  230. float q2 = stateStruct.quat[2];
  231. float q3 = stateStruct.quat[3];
  232. float vn = stateStruct.velocity.x;
  233. float ve = stateStruct.velocity.y;
  234. float vd = stateStruct.velocity.z;
  235. float pd = stateStruct.position.z;
  236. // constrain height above ground to be above range measured on ground
  237. float heightAboveGndEst = MAX((terrainState - pd), rngOnGnd);
  238. float ptd = pd + heightAboveGndEst;
  239. // Calculate common expressions for observation jacobians
  240. SH_LOS[0] = sq(q0) - sq(q1) - sq(q2) + sq(q3);
  241. SH_LOS[1] = vn*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + ve*(2*q0*q3 + 2*q1*q2);
  242. SH_LOS[2] = ve*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + vd*(2*q0*q1 + 2*q2*q3) - vn*(2*q0*q3 - 2*q1*q2);
  243. SH_LOS[3] = 1/(pd - ptd);
  244. SH_LOS[4] = vd*SH_LOS[0] - ve*(2*q0*q1 - 2*q2*q3) + vn*(2*q0*q2 + 2*q1*q3);
  245. SH_LOS[5] = 2.0f*q0*q2 - 2.0f*q1*q3;
  246. SH_LOS[6] = 2.0f*q0*q1 + 2.0f*q2*q3;
  247. SH_LOS[7] = q0*q0;
  248. SH_LOS[8] = q1*q1;
  249. SH_LOS[9] = q2*q2;
  250. SH_LOS[10] = q3*q3;
  251. SH_LOS[11] = q0*q3*2.0f;
  252. SH_LOS[12] = pd-ptd;
  253. SH_LOS[13] = 1.0f/(SH_LOS[12]*SH_LOS[12]);
  254. // Fuse X and Y axis measurements sequentially assuming observation errors are uncorrelated
  255. for (uint8_t obsIndex=0; obsIndex<=1; obsIndex++) { // fuse X axis data first
  256. // calculate range from ground plain to centre of sensor fov assuming flat earth
  257. float range = constrain_float((heightAboveGndEst/prevTnb.c.z),rngOnGnd,1000.0f);
  258. // correct range for flow sensor offset body frame position offset
  259. // the corrected value is the predicted range from the sensor focal point to the
  260. // centre of the image on the ground assuming flat terrain
  261. Vector3f posOffsetBody = (*ofDataDelayed.body_offset) - accelPosOffset;
  262. if (!posOffsetBody.is_zero()) {
  263. Vector3f posOffsetEarth = prevTnb.mul_transpose(posOffsetBody);
  264. range -= posOffsetEarth.z / prevTnb.c.z;
  265. }
  266. // calculate relative velocity in sensor frame including the relative motion due to rotation
  267. relVelSensor = prevTnb*stateStruct.velocity + ofDataDelayed.bodyRadXYZ % posOffsetBody;
  268. // divide velocity by range to get predicted angular LOS rates relative to X and Y axes
  269. losPred[0] = relVelSensor.y/range;
  270. losPred[1] = -relVelSensor.x/range;
  271. // calculate observation jacobians and Kalman gains
  272. memset(&H_LOS[0], 0, sizeof(H_LOS));
  273. if (obsIndex == 0) {
  274. H_LOS[0] = SH_LOS[3]*SH_LOS[2]*SH_LOS[6]-SH_LOS[3]*SH_LOS[0]*SH_LOS[4];
  275. H_LOS[1] = SH_LOS[3]*SH_LOS[2]*SH_LOS[5];
  276. H_LOS[2] = SH_LOS[3]*SH_LOS[0]*SH_LOS[1];
  277. H_LOS[3] = SH_LOS[3]*SH_LOS[0]*(SH_LOS[11]-q1*q2*2.0f);
  278. H_LOS[4] = -SH_LOS[3]*SH_LOS[0]*(SH_LOS[7]-SH_LOS[8]+SH_LOS[9]-SH_LOS[10]);
  279. H_LOS[5] = -SH_LOS[3]*SH_LOS[0]*SH_LOS[6];
  280. H_LOS[8] = SH_LOS[2]*SH_LOS[0]*SH_LOS[13];
  281. float t2 = SH_LOS[3];
  282. float t3 = SH_LOS[0];
  283. float t4 = SH_LOS[2];
  284. float t5 = SH_LOS[6];
  285. float t100 = t2 * t3 * t5;
  286. float t6 = SH_LOS[4];
  287. float t7 = t2*t3*t6;
  288. float t9 = t2*t4*t5;
  289. float t8 = t7-t9;
  290. float t10 = q0*q3*2.0f;
  291. float t21 = q1*q2*2.0f;
  292. float t11 = t10-t21;
  293. float t101 = t2 * t3 * t11;
  294. float t12 = pd-ptd;
  295. float t13 = 1.0f/(t12*t12);
  296. float t104 = t3 * t4 * t13;
  297. float t14 = SH_LOS[5];
  298. float t102 = t2 * t4 * t14;
  299. float t15 = SH_LOS[1];
  300. float t103 = t2 * t3 * t15;
  301. float t16 = q0*q0;
  302. float t17 = q1*q1;
  303. float t18 = q2*q2;
  304. float t19 = q3*q3;
  305. float t20 = t16-t17+t18-t19;
  306. float t105 = t2 * t3 * t20;
  307. float t22 = P[1][1]*t102;
  308. float t23 = P[3][0]*t101;
  309. float t24 = P[8][0]*t104;
  310. float t25 = P[1][0]*t102;
  311. float t26 = P[2][0]*t103;
  312. float t63 = P[0][0]*t8;
  313. float t64 = P[5][0]*t100;
  314. float t65 = P[4][0]*t105;
  315. float t27 = t23+t24+t25+t26-t63-t64-t65;
  316. float t28 = P[3][3]*t101;
  317. float t29 = P[8][3]*t104;
  318. float t30 = P[1][3]*t102;
  319. float t31 = P[2][3]*t103;
  320. float t67 = P[0][3]*t8;
  321. float t68 = P[5][3]*t100;
  322. float t69 = P[4][3]*t105;
  323. float t32 = t28+t29+t30+t31-t67-t68-t69;
  324. float t33 = t101*t32;
  325. float t34 = P[3][8]*t101;
  326. float t35 = P[8][8]*t104;
  327. float t36 = P[1][8]*t102;
  328. float t37 = P[2][8]*t103;
  329. float t70 = P[0][8]*t8;
  330. float t71 = P[5][8]*t100;
  331. float t72 = P[4][8]*t105;
  332. float t38 = t34+t35+t36+t37-t70-t71-t72;
  333. float t39 = t104*t38;
  334. float t40 = P[3][1]*t101;
  335. float t41 = P[8][1]*t104;
  336. float t42 = P[2][1]*t103;
  337. float t73 = P[0][1]*t8;
  338. float t74 = P[5][1]*t100;
  339. float t75 = P[4][1]*t105;
  340. float t43 = t22+t40+t41+t42-t73-t74-t75;
  341. float t44 = t102*t43;
  342. float t45 = P[3][2]*t101;
  343. float t46 = P[8][2]*t104;
  344. float t47 = P[1][2]*t102;
  345. float t48 = P[2][2]*t103;
  346. float t76 = P[0][2]*t8;
  347. float t77 = P[5][2]*t100;
  348. float t78 = P[4][2]*t105;
  349. float t49 = t45+t46+t47+t48-t76-t77-t78;
  350. float t50 = t103*t49;
  351. float t51 = P[3][5]*t101;
  352. float t52 = P[8][5]*t104;
  353. float t53 = P[1][5]*t102;
  354. float t54 = P[2][5]*t103;
  355. float t79 = P[0][5]*t8;
  356. float t80 = P[5][5]*t100;
  357. float t81 = P[4][5]*t105;
  358. float t55 = t51+t52+t53+t54-t79-t80-t81;
  359. float t56 = P[3][4]*t101;
  360. float t57 = P[8][4]*t104;
  361. float t58 = P[1][4]*t102;
  362. float t59 = P[2][4]*t103;
  363. float t83 = P[0][4]*t8;
  364. float t84 = P[5][4]*t100;
  365. float t85 = P[4][4]*t105;
  366. float t60 = t56+t57+t58+t59-t83-t84-t85;
  367. float t66 = t8*t27;
  368. float t82 = t100*t55;
  369. float t86 = t105*t60;
  370. float t61 = R_LOS+t33+t39+t44+t50-t66-t82-t86;
  371. float t62 = 1.0f/t61;
  372. // calculate innovation variance for X axis observation and protect against a badly conditioned calculation
  373. if (t61 > R_LOS) {
  374. t62 = 1.0f/t61;
  375. faultStatus.bad_yflow = false;
  376. } else {
  377. t61 = 0.0f;
  378. t62 = 1.0f/R_LOS;
  379. faultStatus.bad_yflow = true;
  380. return;
  381. }
  382. varInnovOptFlow[0] = t61;
  383. // calculate innovation for X axis observation
  384. innovOptFlow[0] = losPred[0] - ofDataDelayed.flowRadXYcomp.x;
  385. // calculate Kalman gains for X-axis observation
  386. Kfusion[0] = t62*(-P[0][0]*t8-P[0][5]*t100+P[0][3]*t101+P[0][1]*t102+P[0][2]*t103+P[0][8]*t104-P[0][4]*t105);
  387. Kfusion[1] = t62*(t22-P[1][0]*t8-P[1][5]*t100+P[1][3]*t101+P[1][2]*t103+P[1][8]*t104-P[1][4]*t105);
  388. Kfusion[2] = t62*(t48-P[2][0]*t8-P[2][5]*t100+P[2][3]*t101+P[2][1]*t102+P[2][8]*t104-P[2][4]*t105);
  389. Kfusion[3] = t62*(t28-P[3][0]*t8-P[3][5]*t100+P[3][1]*t102+P[3][2]*t103+P[3][8]*t104-P[3][4]*t105);
  390. Kfusion[4] = t62*(-t85-P[4][0]*t8-P[4][5]*t100+P[4][3]*t101+P[4][1]*t102+P[4][2]*t103+P[4][8]*t104);
  391. Kfusion[5] = t62*(-t80-P[5][0]*t8+P[5][3]*t101+P[5][1]*t102+P[5][2]*t103+P[5][8]*t104-P[5][4]*t105);
  392. Kfusion[6] = t62*(-P[6][0]*t8-P[6][5]*t100+P[6][3]*t101+P[6][1]*t102+P[6][2]*t103+P[6][8]*t104-P[6][4]*t105);
  393. Kfusion[7] = t62*(-P[7][0]*t8-P[7][5]*t100+P[7][3]*t101+P[7][1]*t102+P[7][2]*t103+P[7][8]*t104-P[7][4]*t105);
  394. Kfusion[8] = t62*(t35-P[8][0]*t8-P[8][5]*t100+P[8][3]*t101+P[8][1]*t102+P[8][2]*t103-P[8][4]*t105);
  395. Kfusion[9] = t62*(-P[9][0]*t8-P[9][5]*t100+P[9][3]*t101+P[9][1]*t102+P[9][2]*t103+P[9][8]*t104-P[9][4]*t105);
  396. Kfusion[10] = t62*(-P[10][0]*t8-P[10][5]*t100+P[10][3]*t101+P[10][1]*t102+P[10][2]*t103+P[10][8]*t104-P[10][4]*t105);
  397. Kfusion[11] = t62*(-P[11][0]*t8-P[11][5]*t100+P[11][3]*t101+P[11][1]*t102+P[11][2]*t103+P[11][8]*t104-P[11][4]*t105);
  398. Kfusion[12] = t62*(-P[12][0]*t8-P[12][5]*t100+P[12][3]*t101+P[12][1]*t102+P[12][2]*t103+P[12][8]*t104-P[12][4]*t105);
  399. Kfusion[13] = t62*(-P[13][0]*t8-P[13][5]*t100+P[13][3]*t101+P[13][1]*t102+P[13][2]*t103+P[13][8]*t104-P[13][4]*t105);
  400. Kfusion[14] = t62*(-P[14][0]*t8-P[14][5]*t100+P[14][3]*t101+P[14][1]*t102+P[14][2]*t103+P[14][8]*t104-P[14][4]*t105);
  401. Kfusion[15] = t62*(-P[15][0]*t8-P[15][5]*t100+P[15][3]*t101+P[15][1]*t102+P[15][2]*t103+P[15][8]*t104-P[15][4]*t105);
  402. if (!inhibitWindStates) {
  403. Kfusion[22] = t62*(-P[22][0]*t8-P[22][5]*t100+P[22][3]*t101+P[22][1]*t102+P[22][2]*t103+P[22][8]*t104-P[22][4]*t105);
  404. Kfusion[23] = t62*(-P[23][0]*t8-P[23][5]*t100+P[23][3]*t101+P[23][1]*t102+P[23][2]*t103+P[23][8]*t104-P[23][4]*t105);
  405. } else {
  406. Kfusion[22] = 0.0f;
  407. Kfusion[23] = 0.0f;
  408. }
  409. if (!inhibitMagStates) {
  410. Kfusion[16] = t62*(-P[16][0]*t8-P[16][5]*t100+P[16][3]*t101+P[16][1]*t102+P[16][2]*t103+P[16][8]*t104-P[16][4]*t105);
  411. Kfusion[17] = t62*(-P[17][0]*t8-P[17][5]*t100+P[17][3]*t101+P[17][1]*t102+P[17][2]*t103+P[17][8]*t104-P[17][4]*t105);
  412. Kfusion[18] = t62*(-P[18][0]*t8-P[18][5]*t100+P[18][3]*t101+P[18][1]*t102+P[18][2]*t103+P[18][8]*t104-P[18][4]*t105);
  413. Kfusion[19] = t62*(-P[19][0]*t8-P[19][5]*t100+P[19][3]*t101+P[19][1]*t102+P[19][2]*t103+P[19][8]*t104-P[19][4]*t105);
  414. Kfusion[20] = t62*(-P[20][0]*t8-P[20][5]*t100+P[20][3]*t101+P[20][1]*t102+P[20][2]*t103+P[20][8]*t104-P[20][4]*t105);
  415. Kfusion[21] = t62*(-P[21][0]*t8-P[21][5]*t100+P[21][3]*t101+P[21][1]*t102+P[21][2]*t103+P[21][8]*t104-P[21][4]*t105);
  416. } else {
  417. for (uint8_t i = 16; i <= 21; i++) {
  418. Kfusion[i] = 0.0f;
  419. }
  420. }
  421. } else {
  422. H_LOS[0] = -SH_LOS[3]*SH_LOS[6]*SH_LOS[1];
  423. H_LOS[1] = -SH_LOS[3]*SH_LOS[0]*SH_LOS[4]-SH_LOS[3]*SH_LOS[1]*SH_LOS[5];
  424. H_LOS[2] = SH_LOS[3]*SH_LOS[2]*SH_LOS[0];
  425. H_LOS[3] = SH_LOS[3]*SH_LOS[0]*(SH_LOS[7]+SH_LOS[8]-SH_LOS[9]-SH_LOS[10]);
  426. H_LOS[4] = SH_LOS[3]*SH_LOS[0]*(SH_LOS[11]+q1*q2*2.0f);
  427. H_LOS[5] = -SH_LOS[3]*SH_LOS[0]*SH_LOS[5];
  428. H_LOS[8] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[13];
  429. float t2 = SH_LOS[3];
  430. float t3 = SH_LOS[0];
  431. float t4 = SH_LOS[1];
  432. float t5 = SH_LOS[5];
  433. float t100 = t2 * t3 * t5;
  434. float t6 = SH_LOS[4];
  435. float t7 = t2*t3*t6;
  436. float t8 = t2*t4*t5;
  437. float t9 = t7+t8;
  438. float t10 = q0*q3*2.0f;
  439. float t11 = q1*q2*2.0f;
  440. float t12 = t10+t11;
  441. float t101 = t2 * t3 * t12;
  442. float t13 = pd-ptd;
  443. float t14 = 1.0f/(t13*t13);
  444. float t104 = t3 * t4 * t14;
  445. float t15 = SH_LOS[6];
  446. float t105 = t2 * t4 * t15;
  447. float t16 = SH_LOS[2];
  448. float t102 = t2 * t3 * t16;
  449. float t17 = q0*q0;
  450. float t18 = q1*q1;
  451. float t19 = q2*q2;
  452. float t20 = q3*q3;
  453. float t21 = t17+t18-t19-t20;
  454. float t103 = t2 * t3 * t21;
  455. float t22 = P[0][0]*t105;
  456. float t23 = P[1][1]*t9;
  457. float t24 = P[8][1]*t104;
  458. float t25 = P[0][1]*t105;
  459. float t26 = P[5][1]*t100;
  460. float t64 = P[4][1]*t101;
  461. float t65 = P[2][1]*t102;
  462. float t66 = P[3][1]*t103;
  463. float t27 = t23+t24+t25+t26-t64-t65-t66;
  464. float t28 = t9*t27;
  465. float t29 = P[1][4]*t9;
  466. float t30 = P[8][4]*t104;
  467. float t31 = P[0][4]*t105;
  468. float t32 = P[5][4]*t100;
  469. float t67 = P[4][4]*t101;
  470. float t68 = P[2][4]*t102;
  471. float t69 = P[3][4]*t103;
  472. float t33 = t29+t30+t31+t32-t67-t68-t69;
  473. float t34 = P[1][8]*t9;
  474. float t35 = P[8][8]*t104;
  475. float t36 = P[0][8]*t105;
  476. float t37 = P[5][8]*t100;
  477. float t71 = P[4][8]*t101;
  478. float t72 = P[2][8]*t102;
  479. float t73 = P[3][8]*t103;
  480. float t38 = t34+t35+t36+t37-t71-t72-t73;
  481. float t39 = t104*t38;
  482. float t40 = P[1][0]*t9;
  483. float t41 = P[8][0]*t104;
  484. float t42 = P[5][0]*t100;
  485. float t74 = P[4][0]*t101;
  486. float t75 = P[2][0]*t102;
  487. float t76 = P[3][0]*t103;
  488. float t43 = t22+t40+t41+t42-t74-t75-t76;
  489. float t44 = t105*t43;
  490. float t45 = P[1][2]*t9;
  491. float t46 = P[8][2]*t104;
  492. float t47 = P[0][2]*t105;
  493. float t48 = P[5][2]*t100;
  494. float t63 = P[2][2]*t102;
  495. float t77 = P[4][2]*t101;
  496. float t78 = P[3][2]*t103;
  497. float t49 = t45+t46+t47+t48-t63-t77-t78;
  498. float t50 = P[1][5]*t9;
  499. float t51 = P[8][5]*t104;
  500. float t52 = P[0][5]*t105;
  501. float t53 = P[5][5]*t100;
  502. float t80 = P[4][5]*t101;
  503. float t81 = P[2][5]*t102;
  504. float t82 = P[3][5]*t103;
  505. float t54 = t50+t51+t52+t53-t80-t81-t82;
  506. float t55 = t100*t54;
  507. float t56 = P[1][3]*t9;
  508. float t57 = P[8][3]*t104;
  509. float t58 = P[0][3]*t105;
  510. float t59 = P[5][3]*t100;
  511. float t83 = P[4][3]*t101;
  512. float t84 = P[2][3]*t102;
  513. float t85 = P[3][3]*t103;
  514. float t60 = t56+t57+t58+t59-t83-t84-t85;
  515. float t70 = t101*t33;
  516. float t79 = t102*t49;
  517. float t86 = t103*t60;
  518. float t61 = R_LOS+t28+t39+t44+t55-t70-t79-t86;
  519. float t62 = 1.0f/t61;
  520. // calculate innovation variance for Y axis observation and protect against a badly conditioned calculation
  521. if (t61 > R_LOS) {
  522. t62 = 1.0f/t61;
  523. faultStatus.bad_yflow = false;
  524. } else {
  525. t61 = 0.0f;
  526. t62 = 1.0f/R_LOS;
  527. faultStatus.bad_yflow = true;
  528. return;
  529. }
  530. varInnovOptFlow[1] = t61;
  531. // calculate innovation for Y observation
  532. innovOptFlow[1] = losPred[1] - ofDataDelayed.flowRadXYcomp.y;
  533. // calculate Kalman gains for the Y-axis observation
  534. Kfusion[0] = -t62*(t22+P[0][1]*t9+P[0][5]*t100-P[0][4]*t101-P[0][2]*t102-P[0][3]*t103+P[0][8]*t104);
  535. Kfusion[1] = -t62*(t23+P[1][5]*t100+P[1][0]*t105-P[1][4]*t101-P[1][2]*t102-P[1][3]*t103+P[1][8]*t104);
  536. Kfusion[2] = -t62*(-t63+P[2][1]*t9+P[2][5]*t100+P[2][0]*t105-P[2][4]*t101-P[2][3]*t103+P[2][8]*t104);
  537. Kfusion[3] = -t62*(-t85+P[3][1]*t9+P[3][5]*t100+P[3][0]*t105-P[3][4]*t101-P[3][2]*t102+P[3][8]*t104);
  538. Kfusion[4] = -t62*(-t67+P[4][1]*t9+P[4][5]*t100+P[4][0]*t105-P[4][2]*t102-P[4][3]*t103+P[4][8]*t104);
  539. Kfusion[5] = -t62*(t53+P[5][1]*t9+P[5][0]*t105-P[5][4]*t101-P[5][2]*t102-P[5][3]*t103+P[5][8]*t104);
  540. Kfusion[6] = -t62*(P[6][1]*t9+P[6][5]*t100+P[6][0]*t105-P[6][4]*t101-P[6][2]*t102-P[6][3]*t103+P[6][8]*t104);
  541. Kfusion[7] = -t62*(P[7][1]*t9+P[7][5]*t100+P[7][0]*t105-P[7][4]*t101-P[7][2]*t102-P[7][3]*t103+P[7][8]*t104);
  542. Kfusion[8] = -t62*(t35+P[8][1]*t9+P[8][5]*t100+P[8][0]*t105-P[8][4]*t101-P[8][2]*t102-P[8][3]*t103);
  543. Kfusion[9] = -t62*(P[9][1]*t9+P[9][5]*t100+P[9][0]*t105-P[9][4]*t101-P[9][2]*t102-P[9][3]*t103+P[9][8]*t104);
  544. Kfusion[10] = -t62*(P[10][1]*t9+P[10][5]*t100+P[10][0]*t105-P[10][4]*t101-P[10][2]*t102-P[10][3]*t103+P[10][8]*t104);
  545. Kfusion[11] = -t62*(P[11][1]*t9+P[11][5]*t100+P[11][0]*t105-P[11][4]*t101-P[11][2]*t102-P[11][3]*t103+P[11][8]*t104);
  546. Kfusion[12] = -t62*(P[12][1]*t9+P[12][5]*t100+P[12][0]*t105-P[12][4]*t101-P[12][2]*t102-P[12][3]*t103+P[12][8]*t104);
  547. Kfusion[13] = -t62*(P[13][1]*t9+P[13][5]*t100+P[13][0]*t105-P[13][4]*t101-P[13][2]*t102-P[13][3]*t103+P[13][8]*t104);
  548. Kfusion[14] = -t62*(P[14][1]*t9+P[14][5]*t100+P[14][0]*t105-P[14][4]*t101-P[14][2]*t102-P[14][3]*t103+P[14][8]*t104);
  549. Kfusion[15] = -t62*(P[15][1]*t9+P[15][5]*t100+P[15][0]*t105-P[15][4]*t101-P[15][2]*t102-P[15][3]*t103+P[15][8]*t104);
  550. if (!inhibitWindStates) {
  551. Kfusion[22] = -t62*(P[22][1]*t9+P[22][5]*t100+P[22][0]*t105-P[22][4]*t101-P[22][2]*t102-P[22][3]*t103+P[22][8]*t104);
  552. Kfusion[23] = -t62*(P[23][1]*t9+P[23][5]*t100+P[23][0]*t105-P[23][4]*t101-P[23][2]*t102-P[23][3]*t103+P[23][8]*t104);
  553. } else {
  554. Kfusion[22] = 0.0f;
  555. Kfusion[23] = 0.0f;
  556. }
  557. if (!inhibitMagStates) {
  558. Kfusion[16] = -t62*(P[16][1]*t9+P[16][5]*t100+P[16][0]*t105-P[16][4]*t101-P[16][2]*t102-P[16][3]*t103+P[16][8]*t104);
  559. Kfusion[17] = -t62*(P[17][1]*t9+P[17][5]*t100+P[17][0]*t105-P[17][4]*t101-P[17][2]*t102-P[17][3]*t103+P[17][8]*t104);
  560. Kfusion[18] = -t62*(P[18][1]*t9+P[18][5]*t100+P[18][0]*t105-P[18][4]*t101-P[18][2]*t102-P[18][3]*t103+P[18][8]*t104);
  561. Kfusion[19] = -t62*(P[19][1]*t9+P[19][5]*t100+P[19][0]*t105-P[19][4]*t101-P[19][2]*t102-P[19][3]*t103+P[19][8]*t104);
  562. Kfusion[20] = -t62*(P[20][1]*t9+P[20][5]*t100+P[20][0]*t105-P[20][4]*t101-P[20][2]*t102-P[20][3]*t103+P[20][8]*t104);
  563. Kfusion[21] = -t62*(P[21][1]*t9+P[21][5]*t100+P[21][0]*t105-P[21][4]*t101-P[21][2]*t102-P[21][3]*t103+P[21][8]*t104);
  564. } else {
  565. for (uint8_t i = 16; i <= 21; i++) {
  566. Kfusion[i] = 0.0f;
  567. }
  568. }
  569. }
  570. // calculate the innovation consistency test ratio
  571. flowTestRatio[obsIndex] = sq(innovOptFlow[obsIndex]) / (sq(MAX(0.01f * (float)frontend->_flowInnovGate, 1.0f)) * varInnovOptFlow[obsIndex]);
  572. // Check the innovation for consistency and don't fuse if out of bounds or flow is too fast to be reliable
  573. if ((flowTestRatio[obsIndex]) < 1.0f && (ofDataDelayed.flowRadXY.x < frontend->_maxFlowRate) && (ofDataDelayed.flowRadXY.y < frontend->_maxFlowRate)) {
  574. // record the last time observations were accepted for fusion
  575. prevFlowFuseTime_ms = imuSampleTime_ms;
  576. // correct the covariance P = (I - K*H)*P
  577. // take advantage of the empty columns in KH to reduce the
  578. // number of operations
  579. for (unsigned i = 0; i<=stateIndexLim; i++) {
  580. for (unsigned j = 0; j<=5; j++) {
  581. KH[i][j] = Kfusion[i] * H_LOS[j];
  582. }
  583. for (unsigned j = 6; j<=7; j++) {
  584. KH[i][j] = 0.0f;
  585. }
  586. KH[i][8] = Kfusion[i] * H_LOS[8];
  587. for (unsigned j = 9; j<=23; j++) {
  588. KH[i][j] = 0.0f;
  589. }
  590. }
  591. for (unsigned j = 0; j<=stateIndexLim; j++) {
  592. for (unsigned i = 0; i<=stateIndexLim; i++) {
  593. ftype res = 0;
  594. res += KH[i][0] * P[0][j];
  595. res += KH[i][1] * P[1][j];
  596. res += KH[i][2] * P[2][j];
  597. res += KH[i][3] * P[3][j];
  598. res += KH[i][4] * P[4][j];
  599. res += KH[i][5] * P[5][j];
  600. res += KH[i][8] * P[8][j];
  601. KHP[i][j] = res;
  602. }
  603. }
  604. // Check that we are not going to drive any variances negative and skip the update if so
  605. bool healthyFusion = true;
  606. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  607. if (KHP[i][i] > P[i][i]) {
  608. healthyFusion = false;
  609. }
  610. }
  611. if (healthyFusion) {
  612. // update the covariance matrix
  613. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  614. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  615. P[i][j] = P[i][j] - KHP[i][j];
  616. }
  617. }
  618. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  619. ForceSymmetry();
  620. ConstrainVariances();
  621. // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
  622. stateStruct.angErr.zero();
  623. // correct the state vector
  624. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  625. statesArray[j] = statesArray[j] - Kfusion[j] * innovOptFlow[obsIndex];
  626. }
  627. // the first 3 states represent the angular misalignment vector. This is
  628. // is used to correct the estimated quaternion on the current time step
  629. stateStruct.quat.rotate(stateStruct.angErr);
  630. } else {
  631. // record bad axis
  632. if (obsIndex == 0) {
  633. faultStatus.bad_xflow = true;
  634. } else if (obsIndex == 1) {
  635. faultStatus.bad_yflow = true;
  636. }
  637. }
  638. }
  639. }
  640. }
  641. /********************************************************
  642. * MISC FUNCTIONS *
  643. ********************************************************/