3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 94 float losRateSq = velHorizSq /
sq(heightAboveGndEst);
111 distanceTravelledSq =
MIN(distanceTravelledSq, 100.0
f);
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)));
190 losPred =
norm(relVelSensor.
x, relVelSensor.
y)/flowRngPred;
200 float t10 = q0*q3*2.0f;
201 float t11 = q1*q2*2.0f;
202 float t14 = t3+t4-t5-
t6;
206 float t18 = q0*q2*2.0f;
207 float t19 = q1*q3*2.0f;
210 float t2 = t15+t17-
t21;
211 float t7 = t3-t4-t5+
t6;
213 float t9 = 1.0f/
sq(t8);
214 float t24 = t3-t4+t5-
t6;
218 float t28 = q0*q1*2.0f;
219 float t29 = q2*q3*2.0f;
225 float t23 = 1.0f/(t8*t8*
t8);
227 H_OPT = 0.5f*(t13*t22*t23*2.0f+t13*t23*t32*2.0f)/sqrtf(t9*t13*t22+t9*t13*t32);
251 Popt =
MAX(Popt,0.0
f);
285 float ptd = pd + heightAboveGndEst;
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;
299 SH_LOS[11] = q0*q3*2.0f;
301 SH_LOS[13] = 1.0f/(SH_LOS[12]*SH_LOS[12]);
312 if (!posOffsetBody.
is_zero()) {
321 losPred[0] = relVelSensor.
y/range;
322 losPred[1] = -relVelSensor.
x/range;
325 memset(&H_LOS[0], 0,
sizeof(H_LOS));
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);
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;
345 float t8 = q0*q1*2.0f;
346 float t9 = q2*q3*2.0f;
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;
353 float t16 = q3*vd*2.0f;
354 float t17 = q2*ve*2.0f;
355 float t18 = q1*vn*2.0f;
357 float t20 = q3*ve*2.0f;
358 float t21 = q0*vn*2.0f;
359 float t30 = q2*vd*2.0f;
365 float t27 = t23-t24+t25-
t26;
371 float t79 =
P[4][0]*t2*
t7;
373 float t36 = t12+t32+t33+t34+t35-t79-
t80;
376 float t39 =
P[0][1]*t2*
t5;
379 float t81 =
P[4][1]*t2*
t7;
381 float t42 = t31+t38+t39+t40+t41-t81-
t82;
384 float t45 =
P[0][2]*t2*
t5;
388 float t83 =
P[4][2]*t2*
t7;
390 float t49 = t44+t45+t46+t47+t48-t83-
t84;
393 float t52 =
P[0][3]*t2*
t5;
397 float t85 =
P[4][3]*t2*
t7;
399 float t56 = t51+t52+t53+t54+t55-t85-
t86;
401 float t58 =
P[0][5]*t2*
t5;
405 float t88 =
P[4][5]*t2*
t7;
407 float t62 = t57+t58+t59+t60+t61-t88-
t89;
410 float t65 =
P[0][4]*t2*
t5;
414 float t90 =
P[4][4]*t2*
t7;
416 float t69 = t64+t65+t66+t67+t68-t90-
t91;
418 float t71 =
P[0][6]*t2*
t5;
422 float t93 =
P[4][6]*t2*
t7;
424 float t75 = t70+t71+t72+t73+t74-t93-
t94;
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);
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);
464 memset(&Kfusion[10], 0, 12);
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);
473 memset(&Kfusion[13], 0, 12);
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);
485 memset(&Kfusion[16], 0, 24);
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);
493 memset(&Kfusion[22], 0, 8);
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);
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;
516 float t9 = q0*q2*2.0f;
517 float t28 = q1*q3*2.0f;
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;
524 float t17 = q0*vd*2.0f;
525 float t18 = q2*vn*2.0f;
526 float t29 = q1*ve*2.0f;
528 float t20 = q1*vd*2.0f;
529 float t21 = q0*ve*2.0f;
530 float t30 = q3*vn*2.0f;
536 float t27 = t23+t24-t25-
t26;
538 float t32 =
P[5][0]*t2*
t8;
544 float t36 = t12+t32+t33+t34+t35-t80-
t81;
546 float t38 =
P[5][1]*t2*
t8;
547 float t39 =
P[0][1]*t2*
t5;
552 float t42 = t31+t38+t39+t40+t41-t82-
t83;
554 float t44 =
P[5][2]*t2*
t8;
555 float t45 =
P[0][2]*t2*
t5;
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;
569 float t55 = t50+t51+t52+t53+t54-t86-
t87;
571 float t57 =
P[5][4]*t2*
t8;
572 float t58 =
P[0][4]*t2*
t5;
578 float t62 = t57+t58+t59+t60+t61-t88-
t89;
580 float t64 =
P[5][5]*t2*
t8;
581 float t65 =
P[0][5]*t2*
t5;
587 float t69 = t64+t65+t66+t67+t68-t90-
t91;
589 float t71 =
P[5][6]*t2*
t8;
590 float t72 =
P[0][6]*t2*
t5;
596 float t76 = t71+t72+t73+t74+t75-t92-
t93;
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);
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);
636 memset(&Kfusion[10], 0, 12);
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);
645 memset(&Kfusion[13], 0, 12);
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);
657 memset(&Kfusion[16], 0, 24);
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);
665 memset(&Kfusion[22], 0, 8);
685 for (
unsigned j = 0; j<=6; j++) {
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];
707 bool healthyFusion =
true;
709 if (
KHP[i][i] >
P[i][i]) {
710 healthyFusion =
false;
718 P[i][j] =
P[i][j] -
KHP[i][j];
736 }
else if (obsIndex == 1) {
749 #endif // HAL_CPU_CLASS
float norm(const T first, const U second, const Params... parameters)
uint32_t gndHgtValidTime_ms
uint32_t prevFlowFuseTime_ms
bool optFlowFusionDelayed
imu_elements imuDataDelayed
Interface definition for the various Ground Control System.
of_elements ofDataDelayed
const uint8_t gndGradientSigma
struct NavEKF3_core::@153 faultStatus
uint32_t flowValidMeaTime_ms
uint32_t timeAtLastAuxEKF_ms
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
range_elements rangeDataDelayed
struct NavEKF3_core::state_elements & stateStruct
bool inhibitDelAngBiasStates
AP_HAL::Util::perf_counter_t _perf_FuseOptFlow
virtual void perf_end(perf_counter_t h)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Vector3< T > mul_transpose(const Vector3< T > &v) const
bool inhibitDelVelBiasStates
obs_ring_buffer_t< of_elements > storedOF
float constrain_float(const float amt, const float low, const float high)
virtual void perf_begin(perf_counter_t h)
AP_HAL::Util::perf_counter_t _perf_TerrainOffset
void ConstrainVariances()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
const Vector3f * body_offset
void EstimateTerrainOffset()
uint32_t imuSampleTime_ms