3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 48 P[5][5] =
P[4][4] =
sq(25.0
f);
246 if (!posOffsetBody.
is_zero()) {
250 Vector3f velOffsetBody = angRate % posOffsetBody;
372 bool fuseData[6] = {
false,
false,
false,
false,
false,
false};
414 for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
439 for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
449 if ((hgtErr*velDErr > 0.0
f) && (
sq(hgtErr) > 9.0
f * (
P[9][9] + R_OBS_DATA_CHECKS[5])) && (
sq(velDErr) > 9.0
f * (
P[6][6] + R_OBS_DATA_CHECKS[2]))) {
506 float innovVelSumSq = 0;
508 for (uint8_t i = 0; i<=imax; i++) {
516 innovVelSumSq +=
sq(velInnov[i]);
558 const float hgtInnovFiltTC = 2.0f;
593 for (obsIndex=0; obsIndex<=5; obsIndex++) {
594 if (fuseData[obsIndex]) {
603 else if (obsIndex == 3 || obsIndex == 4) {
606 }
else if (obsIndex == 5) {
608 const float gndMaxBaroErr = 4.0f;
609 const float gndBaroInnovFloor = -0.5f;
627 for (uint8_t i= 0; i<=9; i++) {
633 for (uint8_t i = 10; i<=12; i++) {
643 for (uint8_t i = 13; i<=15; i++) {
653 for (uint8_t i = 16; i<=21; i++) {
679 bool healthyFusion =
true;
681 if (
KHP[i][i] >
P[i][i]) {
682 healthyFusion =
false;
689 P[i][j] =
P[i][j] -
KHP[i][j];
706 }
else if (obsIndex == 1) {
708 }
else if (obsIndex == 2) {
710 }
else if (obsIndex == 3) {
712 }
else if (obsIndex == 4) {
714 }
else if (obsIndex == 5) {
721 }
else if (obsIndex == 1) {
723 }
else if (obsIndex == 2) {
725 }
else if (obsIndex == 3) {
727 }
else if (obsIndex == 4) {
729 }
else if (obsIndex == 5) {
758 if (sensor !=
nullptr) {
760 if (!posOffsetBody.
is_zero()) {
785 bool dontTrustTerrain, trustTerrain;
826 if (lostRngHgt || lostGpsHgt) {
839 const float gndHgtFiltTC = 0.5f;
953 H_VEL[0] = q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f;
954 H_VEL[1] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
955 H_VEL[2] = q0*vd*-2.0f+q1*ve*2.0f-q2*vn*2.0f;
956 H_VEL[3] = q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f;
957 H_VEL[4] = q0*q0+q1*q1-q2*q2-q3*
q3;
958 H_VEL[5] = q0*q3*2.0f+q1*q2*2.0f;
959 H_VEL[6] = q0*q2*-2.0f+q1*q3*2.0f;
960 for (uint8_t index = 7; index < 24; index++) {
966 float t2 = q0*q3*2.0f;
967 float t3 = q1*q2*2.0f;
973 float t9 = t5+t6-t7-
t8;
974 float t10 = q0*q2*2.0f;
975 float t25 = q1*q3*2.0f;
977 float t12 = q3*ve*2.0f;
978 float t13 = q0*vn*2.0f;
979 float t26 = q2*vd*2.0f;
981 float t15 = q3*vd*2.0f;
982 float t16 = q2*ve*2.0f;
983 float t17 = q1*vn*2.0f;
985 float t19 = q0*vd*2.0f;
986 float t20 = q2*vn*2.0f;
987 float t27 = q1*ve*2.0f;
989 float t22 = q1*vd*2.0f;
990 float t23 = q0*ve*2.0f;
991 float t28 = q3*vn*2.0f;
1002 float t36 = t31+t32+t33+t34+t35-t79-
t80;
1011 float t43 = t38+t39+t40+t41+t42-t81-
t82;
1018 float t48 = t29+t44+t45+t46+t47-t84-
t85;
1026 float t54 = t30+t50+t51+t52+t53-t86-
t87;
1035 float t61 = t56+t57+t58+t59+t60-t78-
t88;
1043 float t67 = t62+t63+t64+t65+t66-t90-
t91;
1052 float t74 = t69+t70+t71+t72+t73-t92-
t93;
1056 float t76 = R_VEL+t37+t49+t55+t68+t75-t83-
t89;
1075 Kfusion[0] = t77*(t29+
P[0][5]*t4+
P[0][4]*t9-
P[0][6]*t11+
P[0][1]*t18-
P[0][2]*t21+
P[0][3]*
t24);
1076 Kfusion[1] = t77*(t30+
P[1][5]*t4+
P[1][4]*t9+
P[1][0]*t14-
P[1][6]*t11-
P[1][2]*t21+
P[1][3]*
t24);
1077 Kfusion[2] = t77*(-t78+
P[2][5]*t4+
P[2][4]*t9+
P[2][0]*t14-
P[2][6]*t11+
P[2][1]*t18+
P[2][3]*
t24);
1078 Kfusion[3] = t77*(t66+
P[3][5]*t4+
P[3][4]*t9+
P[3][0]*t14-
P[3][6]*t11+
P[3][1]*t18-
P[3][2]*
t21);
1079 Kfusion[4] = t77*(t69+
P[4][5]*t4+
P[4][0]*t14-
P[4][6]*t11+
P[4][1]*t18-
P[4][2]*t21+
P[4][3]*
t24);
1080 Kfusion[5] = t77*(t32+
P[5][4]*t9+
P[5][0]*t14-
P[5][6]*t11+
P[5][1]*t18-
P[5][2]*t21+
P[5][3]*
t24);
1081 Kfusion[6] = t77*(-t81+
P[6][5]*t4+
P[6][4]*t9+
P[6][0]*t14+
P[6][1]*t18-
P[6][2]*t21+
P[6][3]*
t24);
1082 Kfusion[7] = t77*(
P[7][5]*t4+
P[7][4]*t9+
P[7][0]*t14-
P[7][6]*t11+
P[7][1]*t18-
P[7][2]*t21+
P[7][3]*
t24);
1083 Kfusion[8] = t77*(
P[8][5]*t4+
P[8][4]*t9+
P[8][0]*t14-
P[8][6]*t11+
P[8][1]*t18-
P[8][2]*t21+
P[8][3]*
t24);
1084 Kfusion[9] = t77*(
P[9][5]*t4+
P[9][4]*t9+
P[9][0]*t14-
P[9][6]*t11+
P[9][1]*t18-
P[9][2]*t21+
P[9][3]*
t24);
1087 Kfusion[10] = t77*(
P[10][5]*t4+
P[10][4]*t9+
P[10][0]*t14-
P[10][6]*t11+
P[10][1]*t18-
P[10][2]*t21+
P[10][3]*
t24);
1088 Kfusion[11] = t77*(
P[11][5]*t4+
P[11][4]*t9+
P[11][0]*t14-
P[11][6]*t11+
P[11][1]*t18-
P[11][2]*t21+
P[11][3]*
t24);
1089 Kfusion[12] = t77*(
P[12][5]*t4+
P[12][4]*t9+
P[12][0]*t14-
P[12][6]*t11+
P[12][1]*t18-
P[12][2]*t21+
P[12][3]*
t24);
1092 memset(&Kfusion[10], 0, 12);
1096 Kfusion[13] = t77*(
P[13][5]*t4+
P[13][4]*t9+
P[13][0]*t14-
P[13][6]*t11+
P[13][1]*t18-
P[13][2]*t21+
P[13][3]*
t24);
1097 Kfusion[14] = t77*(
P[14][5]*t4+
P[14][4]*t9+
P[14][0]*t14-
P[14][6]*t11+
P[14][1]*t18-
P[14][2]*t21+
P[14][3]*
t24);
1098 Kfusion[15] = t77*(
P[15][5]*t4+
P[15][4]*t9+
P[15][0]*t14-
P[15][6]*t11+
P[15][1]*t18-
P[15][2]*t21+
P[15][3]*
t24);
1101 memset(&Kfusion[13], 0, 12);
1105 Kfusion[16] = t77*(
P[16][5]*t4+
P[16][4]*t9+
P[16][0]*t14-
P[16][6]*t11+
P[16][1]*t18-
P[16][2]*t21+
P[16][3]*
t24);
1106 Kfusion[17] = t77*(
P[17][5]*t4+
P[17][4]*t9+
P[17][0]*t14-
P[17][6]*t11+
P[17][1]*t18-
P[17][2]*t21+
P[17][3]*
t24);
1107 Kfusion[18] = t77*(
P[18][5]*t4+
P[18][4]*t9+
P[18][0]*t14-
P[18][6]*t11+
P[18][1]*t18-
P[18][2]*t21+
P[18][3]*
t24);
1108 Kfusion[19] = t77*(
P[19][5]*t4+
P[19][4]*t9+
P[19][0]*t14-
P[19][6]*t11+
P[19][1]*t18-
P[19][2]*t21+
P[19][3]*
t24);
1109 Kfusion[20] = t77*(
P[20][5]*t4+
P[20][4]*t9+
P[20][0]*t14-
P[20][6]*t11+
P[20][1]*t18-
P[20][2]*t21+
P[20][3]*
t24);
1110 Kfusion[21] = t77*(
P[21][5]*t4+
P[21][4]*t9+
P[21][0]*t14-
P[21][6]*t11+
P[21][1]*t18-
P[21][2]*t21+
P[21][3]*
t24);
1113 memset(&Kfusion[16], 0, 24);
1117 Kfusion[22] = t77*(
P[22][5]*t4+
P[22][4]*t9+
P[22][0]*t14-
P[22][6]*t11+
P[22][1]*t18-
P[22][2]*t21+
P[22][3]*
t24);
1118 Kfusion[23] = t77*(
P[23][5]*t4+
P[23][4]*t9+
P[23][0]*t14-
P[23][6]*t11+
P[23][1]*t18-
P[23][2]*t21+
P[23][3]*
t24);
1121 memset(&Kfusion[22], 0, 8);
1125 H_VEL[0] = q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f;
1126 H_VEL[1] = q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f;
1127 H_VEL[2] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
1128 H_VEL[3] = q2*vd*2.0f-q3*ve*2.0f-q0*vn*2.0f;
1129 H_VEL[4] = q0*q3*-2.0f+q1*q2*2.0f;
1130 H_VEL[5] = q0*q0-q1*q1+q2*q2-q3*
q3;
1131 H_VEL[6] = q0*q1*2.0f+q2*q3*2.0f;
1132 for (uint8_t index = 7; index < 24; index++) {
1133 H_VEL[index] = 0.0f;
1138 float t2 = q0*q3*2.0f;
1139 float t9 = q1*q2*2.0f;
1145 float t8 = t4-t5+t6-
t7;
1146 float t10 = q0*q1*2.0f;
1147 float t11 = q2*q3*2.0f;
1149 float t13 = q1*vd*2.0f;
1150 float t14 = q0*ve*2.0f;
1151 float t26 = q3*vn*2.0f;
1153 float t16 = q0*vd*2.0f;
1154 float t17 = q2*vn*2.0f;
1155 float t27 = q1*ve*2.0f;
1157 float t19 = q3*vd*2.0f;
1158 float t20 = q2*ve*2.0f;
1159 float t21 = q1*vn*2.0f;
1161 float t23 = q3*ve*2.0f;
1162 float t24 = q0*vn*2.0f;
1163 float t28 = q2*vd*2.0f;
1174 float t36 = t31+t32+t33+t34+t35-t78-
t79;
1182 float t42 = t37+t38+t39+t40+t41-t81-
t82;
1190 float t48 = t29+t44+t45+t46+t47-t83-
t84;
1198 float t54 = t30+t50+t51+t52+t53-t85-
t86;
1207 float t61 = t56+t57+t58+t59+t60-t87-
t88;
1216 float t68 = t63+t64+t65+t66+t67-t89-
t90;
1224 float t74 = t69+t70+t71+t72+t73-t92-
t93;
1228 float t76 = R_VEL+t43+t49+t55+t62+t75-t80-
t91;
1247 Kfusion[0] = t77*(t29-
P[0][4]*t3+
P[0][5]*t8+
P[0][6]*t12+
P[0][1]*t18+
P[0][2]*t22-
P[0][3]*
t25);
1248 Kfusion[1] = t77*(t30-
P[1][4]*t3+
P[1][5]*t8+
P[1][0]*t15+
P[1][6]*t12+
P[1][2]*t22-
P[1][3]*
t25);
1249 Kfusion[2] = t77*(t60-
P[2][4]*t3+
P[2][5]*t8+
P[2][0]*t15+
P[2][6]*t12+
P[2][1]*t18-
P[2][3]*
t25);
1250 Kfusion[3] = t77*(-t90-
P[3][4]*t3+
P[3][5]*t8+
P[3][0]*t15+
P[3][6]*t12+
P[3][1]*t18+
P[3][2]*
t22);
1251 Kfusion[4] = t77*(-t78+
P[4][5]*t8+
P[4][0]*t15+
P[4][6]*t12+
P[4][1]*t18+
P[4][2]*t22-
P[4][3]*
t25);
1252 Kfusion[5] = t77*(t69-
P[5][4]*t3+
P[5][0]*t15+
P[5][6]*t12+
P[5][1]*t18+
P[5][2]*t22-
P[5][3]*
t25);
1253 Kfusion[6] = t77*(t38-
P[6][4]*t3+
P[6][5]*t8+
P[6][0]*t15+
P[6][1]*t18+
P[6][2]*t22-
P[6][3]*
t25);
1254 Kfusion[7] = t77*(-
P[7][4]*t3+
P[7][5]*t8+
P[7][0]*t15+
P[7][6]*t12+
P[7][1]*t18+
P[7][2]*t22-
P[7][3]*
t25);
1255 Kfusion[8] = t77*(-
P[8][4]*t3+
P[8][5]*t8+
P[8][0]*t15+
P[8][6]*t12+
P[8][1]*t18+
P[8][2]*t22-
P[8][3]*
t25);
1256 Kfusion[9] = t77*(-
P[9][4]*t3+
P[9][5]*t8+
P[9][0]*t15+
P[9][6]*t12+
P[9][1]*t18+
P[9][2]*t22-
P[9][3]*
t25);
1259 Kfusion[10] = t77*(-
P[10][4]*t3+
P[10][5]*t8+
P[10][0]*t15+
P[10][6]*t12+
P[10][1]*t18+
P[10][2]*t22-
P[10][3]*
t25);
1260 Kfusion[11] = t77*(-
P[11][4]*t3+
P[11][5]*t8+
P[11][0]*t15+
P[11][6]*t12+
P[11][1]*t18+
P[11][2]*t22-
P[11][3]*
t25);
1261 Kfusion[12] = t77*(-
P[12][4]*t3+
P[12][5]*t8+
P[12][0]*t15+
P[12][6]*t12+
P[12][1]*t18+
P[12][2]*t22-
P[12][3]*
t25);
1264 memset(&Kfusion[10], 0, 12);
1268 Kfusion[13] = t77*(-
P[13][4]*t3+
P[13][5]*t8+
P[13][0]*t15+
P[13][6]*t12+
P[13][1]*t18+
P[13][2]*t22-
P[13][3]*
t25);
1269 Kfusion[14] = t77*(-
P[14][4]*t3+
P[14][5]*t8+
P[14][0]*t15+
P[14][6]*t12+
P[14][1]*t18+
P[14][2]*t22-
P[14][3]*
t25);
1270 Kfusion[15] = t77*(-
P[15][4]*t3+
P[15][5]*t8+
P[15][0]*t15+
P[15][6]*t12+
P[15][1]*t18+
P[15][2]*t22-
P[15][3]*
t25);
1273 memset(&Kfusion[13], 0, 12);
1277 Kfusion[16] = t77*(-
P[16][4]*t3+
P[16][5]*t8+
P[16][0]*t15+
P[16][6]*t12+
P[16][1]*t18+
P[16][2]*t22-
P[16][3]*
t25);
1278 Kfusion[17] = t77*(-
P[17][4]*t3+
P[17][5]*t8+
P[17][0]*t15+
P[17][6]*t12+
P[17][1]*t18+
P[17][2]*t22-
P[17][3]*
t25);
1279 Kfusion[18] = t77*(-
P[18][4]*t3+
P[18][5]*t8+
P[18][0]*t15+
P[18][6]*t12+
P[18][1]*t18+
P[18][2]*t22-
P[18][3]*
t25);
1280 Kfusion[19] = t77*(-
P[19][4]*t3+
P[19][5]*t8+
P[19][0]*t15+
P[19][6]*t12+
P[19][1]*t18+
P[19][2]*t22-
P[19][3]*
t25);
1281 Kfusion[20] = t77*(-
P[20][4]*t3+
P[20][5]*t8+
P[20][0]*t15+
P[20][6]*t12+
P[20][1]*t18+
P[20][2]*t22-
P[20][3]*
t25);
1282 Kfusion[21] = t77*(-
P[21][4]*t3+
P[21][5]*t8+
P[21][0]*t15+
P[21][6]*t12+
P[21][1]*t18+
P[21][2]*t22-
P[21][3]*
t25);
1285 memset(&Kfusion[16], 0, 24);
1289 Kfusion[22] = t77*(-
P[22][4]*t3+
P[22][5]*t8+
P[22][0]*t15+
P[22][6]*t12+
P[22][1]*t18+
P[22][2]*t22-
P[22][3]*
t25);
1290 Kfusion[23] = t77*(-
P[23][4]*t3+
P[23][5]*t8+
P[23][0]*t15+
P[23][6]*t12+
P[23][1]*t18+
P[23][2]*t22-
P[23][3]*
t25);
1293 memset(&Kfusion[22], 0, 8);
1297 H_VEL[0] = q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f;
1298 H_VEL[1] = q1*vd*-2.0f-q0*ve*2.0f+q3*vn*2.0f;
1299 H_VEL[2] = q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f;
1300 H_VEL[3] = q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f;
1301 H_VEL[4] = q0*q2*2.0f+q1*q3*2.0f;
1302 H_VEL[5] = q0*q1*-2.0f+q2*q3*2.0f;
1303 H_VEL[6] = q0*q0-q1*q1-q2*q2+q3*
q3;
1304 for (uint8_t index = 7; index < 24; index++) {
1305 H_VEL[index] = 0.0f;
1310 float t2 = q0*q2*2.0f;
1311 float t3 = q1*q3*2.0f;
1317 float t9 = t5-t6-t7+
t8;
1318 float t10 = q0*q1*2.0f;
1319 float t25 = q2*q3*2.0f;
1321 float t12 = q0*vd*2.0f;
1322 float t13 = q2*vn*2.0f;
1323 float t26 = q1*ve*2.0f;
1325 float t15 = q1*vd*2.0f;
1326 float t16 = q0*ve*2.0f;
1327 float t27 = q3*vn*2.0f;
1329 float t18 = q3*ve*2.0f;
1330 float t19 = q0*vn*2.0f;
1331 float t28 = q2*vd*2.0f;
1333 float t21 = q3*vd*2.0f;
1334 float t22 = q2*ve*2.0f;
1335 float t23 = q1*vn*2.0f;
1345 float t35 = t30+t31+t32+t33+t34-t78-
t79;
1354 float t42 = t37+t38+t39+t40+t41-t80-
t81;
1361 float t47 = t29+t43+t44+t45+t46-t83-
t84;
1370 float t54 = t49+t50+t51+t52+t53-t85-
t86;
1378 float t60 = t55+t56+t57+t58+t59-t88-
t89;
1387 float t67 = t62+t63+t64+t65+t66-t90-
t91;
1396 float t74 = t69+t70+t71+t72+t73-t92-
t93;
1400 float t76 = R_VEL+t36+t48+t61+t68+t75-t82-
t87;
1419 Kfusion[0] = t77*(t29+
P[0][4]*t4+
P[0][6]*t9-
P[0][5]*t11-
P[0][1]*t17+
P[0][2]*t20+
P[0][3]*
t24);
1420 Kfusion[1] = t77*(
P[1][4]*t4+
P[1][0]*t14+
P[1][6]*t9-
P[1][5]*t11-
P[1][1]*t17+
P[1][2]*t20+
P[1][3]*
t24);
1421 Kfusion[2] = t77*(t58+
P[2][4]*t4+
P[2][0]*t14+
P[2][6]*t9-
P[2][5]*t11-
P[2][1]*t17+
P[2][3]*
t24);
1422 Kfusion[3] = t77*(t66+
P[3][4]*t4+
P[3][0]*t14+
P[3][6]*t9-
P[3][5]*t11-
P[3][1]*t17+
P[3][2]*
t20);
1423 Kfusion[4] = t77*(t31+
P[4][0]*t14+
P[4][6]*t9-
P[4][5]*t11-
P[4][1]*t17+
P[4][2]*t20+
P[4][3]*
t24);
1424 Kfusion[5] = t77*(-t80+
P[5][4]*t4+
P[5][0]*t14+
P[5][6]*t9-
P[5][1]*t17+
P[5][2]*t20+
P[5][3]*
t24);
1425 Kfusion[6] = t77*(t69+
P[6][4]*t4+
P[6][0]*t14-
P[6][5]*t11-
P[6][1]*t17+
P[6][2]*t20+
P[6][3]*
t24);
1426 Kfusion[7] = t77*(
P[7][4]*t4+
P[7][0]*t14+
P[7][6]*t9-
P[7][5]*t11-
P[7][1]*t17+
P[7][2]*t20+
P[7][3]*
t24);
1427 Kfusion[8] = t77*(
P[8][4]*t4+
P[8][0]*t14+
P[8][6]*t9-
P[8][5]*t11-
P[8][1]*t17+
P[8][2]*t20+
P[8][3]*
t24);
1428 Kfusion[9] = t77*(
P[9][4]*t4+
P[9][0]*t14+
P[9][6]*t9-
P[9][5]*t11-
P[9][1]*t17+
P[9][2]*t20+
P[9][3]*
t24);
1431 Kfusion[10] = t77*(
P[10][4]*t4+
P[10][0]*t14+
P[10][6]*t9-
P[10][5]*t11-
P[10][1]*t17+
P[10][2]*t20+
P[10][3]*
t24);
1432 Kfusion[11] = t77*(
P[11][4]*t4+
P[11][0]*t14+
P[11][6]*t9-
P[11][5]*t11-
P[11][1]*t17+
P[11][2]*t20+
P[11][3]*
t24);
1433 Kfusion[12] = t77*(
P[12][4]*t4+
P[12][0]*t14+
P[12][6]*t9-
P[12][5]*t11-
P[12][1]*t17+
P[12][2]*t20+
P[12][3]*
t24);
1436 memset(&Kfusion[10], 0, 12);
1441 Kfusion[13] = t77*(
P[13][4]*t4+
P[13][0]*t14+
P[13][6]*t9-
P[13][5]*t11-
P[13][1]*t17+
P[13][2]*t20+
P[13][3]*
t24);
1442 Kfusion[14] = t77*(
P[14][4]*t4+
P[14][0]*t14+
P[14][6]*t9-
P[14][5]*t11-
P[14][1]*t17+
P[14][2]*t20+
P[14][3]*
t24);
1443 Kfusion[15] = t77*(
P[15][4]*t4+
P[15][0]*t14+
P[15][6]*t9-
P[15][5]*t11-
P[15][1]*t17+
P[15][2]*t20+
P[15][3]*
t24);
1446 memset(&Kfusion[13], 0, 12);
1450 Kfusion[16] = t77*(
P[16][4]*t4+
P[16][0]*t14+
P[16][6]*t9-
P[16][5]*t11-
P[16][1]*t17+
P[16][2]*t20+
P[16][3]*
t24);
1451 Kfusion[17] = t77*(
P[17][4]*t4+
P[17][0]*t14+
P[17][6]*t9-
P[17][5]*t11-
P[17][1]*t17+
P[17][2]*t20+
P[17][3]*
t24);
1452 Kfusion[18] = t77*(
P[18][4]*t4+
P[18][0]*t14+
P[18][6]*t9-
P[18][5]*t11-
P[18][1]*t17+
P[18][2]*t20+
P[18][3]*
t24);
1453 Kfusion[19] = t77*(
P[19][4]*t4+
P[19][0]*t14+
P[19][6]*t9-
P[19][5]*t11-
P[19][1]*t17+
P[19][2]*t20+
P[19][3]*
t24);
1454 Kfusion[20] = t77*(
P[20][4]*t4+
P[20][0]*t14+
P[20][6]*t9-
P[20][5]*t11-
P[20][1]*t17+
P[20][2]*t20+
P[20][3]*
t24);
1455 Kfusion[21] = t77*(
P[21][4]*t4+
P[21][0]*t14+
P[21][6]*t9-
P[21][5]*t11-
P[21][1]*t17+
P[21][2]*t20+
P[21][3]*
t24);
1458 memset(&Kfusion[16], 0, 24);
1462 Kfusion[22] = t77*(
P[22][4]*t4+
P[22][0]*t14+
P[22][6]*t9-
P[22][5]*t11-
P[22][1]*t17+
P[22][2]*t20+
P[22][3]*
t24);
1463 Kfusion[23] = t77*(
P[23][4]*t4+
P[23][0]*t14+
P[23][6]*t9-
P[23][5]*t11-
P[23][1]*t17+
P[23][2]*t20+
P[23][3]*
t24);
1466 memset(&Kfusion[22], 0, 8);
1490 for (
unsigned j = 0; j<=6; j++) {
1500 res +=
KH[i][0] *
P[0][j];
1501 res +=
KH[i][1] * P[1][j];
1502 res +=
KH[i][2] * P[2][j];
1503 res +=
KH[i][3] * P[3][j];
1504 res +=
KH[i][4] * P[4][j];
1505 res +=
KH[i][5] * P[5][j];
1506 res +=
KH[i][6] * P[6][j];
1512 bool healthyFusion =
true;
1514 if (
KHP[i][i] >
P[i][i]) {
1515 healthyFusion =
false;
1519 if (healthyFusion) {
1523 P[i][j] =
P[i][j] -
KHP[i][j];
1539 if (obsIndex == 0) {
1541 }
else if (obsIndex == 1) {
1543 }
else if (obsIndex == 2) {
1595 Vector3f velNED = unitVec * fwdSpd;
1612 #endif // HAL_CPU_CLASS
float norm(const T first, const U second, const Params... parameters)
AP_Int8 _gpsGlitchRadiusMax
AP_RangeFinder_Backend * get_backend(uint8_t id) const
gps_elements gpsDataDelayed
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
uint32_t lastPosPassTime_ms
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
baro_elements baroDataDelayed
void update_calibration(void)
AP_Int16 _gpsVelInnovGate
obs_ring_buffer_t< vel_odm_elements > storedBodyOdm
void selectHeightForFusion()
imu_elements imuDataDelayed
Interface definition for the various Ground Control System.
void SelectBodyOdomFusion()
void calcFiltBaroOffset()
vel_odm_elements bodyOdmDataDelayed
imu_ring_buffer_t< output_elements > storedOutput
AP_Float _gpsHorizPosNoise
void SelectVelPosFusion()
AP_Float _noaidHorizNoise
uint32_t lastVelPassTime_ms
uint32_t lastPosResetD_ms
struct NavEKF3_core::@153 faultStatus
uint32_t lastRngBcnPassTime_ms
const Vector3f & get_pos_offset() const
wheel_odm_elements wheelOdmDataDelayed
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
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
bool inhibitGpsVertVelUse
output_elements outputDataNew
const Vector3f & get_antenna_offset(uint8_t instance) const
Vector2f lastKnownPositionNE
uint32_t lastHgtPassTime_ms
float receiverPosCov[3][3]
const uint16_t hgtRetryTimeMode0_ms
uint32_t lastTimeGpsReceived_ms
AP_Int16 _gpsPosInnovGate
obs_ring_buffer_t< gps_elements > storedGPS
resetDataSource velResetSource
const uint16_t hgtRetryTimeMode12_ms
virtual void perf_end(perf_counter_t h)
obs_ring_buffer_t< range_elements > storedRange
const float gpsPosVarAccScale
int16_t max_distance_cm_orient(enum Rotation orientation) const
resetDataSource posResetSource
void send_text(MAV_SEVERITY severity, const char *fmt,...)
AP_HAL::Util::perf_counter_t _perf_FuseBodyOdom
void correctEkfOriginHeight()
Vector3< T > mul_transpose(const Vector3< T > &v) const
bool inhibitDelVelBiasStates
output_elements outputDataDelayed
struct nav_filter_status::@138 flags
float constrain_float(const float amt, const float low, const float high)
virtual void perf_begin(perf_counter_t h)
const float gndEffectBaroScaler
bool getTouchdownExpected()
obs_ring_buffer_t< wheel_odm_elements > storedWheelOdm
uint32_t rngValidMeaTime_ms
uint32_t rngBcnLast3DmeasTime_ms
bool getTakeoffExpected()
void ConstrainVariances()
AP_Float _gpsVertVelNoise
bool bodyVelFusionDelayed
nav_filter_status filterStatus
const Vector3f * hub_offset
obs_ring_buffer_t< baro_elements > storedBaro
uint32_t imuSampleTime_ms
const float gpsDVelVarAccScale
uint32_t prevBodyVelFuseTime_ms
const float gpsNEVelVarAccScale
uint8_t imu_buffer_length
AP_Float _gpsHorizVelNoise
bool resetHeightDatum(void)
const Vector3f * body_offset