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