3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 91 float losRateSq = velHorizSq /
sq(heightAboveGndEst);
108 distanceTravelledSq =
MIN(distanceTravelledSq, 100.0
f);
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)));
187 losPred =
norm(relVelSensor.
x, relVelSensor.
y)/flowRngPred;
197 float t10 = q0*q3*2.0f;
198 float t11 = q1*q2*2.0f;
199 float t14 = t3+t4-t5-
t6;
203 float t18 = q0*q2*2.0f;
204 float t19 = q1*q3*2.0f;
207 float t2 = t15+t17-
t21;
208 float t7 = t3-t4-t5+
t6;
210 float t9 = 1.0f/
sq(t8);
211 float t24 = t3-t4+t5-
t6;
215 float t28 = q0*q1*2.0f;
216 float t29 = q2*q3*2.0f;
222 float t23 = 1.0f/(t8*t8*
t8);
224 H_OPT = 0.5f*(t13*t22*t23*2.0f+t13*t23*t32*2.0f)/sqrtf(t9*t13*t22+t9*t13*t32);
248 Popt =
MAX(Popt,0.0
f);
282 float ptd = pd + heightAboveGndEst;
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;
296 SH_LOS[11] = q0*q3*2.0f;
298 SH_LOS[13] = 1.0f/(SH_LOS[12]*SH_LOS[12]);
309 if (!posOffsetBody.
is_zero()) {
318 losPred[0] = relVelSensor.
y/range;
319 losPred[1] = -relVelSensor.
x/range;
322 memset(&H_LOS[0], 0,
sizeof(H_LOS));
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];
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];
341 float t10 = q0*q3*2.0f;
342 float t21 = q1*q2*2.0f;
346 float t13 = 1.0f/(t12*
t12);
348 float t14 = SH_LOS[5];
350 float t15 = SH_LOS[1];
356 float t20 = t16-t17+t18-
t19;
366 float t27 = t23+t24+t25+t26-t63-t64-
t65;
374 float t32 = t28+t29+t30+t31-t67-t68-
t69;
383 float t38 = t34+t35+t36+t37-t70-t71-
t72;
391 float t43 = t22+t40+t41+t42-t73-t74-
t75;
400 float t49 = t45+t46+t47+t48-t76-t77-
t78;
409 float t55 = t51+t52+t53+t54-t79-t80-
t81;
417 float t60 = t56+t57+t58+t59-t83-t84-
t85;
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);
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);
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);
471 for (uint8_t i = 16; i <= 21; i++) {
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];
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];
495 float t10 = q0*q3*2.0f;
496 float t11 = q1*q2*2.0f;
500 float t14 = 1.0f/(t13*
t13);
502 float t15 = SH_LOS[6];
504 float t16 = SH_LOS[2];
510 float t21 = t17+t18-t19-
t20;
520 float t27 = t23+t24+t25+t26-t64-t65-
t66;
529 float t33 = t29+t30+t31+t32-t67-t68-
t69;
537 float t38 = t34+t35+t36+t37-t71-t72-
t73;
545 float t43 = t22+t40+t41+t42-t74-t75-
t76;
554 float t49 = t45+t46+t47+t48-t63-t77-
t78;
562 float t54 = t50+t51+t52+t53-t80-t81-
t82;
571 float t60 = t56+t57+t58+t59-t83-t84-
t85;
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);
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);
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);
625 for (uint8_t i = 16; i <= 21; i++) {
643 for (
unsigned j = 0; j<=5; j++) {
646 for (
unsigned j = 6; j<=7; j++) {
650 for (
unsigned j = 9; j<=23; j++) {
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];
669 bool healthyFusion =
true;
671 if (
KHP[i][i] >
P[i][i]) {
672 healthyFusion =
false;
680 P[i][j] =
P[i][j] -
KHP[i][j];
704 }
else if (obsIndex == 1) {
717 #endif // HAL_CPU_CLASS
float norm(const T first, const U second, const Params... parameters)
const uint8_t gndGradientSigma
bool optFlowFusionDelayed
void EstimateTerrainOffset()
struct NavEKF2_core::state_elements & stateStruct
uint32_t timeAtLastAuxEKF_ms
uint32_t imuSampleTime_ms
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
struct NavEKF2_core::@145 faultStatus
uint32_t prevFlowFuseTime_ms
const Vector3f * body_offset
virtual void perf_end(perf_counter_t h)
uint32_t gndHgtValidTime_ms
Vector3< T > mul_transpose(const Vector3< T > &v) const
void ConstrainVariances()
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
of_elements ofDataDelayed
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void rotate(const Vector3f &v)
AP_HAL::Util::perf_counter_t _perf_FuseOptFlow
range_elements rangeDataDelayed
uint32_t flowValidMeaTime_ms