AP_NavEKF2_MagFusion.cpp 57 KB

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