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