3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 7 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX 8 #pragma GCC optimize("O0") 10 #pragma GCC optimize("O3") 28 #define GYRO_BIAS_LIMIT 0.349066f // maximum allowed gyro bias (rad/sec) 46 memset(&
Cov,0,
sizeof(
Cov));
76 bool main_ekf_healthy =
false;
81 main_ekf_healthy =
true;
96 vehicle_to_gimbal_quat.
from_vector312(joint_angles.
x,joint_angles.
y,joint_angles.
z);
99 state.
quat = ned_to_vehicle_quat * vehicle_to_gimbal_quat;
101 const float Sigma_velNED = 0.5f;
102 const float Sigma_dAngBias = 0.002f*
dtIMU;
103 const float Sigma_angErr = 0.1f;
104 for (uint8_t i=0; i <= 2; i++)
Cov[i][i] =
sq(Sigma_angErr);
105 for (uint8_t i=3; i <= 5; i++)
Cov[i][i] =
sq(Sigma_velNED);
106 for (uint8_t i=6; i <= 8; i++)
Cov[i][i] =
sq(Sigma_dAngBias);
117 gSense.gTheta = joint_angles.
y;
124 gSense.delAng = delta_angles;
125 gSense.delVel = delta_velocity;
143 hal.
console->
printf(
"\nSoloGimbalEKF Alignment Completed\n");
167 gimDelAngCorrected =
gSense.delAng -
state.
delAngBias - (gimDelAngPrev % gimDelAngCorrected) * 8.333333e-2
f;
197 float delAngBiasVariance =
sq(
dtIMU*5E-6
f);
199 delAngBiasVariance *= 4.0f;
203 float dayNoise =
sq(
dtIMU*0.0087f);
204 float dazNoise =
sq(
dtIMU*0.0087f);
206 float dvxNoise =
sq(
dtIMU*0.5f);
207 float dvyNoise =
sq(
dtIMU*0.5f);
208 float dvzNoise =
sq(
dtIMU*0.5f);
209 float dvx =
gSense.delVel.x;
210 float dvy =
gSense.delVel.y;
211 float dvz =
gSense.delVel.z;
212 float dax =
gSense.delAng.x;
213 float day =
gSense.delAng.y;
214 float daz =
gSense.delAng.z;
222 float t1365 = dax*0.5f;
223 float t1366 = dax_b*0.5f;
224 float t1367 = t1365-t1366;
225 float t1368 = day*0.5f;
226 float t1369 = day_b*0.5f;
227 float t1370 = t1368-t1369;
228 float t1371 = daz*0.5f;
229 float t1372 = daz_b*0.5f;
230 float t1373 = t1371-t1372;
231 float t1374 = q2*t1367*0.5f;
232 float t1375 = q1*t1370*0.5f;
233 float t1376 = q0*t1373*0.5f;
234 float t1377 = q2*0.5f;
235 float t1378 = q3*t1367*0.5f;
236 float t1379 = q1*t1373*0.5f;
237 float t1380 = q1*0.5f;
238 float t1381 = q0*t1367*0.5f;
239 float t1382 = q3*t1370*0.5f;
240 float t1383 = q0*0.5f;
241 float t1384 = q2*t1370*0.5f;
242 float t1385 = q3*t1373*0.5f;
243 float t1386 = q0*t1370*0.5f;
244 float t1387 = q3*0.5f;
245 float t1388 = q1*t1367*0.5f;
246 float t1389 = q2*t1373*0.5f;
247 float t1390 = t1374+t1375+t1376-t1387;
248 float t1391 = t1377+t1378+t1379-t1386;
249 float t1392 = q2*t1391*2.0f;
250 float t1393 = t1380+t1381+t1382-t1389;
251 float t1394 = q1*t1393*2.0f;
252 float t1395 = t1383+t1384+t1385-t1388;
253 float t1396 = q0*t1395*2.0f;
254 float t1403 = q3*t1390*2.0f;
255 float t1397 = t1392+t1394+t1396-t1403;
256 float t1398 =
sq(q0);
257 float t1399 =
sq(q1);
258 float t1400 =
sq(q2);
259 float t1401 =
sq(q3);
260 float t1402 = t1398+t1399+t1400+t1401;
261 float t1404 = t1374+t1375-t1376+t1387;
262 float t1405 = t1377-t1378+t1379+t1386;
263 float t1406 = q1*t1405*2.0f;
264 float t1407 = -t1380+t1381+t1382+t1389;
265 float t1408 = q2*t1407*2.0f;
266 float t1409 = t1383-t1384+t1385+t1388;
267 float t1410 = q3*t1409*2.0f;
268 float t1420 = q0*t1404*2.0f;
269 float t1411 = t1406+t1408+t1410-t1420;
270 float t1412 = -t1377+t1378+t1379+t1386;
271 float t1413 = q0*t1412*2.0f;
272 float t1414 = t1374-t1375+t1376+t1387;
273 float t1415 = t1383+t1384-t1385+t1388;
274 float t1416 = q2*t1415*2.0f;
275 float t1417 = t1380-t1381+t1382+t1389;
276 float t1418 = q3*t1417*2.0f;
277 float t1421 = q1*t1414*2.0f;
278 float t1419 = t1413+t1416+t1418-t1421;
279 float t1422 =
Cov[0][0]*t1397;
280 float t1423 =
Cov[1][0]*t1411;
281 float t1429 =
Cov[6][0]*t1402;
282 float t1430 =
Cov[2][0]*t1419;
283 float t1424 = t1422+t1423-t1429-t1430;
284 float t1425 =
Cov[0][1]*t1397;
285 float t1426 =
Cov[1][1]*t1411;
286 float t1427 =
Cov[0][2]*t1397;
287 float t1428 =
Cov[1][2]*t1411;
288 float t1434 =
Cov[6][1]*t1402;
289 float t1435 =
Cov[2][1]*t1419;
290 float t1431 = t1425+t1426-t1434-t1435;
291 float t1442 =
Cov[6][2]*t1402;
292 float t1443 =
Cov[2][2]*t1419;
293 float t1432 = t1427+t1428-t1442-t1443;
294 float t1433 = t1398+t1399-t1400-t1401;
295 float t1436 = q0*q2*2.0f;
296 float t1437 = q1*q3*2.0f;
297 float t1438 = t1436+t1437;
298 float t1439 = q0*q3*2.0f;
299 float t1441 = q1*q2*2.0f;
300 float t1440 = t1439-t1441;
301 float t1444 = t1398-t1399+t1400-t1401;
302 float t1445 = q0*q1*2.0f;
303 float t1449 = q2*q3*2.0f;
304 float t1446 = t1445-t1449;
305 float t1447 = t1439+t1441;
306 float t1448 = t1398-t1399-t1400+t1401;
307 float t1450 = t1445+t1449;
308 float t1451 = t1436-t1437;
309 float t1452 =
Cov[0][6]*t1397;
310 float t1453 =
Cov[1][6]*t1411;
311 float t1628 =
Cov[6][6]*t1402;
312 float t1454 = t1452+t1453-t1628-
Cov[2][6]*t1419;
313 float t1455 =
Cov[0][7]*t1397;
314 float t1456 =
Cov[1][7]*t1411;
315 float t1629 =
Cov[6][7]*t1402;
316 float t1457 = t1455+t1456-t1629-
Cov[2][7]*t1419;
317 float t1458 =
Cov[0][8]*t1397;
318 float t1459 =
Cov[1][8]*t1411;
319 float t1630 =
Cov[6][8]*t1402;
320 float t1460 = t1458+t1459-t1630-
Cov[2][8]*t1419;
321 float t1461 = q0*t1390*2.0f;
322 float t1462 = q1*t1391*2.0f;
323 float t1463 = q3*t1395*2.0f;
324 float t1473 = q2*t1393*2.0f;
325 float t1464 = t1461+t1462+t1463-t1473;
326 float t1465 = q0*t1409*2.0f;
327 float t1466 = q2*t1405*2.0f;
328 float t1467 = q3*t1404*2.0f;
329 float t1474 = q1*t1407*2.0f;
330 float t1468 = t1465+t1466+t1467-t1474;
331 float t1469 = q1*t1415*2.0f;
332 float t1470 = q2*t1414*2.0f;
333 float t1471 = q3*t1412*2.0f;
334 float t1475 = q0*t1417*2.0f;
335 float t1472 = t1469+t1470+t1471-t1475;
336 float t1476 =
Cov[7][0]*t1402;
337 float t1477 =
Cov[0][0]*t1464;
338 float t1486 =
Cov[1][0]*t1468;
339 float t1487 =
Cov[2][0]*t1472;
340 float t1478 = t1476+t1477-t1486-t1487;
341 float t1479 =
Cov[7][1]*t1402;
342 float t1480 =
Cov[0][1]*t1464;
343 float t1492 =
Cov[1][1]*t1468;
344 float t1493 =
Cov[2][1]*t1472;
345 float t1481 = t1479+t1480-t1492-t1493;
346 float t1482 =
Cov[7][2]*t1402;
347 float t1483 =
Cov[0][2]*t1464;
348 float t1498 =
Cov[1][2]*t1468;
349 float t1499 =
Cov[2][2]*t1472;
350 float t1484 = t1482+t1483-t1498-t1499;
351 float t1485 =
sq(t1402);
352 float t1488 = q1*t1390*2.0f;
353 float t1489 = q2*t1395*2.0f;
354 float t1490 = q3*t1393*2.0f;
355 float t1533 = q0*t1391*2.0f;
356 float t1491 = t1488+t1489+t1490-t1533;
357 float t1494 = q0*t1407*2.0f;
358 float t1495 = q1*t1409*2.0f;
359 float t1496 = q2*t1404*2.0f;
360 float t1534 = q3*t1405*2.0f;
361 float t1497 = t1494+t1495+t1496-t1534;
362 float t1500 = q0*t1415*2.0f;
363 float t1501 = q1*t1417*2.0f;
364 float t1502 = q3*t1414*2.0f;
365 float t1535 = q2*t1412*2.0f;
366 float t1503 = t1500+t1501+t1502-t1535;
367 float t1504 = dvy*t1433;
368 float t1505 = dvx*t1440;
369 float t1506 = t1504+t1505;
370 float t1507 = dvx*t1438;
371 float t1508 = dvy*t1438;
372 float t1509 = dvz*t1440;
373 float t1510 = t1508+t1509;
374 float t1511 = dvx*t1444;
375 float t1551 = dvy*t1447;
376 float t1512 = t1511-t1551;
377 float t1513 = dvz*t1444;
378 float t1514 = dvy*t1446;
379 float t1515 = t1513+t1514;
380 float t1516 = dvx*t1446;
381 float t1517 = dvz*t1447;
382 float t1518 = t1516+t1517;
383 float t1519 = dvx*t1448;
384 float t1520 = dvz*t1451;
385 float t1521 = t1519+t1520;
386 float t1522 = dvy*t1448;
387 float t1552 = dvz*t1450;
388 float t1523 = t1522-t1552;
389 float t1524 = dvx*t1450;
390 float t1525 = dvy*t1451;
391 float t1526 = t1524+t1525;
392 float t1527 =
Cov[7][6]*t1402;
393 float t1528 =
Cov[0][6]*t1464;
394 float t1529 =
Cov[7][7]*t1402;
395 float t1530 =
Cov[0][7]*t1464;
396 float t1531 =
Cov[7][8]*t1402;
397 float t1532 =
Cov[0][8]*t1464;
398 float t1536 =
Cov[8][0]*t1402;
399 float t1537 =
Cov[1][0]*t1497;
400 float t1545 =
Cov[0][0]*t1491;
401 float t1546 =
Cov[2][0]*t1503;
402 float t1538 = t1536+t1537-t1545-t1546;
403 float t1539 =
Cov[8][1]*t1402;
404 float t1540 =
Cov[1][1]*t1497;
405 float t1547 =
Cov[0][1]*t1491;
406 float t1548 =
Cov[2][1]*t1503;
407 float t1541 = t1539+t1540-t1547-t1548;
408 float t1542 =
Cov[8][2]*t1402;
409 float t1543 =
Cov[1][2]*t1497;
410 float t1549 =
Cov[0][2]*t1491;
411 float t1550 =
Cov[2][2]*t1503;
412 float t1544 = t1542+t1543-t1549-t1550;
413 float t1553 =
Cov[8][6]*t1402;
414 float t1554 =
Cov[1][6]*t1497;
415 float t1555 =
Cov[8][7]*t1402;
416 float t1556 =
Cov[1][7]*t1497;
417 float t1557 =
Cov[8][8]*t1402;
418 float t1558 =
Cov[1][8]*t1497;
419 float t1560 = dvz*t1433;
420 float t1559 = t1507-t1560;
421 float t1561 =
Cov[0][0]*t1510;
422 float t1567 =
Cov[2][0]*t1506;
423 float t1568 =
Cov[1][0]*t1559;
424 float t1562 =
Cov[3][0]+t1561-t1567-t1568;
425 float t1563 =
Cov[0][1]*t1510;
426 float t1569 =
Cov[2][1]*t1506;
427 float t1570 =
Cov[1][1]*t1559;
428 float t1564 =
Cov[3][1]+t1563-t1569-t1570;
429 float t1565 =
Cov[0][2]*t1510;
430 float t1571 =
Cov[2][2]*t1506;
431 float t1572 =
Cov[1][2]*t1559;
432 float t1566 =
Cov[3][2]+t1565-t1571-t1572;
433 float t1573 = -t1507+t1560;
434 float t1574 =
Cov[1][0]*t1573;
435 float t1575 =
Cov[3][0]+t1561-t1567+t1574;
436 float t1576 =
Cov[1][1]*t1573;
437 float t1577 =
Cov[3][1]+t1563-t1569+t1576;
438 float t1578 =
Cov[1][2]*t1573;
439 float t1579 =
Cov[3][2]+t1565-t1571+t1578;
440 float t1580 =
Cov[0][6]*t1510;
441 float t1581 =
Cov[0][7]*t1510;
442 float t1582 =
Cov[0][8]*t1510;
443 float t1583 =
Cov[1][0]*t1518;
444 float t1584 =
Cov[2][0]*t1512;
445 float t1592 =
Cov[0][0]*t1515;
446 float t1585 =
Cov[4][0]+t1583+t1584-t1592;
447 float t1586 =
Cov[1][1]*t1518;
448 float t1587 =
Cov[2][1]*t1512;
449 float t1593 =
Cov[0][1]*t1515;
450 float t1588 =
Cov[4][1]+t1586+t1587-t1593;
451 float t1589 =
Cov[1][2]*t1518;
452 float t1590 =
Cov[2][2]*t1512;
453 float t1594 =
Cov[0][2]*t1515;
454 float t1591 =
Cov[4][2]+t1589+t1590-t1594;
455 float t1595 = dvxNoise*t1433*t1447;
456 float t1596 =
Cov[1][6]*t1518;
457 float t1597 =
Cov[2][6]*t1512;
458 float t1598 =
Cov[4][6]+t1596+t1597-
Cov[0][6]*t1515;
459 float t1599 =
Cov[1][7]*t1518;
460 float t1600 =
Cov[2][7]*t1512;
461 float t1601 =
Cov[4][7]+t1599+t1600-
Cov[0][7]*t1515;
462 float t1602 =
Cov[1][8]*t1518;
463 float t1603 =
Cov[2][8]*t1512;
464 float t1604 =
Cov[4][8]+t1602+t1603-
Cov[0][8]*t1515;
465 float t1605 =
Cov[2][0]*t1526;
466 float t1606 =
Cov[0][0]*t1523;
467 float t1614 =
Cov[1][0]*t1521;
468 float t1607 =
Cov[5][0]+t1605+t1606-t1614;
469 float t1608 =
Cov[2][1]*t1526;
470 float t1609 =
Cov[0][1]*t1523;
471 float t1615 =
Cov[1][1]*t1521;
472 float t1610 =
Cov[5][1]+t1608+t1609-t1615;
473 float t1611 =
Cov[2][2]*t1526;
474 float t1612 =
Cov[0][2]*t1523;
475 float t1616 =
Cov[1][2]*t1521;
476 float t1613 =
Cov[5][2]+t1611+t1612-t1616;
477 float t1617 = dvzNoise*t1438*t1448;
478 float t1618 = dvyNoise*t1444*t1450;
479 float t1619 =
Cov[2][6]*t1526;
480 float t1620 =
Cov[0][6]*t1523;
481 float t1621 =
Cov[5][6]+t1619+t1620-
Cov[1][6]*t1521;
482 float t1622 =
Cov[2][7]*t1526;
483 float t1623 =
Cov[0][7]*t1523;
484 float t1624 =
Cov[5][7]+t1622+t1623-
Cov[1][7]*t1521;
485 float t1625 =
Cov[2][8]*t1526;
486 float t1626 =
Cov[0][8]*t1523;
487 float t1627 =
Cov[5][8]+t1625+t1626-
Cov[1][8]*t1521;
489 nextCov[0][0] = daxNoise*t1485+t1397*t1424+t1411*t1431-t1419*t1432-t1402*t1454;
490 nextCov[1][0] = -t1397*t1478-t1411*t1481+t1419*t1484+t1402*(t1527+t1528-
Cov[1][6]*t1468-
Cov[2][6]*t1472);
491 nextCov[2][0] = -t1397*t1538-t1411*t1541+t1419*t1544+t1402*(t1553+t1554-
Cov[0][6]*t1491-
Cov[2][6]*t1503);
492 nextCov[3][0] = -t1402*(
Cov[3][6]+t1580-
Cov[2][6]*t1506-
Cov[1][6]*t1559)+t1397*t1562+t1411*t1564-t1419*t1566;
493 nextCov[4][0] = t1397*t1585+t1411*t1588-t1402*t1598-t1419*t1591;
494 nextCov[5][0] = t1397*t1607+t1411*t1610-t1402*t1621-t1419*t1613;
495 nextCov[6][0] = -t1628+
Cov[6][0]*t1397+
Cov[6][1]*t1411-
Cov[6][2]*t1419;
496 nextCov[7][0] = -t1527+
Cov[7][0]*t1397+
Cov[7][1]*t1411-
Cov[7][2]*t1419;
497 nextCov[8][0] = -t1553+
Cov[8][0]*t1397+
Cov[8][1]*t1411-
Cov[8][2]*t1419;
498 nextCov[0][1] = -t1402*t1457-t1424*t1464+t1431*t1468+t1432*t1472;
499 nextCov[1][1] = dayNoise*t1485+t1464*t1478-t1468*t1481-t1472*t1484+t1402*(t1529+t1530-
Cov[1][7]*t1468-
Cov[2][7]*t1472);
500 nextCov[2][1] = t1464*t1538-t1468*t1541-t1472*t1544+t1402*(t1555+t1556-
Cov[0][7]*t1491-
Cov[2][7]*t1503);
501 nextCov[3][1] = -t1402*(
Cov[3][7]+t1581-
Cov[2][7]*t1506-
Cov[1][7]*t1559)-t1464*t1562+t1468*t1564+t1472*t1566;
502 nextCov[4][1] = -t1402*t1601-t1464*t1585+t1468*t1588+t1472*t1591;
503 nextCov[5][1] = -t1402*t1624-t1464*t1607+t1468*t1610+t1472*t1613;
504 nextCov[6][1] = -t1629-
Cov[6][0]*t1464+
Cov[6][1]*t1468+
Cov[6][2]*t1472;
505 nextCov[7][1] = -t1529-
Cov[7][0]*t1464+
Cov[7][1]*t1468+
Cov[7][2]*t1472;
506 nextCov[8][1] = -t1555-
Cov[8][0]*t1464+
Cov[8][1]*t1468+
Cov[8][2]*t1472;
507 nextCov[0][2] = -t1402*t1460-t1431*t1497+t1432*t1503+t1491*(t1422+t1423-t1429-t1430);
508 nextCov[1][2] = -t1478*t1491+t1481*t1497-t1484*t1503+t1402*(t1531+t1532-
Cov[1][8]*t1468-
Cov[2][8]*t1472);
509 nextCov[2][2] = dazNoise*t1485-t1491*t1538+t1497*t1541-t1503*t1544+t1402*(t1557+t1558-
Cov[0][8]*t1491-
Cov[2][8]*t1503);
510 nextCov[3][2] = -t1402*(
Cov[3][8]+t1582-
Cov[2][8]*t1506-
Cov[1][8]*t1559)+t1491*t1562-t1497*t1564+t1503*t1566;
511 nextCov[4][2] = -t1402*t1604+t1491*t1585-t1497*t1588+t1503*t1591;
512 nextCov[5][2] = -t1402*t1627+t1491*t1607-t1497*t1610+t1503*t1613;
513 nextCov[6][2] = -t1630+
Cov[6][0]*t1491-
Cov[6][1]*t1497+
Cov[6][2]*t1503;
514 nextCov[7][2] = -t1531+
Cov[7][0]*t1491-
Cov[7][1]*t1497+
Cov[7][2]*t1503;
515 nextCov[8][2] = -t1557+
Cov[8][0]*t1491-
Cov[8][1]*t1497+
Cov[8][2]*t1503;
516 nextCov[0][3] =
Cov[0][3]*t1397+
Cov[1][3]*t1411-
Cov[2][3]*t1419-
Cov[6][3]*t1402-t1432*t1506+t1510*(t1422+t1423-t1429-t1430)-t1559*(t1425+t1426-t1434-t1435);
517 nextCov[1][3] = -
Cov[0][3]*t1464-
Cov[7][3]*t1402+
Cov[1][3]*t1468+
Cov[2][3]*t1472-t1478*t1510+t1484*t1506+t1481*t1559;
518 nextCov[2][3] = -
Cov[8][3]*t1402+
Cov[0][3]*t1491-
Cov[1][3]*t1497+
Cov[2][3]*t1503-t1510*t1538+t1506*t1544+t1541*t1559;
519 nextCov[3][3] =
Cov[3][3]+
Cov[0][3]*t1510-
Cov[2][3]*t1506+
Cov[1][3]*t1573-t1506*t1566+t1510*t1575+t1573*t1577+dvxNoise*
sq(t1433)+dvyNoise*
sq(t1440)+dvzNoise*
sq(t1438);
520 nextCov[4][3] =
Cov[4][3]+t1595-
Cov[0][3]*t1515+
Cov[1][3]*t1518+
Cov[2][3]*t1512+t1510*t1585-t1506*t1591+t1573*t1588-dvyNoise*t1440*t1444-dvzNoise*t1438*t1446;
521 nextCov[5][3] =
Cov[5][3]+t1617+
Cov[0][3]*t1523-
Cov[1][3]*t1521+
Cov[2][3]*t1526+t1510*t1607-t1506*t1613+t1573*t1610-dvxNoise*t1433*t1451-dvyNoise*t1440*t1450;
522 nextCov[6][3] =
Cov[6][3]-
Cov[6][2]*t1506+
Cov[6][0]*t1510+
Cov[6][1]*t1573;
523 nextCov[7][3] =
Cov[7][3]-
Cov[7][2]*t1506+
Cov[7][0]*t1510+
Cov[7][1]*t1573;
524 nextCov[8][3] =
Cov[8][3]-
Cov[8][2]*t1506+
Cov[8][0]*t1510+
Cov[8][1]*t1573;
525 nextCov[0][4] =
Cov[0][4]*t1397+
Cov[1][4]*t1411-
Cov[2][4]*t1419-
Cov[6][4]*t1402-t1424*t1515+t1432*t1512+t1518*(t1425+t1426-t1434-t1435);
526 nextCov[1][4] = -
Cov[0][4]*t1464-
Cov[7][4]*t1402+
Cov[1][4]*t1468+
Cov[2][4]*t1472+t1478*t1515-t1484*t1512-t1481*t1518;
527 nextCov[2][4] = -
Cov[8][4]*t1402+
Cov[0][4]*t1491-
Cov[1][4]*t1497+
Cov[2][4]*t1503+t1515*t1538-t1512*t1544-t1518*t1541;
528 nextCov[3][4] =
Cov[3][4]+t1595+
Cov[0][4]*t1510-
Cov[2][4]*t1506+
Cov[1][4]*t1573-t1515*t1575+t1512*t1579+t1518*t1577-dvyNoise*t1440*t1444-dvzNoise*t1438*t1446;
529 nextCov[4][4] =
Cov[4][4]-
Cov[0][4]*t1515+
Cov[1][4]*t1518+
Cov[2][4]*t1512-t1515*t1585+t1512*t1591+t1518*t1588+dvxNoise*
sq(t1447)+dvyNoise*
sq(t1444)+dvzNoise*
sq(t1446);
530 nextCov[5][4] =
Cov[5][4]+t1618+
Cov[0][4]*t1523-
Cov[1][4]*t1521+
Cov[2][4]*t1526-t1515*t1607+t1512*t1613+t1518*t1610-dvxNoise*t1447*t1451-dvzNoise*t1446*t1448;
531 nextCov[6][4] =
Cov[6][4]+
Cov[6][2]*t1512-
Cov[6][0]*t1515+
Cov[6][1]*t1518;
532 nextCov[7][4] =
Cov[7][4]+
Cov[7][2]*t1512-
Cov[7][0]*t1515+
Cov[7][1]*t1518;
533 nextCov[8][4] =
Cov[8][4]+
Cov[8][2]*t1512-
Cov[8][0]*t1515+
Cov[8][1]*t1518;
534 nextCov[0][5] =
Cov[0][5]*t1397+
Cov[1][5]*t1411-
Cov[2][5]*t1419-
Cov[6][5]*t1402+t1424*t1523-t1431*t1521+t1526*(t1427+t1428-t1442-t1443);
535 nextCov[1][5] = -
Cov[0][5]*t1464-
Cov[7][5]*t1402+
Cov[1][5]*t1468+
Cov[2][5]*t1472-t1478*t1523+t1481*t1521-t1484*t1526;
536 nextCov[2][5] = -
Cov[8][5]*t1402+
Cov[0][5]*t1491-
Cov[1][5]*t1497+
Cov[2][5]*t1503-t1523*t1538+t1521*t1541-t1526*t1544;
537 nextCov[3][5] =
Cov[3][5]+t1617+
Cov[0][5]*t1510-
Cov[2][5]*t1506+
Cov[1][5]*t1573-t1521*t1577+t1523*t1575+t1526*t1579-dvxNoise*t1433*t1451-dvyNoise*t1440*t1450;
538 nextCov[4][5] =
Cov[4][5]+t1618-
Cov[0][5]*t1515+
Cov[1][5]*t1518+
Cov[2][5]*t1512+t1523*t1585-t1521*t1588+t1526*t1591-dvxNoise*t1447*t1451-dvzNoise*t1446*t1448;
539 nextCov[5][5] =
Cov[5][5]+
Cov[0][5]*t1523-
Cov[1][5]*t1521+
Cov[2][5]*t1526+t1523*t1607-t1521*t1610+t1526*t1613+dvxNoise*
sq(t1451)+dvyNoise*
sq(t1450)+dvzNoise*
sq(t1448);
540 nextCov[6][5] =
Cov[6][5]-
Cov[6][1]*t1521+
Cov[6][0]*t1523+
Cov[6][2]*t1526;
541 nextCov[7][5] =
Cov[7][5]-
Cov[7][1]*t1521+
Cov[7][0]*t1523+
Cov[7][2]*t1526;
542 nextCov[8][5] =
Cov[8][5]-
Cov[8][1]*t1521+
Cov[8][0]*t1523+
Cov[8][2]*t1526;
543 nextCov[0][6] = t1454;
544 nextCov[1][6] = -t1527-t1528+
Cov[1][6]*t1468+
Cov[2][6]*t1472;
545 nextCov[2][6] = -t1553-t1554+
Cov[0][6]*t1491+
Cov[2][6]*t1503;
546 nextCov[3][6] =
Cov[3][6]+t1580-
Cov[2][6]*t1506+
Cov[1][6]*t1573;
547 nextCov[4][6] = t1598;
548 nextCov[5][6] = t1621;
549 nextCov[6][6] =
Cov[6][6];
550 nextCov[7][6] =
Cov[7][6];
551 nextCov[8][6] =
Cov[8][6];
552 nextCov[0][7] = t1457;
553 nextCov[1][7] = -t1529-t1530+
Cov[1][7]*t1468+
Cov[2][7]*t1472;
554 nextCov[2][7] = -t1555-t1556+
Cov[0][7]*t1491+
Cov[2][7]*t1503;
555 nextCov[3][7] =
Cov[3][7]+t1581-
Cov[2][7]*t1506+
Cov[1][7]*t1573;
556 nextCov[4][7] = t1601;
557 nextCov[5][7] = t1624;
558 nextCov[6][7] =
Cov[6][7];
559 nextCov[7][7] =
Cov[7][7];
560 nextCov[8][7] =
Cov[8][7];
561 nextCov[0][8] = t1460;
562 nextCov[1][8] = -t1531-t1532+
Cov[1][8]*t1468+
Cov[2][8]*t1472;
563 nextCov[2][8] = -t1557-t1558+
Cov[0][8]*t1491+
Cov[2][8]*t1503;
564 nextCov[3][8] =
Cov[3][8]+t1582-
Cov[2][8]*t1506+
Cov[1][8]*t1573;
565 nextCov[4][8] = t1604;
566 nextCov[5][8] = t1627;
567 nextCov[6][8] =
Cov[6][8];
568 nextCov[7][8] =
Cov[7][8];
569 nextCov[8][8] =
Cov[8][8];
572 for (uint8_t i=6;i<=8;i++) {
573 nextCov[i][i] = nextCov[i][i] + delAngBiasVariance;
577 for (uint8_t index=0; index<=8; index++) {
578 if (nextCov[index][index] < 0.0f) {
579 Cov[index][index] = 0.0f;
581 Cov[index][index] = nextCov[index][index];
586 for (uint8_t rowIndex=1; rowIndex<=8; rowIndex++) {
587 for (uint8_t colIndex=0; colIndex<=rowIndex-1; colIndex++) {
588 Cov[rowIndex][colIndex] = 0.5f*(nextCov[rowIndex][colIndex] + nextCov[colIndex][rowIndex]);
589 Cov[colIndex][rowIndex] =
Cov[rowIndex][colIndex];
609 for (uint8_t obsIndex=0;obsIndex<=2;obsIndex++) {
610 stateIndex = 3 + obsIndex;
624 innovation[obsIndex] =
state.
velocity[obsIndex] - measVelNED[obsIndex];
632 varInnov[obsIndex] =
Cov[stateIndex][stateIndex] + R_OBS;
634 for (uint8_t rowIndex=0;rowIndex<=8;rowIndex++) {
635 K[rowIndex] =
Cov[rowIndex][stateIndex]/varInnov[obsIndex];
636 states[rowIndex] -= K[rowIndex] * innovation[obsIndex];
650 for (uint8_t rowIndex=0;rowIndex<=8;rowIndex++) {
651 for (uint8_t colIndex=0;colIndex<=8;colIndex++) {
652 Cov[rowIndex][colIndex] =
Cov[rowIndex][colIndex] - K[rowIndex]*
Cov[stateIndex][colIndex];
696 const float R_MAG = 3e-2
f;
699 float t5695 =
sq(q0);
700 float t5696 =
sq(q1);
701 float t5697 =
sq(q2);
702 float t5698 =
sq(q3);
703 float t5699 = t5695+t5696-t5697-t5698;
704 float t5702 = q0*q2*2.0f;
705 float t5703 = q1*q3*2.0f;
706 float t5704 = t5702+t5703;
707 float t5705 = q0*q3*2.0f;
708 float t5707 = q1*q2*2.0f;
709 float t5706 = t5705-t5707;
712 float t5710 = t5708+t5709;
713 float t5711 = t5705+t5707;
716 float t5713 = t5712-t5730;
717 float t5714 = q0*q1*2.0f;
718 float t5720 = q2*q3*2.0f;
719 float t5715 = t5714-t5720;
720 float t5716 = t5695-t5696+t5697-t5698;
723 float t5719 = t5717+t5718;
726 float t5722 = t5721-t5735;
727 float t5724 =
sinPhi*t5706;
730 float t5727 = t5724+t5725-t5726;
731 float t5728 = magZ*t5727;
732 float t5729 = t5699*t5710;
733 float t5731 = t5704*t5713;
734 float t5732 =
cosPhi*cosPsi*t5706;
735 float t5733 = t5729+t5731-t5732;
736 float t5734 = magY*t5733;
737 float t5736 = t5699*t5722;
738 float t5737 = t5704*t5719;
739 float t5738 =
cosPhi*sinPsi*t5706;
740 float t5739 = t5736+t5737+t5738;
741 float t5740 = magX*t5739;
742 float t5741 = -t5728+t5734+t5740;
743 float t5742 = 1.0f/t5741;
744 float t5743 =
sinPhi*t5716;
747 float t5746 = -t5743+t5744+t5745;
748 float t5747 = magZ*t5746;
749 float t5748 = t5710*t5711;
750 float t5749 = t5713*t5715;
751 float t5750 =
cosPhi*cosPsi*t5716;
752 float t5751 = t5748-t5749+t5750;
753 float t5752 = magY*t5751;
754 float t5753 = t5715*t5719;
755 float t5754 = t5711*t5722;
756 float t5755 =
cosPhi*sinPsi*t5716;
757 float t5756 = t5753-t5754+t5755;
758 float t5757 = magX*t5756;
759 float t5758 = t5747-t5752+t5757;
760 float t5759 = t5742*t5758;
761 float t5723 = tanf(t5759);
762 float t5760 =
sq(t5723);
763 float t5761 = t5760+1.0f;
764 float t5762 = 1.0f/
sq(t5741);
772 float varInnov = R_MAG;
773 for (uint8_t rowIndex=0;rowIndex<=2;rowIndex++) {
775 for (uint8_t colIndex=0;colIndex<=2;colIndex++) {
776 PH[rowIndex] +=
Cov[rowIndex][colIndex]*H_MAG[colIndex];
778 varInnov += H_MAG[rowIndex]*PH[rowIndex];
781 float varInnovInv = 1.0f / varInnov;
782 for (uint8_t rowIndex=0;rowIndex<=8;rowIndex++) {
783 K_MAG[rowIndex] = 0.0f;
784 for (uint8_t colIndex=0;colIndex<=2;colIndex++) {
785 K_MAG[rowIndex] +=
Cov[rowIndex][colIndex]*H_MAG[colIndex];
787 K_MAG[rowIndex] *= varInnovInv;
794 if (innovation > 0.5f) {
796 }
else if (innovation < -0.5f) {
802 for (uint8_t i=0;i<=8;i++) {
803 states[i] -= K_MAG[i] * innovation;
815 for (uint8_t colIndex=0;colIndex<=8;colIndex++) {
817 for (uint8_t rowIndex=0;rowIndex<=2;rowIndex++) {
818 HP[colIndex] += H_MAG[rowIndex]*
Cov[rowIndex][colIndex];
821 for (uint8_t rowIndex=0;rowIndex<=8;rowIndex++) {
822 for (uint8_t colIndex=0;colIndex<=8;colIndex++) {
823 Cov[rowIndex][colIndex] -= K_MAG[rowIndex] * HP[colIndex];
860 Tms[0][2] = -sinTheta*
cosPhi;
869 if (!earth_magfield.
is_zero()) {
870 declination = atan2f(earth_magfield.
y,earth_magfield.
x);
885 float innovation = atan2f(magMeasNED.
y,magMeasNED.
x) - declination;
888 if (innovation >
M_PI) {
889 innovation = innovation - 2*
M_PI;
890 }
else if (innovation < -
M_PI) {
891 innovation = innovation + 2*
M_PI;
911 for (uint8_t rowIndex=1; rowIndex<=8; rowIndex++) {
912 for (uint8_t colIndex=0; colIndex<=rowIndex-1; colIndex++) {
913 Cov[rowIndex][colIndex] = 0.5f*(
Cov[rowIndex][colIndex] +
Cov[colIndex][rowIndex]);
914 Cov[colIndex][rowIndex] =
Cov[rowIndex][colIndex];
919 for (uint8_t index=1; index<=8; index++) {
920 if (
Cov[index][index] < 0.0
f) {
921 Cov[index][index] = 0.0f;
971 #endif // HAL_CPU_CLASS
void to_euler(float &roll, float &pitch, float &yaw) const
bool get_soft_armed() const
Vector3< float > Vector3f
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
void from_vector312(float roll, float pitch, float yaw)
float get_declination() const
uint32_t imuSampleTime_ms
bool getStatus(void) const
bool have_inertial_nav() const override
AP_HAL::UARTDriver * console
void getGyroBias(Vector3f &gyroBias) const
static const struct AP_Param::GroupInfo var_info[]
bool get_filter_status(nav_filter_status &status) const
bool get_mag_field_correction(Vector3f &ret) const override
struct SoloGimbalEKF::@137 gSense
float innovationIncrement
SoloGimbalEKF(const AP_AHRS_NavEKF &ahrs)
void from_rotation_matrix(const Matrix3f &m)
const Compass * get_compass() const
void getDebug(float &tilt, Vector3f &velocity, Vector3f &euler, Vector3f &gyroBias) const
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
A system for managing and storing variables that are of general interest to the system.
void getQuat(Quaternion &quat) const
Matrix3< T > transposed(void) const
virtual void printf(const char *,...) FMT_PRINTF(2
const AP_AHRS_NavEKF & _ahrs
void RunEKF(float delta_time, const Vector3f &delta_angles, const Vector3f &delta_velocity, const Vector3f &joint_angles)
void setGyroBias(const Vector3f &gyroBias)
void rotation_matrix(Matrix3f &m) const
struct nav_filter_status::@138 flags
float constrain_float(const float amt, const float low, const float high)
uint32_t last_update_usec(void) const
const Matrix3f & get_rotation_body_to_ned(void) const override
float calcMagHeadingInnov()
bool get_mag_field_NED(Vector3f &ret) const
void rotate(const Vector3f &v)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool get_velocity_NED(Vector3f &vec) const override
struct SoloGimbalEKF::state_elements & state
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)