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