AP_NavEKF3_OptFlowFusion.cpp 36 KB

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