AP_NavEKF3_MagFusion.cpp 66 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288
  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. // Control reset of yaw and magnetic field states
  12. void NavEKF3_core::controlMagYawReset()
  13. {
  14. // Vehicles that can use a zero sideslip assumption (Planes) are a special case
  15. // They can use the GPS velocity to recover from bad initial compass data
  16. // This allows recovery for heading alignment errors due to compass faults
  17. if (assume_zero_sideslip() && !finalInflightYawInit && inFlight ) {
  18. gpsYawResetRequest = true;
  19. return;
  20. } else {
  21. gpsYawResetRequest = false;
  22. }
  23. // Quaternion and delta rotation vector that are re-used for different calculations
  24. Vector3f deltaRotVecTemp;
  25. Quaternion deltaQuatTemp;
  26. bool flightResetAllowed = false;
  27. bool initialResetAllowed = false;
  28. if (!finalInflightYawInit) {
  29. // Use a quaternion division to calculate the delta quaternion between the rotation at the current and last time
  30. deltaQuatTemp = stateStruct.quat / prevQuatMagReset;
  31. prevQuatMagReset = stateStruct.quat;
  32. // convert the quaternion to a rotation vector and find its length
  33. deltaQuatTemp.to_axis_angle(deltaRotVecTemp);
  34. // check if the spin rate is OK - high spin rates can cause angular alignment errors
  35. bool angRateOK = deltaRotVecTemp.length() < 0.1745f;
  36. initialResetAllowed = angRateOK;
  37. flightResetAllowed = angRateOK && !onGround;
  38. }
  39. // Check if conditions for a interim or final yaw/mag reset are met
  40. bool finalResetRequest = false;
  41. bool interimResetRequest = false;
  42. if (flightResetAllowed && !assume_zero_sideslip()) {
  43. // check that we have reached a height where ground magnetic interference effects are insignificant
  44. // and can perform a final reset of the yaw and field states
  45. finalResetRequest = (stateStruct.position.z - posDownAtTakeoff) < -EKF3_MAG_FINAL_RESET_ALT;
  46. // check for increasing height
  47. bool hgtIncreasing = (posDownAtLastMagReset-stateStruct.position.z) > 0.5f;
  48. float yawInnovIncrease = fabsf(innovYaw) - fabsf(yawInnovAtLastMagReset);
  49. // check for increasing yaw innovations
  50. bool yawInnovIncreasing = yawInnovIncrease > 0.25f;
  51. // check that the yaw innovations haven't been caused by a large change in attitude
  52. deltaQuatTemp = quatAtLastMagReset / stateStruct.quat;
  53. deltaQuatTemp.to_axis_angle(deltaRotVecTemp);
  54. bool largeAngleChange = deltaRotVecTemp.length() > yawInnovIncrease;
  55. // if yaw innovations and height have increased and we haven't rotated much
  56. // then we are climbing away from a ground based magnetic anomaly and need to reset
  57. interimResetRequest = hgtIncreasing && yawInnovIncreasing && !largeAngleChange;
  58. }
  59. // an initial reset is required if we have not yet aligned the yaw angle
  60. bool initialResetRequest = initialResetAllowed && !yawAlignComplete;
  61. // a combined yaw angle and magnetic field reset can be initiated by:
  62. magYawResetRequest = magYawResetRequest || // an external request
  63. initialResetRequest || // an initial alignment performed by all vehicle types using magnetometer
  64. interimResetRequest || // an interim alignment required to recover from ground based magnetic anomaly
  65. finalResetRequest; // the final reset when we have achieved enough height to be in stable magnetic field environment
  66. // Perform a reset of magnetic field states and reset yaw to corrected magnetic heading
  67. if (magYawResetRequest || magStateResetRequest) {
  68. // get the euler angles from the current state estimate
  69. Vector3f eulerAngles;
  70. stateStruct.quat.to_euler(eulerAngles.x, eulerAngles.y, eulerAngles.z);
  71. // Use the Euler angles and magnetometer measurement to update the magnetic field states
  72. // and get an updated quaternion
  73. Quaternion newQuat = calcQuatAndFieldStates(eulerAngles.x, eulerAngles.y);
  74. // if a yaw reset has been requested, apply the updated quaternion to the current state
  75. if (magYawResetRequest) {
  76. // previous value used to calculate a reset delta
  77. Quaternion prevQuat = stateStruct.quat;
  78. // calculate the variance for the rotation estimate expressed as a rotation vector
  79. // this will be used later to reset the quaternion state covariances
  80. Vector3f angleErrVarVec = calcRotVecVariances();
  81. // update the quaternion states using the new yaw angle
  82. stateStruct.quat = newQuat;
  83. // update the yaw angle variance using the variance of the measurement
  84. angleErrVarVec.z = sq(MAX(frontend->_yawNoise, 1.0e-2f));
  85. // reset the quaternion covariances using the rotation vector variances
  86. initialiseQuatCovariances(angleErrVarVec);
  87. // calculate the change in the quaternion state and apply it to the output history buffer
  88. prevQuat = stateStruct.quat/prevQuat;
  89. StoreQuatRotate(prevQuat);
  90. // send initial alignment status to console
  91. if (!yawAlignComplete) {
  92. gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u initial yaw alignment complete",(unsigned)imu_index);
  93. }
  94. // send in-flight yaw alignment status to console
  95. if (finalResetRequest) {
  96. gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
  97. } else if (interimResetRequest) {
  98. gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
  99. }
  100. // prevent reset of variances in ConstrainVariances()
  101. inhibitMagStates = false;
  102. // update the yaw reset completed status
  103. recordYawReset();
  104. // clear the yaw reset request flag
  105. magYawResetRequest = false;
  106. // clear the complete flags if an interim reset has been performed to allow subsequent
  107. // and final reset to occur
  108. if (interimResetRequest) {
  109. finalInflightYawInit = false;
  110. finalInflightMagInit = false;
  111. }
  112. }
  113. }
  114. }
  115. // this function is used to do a forced re-alignment of the yaw angle to align with the horizontal velocity
  116. // vector from GPS. It is used to align the yaw angle after launch or takeoff.
  117. void NavEKF3_core::realignYawGPS()
  118. {
  119. // get quaternion from existing filter states and calculate roll, pitch and yaw angles
  120. Vector3f eulerAngles;
  121. stateStruct.quat.to_euler(eulerAngles.x, eulerAngles.y, eulerAngles.z);
  122. if ((sq(gpsDataDelayed.vel.x) + sq(gpsDataDelayed.vel.y)) > 25.0f) {
  123. // calculate course yaw angle
  124. float velYaw = atan2f(stateStruct.velocity.y,stateStruct.velocity.x);
  125. // calculate course yaw angle from GPS velocity
  126. float gpsYaw = atan2f(gpsDataDelayed.vel.y,gpsDataDelayed.vel.x);
  127. // Check the yaw angles for consistency
  128. float yawErr = MAX(fabsf(wrap_PI(gpsYaw - velYaw)),fabsf(wrap_PI(gpsYaw - eulerAngles.z)));
  129. // If the angles disagree by more than 45 degrees and GPS innovations are large or no previous yaw alignment, we declare the magnetic yaw as bad
  130. badMagYaw = ((yawErr > 0.7854f) && (velTestRatio > 1.0f) && (PV_AidingMode == AID_ABSOLUTE)) || !yawAlignComplete;
  131. // correct yaw angle using GPS ground course if compass yaw bad
  132. if (badMagYaw) {
  133. // calculate the variance for the rotation estimate expressed as a rotation vector
  134. // this will be used later to reset the quaternion state covariances
  135. Vector3f angleErrVarVec = calcRotVecVariances();
  136. // calculate new filter quaternion states from Euler angles
  137. stateStruct.quat.from_euler(eulerAngles.x, eulerAngles.y, gpsYaw);
  138. // reset the velocity and position states as they will be inaccurate due to bad yaw
  139. velResetSource = GPS;
  140. ResetVelocity();
  141. posResetSource = GPS;
  142. ResetPosition();
  143. // set the yaw angle variance to a larger value to reflect the uncertainty in yaw
  144. angleErrVarVec.z = sq(radians(45.0f));
  145. // reset the quaternion covariances using the rotation vector variances
  146. zeroRows(P,0,3);
  147. zeroCols(P,0,3);
  148. initialiseQuatCovariances(angleErrVarVec);
  149. // send yaw alignment information to console
  150. gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned to GPS velocity",(unsigned)imu_index);
  151. // record the yaw reset event
  152. recordYawReset();
  153. // clear all pending yaw reset requests
  154. gpsYawResetRequest = false;
  155. magYawResetRequest = false;
  156. if (use_compass()) {
  157. // request a mag field reset which may enable us to use the magnetometer if the previous fault was due to bad initialisation
  158. magStateResetRequest = true;
  159. // clear the all sensors failed status so that the magnetometers sensors get a second chance now that we are flying
  160. allMagSensorsFailed = false;
  161. }
  162. }
  163. }
  164. }
  165. void NavEKF3_core::alignYawAngle()
  166. {
  167. // calculate the variance for the rotation estimate expressed as a rotation vector
  168. // this will be used later to reset the quaternion state covariances
  169. Vector3f angleErrVarVec = calcRotVecVariances();
  170. if (yawAngDataDelayed.type == 2) {
  171. Vector3f euler321;
  172. stateStruct.quat.to_euler(euler321.x, euler321.y, euler321.z);
  173. stateStruct.quat.from_euler(euler321.x, euler321.y, yawAngDataDelayed.yawAng);
  174. } else if (yawAngDataDelayed.type == 1) {
  175. Vector3f euler312 = stateStruct.quat.to_vector312();
  176. stateStruct.quat.from_vector312(euler312.x, euler312.y, yawAngDataDelayed.yawAng);
  177. }
  178. // set the yaw angle variance to a larger value to reflect the uncertainty in yaw
  179. angleErrVarVec.z = sq(yawAngDataDelayed.yawAngErr);
  180. // reset the quaternion covariances using the rotation vector variances
  181. zeroRows(P,0,3);
  182. zeroCols(P,0,3);
  183. initialiseQuatCovariances(angleErrVarVec);
  184. // send yaw alignment information to console
  185. gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned",(unsigned)imu_index);
  186. // record the yaw reset event
  187. recordYawReset();
  188. // clear any pending yaw reset requests
  189. gpsYawResetRequest = false;
  190. magYawResetRequest = false;
  191. }
  192. /********************************************************
  193. * FUSE MEASURED_DATA *
  194. ********************************************************/
  195. // select fusion of magnetometer data
  196. void NavEKF3_core::SelectMagFusion()
  197. {
  198. // start performance timer
  199. hal.util->perf_begin(_perf_FuseMagnetometer);
  200. // clear the flag that lets other processes know that the expensive magnetometer fusion operation has been performed on that time step
  201. // used for load levelling
  202. magFusePerformed = false;
  203. // Handle case where we are using an external yaw sensor instead of a magnetomer
  204. if ((frontend->_magCal == 5)) {
  205. if (storedYawAng.recall(yawAngDataDelayed,imuDataDelayed.time_ms)) {
  206. if (tiltAlignComplete && !yawAlignComplete) {
  207. alignYawAngle();
  208. } else if (tiltAlignComplete && yawAlignComplete) {
  209. fuseEulerYaw(false, true);
  210. } else {
  211. fuseEulerYaw(true, true);
  212. }
  213. }
  214. return;
  215. }
  216. // check for and read new magnetometer measurements
  217. readMagData();
  218. // If we are using the compass and the magnetometer has been unhealthy for too long we declare a timeout
  219. if (magHealth) {
  220. magTimeout = false;
  221. lastHealthyMagTime_ms = imuSampleTime_ms;
  222. } else if ((imuSampleTime_ms - lastHealthyMagTime_ms) > frontend->magFailTimeLimit_ms && use_compass()) {
  223. magTimeout = true;
  224. }
  225. // check for availability of magnetometer or other yaw data to fuse
  226. magDataToFuse = storedMag.recall(magDataDelayed,imuDataDelayed.time_ms);
  227. // Control reset of yaw and magnetic field states if we are using compass data
  228. if (magDataToFuse) {
  229. controlMagYawReset();
  230. }
  231. // determine if conditions are right to start a new fusion cycle
  232. // wait until the EKF time horizon catches up with the measurement
  233. bool dataReady = (magDataToFuse && statesInitialised && use_compass() && yawAlignComplete);
  234. if (dataReady) {
  235. // use the simple method of declination to maintain heading if we cannot use the magnetic field states
  236. if(inhibitMagStates || magStateResetRequest || !magStateInitComplete) {
  237. fuseEulerYaw(false, false);
  238. // zero the test ratio output from the inactive 3-axis magnetometer fusion
  239. magTestRatio.zero();
  240. } else {
  241. // if we are not doing aiding with earth relative observations (eg GPS) then the declination is
  242. // maintained by fusing declination as a synthesised observation
  243. if (PV_AidingMode != AID_ABSOLUTE) {
  244. FuseDeclination(0.34f);
  245. }
  246. // fuse the three magnetometer componenents sequentially
  247. hal.util->perf_begin(_perf_test[0]);
  248. for (mag_state.obsIndex = 0; mag_state.obsIndex <= 2; mag_state.obsIndex++) {
  249. FuseMagnetometer();
  250. // don't continue fusion if unhealthy
  251. if (!magHealth) {
  252. hal.util->perf_end(_perf_test[0]);
  253. break;
  254. }
  255. }
  256. hal.util->perf_end(_perf_test[0]);
  257. // zero the test ratio output from the inactive simple magnetometer yaw fusion
  258. yawTestRatio = 0.0f;
  259. }
  260. }
  261. // If we have no magnetometer, fuse in a synthetic heading measurement at 7Hz to prevent the filter covariances
  262. // from becoming badly conditioned. For planes we only do this on-ground because they can align the yaw from GPS when
  263. // airborne. For other platform types we do this all the time.
  264. if (!use_compass()) {
  265. if ((onGround || !assume_zero_sideslip()) && (imuSampleTime_ms - lastSynthYawTime_ms > 140)) {
  266. fuseEulerYaw(true, false);
  267. magTestRatio.zero();
  268. yawTestRatio = 0.0f;
  269. lastSynthYawTime_ms = imuSampleTime_ms;
  270. }
  271. }
  272. // If the final yaw reset has been performed and the state variances are sufficiently low
  273. // record that the earth field has been learned.
  274. if (!magFieldLearned && finalInflightMagInit) {
  275. magFieldLearned = (P[16][16] < sq(0.01f)) && (P[17][17] < sq(0.01f)) && (P[18][18] < sq(0.01f));
  276. }
  277. // record the last learned field variances
  278. if (magFieldLearned && !inhibitMagStates) {
  279. earthMagFieldVar.x = P[16][16];
  280. earthMagFieldVar.y = P[17][17];
  281. earthMagFieldVar.z = P[18][18];
  282. bodyMagFieldVar.x = P[19][19];
  283. bodyMagFieldVar.y = P[20][20];
  284. bodyMagFieldVar.z = P[21][21];
  285. }
  286. // stop performance timer
  287. hal.util->perf_end(_perf_FuseMagnetometer);
  288. }
  289. /*
  290. * Fuse magnetometer measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
  291. * The script file used to generate these and other equations in this filter can be found here:
  292. * https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
  293. */
  294. void NavEKF3_core::FuseMagnetometer()
  295. {
  296. // declarations
  297. ftype &q0 = mag_state.q0;
  298. ftype &q1 = mag_state.q1;
  299. ftype &q2 = mag_state.q2;
  300. ftype &q3 = mag_state.q3;
  301. ftype &magN = mag_state.magN;
  302. ftype &magE = mag_state.magE;
  303. ftype &magD = mag_state.magD;
  304. ftype &magXbias = mag_state.magXbias;
  305. ftype &magYbias = mag_state.magYbias;
  306. ftype &magZbias = mag_state.magZbias;
  307. uint8_t &obsIndex = mag_state.obsIndex;
  308. Matrix3f &DCM = mag_state.DCM;
  309. Vector3f &MagPred = mag_state.MagPred;
  310. ftype &R_MAG = mag_state.R_MAG;
  311. ftype *SH_MAG = &mag_state.SH_MAG[0];
  312. Vector24 H_MAG;
  313. Vector5 SK_MX;
  314. Vector5 SK_MY;
  315. Vector5 SK_MZ;
  316. // perform sequential fusion of magnetometer measurements.
  317. // this assumes that the errors in the different components are
  318. // uncorrelated which is not true, however in the absence of covariance
  319. // data fit is the only assumption we can make
  320. // so we might as well take advantage of the computational efficiencies
  321. // associated with sequential fusion
  322. // calculate observation jacobians and Kalman gains
  323. // copy required states to local variable names
  324. q0 = stateStruct.quat[0];
  325. q1 = stateStruct.quat[1];
  326. q2 = stateStruct.quat[2];
  327. q3 = stateStruct.quat[3];
  328. magN = stateStruct.earth_magfield[0];
  329. magE = stateStruct.earth_magfield[1];
  330. magD = stateStruct.earth_magfield[2];
  331. magXbias = stateStruct.body_magfield[0];
  332. magYbias = stateStruct.body_magfield[1];
  333. magZbias = stateStruct.body_magfield[2];
  334. // rotate predicted earth components into body axes and calculate
  335. // predicted measurements
  336. DCM[0][0] = q0*q0 + q1*q1 - q2*q2 - q3*q3;
  337. DCM[0][1] = 2.0f*(q1*q2 + q0*q3);
  338. DCM[0][2] = 2.0f*(q1*q3-q0*q2);
  339. DCM[1][0] = 2.0f*(q1*q2 - q0*q3);
  340. DCM[1][1] = q0*q0 - q1*q1 + q2*q2 - q3*q3;
  341. DCM[1][2] = 2.0f*(q2*q3 + q0*q1);
  342. DCM[2][0] = 2.0f*(q1*q3 + q0*q2);
  343. DCM[2][1] = 2.0f*(q2*q3 - q0*q1);
  344. DCM[2][2] = q0*q0 - q1*q1 - q2*q2 + q3*q3;
  345. MagPred[0] = DCM[0][0]*magN + DCM[0][1]*magE + DCM[0][2]*magD + magXbias;
  346. MagPred[1] = DCM[1][0]*magN + DCM[1][1]*magE + DCM[1][2]*magD + magYbias;
  347. MagPred[2] = DCM[2][0]*magN + DCM[2][1]*magE + DCM[2][2]*magD + magZbias;
  348. // calculate the measurement innovation for each axis
  349. for (uint8_t i = 0; i<=2; i++) {
  350. innovMag[i] = MagPred[i] - magDataDelayed.mag[i];
  351. }
  352. // scale magnetometer observation error with total angular rate to allow for timing errors
  353. R_MAG = sq(constrain_float(frontend->_magNoise, 0.01f, 0.5f)) + sq(frontend->magVarRateScale*imuDataDelayed.delAng.length() / imuDataDelayed.delAngDT);
  354. // calculate common expressions used to calculate observation jacobians an innovation variance for each component
  355. SH_MAG[0] = 2.0f*magD*q3 + 2.0f*magE*q2 + 2.0f*magN*q1;
  356. SH_MAG[1] = 2.0f*magD*q0 - 2.0f*magE*q1 + 2.0f*magN*q2;
  357. SH_MAG[2] = 2.0f*magD*q1 + 2.0f*magE*q0 - 2.0f*magN*q3;
  358. SH_MAG[3] = sq(q3);
  359. SH_MAG[4] = sq(q2);
  360. SH_MAG[5] = sq(q1);
  361. SH_MAG[6] = sq(q0);
  362. SH_MAG[7] = 2.0f*magN*q0;
  363. SH_MAG[8] = 2.0f*magE*q3;
  364. // Calculate the innovation variance for each axis
  365. // X axis
  366. varInnovMag[0] = (P[19][19] + R_MAG + P[1][19]*SH_MAG[0] - P[2][19]*SH_MAG[1] + P[3][19]*SH_MAG[2] - P[16][19]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + (2.0f*q0*q3 + 2.0f*q1*q2)*(P[19][17] + P[1][17]*SH_MAG[0] - P[2][17]*SH_MAG[1] + P[3][17]*SH_MAG[2] - P[16][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][17]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][17]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - (2.0f*q0*q2 - 2.0f*q1*q3)*(P[19][18] + P[1][18]*SH_MAG[0] - P[2][18]*SH_MAG[1] + P[3][18]*SH_MAG[2] - P[16][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][18]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][18]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)*(P[19][0] + P[1][0]*SH_MAG[0] - P[2][0]*SH_MAG[1] + P[3][0]*SH_MAG[2] - P[16][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][0]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][0]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + P[17][19]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][19]*(2.0f*q0*q2 - 2.0f*q1*q3) + SH_MAG[0]*(P[19][1] + P[1][1]*SH_MAG[0] - P[2][1]*SH_MAG[1] + P[3][1]*SH_MAG[2] - P[16][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][1]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][1]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - SH_MAG[1]*(P[19][2] + P[1][2]*SH_MAG[0] - P[2][2]*SH_MAG[1] + P[3][2]*SH_MAG[2] - P[16][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][2]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][2]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + SH_MAG[2]*(P[19][3] + P[1][3]*SH_MAG[0] - P[2][3]*SH_MAG[1] + P[3][3]*SH_MAG[2] - P[16][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][3]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][3]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[1][16]*SH_MAG[0] - P[2][16]*SH_MAG[1] + P[3][16]*SH_MAG[2] - P[16][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][16]*(2.0f*q0*q3 + 2.0f*q1*q2) - P[18][16]*(2.0f*q0*q2 - 2.0f*q1*q3) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + P[0][19]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2));
  367. if (varInnovMag[0] >= R_MAG) {
  368. faultStatus.bad_xmag = false;
  369. } else {
  370. // the calculation is badly conditioned, so we cannot perform fusion on this step
  371. // we reset the covariance matrix and try again next measurement
  372. CovarianceInit();
  373. faultStatus.bad_xmag = true;
  374. return;
  375. }
  376. // Y axis
  377. varInnovMag[1] = (P[20][20] + R_MAG + P[0][20]*SH_MAG[2] + P[1][20]*SH_MAG[1] + P[2][20]*SH_MAG[0] - P[17][20]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2.0f*q0*q3 - 2.0f*q1*q2)*(P[20][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[17][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][16]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][16]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + (2.0f*q0*q1 + 2.0f*q2*q3)*(P[20][18] + P[0][18]*SH_MAG[2] + P[1][18]*SH_MAG[1] + P[2][18]*SH_MAG[0] - P[17][18]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][18]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][18]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][18]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)*(P[20][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[17][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][3]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][3]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - P[16][20]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][20]*(2.0f*q0*q1 + 2.0f*q2*q3) + SH_MAG[2]*(P[20][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[17][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][0]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][0]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + SH_MAG[1]*(P[20][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[17][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][1]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][1]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + SH_MAG[0]*(P[20][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[17][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][2]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][2]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[17][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][17]*(2.0f*q0*q3 - 2.0f*q1*q2) + P[18][17]*(2.0f*q0*q1 + 2.0f*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - P[3][20]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2));
  378. if (varInnovMag[1] >= R_MAG) {
  379. faultStatus.bad_ymag = false;
  380. } else {
  381. // the calculation is badly conditioned, so we cannot perform fusion on this step
  382. // we reset the covariance matrix and try again next measurement
  383. CovarianceInit();
  384. faultStatus.bad_ymag = true;
  385. return;
  386. }
  387. // Z axis
  388. varInnovMag[2] = (P[21][21] + R_MAG + P[0][21]*SH_MAG[1] - P[1][21]*SH_MAG[2] + P[3][21]*SH_MAG[0] + P[18][21]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + (2.0f*q0*q2 + 2.0f*q1*q3)*(P[21][16] + P[0][16]*SH_MAG[1] - P[1][16]*SH_MAG[2] + P[3][16]*SH_MAG[0] + P[18][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][16]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][16]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - (2.0f*q0*q1 - 2.0f*q2*q3)*(P[21][17] + P[0][17]*SH_MAG[1] - P[1][17]*SH_MAG[2] + P[3][17]*SH_MAG[0] + P[18][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][17]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][17]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)*(P[21][2] + P[0][2]*SH_MAG[1] - P[1][2]*SH_MAG[2] + P[3][2]*SH_MAG[0] + P[18][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][2]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][2]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + P[16][21]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][21]*(2.0f*q0*q1 - 2.0f*q2*q3) + SH_MAG[1]*(P[21][0] + P[0][0]*SH_MAG[1] - P[1][0]*SH_MAG[2] + P[3][0]*SH_MAG[0] + P[18][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][0]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][0]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) - SH_MAG[2]*(P[21][1] + P[0][1]*SH_MAG[1] - P[1][1]*SH_MAG[2] + P[3][1]*SH_MAG[0] + P[18][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][1]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][1]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + SH_MAG[0]*(P[21][3] + P[0][3]*SH_MAG[1] - P[1][3]*SH_MAG[2] + P[3][3]*SH_MAG[0] + P[18][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][3]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][3]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[21][18] + P[0][18]*SH_MAG[1] - P[1][18]*SH_MAG[2] + P[3][18]*SH_MAG[0] + P[18][18]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][18]*(2.0f*q0*q2 + 2.0f*q1*q3) - P[17][18]*(2.0f*q0*q1 - 2.0f*q2*q3) + P[2][18]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2)) + P[2][21]*(SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2));
  389. if (varInnovMag[2] >= R_MAG) {
  390. faultStatus.bad_zmag = false;
  391. } else {
  392. // the calculation is badly conditioned, so we cannot perform fusion on this step
  393. // we reset the covariance matrix and try again next measurement
  394. CovarianceInit();
  395. faultStatus.bad_zmag = true;
  396. return;
  397. }
  398. // calculate the innovation test ratios
  399. for (uint8_t i = 0; i<=2; i++) {
  400. magTestRatio[i] = sq(innovMag[i]) / (sq(MAX(0.01f * (float)frontend->_magInnovGate, 1.0f)) * varInnovMag[i]);
  401. }
  402. // check the last values from all components and set magnetometer health accordingly
  403. magHealth = (magTestRatio[0] < 1.0f && magTestRatio[1] < 1.0f && magTestRatio[2] < 1.0f);
  404. // if the magnetometer is unhealthy, do not proceed further
  405. if (!magHealth) {
  406. return;
  407. }
  408. for (obsIndex = 0; obsIndex <= 2; obsIndex++) {
  409. if (obsIndex == 0) {
  410. for (uint8_t i = 0; i<=stateIndexLim; i++) H_MAG[i] = 0.0f;
  411. H_MAG[0] = SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2;
  412. H_MAG[1] = SH_MAG[0];
  413. H_MAG[2] = -SH_MAG[1];
  414. H_MAG[3] = SH_MAG[2];
  415. H_MAG[16] = SH_MAG[5] - SH_MAG[4] - SH_MAG[3] + SH_MAG[6];
  416. H_MAG[17] = 2.0f*q0*q3 + 2.0f*q1*q2;
  417. H_MAG[18] = 2.0f*q1*q3 - 2.0f*q0*q2;
  418. H_MAG[19] = 1.0f;
  419. H_MAG[20] = 0.0f;
  420. H_MAG[21] = 0.0f;
  421. // calculate Kalman gain
  422. SK_MX[0] = 1.0f / varInnovMag[0];
  423. SK_MX[1] = SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6];
  424. SK_MX[2] = SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2;
  425. SK_MX[3] = 2.0f*q0*q2 - 2.0f*q1*q3;
  426. SK_MX[4] = 2.0f*q0*q3 + 2.0f*q1*q2;
  427. Kfusion[0] = SK_MX[0]*(P[0][19] + P[0][1]*SH_MAG[0] - P[0][2]*SH_MAG[1] + P[0][3]*SH_MAG[2] + P[0][0]*SK_MX[2] - P[0][16]*SK_MX[1] + P[0][17]*SK_MX[4] - P[0][18]*SK_MX[3]);
  428. Kfusion[1] = SK_MX[0]*(P[1][19] + P[1][1]*SH_MAG[0] - P[1][2]*SH_MAG[1] + P[1][3]*SH_MAG[2] + P[1][0]*SK_MX[2] - P[1][16]*SK_MX[1] + P[1][17]*SK_MX[4] - P[1][18]*SK_MX[3]);
  429. Kfusion[2] = SK_MX[0]*(P[2][19] + P[2][1]*SH_MAG[0] - P[2][2]*SH_MAG[1] + P[2][3]*SH_MAG[2] + P[2][0]*SK_MX[2] - P[2][16]*SK_MX[1] + P[2][17]*SK_MX[4] - P[2][18]*SK_MX[3]);
  430. Kfusion[3] = SK_MX[0]*(P[3][19] + P[3][1]*SH_MAG[0] - P[3][2]*SH_MAG[1] + P[3][3]*SH_MAG[2] + P[3][0]*SK_MX[2] - P[3][16]*SK_MX[1] + P[3][17]*SK_MX[4] - P[3][18]*SK_MX[3]);
  431. Kfusion[4] = SK_MX[0]*(P[4][19] + P[4][1]*SH_MAG[0] - P[4][2]*SH_MAG[1] + P[4][3]*SH_MAG[2] + P[4][0]*SK_MX[2] - P[4][16]*SK_MX[1] + P[4][17]*SK_MX[4] - P[4][18]*SK_MX[3]);
  432. Kfusion[5] = SK_MX[0]*(P[5][19] + P[5][1]*SH_MAG[0] - P[5][2]*SH_MAG[1] + P[5][3]*SH_MAG[2] + P[5][0]*SK_MX[2] - P[5][16]*SK_MX[1] + P[5][17]*SK_MX[4] - P[5][18]*SK_MX[3]);
  433. Kfusion[6] = SK_MX[0]*(P[6][19] + P[6][1]*SH_MAG[0] - P[6][2]*SH_MAG[1] + P[6][3]*SH_MAG[2] + P[6][0]*SK_MX[2] - P[6][16]*SK_MX[1] + P[6][17]*SK_MX[4] - P[6][18]*SK_MX[3]);
  434. Kfusion[7] = SK_MX[0]*(P[7][19] + P[7][1]*SH_MAG[0] - P[7][2]*SH_MAG[1] + P[7][3]*SH_MAG[2] + P[7][0]*SK_MX[2] - P[7][16]*SK_MX[1] + P[7][17]*SK_MX[4] - P[7][18]*SK_MX[3]);
  435. Kfusion[8] = SK_MX[0]*(P[8][19] + P[8][1]*SH_MAG[0] - P[8][2]*SH_MAG[1] + P[8][3]*SH_MAG[2] + P[8][0]*SK_MX[2] - P[8][16]*SK_MX[1] + P[8][17]*SK_MX[4] - P[8][18]*SK_MX[3]);
  436. Kfusion[9] = SK_MX[0]*(P[9][19] + P[9][1]*SH_MAG[0] - P[9][2]*SH_MAG[1] + P[9][3]*SH_MAG[2] + P[9][0]*SK_MX[2] - P[9][16]*SK_MX[1] + P[9][17]*SK_MX[4] - P[9][18]*SK_MX[3]);
  437. if (!inhibitDelAngBiasStates) {
  438. Kfusion[10] = SK_MX[0]*(P[10][19] + P[10][1]*SH_MAG[0] - P[10][2]*SH_MAG[1] + P[10][3]*SH_MAG[2] + P[10][0]*SK_MX[2] - P[10][16]*SK_MX[1] + P[10][17]*SK_MX[4] - P[10][18]*SK_MX[3]);
  439. Kfusion[11] = SK_MX[0]*(P[11][19] + P[11][1]*SH_MAG[0] - P[11][2]*SH_MAG[1] + P[11][3]*SH_MAG[2] + P[11][0]*SK_MX[2] - P[11][16]*SK_MX[1] + P[11][17]*SK_MX[4] - P[11][18]*SK_MX[3]);
  440. Kfusion[12] = SK_MX[0]*(P[12][19] + P[12][1]*SH_MAG[0] - P[12][2]*SH_MAG[1] + P[12][3]*SH_MAG[2] + P[12][0]*SK_MX[2] - P[12][16]*SK_MX[1] + P[12][17]*SK_MX[4] - P[12][18]*SK_MX[3]);
  441. } else {
  442. // zero indexes 10 to 12 = 3*4 bytes
  443. memset(&Kfusion[10], 0, 12);
  444. }
  445. if (!inhibitDelVelBiasStates) {
  446. Kfusion[13] = SK_MX[0]*(P[13][19] + P[13][1]*SH_MAG[0] - P[13][2]*SH_MAG[1] + P[13][3]*SH_MAG[2] + P[13][0]*SK_MX[2] - P[13][16]*SK_MX[1] + P[13][17]*SK_MX[4] - P[13][18]*SK_MX[3]);
  447. Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][1]*SH_MAG[0] - P[14][2]*SH_MAG[1] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[2] - P[14][16]*SK_MX[1] + P[14][17]*SK_MX[4] - P[14][18]*SK_MX[3]);
  448. Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][1]*SH_MAG[0] - P[15][2]*SH_MAG[1] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[2] - P[15][16]*SK_MX[1] + P[15][17]*SK_MX[4] - P[15][18]*SK_MX[3]);
  449. } else {
  450. // zero indexes 13 to 15 = 3*4 bytes
  451. memset(&Kfusion[13], 0, 12);
  452. }
  453. // zero Kalman gains to inhibit magnetic field state estimation
  454. if (!inhibitMagStates) {
  455. Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][1]*SH_MAG[0] - P[16][2]*SH_MAG[1] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[2] - P[16][16]*SK_MX[1] + P[16][17]*SK_MX[4] - P[16][18]*SK_MX[3]);
  456. Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][1]*SH_MAG[0] - P[17][2]*SH_MAG[1] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[2] - P[17][16]*SK_MX[1] + P[17][17]*SK_MX[4] - P[17][18]*SK_MX[3]);
  457. Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][1]*SH_MAG[0] - P[18][2]*SH_MAG[1] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[2] - P[18][16]*SK_MX[1] + P[18][17]*SK_MX[4] - P[18][18]*SK_MX[3]);
  458. Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] - P[19][2]*SH_MAG[1] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[4] - P[19][18]*SK_MX[3]);
  459. Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] - P[20][2]*SH_MAG[1] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[4] - P[20][18]*SK_MX[3]);
  460. Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] - P[21][2]*SH_MAG[1] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[4] - P[21][18]*SK_MX[3]);
  461. } else {
  462. // zero indexes 16 to 21 = 6*4 bytes
  463. memset(&Kfusion[16], 0, 24);
  464. }
  465. // zero Kalman gains to inhibit wind state estimation
  466. if (!inhibitWindStates) {
  467. Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] - P[22][2]*SH_MAG[1] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[4] - P[22][18]*SK_MX[3]);
  468. Kfusion[23] = SK_MX[0]*(P[23][19] + P[23][1]*SH_MAG[0] - P[23][2]*SH_MAG[1] + P[23][3]*SH_MAG[2] + P[23][0]*SK_MX[2] - P[23][16]*SK_MX[1] + P[23][17]*SK_MX[4] - P[23][18]*SK_MX[3]);
  469. } else {
  470. // zero indexes 22 to 23 = 2*4 bytes
  471. memset(&Kfusion[22], 0, 8);
  472. }
  473. // set flags to indicate to other processes that fusion has been performed and is required on the next frame
  474. // this can be used by other fusion processes to avoid fusing on the same frame as this expensive step
  475. magFusePerformed = true;
  476. magFuseRequired = true;
  477. } else if (obsIndex == 1) { // Fuse Y axis
  478. // calculate observation jacobians
  479. for (uint8_t i = 0; i<=stateIndexLim; i++) H_MAG[i] = 0.0f;
  480. H_MAG[0] = SH_MAG[2];
  481. H_MAG[1] = SH_MAG[1];
  482. H_MAG[2] = SH_MAG[0];
  483. H_MAG[3] = 2.0f*magD*q2 - SH_MAG[8] - SH_MAG[7];
  484. H_MAG[16] = 2.0f*q1*q2 - 2.0f*q0*q3;
  485. H_MAG[17] = SH_MAG[4] - SH_MAG[3] - SH_MAG[5] + SH_MAG[6];
  486. H_MAG[18] = 2.0f*q0*q1 + 2.0f*q2*q3;
  487. H_MAG[19] = 0.0f;
  488. H_MAG[20] = 1.0f;
  489. H_MAG[21] = 0.0f;
  490. // calculate Kalman gain
  491. SK_MY[0] = 1.0f / varInnovMag[1];
  492. SK_MY[1] = SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6];
  493. SK_MY[2] = SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2;
  494. SK_MY[3] = 2.0f*q0*q3 - 2.0f*q1*q2;
  495. SK_MY[4] = 2.0f*q0*q1 + 2.0f*q2*q3;
  496. Kfusion[0] = SK_MY[0]*(P[0][20] + P[0][0]*SH_MAG[2] + P[0][1]*SH_MAG[1] + P[0][2]*SH_MAG[0] - P[0][3]*SK_MY[2] - P[0][17]*SK_MY[1] - P[0][16]*SK_MY[3] + P[0][18]*SK_MY[4]);
  497. Kfusion[1] = SK_MY[0]*(P[1][20] + P[1][0]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[1][2]*SH_MAG[0] - P[1][3]*SK_MY[2] - P[1][17]*SK_MY[1] - P[1][16]*SK_MY[3] + P[1][18]*SK_MY[4]);
  498. Kfusion[2] = SK_MY[0]*(P[2][20] + P[2][0]*SH_MAG[2] + P[2][1]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[2][3]*SK_MY[2] - P[2][17]*SK_MY[1] - P[2][16]*SK_MY[3] + P[2][18]*SK_MY[4]);
  499. Kfusion[3] = SK_MY[0]*(P[3][20] + P[3][0]*SH_MAG[2] + P[3][1]*SH_MAG[1] + P[3][2]*SH_MAG[0] - P[3][3]*SK_MY[2] - P[3][17]*SK_MY[1] - P[3][16]*SK_MY[3] + P[3][18]*SK_MY[4]);
  500. Kfusion[4] = SK_MY[0]*(P[4][20] + P[4][0]*SH_MAG[2] + P[4][1]*SH_MAG[1] + P[4][2]*SH_MAG[0] - P[4][3]*SK_MY[2] - P[4][17]*SK_MY[1] - P[4][16]*SK_MY[3] + P[4][18]*SK_MY[4]);
  501. Kfusion[5] = SK_MY[0]*(P[5][20] + P[5][0]*SH_MAG[2] + P[5][1]*SH_MAG[1] + P[5][2]*SH_MAG[0] - P[5][3]*SK_MY[2] - P[5][17]*SK_MY[1] - P[5][16]*SK_MY[3] + P[5][18]*SK_MY[4]);
  502. Kfusion[6] = SK_MY[0]*(P[6][20] + P[6][0]*SH_MAG[2] + P[6][1]*SH_MAG[1] + P[6][2]*SH_MAG[0] - P[6][3]*SK_MY[2] - P[6][17]*SK_MY[1] - P[6][16]*SK_MY[3] + P[6][18]*SK_MY[4]);
  503. Kfusion[7] = SK_MY[0]*(P[7][20] + P[7][0]*SH_MAG[2] + P[7][1]*SH_MAG[1] + P[7][2]*SH_MAG[0] - P[7][3]*SK_MY[2] - P[7][17]*SK_MY[1] - P[7][16]*SK_MY[3] + P[7][18]*SK_MY[4]);
  504. Kfusion[8] = SK_MY[0]*(P[8][20] + P[8][0]*SH_MAG[2] + P[8][1]*SH_MAG[1] + P[8][2]*SH_MAG[0] - P[8][3]*SK_MY[2] - P[8][17]*SK_MY[1] - P[8][16]*SK_MY[3] + P[8][18]*SK_MY[4]);
  505. Kfusion[9] = SK_MY[0]*(P[9][20] + P[9][0]*SH_MAG[2] + P[9][1]*SH_MAG[1] + P[9][2]*SH_MAG[0] - P[9][3]*SK_MY[2] - P[9][17]*SK_MY[1] - P[9][16]*SK_MY[3] + P[9][18]*SK_MY[4]);
  506. if (!inhibitDelAngBiasStates) {
  507. Kfusion[10] = SK_MY[0]*(P[10][20] + P[10][0]*SH_MAG[2] + P[10][1]*SH_MAG[1] + P[10][2]*SH_MAG[0] - P[10][3]*SK_MY[2] - P[10][17]*SK_MY[1] - P[10][16]*SK_MY[3] + P[10][18]*SK_MY[4]);
  508. Kfusion[11] = SK_MY[0]*(P[11][20] + P[11][0]*SH_MAG[2] + P[11][1]*SH_MAG[1] + P[11][2]*SH_MAG[0] - P[11][3]*SK_MY[2] - P[11][17]*SK_MY[1] - P[11][16]*SK_MY[3] + P[11][18]*SK_MY[4]);
  509. Kfusion[12] = SK_MY[0]*(P[12][20] + P[12][0]*SH_MAG[2] + P[12][1]*SH_MAG[1] + P[12][2]*SH_MAG[0] - P[12][3]*SK_MY[2] - P[12][17]*SK_MY[1] - P[12][16]*SK_MY[3] + P[12][18]*SK_MY[4]);
  510. } else {
  511. // zero indexes 10 to 12 = 3*4 bytes
  512. memset(&Kfusion[10], 0, 12);
  513. }
  514. if (!inhibitDelVelBiasStates) {
  515. Kfusion[13] = SK_MY[0]*(P[13][20] + P[13][0]*SH_MAG[2] + P[13][1]*SH_MAG[1] + P[13][2]*SH_MAG[0] - P[13][3]*SK_MY[2] - P[13][17]*SK_MY[1] - P[13][16]*SK_MY[3] + P[13][18]*SK_MY[4]);
  516. Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]);
  517. Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]);
  518. } else {
  519. // zero indexes 13 to 15 = 3*4 bytes
  520. memset(&Kfusion[13], 0, 12);
  521. }
  522. // zero Kalman gains to inhibit magnetic field state estimation
  523. if (!inhibitMagStates) {
  524. Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]);
  525. Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]);
  526. Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]);
  527. Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]);
  528. Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]);
  529. Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]);
  530. } else {
  531. // zero indexes 16 to 21 = 6*4 bytes
  532. memset(&Kfusion[16], 0, 24);
  533. }
  534. // zero Kalman gains to inhibit wind state estimation
  535. if (!inhibitWindStates) {
  536. Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]);
  537. Kfusion[23] = SK_MY[0]*(P[23][20] + P[23][0]*SH_MAG[2] + P[23][1]*SH_MAG[1] + P[23][2]*SH_MAG[0] - P[23][3]*SK_MY[2] - P[23][17]*SK_MY[1] - P[23][16]*SK_MY[3] + P[23][18]*SK_MY[4]);
  538. } else {
  539. // zero indexes 22 to 23 = 2*4 bytes
  540. memset(&Kfusion[22], 0, 8);
  541. }
  542. // set flags to indicate to other processes that fusion has been performed and is required on the next frame
  543. // this can be used by other fusion processes to avoid fusing on the same frame as this expensive step
  544. magFusePerformed = true;
  545. magFuseRequired = true;
  546. }
  547. else if (obsIndex == 2) // we are now fusing the Z measurement
  548. {
  549. // calculate observation jacobians
  550. for (uint8_t i = 0; i<=stateIndexLim; i++) H_MAG[i] = 0.0f;
  551. H_MAG[0] = SH_MAG[1];
  552. H_MAG[1] = -SH_MAG[2];
  553. H_MAG[2] = SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2;
  554. H_MAG[3] = SH_MAG[0];
  555. H_MAG[16] = 2.0f*q0*q2 + 2.0f*q1*q3;
  556. H_MAG[17] = 2.0f*q2*q3 - 2.0f*q0*q1;
  557. H_MAG[18] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
  558. H_MAG[19] = 0.0f;
  559. H_MAG[20] = 0.0f;
  560. H_MAG[21] = 1.0f;
  561. // calculate Kalman gain
  562. SK_MZ[0] = 1.0f / varInnovMag[2];
  563. SK_MZ[1] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
  564. SK_MZ[2] = SH_MAG[7] + SH_MAG[8] - 2.0f*magD*q2;
  565. SK_MZ[3] = 2.0f*q0*q1 - 2.0f*q2*q3;
  566. SK_MZ[4] = 2.0f*q0*q2 + 2.0f*q1*q3;
  567. Kfusion[0] = SK_MZ[0]*(P[0][21] + P[0][0]*SH_MAG[1] - P[0][1]*SH_MAG[2] + P[0][3]*SH_MAG[0] + P[0][2]*SK_MZ[2] + P[0][18]*SK_MZ[1] + P[0][16]*SK_MZ[4] - P[0][17]*SK_MZ[3]);
  568. Kfusion[1] = SK_MZ[0]*(P[1][21] + P[1][0]*SH_MAG[1] - P[1][1]*SH_MAG[2] + P[1][3]*SH_MAG[0] + P[1][2]*SK_MZ[2] + P[1][18]*SK_MZ[1] + P[1][16]*SK_MZ[4] - P[1][17]*SK_MZ[3]);
  569. Kfusion[2] = SK_MZ[0]*(P[2][21] + P[2][0]*SH_MAG[1] - P[2][1]*SH_MAG[2] + P[2][3]*SH_MAG[0] + P[2][2]*SK_MZ[2] + P[2][18]*SK_MZ[1] + P[2][16]*SK_MZ[4] - P[2][17]*SK_MZ[3]);
  570. Kfusion[3] = SK_MZ[0]*(P[3][21] + P[3][0]*SH_MAG[1] - P[3][1]*SH_MAG[2] + P[3][3]*SH_MAG[0] + P[3][2]*SK_MZ[2] + P[3][18]*SK_MZ[1] + P[3][16]*SK_MZ[4] - P[3][17]*SK_MZ[3]);
  571. Kfusion[4] = SK_MZ[0]*(P[4][21] + P[4][0]*SH_MAG[1] - P[4][1]*SH_MAG[2] + P[4][3]*SH_MAG[0] + P[4][2]*SK_MZ[2] + P[4][18]*SK_MZ[1] + P[4][16]*SK_MZ[4] - P[4][17]*SK_MZ[3]);
  572. Kfusion[5] = SK_MZ[0]*(P[5][21] + P[5][0]*SH_MAG[1] - P[5][1]*SH_MAG[2] + P[5][3]*SH_MAG[0] + P[5][2]*SK_MZ[2] + P[5][18]*SK_MZ[1] + P[5][16]*SK_MZ[4] - P[5][17]*SK_MZ[3]);
  573. Kfusion[6] = SK_MZ[0]*(P[6][21] + P[6][0]*SH_MAG[1] - P[6][1]*SH_MAG[2] + P[6][3]*SH_MAG[0] + P[6][2]*SK_MZ[2] + P[6][18]*SK_MZ[1] + P[6][16]*SK_MZ[4] - P[6][17]*SK_MZ[3]);
  574. Kfusion[7] = SK_MZ[0]*(P[7][21] + P[7][0]*SH_MAG[1] - P[7][1]*SH_MAG[2] + P[7][3]*SH_MAG[0] + P[7][2]*SK_MZ[2] + P[7][18]*SK_MZ[1] + P[7][16]*SK_MZ[4] - P[7][17]*SK_MZ[3]);
  575. Kfusion[8] = SK_MZ[0]*(P[8][21] + P[8][0]*SH_MAG[1] - P[8][1]*SH_MAG[2] + P[8][3]*SH_MAG[0] + P[8][2]*SK_MZ[2] + P[8][18]*SK_MZ[1] + P[8][16]*SK_MZ[4] - P[8][17]*SK_MZ[3]);
  576. Kfusion[9] = SK_MZ[0]*(P[9][21] + P[9][0]*SH_MAG[1] - P[9][1]*SH_MAG[2] + P[9][3]*SH_MAG[0] + P[9][2]*SK_MZ[2] + P[9][18]*SK_MZ[1] + P[9][16]*SK_MZ[4] - P[9][17]*SK_MZ[3]);
  577. if (!inhibitDelAngBiasStates) {
  578. Kfusion[10] = SK_MZ[0]*(P[10][21] + P[10][0]*SH_MAG[1] - P[10][1]*SH_MAG[2] + P[10][3]*SH_MAG[0] + P[10][2]*SK_MZ[2] + P[10][18]*SK_MZ[1] + P[10][16]*SK_MZ[4] - P[10][17]*SK_MZ[3]);
  579. Kfusion[11] = SK_MZ[0]*(P[11][21] + P[11][0]*SH_MAG[1] - P[11][1]*SH_MAG[2] + P[11][3]*SH_MAG[0] + P[11][2]*SK_MZ[2] + P[11][18]*SK_MZ[1] + P[11][16]*SK_MZ[4] - P[11][17]*SK_MZ[3]);
  580. Kfusion[12] = SK_MZ[0]*(P[12][21] + P[12][0]*SH_MAG[1] - P[12][1]*SH_MAG[2] + P[12][3]*SH_MAG[0] + P[12][2]*SK_MZ[2] + P[12][18]*SK_MZ[1] + P[12][16]*SK_MZ[4] - P[12][17]*SK_MZ[3]);
  581. } else {
  582. // zero indexes 10 to 12 = 3*4 bytes
  583. memset(&Kfusion[10], 0, 12);
  584. }
  585. if (!inhibitDelVelBiasStates) {
  586. Kfusion[13] = SK_MZ[0]*(P[13][21] + P[13][0]*SH_MAG[1] - P[13][1]*SH_MAG[2] + P[13][3]*SH_MAG[0] + P[13][2]*SK_MZ[2] + P[13][18]*SK_MZ[1] + P[13][16]*SK_MZ[4] - P[13][17]*SK_MZ[3]);
  587. Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][0]*SH_MAG[1] - P[14][1]*SH_MAG[2] + P[14][3]*SH_MAG[0] + P[14][2]*SK_MZ[2] + P[14][18]*SK_MZ[1] + P[14][16]*SK_MZ[4] - P[14][17]*SK_MZ[3]);
  588. Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][0]*SH_MAG[1] - P[15][1]*SH_MAG[2] + P[15][3]*SH_MAG[0] + P[15][2]*SK_MZ[2] + P[15][18]*SK_MZ[1] + P[15][16]*SK_MZ[4] - P[15][17]*SK_MZ[3]);
  589. } else {
  590. // zero indexes 13 to 15 = 3*4 bytes
  591. memset(&Kfusion[13], 0, 12);
  592. }
  593. // zero Kalman gains to inhibit magnetic field state estimation
  594. if (!inhibitMagStates) {
  595. Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][0]*SH_MAG[1] - P[16][1]*SH_MAG[2] + P[16][3]*SH_MAG[0] + P[16][2]*SK_MZ[2] + P[16][18]*SK_MZ[1] + P[16][16]*SK_MZ[4] - P[16][17]*SK_MZ[3]);
  596. Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][0]*SH_MAG[1] - P[17][1]*SH_MAG[2] + P[17][3]*SH_MAG[0] + P[17][2]*SK_MZ[2] + P[17][18]*SK_MZ[1] + P[17][16]*SK_MZ[4] - P[17][17]*SK_MZ[3]);
  597. Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][0]*SH_MAG[1] - P[18][1]*SH_MAG[2] + P[18][3]*SH_MAG[0] + P[18][2]*SK_MZ[2] + P[18][18]*SK_MZ[1] + P[18][16]*SK_MZ[4] - P[18][17]*SK_MZ[3]);
  598. Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] - P[19][1]*SH_MAG[2] + P[19][3]*SH_MAG[0] + P[19][2]*SK_MZ[2] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[4] - P[19][17]*SK_MZ[3]);
  599. Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] - P[20][1]*SH_MAG[2] + P[20][3]*SH_MAG[0] + P[20][2]*SK_MZ[2] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[4] - P[20][17]*SK_MZ[3]);
  600. Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] - P[21][1]*SH_MAG[2] + P[21][3]*SH_MAG[0] + P[21][2]*SK_MZ[2] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[4] - P[21][17]*SK_MZ[3]);
  601. } else {
  602. // zero indexes 16 to 21 = 6*4 bytes
  603. memset(&Kfusion[16], 0, 24);
  604. }
  605. // zero Kalman gains to inhibit wind state estimation
  606. if (!inhibitWindStates) {
  607. Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] - P[22][1]*SH_MAG[2] + P[22][3]*SH_MAG[0] + P[22][2]*SK_MZ[2] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[4] - P[22][17]*SK_MZ[3]);
  608. Kfusion[23] = SK_MZ[0]*(P[23][21] + P[23][0]*SH_MAG[1] - P[23][1]*SH_MAG[2] + P[23][3]*SH_MAG[0] + P[23][2]*SK_MZ[2] + P[23][18]*SK_MZ[1] + P[23][16]*SK_MZ[4] - P[23][17]*SK_MZ[3]);
  609. } else {
  610. // zero indexes 22 to 23 = 2*4 bytes
  611. memset(&Kfusion[22], 0, 8);
  612. }
  613. // set flags to indicate to other processes that fusion has been performed and is required on the next frame
  614. // this can be used by other fusion processes to avoid fusing on the same frame as this expensive step
  615. magFusePerformed = true;
  616. }
  617. // correct the covariance P = (I - K*H)*P
  618. // take advantage of the empty columns in KH to reduce the
  619. // number of operations
  620. for (unsigned i = 0; i<=stateIndexLim; i++) {
  621. for (unsigned j = 0; j<=3; j++) {
  622. KH[i][j] = Kfusion[i] * H_MAG[j];
  623. }
  624. for (unsigned j = 4; j<=15; j++) {
  625. KH[i][j] = 0.0f;
  626. }
  627. for (unsigned j = 16; j<=21; j++) {
  628. KH[i][j] = Kfusion[i] * H_MAG[j];
  629. }
  630. for (unsigned j = 22; j<=23; j++) {
  631. KH[i][j] = 0.0f;
  632. }
  633. }
  634. for (unsigned j = 0; j<=stateIndexLim; j++) {
  635. for (unsigned i = 0; i<=stateIndexLim; i++) {
  636. ftype res = 0;
  637. res += KH[i][0] * P[0][j];
  638. res += KH[i][1] * P[1][j];
  639. res += KH[i][2] * P[2][j];
  640. res += KH[i][3] * P[3][j];
  641. res += KH[i][16] * P[16][j];
  642. res += KH[i][17] * P[17][j];
  643. res += KH[i][18] * P[18][j];
  644. res += KH[i][19] * P[19][j];
  645. res += KH[i][20] * P[20][j];
  646. res += KH[i][21] * P[21][j];
  647. KHP[i][j] = res;
  648. }
  649. }
  650. // Check that we are not going to drive any variances negative and skip the update if so
  651. bool healthyFusion = true;
  652. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  653. if (KHP[i][i] > P[i][i]) {
  654. healthyFusion = false;
  655. }
  656. }
  657. if (healthyFusion) {
  658. // update the covariance matrix
  659. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  660. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  661. P[i][j] = P[i][j] - KHP[i][j];
  662. }
  663. }
  664. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  665. ForceSymmetry();
  666. ConstrainVariances();
  667. // correct the state vector
  668. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  669. statesArray[j] = statesArray[j] - Kfusion[j] * innovMag[obsIndex];
  670. }
  671. stateStruct.quat.normalize();
  672. } else {
  673. // record bad axis
  674. if (obsIndex == 0) {
  675. faultStatus.bad_xmag = true;
  676. } else if (obsIndex == 1) {
  677. faultStatus.bad_ymag = true;
  678. } else if (obsIndex == 2) {
  679. faultStatus.bad_zmag = true;
  680. }
  681. CovarianceInit();
  682. return;
  683. }
  684. }
  685. }
  686. /*
  687. * Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox.
  688. * The script file used to generate these and other equations in this filter can be found here:
  689. * https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
  690. * This fusion method only modifies the orientation, does not require use of the magnetic field states and is computationally cheaper.
  691. * It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground).
  692. * It is not as robust to magnetometer failures.
  693. * It is not suitable for operation where the horizontal magnetic field strength is weak (within 30 degrees latitude of the magnetic poles)
  694. *
  695. * The following booleans are passed to the function to control the fusion process:
  696. *
  697. * usePredictedYaw - Set this to true if no valid yaw measurement will be available for an extended periods.
  698. * This uses an innovation set to zero which prevents uncontrolled quaternion covaraince growth.
  699. * UseExternalYawSensor - Set this to true if yaw data from an external yaw sensor is being used instead of the magnetometer.
  700. */
  701. void NavEKF3_core::fuseEulerYaw(bool usePredictedYaw, bool useExternalYawSensor)
  702. {
  703. float q0 = stateStruct.quat[0];
  704. float q1 = stateStruct.quat[1];
  705. float q2 = stateStruct.quat[2];
  706. float q3 = stateStruct.quat[3];
  707. // yaw measurement error variance (rad^2)
  708. float R_YAW;
  709. if (!useExternalYawSensor) {
  710. R_YAW = sq(frontend->_yawNoise);
  711. } else {
  712. R_YAW = sq(yawAngDataDelayed.yawAngErr);
  713. }
  714. // determine if a 321 or 312 Euler sequence is best
  715. bool useEuler321 = true;
  716. if (useExternalYawSensor) {
  717. // If using an external sensor, the definition of yaw is specified through the sensor interface
  718. if (yawAngDataDelayed.type == 2) {
  719. useEuler321 = true;
  720. } else if (yawAngDataDelayed.type == 1) {
  721. useEuler321 = false;
  722. } else {
  723. // invalid selection
  724. return;
  725. }
  726. } else {
  727. // if using the magnetometer, it is determined automatically
  728. useEuler321 = (fabsf(prevTnb[0][2]) < fabsf(prevTnb[1][2]));
  729. }
  730. // calculate observation jacobian, predicted yaw and zero yaw body to earth rotation matrix
  731. float yawAngPredicted;
  732. float H_YAW[4];
  733. Matrix3f Tbn_zeroYaw;
  734. if (useEuler321) {
  735. // calculate observation jacobian when we are observing the first rotation in a 321 sequence
  736. float t9 = q0*q3;
  737. float t10 = q1*q2;
  738. float t2 = t9+t10;
  739. float t3 = q0*q0;
  740. float t4 = q1*q1;
  741. float t5 = q2*q2;
  742. float t6 = q3*q3;
  743. float t7 = t3+t4-t5-t6;
  744. float t8 = t7*t7;
  745. if (t8 > 1e-6f) {
  746. t8 = 1.0f/t8;
  747. } else {
  748. return;
  749. }
  750. float t11 = t2*t2;
  751. float t12 = t8*t11*4.0f;
  752. float t13 = t12+1.0f;
  753. float t14;
  754. if (fabsf(t13) > 1e-6f) {
  755. t14 = 1.0f/t13;
  756. } else {
  757. return;
  758. }
  759. H_YAW[0] = t8*t14*(q3*t3-q3*t4+q3*t5+q3*t6+q0*q1*q2*2.0f)*-2.0f;
  760. H_YAW[1] = t8*t14*(-q2*t3+q2*t4+q2*t5+q2*t6+q0*q1*q3*2.0f)*-2.0f;
  761. H_YAW[2] = t8*t14*(q1*t3+q1*t4+q1*t5-q1*t6+q0*q2*q3*2.0f)*2.0f;
  762. H_YAW[3] = t8*t14*(q0*t3+q0*t4-q0*t5+q0*t6+q1*q2*q3*2.0f)*2.0f;
  763. // Get the 321 euler angles
  764. Vector3f euler321;
  765. stateStruct.quat.to_euler(euler321.x, euler321.y, euler321.z);
  766. yawAngPredicted = euler321.z;
  767. // set the yaw to zero and calculate the zero yaw rotation from body to earth frame
  768. Tbn_zeroYaw.from_euler(euler321.x, euler321.y, 0.0f);
  769. } else {
  770. // calculate observation jacobian when we are observing a rotation in a 312 sequence
  771. float t9 = q0*q3;
  772. float t10 = q1*q2;
  773. float t2 = t9-t10;
  774. float t3 = q0*q0;
  775. float t4 = q1*q1;
  776. float t5 = q2*q2;
  777. float t6 = q3*q3;
  778. float t7 = t3-t4+t5-t6;
  779. float t8 = t7*t7;
  780. if (t8 > 1e-6f) {
  781. t8 = 1.0f/t8;
  782. } else {
  783. return;
  784. }
  785. float t11 = t2*t2;
  786. float t12 = t8*t11*4.0f;
  787. float t13 = t12+1.0f;
  788. float t14;
  789. if (fabsf(t13) > 1e-6f) {
  790. t14 = 1.0f/t13;
  791. } else {
  792. return;
  793. }
  794. H_YAW[0] = t8*t14*(q3*t3+q3*t4-q3*t5+q3*t6-q0*q1*q2*2.0f)*-2.0f;
  795. H_YAW[1] = t8*t14*(q2*t3+q2*t4+q2*t5-q2*t6-q0*q1*q3*2.0f)*-2.0f;
  796. H_YAW[2] = t8*t14*(-q1*t3+q1*t4+q1*t5+q1*t6-q0*q2*q3*2.0f)*2.0f;
  797. H_YAW[3] = t8*t14*(q0*t3-q0*t4+q0*t5+q0*t6-q1*q2*q3*2.0f)*2.0f;
  798. // Get the 321 euler angles
  799. Vector3f euler312 = stateStruct.quat.to_vector312();
  800. yawAngPredicted = euler312.z;
  801. // set the yaw to zero and calculate the zero yaw rotation from body to earth frame
  802. Tbn_zeroYaw.from_euler312(euler312.x, euler312.y, 0.0f);
  803. }
  804. // Calculate the innovation
  805. float innovation;
  806. if (!usePredictedYaw) {
  807. if (!useExternalYawSensor) {
  808. // Use the difference between the horizontal projection and declination to give the measured yaw
  809. // rotate measured mag components into earth frame
  810. Vector3f magMeasNED = Tbn_zeroYaw*magDataDelayed.mag;
  811. float yawAngMeasured = wrap_PI(-atan2f(magMeasNED.y, magMeasNED.x) + _ahrs->get_compass()->get_declination());
  812. innovation = wrap_PI(yawAngPredicted - yawAngMeasured);
  813. } else {
  814. // use the external yaw sensor data
  815. innovation = wrap_PI(yawAngPredicted - yawAngDataDelayed.yawAng);
  816. }
  817. } else {
  818. // setting the innovation to zero enables quaternion covariance growth to be constrained when there is no
  819. // method of observing yaw
  820. innovation = 0.0f;
  821. }
  822. // Copy raw value to output variable used for data logging
  823. innovYaw = innovation;
  824. // Calculate innovation variance and Kalman gains, taking advantage of the fact that only the first 4 elements in H are non zero
  825. float PH[4];
  826. float varInnov = R_YAW;
  827. for (uint8_t rowIndex=0; rowIndex<=3; rowIndex++) {
  828. PH[rowIndex] = 0.0f;
  829. for (uint8_t colIndex=0; colIndex<=3; colIndex++) {
  830. PH[rowIndex] += P[rowIndex][colIndex]*H_YAW[colIndex];
  831. }
  832. varInnov += H_YAW[rowIndex]*PH[rowIndex];
  833. }
  834. float varInnovInv;
  835. if (varInnov >= R_YAW) {
  836. varInnovInv = 1.0f / varInnov;
  837. // output numerical health status
  838. faultStatus.bad_yaw = false;
  839. } else {
  840. // the calculation is badly conditioned, so we cannot perform fusion on this step
  841. // we reset the covariance matrix and try again next measurement
  842. CovarianceInit();
  843. // output numerical health status
  844. faultStatus.bad_yaw = true;
  845. return;
  846. }
  847. // calculate Kalman gain
  848. for (uint8_t rowIndex=0; rowIndex<=stateIndexLim; rowIndex++) {
  849. Kfusion[rowIndex] = 0.0f;
  850. for (uint8_t colIndex=0; colIndex<=3; colIndex++) {
  851. Kfusion[rowIndex] += P[rowIndex][colIndex]*H_YAW[colIndex];
  852. }
  853. Kfusion[rowIndex] *= varInnovInv;
  854. }
  855. // calculate the innovation test ratio
  856. yawTestRatio = sq(innovation) / (sq(MAX(0.01f * (float)frontend->_yawInnovGate, 1.0f)) * varInnov);
  857. // Declare the magnetometer unhealthy if the innovation test fails
  858. if (yawTestRatio > 1.0f) {
  859. magHealth = false;
  860. // On the ground a large innovation could be due to large initial gyro bias or magnetic interference from nearby objects
  861. // If we are flying, then it is more likely due to a magnetometer fault and we should not fuse the data
  862. if (inFlight) {
  863. return;
  864. }
  865. } else {
  866. magHealth = true;
  867. }
  868. // limit the innovation so that initial corrections are not too large
  869. if (innovation > 0.5f) {
  870. innovation = 0.5f;
  871. } else if (innovation < -0.5f) {
  872. innovation = -0.5f;
  873. }
  874. // correct the covariance using P = P - K*H*P taking advantage of the fact that only the first 3 elements in H are non zero
  875. // calculate K*H*P
  876. for (uint8_t row = 0; row <= stateIndexLim; row++) {
  877. for (uint8_t column = 0; column <= 3; column++) {
  878. KH[row][column] = Kfusion[row] * H_YAW[column];
  879. }
  880. }
  881. for (uint8_t row = 0; row <= stateIndexLim; row++) {
  882. for (uint8_t column = 0; column <= stateIndexLim; column++) {
  883. float tmp = KH[row][0] * P[0][column];
  884. tmp += KH[row][1] * P[1][column];
  885. tmp += KH[row][2] * P[2][column];
  886. tmp += KH[row][3] * P[3][column];
  887. KHP[row][column] = tmp;
  888. }
  889. }
  890. // Check that we are not going to drive any variances negative and skip the update if so
  891. bool healthyFusion = true;
  892. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  893. if (KHP[i][i] > P[i][i]) {
  894. healthyFusion = false;
  895. }
  896. }
  897. if (healthyFusion) {
  898. // update the covariance matrix
  899. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  900. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  901. P[i][j] = P[i][j] - KHP[i][j];
  902. }
  903. }
  904. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  905. ForceSymmetry();
  906. ConstrainVariances();
  907. // correct the state vector
  908. for (uint8_t i=0; i<=stateIndexLim; i++) {
  909. statesArray[i] -= Kfusion[i] * innovation;
  910. }
  911. stateStruct.quat.normalize();
  912. // record fusion numerical health status
  913. faultStatus.bad_yaw = false;
  914. } else {
  915. // record fusion numerical health status
  916. faultStatus.bad_yaw = true;
  917. }
  918. }
  919. /*
  920. * Fuse declination angle using explicit algebraic equations generated with Matlab symbolic toolbox.
  921. * The script file used to generate these and other equations in this filter can be found here:
  922. * https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
  923. * This is used to prevent the declination of the EKF earth field states from drifting during operation without GPS
  924. * or some other absolute position or velocity reference
  925. */
  926. void NavEKF3_core::FuseDeclination(float declErr)
  927. {
  928. // declination error variance (rad^2)
  929. const float R_DECL = sq(declErr);
  930. // copy required states to local variables
  931. float magN = stateStruct.earth_magfield.x;
  932. float magE = stateStruct.earth_magfield.y;
  933. // prevent bad earth field states from causing numerical errors or exceptions
  934. if (magN < 1e-3f) {
  935. return;
  936. }
  937. // Calculate observation Jacobian and Kalman gains
  938. // Calculate intermediate variables
  939. float t2 = magE*magE;
  940. float t3 = magN*magN;
  941. float t4 = t2+t3;
  942. // if the horizontal magnetic field is too small, this calculation will be badly conditioned
  943. if (t4 < 1e-4f) {
  944. return;
  945. }
  946. float t5 = P[16][16]*t2;
  947. float t6 = P[17][17]*t3;
  948. float t7 = t2*t2;
  949. float t8 = R_DECL*t7;
  950. float t9 = t3*t3;
  951. float t10 = R_DECL*t9;
  952. float t11 = R_DECL*t2*t3*2.0f;
  953. float t14 = P[16][17]*magE*magN;
  954. float t15 = P[17][16]*magE*magN;
  955. float t12 = t5+t6+t8+t10+t11-t14-t15;
  956. float t13;
  957. if (fabsf(t12) > 1e-6f) {
  958. t13 = 1.0f / t12;
  959. } else {
  960. return;
  961. }
  962. float t18 = magE*magE;
  963. float t19 = magN*magN;
  964. float t20 = t18+t19;
  965. float t21;
  966. if (fabsf(t20) > 1e-6f) {
  967. t21 = 1.0f/t20;
  968. } else {
  969. return;
  970. }
  971. // Calculate the observation Jacobian
  972. // Note only 2 terms are non-zero which can be used in matrix operations for calculation of Kalman gains and covariance update to significantly reduce cost
  973. float H_DECL[24] = {};
  974. H_DECL[16] = -magE*t21;
  975. H_DECL[17] = magN*t21;
  976. Kfusion[0] = -t4*t13*(P[0][16]*magE-P[0][17]*magN);
  977. Kfusion[1] = -t4*t13*(P[1][16]*magE-P[1][17]*magN);
  978. Kfusion[2] = -t4*t13*(P[2][16]*magE-P[2][17]*magN);
  979. Kfusion[3] = -t4*t13*(P[3][16]*magE-P[3][17]*magN);
  980. Kfusion[4] = -t4*t13*(P[4][16]*magE-P[4][17]*magN);
  981. Kfusion[5] = -t4*t13*(P[5][16]*magE-P[5][17]*magN);
  982. Kfusion[6] = -t4*t13*(P[6][16]*magE-P[6][17]*magN);
  983. Kfusion[7] = -t4*t13*(P[7][16]*magE-P[7][17]*magN);
  984. Kfusion[8] = -t4*t13*(P[8][16]*magE-P[8][17]*magN);
  985. Kfusion[9] = -t4*t13*(P[9][16]*magE-P[9][17]*magN);
  986. if (!inhibitDelAngBiasStates) {
  987. Kfusion[10] = -t4*t13*(P[10][16]*magE-P[10][17]*magN);
  988. Kfusion[11] = -t4*t13*(P[11][16]*magE-P[11][17]*magN);
  989. Kfusion[12] = -t4*t13*(P[12][16]*magE-P[12][17]*magN);
  990. } else {
  991. // zero indexes 10 to 12 = 3*4 bytes
  992. memset(&Kfusion[10], 0, 12);
  993. }
  994. if (!inhibitDelVelBiasStates) {
  995. Kfusion[13] = -t4*t13*(P[13][16]*magE-P[13][17]*magN);
  996. Kfusion[14] = -t4*t13*(P[14][16]*magE-P[14][17]*magN);
  997. Kfusion[15] = -t4*t13*(P[15][16]*magE-P[15][17]*magN);
  998. } else {
  999. // zero indexes 13 to 15 = 3*4 bytes
  1000. memset(&Kfusion[13], 0, 12);
  1001. }
  1002. if (!inhibitMagStates) {
  1003. Kfusion[16] = -t4*t13*(P[16][16]*magE-P[16][17]*magN);
  1004. Kfusion[17] = -t4*t13*(P[17][16]*magE-P[17][17]*magN);
  1005. Kfusion[18] = -t4*t13*(P[18][16]*magE-P[18][17]*magN);
  1006. Kfusion[19] = -t4*t13*(P[19][16]*magE-P[19][17]*magN);
  1007. Kfusion[20] = -t4*t13*(P[20][16]*magE-P[20][17]*magN);
  1008. Kfusion[21] = -t4*t13*(P[21][16]*magE-P[21][17]*magN);
  1009. } else {
  1010. // zero indexes 16 to 21 = 6*4 bytes
  1011. memset(&Kfusion[16], 0, 24);
  1012. }
  1013. if (!inhibitWindStates) {
  1014. Kfusion[22] = -t4*t13*(P[22][16]*magE-P[22][17]*magN);
  1015. Kfusion[23] = -t4*t13*(P[23][16]*magE-P[23][17]*magN);
  1016. } else {
  1017. // zero indexes 22 to 23 = 2*4 bytes
  1018. memset(&Kfusion[22], 0, 8);
  1019. }
  1020. // get the magnetic declination
  1021. float magDecAng = use_compass() ? _ahrs->get_compass()->get_declination() : 0;
  1022. // Calculate the innovation
  1023. float innovation = atan2f(magE , magN) - magDecAng;
  1024. // limit the innovation to protect against data errors
  1025. if (innovation > 0.5f) {
  1026. innovation = 0.5f;
  1027. } else if (innovation < -0.5f) {
  1028. innovation = -0.5f;
  1029. }
  1030. // correct the covariance P = (I - K*H)*P
  1031. // take advantage of the empty columns in KH to reduce the
  1032. // number of operations
  1033. for (unsigned i = 0; i<=stateIndexLim; i++) {
  1034. for (unsigned j = 0; j<=15; j++) {
  1035. KH[i][j] = 0.0f;
  1036. }
  1037. KH[i][16] = Kfusion[i] * H_DECL[16];
  1038. KH[i][17] = Kfusion[i] * H_DECL[17];
  1039. for (unsigned j = 18; j<=23; j++) {
  1040. KH[i][j] = 0.0f;
  1041. }
  1042. }
  1043. for (unsigned j = 0; j<=stateIndexLim; j++) {
  1044. for (unsigned i = 0; i<=stateIndexLim; i++) {
  1045. KHP[i][j] = KH[i][16] * P[16][j] + KH[i][17] * P[17][j];
  1046. }
  1047. }
  1048. // Check that we are not going to drive any variances negative and skip the update if so
  1049. bool healthyFusion = true;
  1050. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  1051. if (KHP[i][i] > P[i][i]) {
  1052. healthyFusion = false;
  1053. }
  1054. }
  1055. if (healthyFusion) {
  1056. // update the covariance matrix
  1057. for (uint8_t i= 0; i<=stateIndexLim; i++) {
  1058. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  1059. P[i][j] = P[i][j] - KHP[i][j];
  1060. }
  1061. }
  1062. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
  1063. ForceSymmetry();
  1064. ConstrainVariances();
  1065. // correct the state vector
  1066. for (uint8_t j= 0; j<=stateIndexLim; j++) {
  1067. statesArray[j] = statesArray[j] - Kfusion[j] * innovation;
  1068. }
  1069. stateStruct.quat.normalize();
  1070. // record fusion health status
  1071. faultStatus.bad_decl = false;
  1072. } else {
  1073. // record fusion health status
  1074. faultStatus.bad_decl = true;
  1075. }
  1076. }
  1077. /********************************************************
  1078. * MISC FUNCTIONS *
  1079. ********************************************************/
  1080. // align the NE earth magnetic field states with the published declination
  1081. void NavEKF3_core::alignMagStateDeclination()
  1082. {
  1083. // don't do this if we already have a learned magnetic field
  1084. if (magFieldLearned) {
  1085. return;
  1086. }
  1087. // get the magnetic declination
  1088. float magDecAng = use_compass() ? _ahrs->get_compass()->get_declination() : 0;
  1089. // rotate the NE values so that the declination matches the published value
  1090. Vector3f initMagNED = stateStruct.earth_magfield;
  1091. float magLengthNE = norm(initMagNED.x,initMagNED.y);
  1092. stateStruct.earth_magfield.x = magLengthNE * cosf(magDecAng);
  1093. stateStruct.earth_magfield.y = magLengthNE * sinf(magDecAng);
  1094. if (!inhibitMagStates) {
  1095. // zero the corresponding state covariances if magnetic field state learning is active
  1096. float var_16 = P[16][16];
  1097. float var_17 = P[17][17];
  1098. zeroRows(P,16,17);
  1099. zeroCols(P,16,17);
  1100. P[16][16] = var_16;
  1101. P[17][17] = var_17;
  1102. // fuse the declination angle to establish covariances and prevent large swings in declination
  1103. // during initial fusion
  1104. FuseDeclination(0.1f);
  1105. }
  1106. }
  1107. // record a magnetic field state reset event
  1108. void NavEKF3_core::recordMagReset()
  1109. {
  1110. magStateInitComplete = true;
  1111. if (inFlight) {
  1112. finalInflightMagInit = true;
  1113. }
  1114. // take a snap-shot of the vertical position, quaternion and yaw innovation to use as a reference
  1115. // for post alignment checks
  1116. posDownAtLastMagReset = stateStruct.position.z;
  1117. quatAtLastMagReset = stateStruct.quat;
  1118. yawInnovAtLastMagReset = innovYaw;
  1119. }