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