0.5.1
Loading...
Searching...
No Matches
LooselyCoupledKF.cpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
10
14#include "internal/Node/Pin.hpp"
15#include "util/Eigen.hpp"
16#include <memory>
17#include <numbers>
18#include <cmath>
19
20#include <imgui.h>
21#include <imgui_internal.h>
26
28#include <fmt/format.h>
29#include "NodeRegistry.hpp"
39#include "util/Logger.hpp"
40#include "util/Assert.h"
41
43
44/// @brief Scale factor to convert the attitude error
45constexpr double SCALE_FACTOR_ATTITUDE = 180. / M_PI;
46/// @brief Scale factor to convert the latitude and longitude error
48/// @brief Scale factor to convert the acceleration error
50/// @brief Scale factor to convert the angular rate error
51constexpr double SCALE_FACTOR_ANGULAR_RATE = 1e3;
52
54 : Node(typeStatic())
55{
56 LOG_TRACE("{}: called", name);
57
58 _hasConfig = true;
59 _guiConfigDefaultWindowSize = { 822, 936 };
60
63 [](const Node* node, const InputPin& inputPin) {
64 const auto* lckf = static_cast<const LooselyCoupledKF*>(node); // NOLINT(cppcoreguidelines-pro-type-static-cast-downcast)
65 return !inputPin.queue.empty() && lckf->_inertialIntegrator.hasInitialPosition();
66 },
67 1); // Priority 1 ensures, that the IMU obs (prediction) is evaluated before the PosVel obs (update)
68
69 _dynamicInputPins.addPin(this); // PosVel
71
73}
74
79
81{
82 return "INS/GNSS LCKF"; // Loosely-coupled Kalman Filter
83}
84
85std::string NAV::LooselyCoupledKF::type() const
86{
87 return typeStatic();
88}
89
91{
92 return "Data Processor";
93}
94
96{
98
99 auto updatePin = [&](bool pinExists, bool enabled,
100 const char* pinName, Pin::Type pinType, const std::vector<std::string>& dataIdentifier = {},
101 auto callback = nullptr, InputPin::FlowFirableCheckFunc firable = nullptr, int priority = 0) {
102 if (!pinExists && enabled)
103 {
104 CreateInputPin(pinName, pinType, dataIdentifier, callback,
105 firable, priority, static_cast<int>(pinIdx));
106 _dynamicInputPins.setFirstDynamicPinIdx(_dynamicInputPins.getFirstDynamicPinIdx() + 1);
107 }
108 else if (pinExists && !enabled)
109 {
110 DeleteInputPin(pinIdx);
111 _dynamicInputPins.setFirstDynamicPinIdx(_dynamicInputPins.getFirstDynamicPinIdx() - 1);
112 }
113 if (enabled) { pinIdx++; }
114 };
115
116 updatePin(std::ranges::any_of(inputPins, [](const InputPin& pin) { return pin.dataIdentifier.front() == PosVelAtt::type(); }), _initializeStateOverExternalPin,
118 updatePin(std::ranges::any_of(inputPins, [](const InputPin& pin) { return pin.dataIdentifier.front() == BaroHgt::type(); }), _enableBaroHgt,
120
121 if (std::ranges::count_if(inputPins, [](const InputPin& pin) { return pin.dataIdentifier.front() == PosVel::type(); }) == 0)
122 {
123 _dynamicInputPins.addPin(this); // PosVel
124 }
125}
126
128{
129 node->CreateInputPin(
131 [](const Node* node, const InputPin& inputPin) {
132 const auto* lckf = static_cast<const LooselyCoupledKF*>(node); // NOLINT(cppcoreguidelines-pro-type-static-cast-downcast)
133 return !inputPin.queue.empty() && (!lckf->_initializeStateOverExternalPin || lckf->_inertialIntegrator.hasInitialPosition());
134 },
135 2); // Initially this has higher priority than the IMU obs, to initialize the position from it
136}
137
139{
140 node->DeleteInputPin(pinIdx);
141}
142
144{
145 float configWidth = 400.0F * gui::NodeEditorApplication::windowFontRatio();
146 float unitWidth = 150.0F * gui::NodeEditorApplication::windowFontRatio();
147
148 float taylorOrderWidth = 75.0F * gui::NodeEditorApplication::windowFontRatio();
149
150 if (_dynamicInputPins.ShowGuiWidgets(size_t(id), inputPins, this))
151 {
153 }
154
155 if (ImGui::CollapsingHeader(fmt::format("Initialization##{}", size_t(id)).c_str(), ImGuiTreeNodeFlags_DefaultOpen))
156 {
157 if (ImGui::Checkbox(fmt::format("Initialize over pin##{}", size_t(id)).c_str(), &_initializeStateOverExternalPin))
158 {
161 }
163 {
164 ImGui::SetNextItemWidth(80 * gui::NodeEditorApplication::windowFontRatio());
165 if (ImGui::DragDouble(fmt::format("##initalRollPitchYaw(0) {}", size_t(id)).c_str(),
166 _initalRollPitchYaw.data(), 1.0F, -180.0, 180.0, "%.3f °"))
167 {
169 }
170 ImGui::SameLine();
171 ImGui::SetNextItemWidth(80 * gui::NodeEditorApplication::windowFontRatio());
172 if (ImGui::DragDouble(fmt::format("##initalRollPitchYaw(1) {}", size_t(id)).c_str(),
173 &_initalRollPitchYaw[1], 1.0F, -90.0, 90.0, "%.3f °"))
174 {
176 }
177 ImGui::SameLine();
178 ImGui::SetNextItemWidth(80 * gui::NodeEditorApplication::windowFontRatio());
179 if (ImGui::DragDouble(fmt::format("##initalRollPitchYaw(2) {}", size_t(id)).c_str(),
180 &_initalRollPitchYaw[2], 1.0, -180.0, 180.0, "%.3f °"))
181 {
183 }
184 ImGui::SameLine();
185 ImGui::TextUnformatted("Roll, Pitch, Yaw");
186 }
187 }
188
189 if (ImGui::CollapsingHeader(fmt::format("IMU Integrator settings##{}", size_t(id)).c_str(), ImGuiTreeNodeFlags_DefaultOpen))
190 {
192 {
194 }
195 }
196 if (ImGui::CollapsingHeader(fmt::format("Kalman Filter settings##{}", size_t(id)).c_str(), ImGuiTreeNodeFlags_DefaultOpen))
197 {
199 {
200 ImGui::SetNextItemWidth(configWidth - taylorOrderWidth);
201 }
202 else
203 {
204 ImGui::SetNextItemWidth(configWidth + ImGui::GetStyle().ItemSpacing.x);
205 }
206 if (auto phiCalculationAlgorithm = static_cast<int>(_phiCalculationAlgorithm);
207 ImGui::Combo(fmt::format("##Phi calculation algorithm {}", size_t(id)).c_str(), &phiCalculationAlgorithm, "Van Loan\0Taylor\0\0"))
208 {
209 _phiCalculationAlgorithm = static_cast<decltype(_phiCalculationAlgorithm)>(phiCalculationAlgorithm);
210 LOG_DEBUG("{}: Phi calculation algorithm changed to {}", nameId(), fmt::underlying(_phiCalculationAlgorithm));
212 }
213
215 {
216 ImGui::SameLine();
217 ImGui::SetNextItemWidth(taylorOrderWidth);
218 if (ImGui::InputIntL(fmt::format("##Phi calculation Taylor Order {}", size_t(id)).c_str(), &_phiCalculationTaylorOrder, 1, 9))
219 {
220 LOG_DEBUG("{}: Phi calculation Taylor Order changed to {}", nameId(), _phiCalculationTaylorOrder);
222 }
223 }
224 ImGui::SameLine();
225 ImGui::SetCursorPosX(ImGui::GetCursorPosX() - ImGui::GetStyle().ItemSpacing.x + ImGui::GetStyle().ItemInnerSpacing.x);
226 ImGui::Text("Phi calculation algorithm%s", _phiCalculationAlgorithm == PhiCalculationAlgorithm::Taylor ? " (up to order)" : "");
227
228 ImGui::SetNextItemWidth(configWidth + ImGui::GetStyle().ItemSpacing.x);
229 if (auto qCalculationAlgorithm = static_cast<int>(_qCalculationAlgorithm);
230 ImGui::Combo(fmt::format("Q calculation algorithm##{}", size_t(id)).c_str(), &qCalculationAlgorithm, "Van Loan\0Taylor 1st Order (Groves 2013)\0\0"))
231 {
232 _qCalculationAlgorithm = static_cast<decltype(_qCalculationAlgorithm)>(qCalculationAlgorithm);
233 LOG_DEBUG("{}: Q calculation algorithm changed to {}", nameId(), fmt::underlying(_qCalculationAlgorithm));
235 }
236 if (ImGui::Checkbox(fmt::format("Enable barometric height pin##{}", size_t(id)).c_str(), &_enableBaroHgt))
237 {
240 }
241
242 ImGui::Separator();
243
244 // ###########################################################################################################
245 // Q - System/Process noise covariance matrix
246 // ###########################################################################################################
247
248 auto inputVector3WithUnit = [&](const char* title, Eigen::Vector3d& data, auto& unit, const char* combo_items_separated_by_zeros, const char* format) {
249 if (auto response = gui::widgets::InputDouble3WithUnit(fmt::format("{}##{}", title, size_t(id)).c_str(), configWidth, unitWidth,
250 data.data(), unit, combo_items_separated_by_zeros,
251 format, ImGuiInputTextFlags_CharsScientific))
252 {
253 if (response == gui::widgets::InputWithUnitChange_Input) { LOG_DEBUG("{}: {} changed to {}", nameId(), title, data.transpose()); }
254 if (response == gui::widgets::InputWithUnitChange_Unit) { LOG_DEBUG("{}: {} unit changed to {}", nameId(), title, fmt::underlying(unit)); }
256 }
257 };
258
259 ImGui::SetNextItemOpen(true, ImGuiCond_FirstUseEver);
260 if (ImGui::TreeNode(fmt::format("Q - System/Process noise covariance matrix##{}", size_t(id)).c_str()))
261 {
262 // --------------------------------------------- Accelerometer -----------------------------------------------
264 {
265 ImGui::SetNextItemWidth(configWidth + ImGui::GetStyle().ItemSpacing.x);
266 if (auto randomProcessAccel = static_cast<int>(_randomProcessAccel);
267 ImGui::Combo(fmt::format("Random Process Accelerometer##{}", size_t(id)).c_str(), &randomProcessAccel, "Random Walk\0"
268 "Gauss-Markov 1st Order\0\0"))
269 {
270 _randomProcessAccel = static_cast<decltype(_randomProcessAccel)>(randomProcessAccel);
271 LOG_DEBUG("{}: randomProcessAccel changed to {}", nameId(), fmt::underlying(_randomProcessAccel));
273 }
274 }
275
276 inputVector3WithUnit("Standard deviation of the noise on the\naccelerometer specific-force measurements",
278 inputVector3WithUnit(fmt::format("Standard deviation σ of the accel {}",
280 ? "dynamic bias, in σ²/τ"
281 : (_randomProcessAccel == RandomProcess::RandomWalk ? "bias noise" : "bias noise, in √(2σ²β)"))
282 .c_str(),
284
286 {
287 int unitCorrelationLength = 0;
288 if (gui::widgets::InputDouble3LWithUnit(fmt::format("Correlation length τ of the accel dynamic bias##Correlation length τ of the accel dynamic bias {}", size_t(id)).c_str(),
289 configWidth, unitWidth, _tau_bad.data(), 0., std::numeric_limits<double>::max(),
290 unitCorrelationLength, "s\0\0", "%.2e", ImGuiInputTextFlags_CharsScientific))
291 {
292 LOG_DEBUG("{}: tau_bad changed to {}", nameId(), _tau_bad);
294 }
295 }
296
297 ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 20.F);
298
299 // ----------------------------------------------- Gyroscope -------------------------------------------------
300
302 {
303 ImGui::SetNextItemWidth(configWidth + ImGui::GetStyle().ItemSpacing.x);
304 if (auto randomProcessGyro = static_cast<int>(_randomProcessGyro);
305 ImGui::Combo(fmt::format("Random Process Gyroscope##{}", size_t(id)).c_str(), &randomProcessGyro, "Random Walk\0"
306 "Gauss-Markov 1st Order\0\0"))
307 {
308 _randomProcessGyro = static_cast<decltype(_randomProcessGyro)>(randomProcessGyro);
309 LOG_DEBUG("{}: randomProcessGyro changed to {}", nameId(), fmt::underlying(_randomProcessGyro));
311 }
312 }
313
314 inputVector3WithUnit("Standard deviation of the noise on\nthe gyro angular-rate measurements",
316 inputVector3WithUnit(fmt::format("Standard deviation σ of the gyro {}",
318 ? "dynamic bias, in σ²/τ"
319 : (_randomProcessGyro == RandomProcess::RandomWalk ? "bias noise" : "bias noise, in √(2σ²β)"))
320 .c_str(),
322
324 {
325 int unitCorrelationLength = 0;
326 if (gui::widgets::InputDouble3LWithUnit(fmt::format("Correlation length τ of the gyro {}##Correlation length τ of the gyro dynamic bias {}",
327 _qCalculationAlgorithm == QCalculationAlgorithm::VanLoan ? "bias noise" : "dynamic bias", size_t(id))
328 .c_str(),
329 configWidth, unitWidth, _tau_bgd.data(), 0., std::numeric_limits<double>::max(),
330 unitCorrelationLength, "s\0\0", "%.2e", ImGuiInputTextFlags_CharsScientific))
331 {
332 LOG_DEBUG("{}: tau_bgd changed to {}", nameId(), _tau_bgd);
334 }
335 }
336
337 ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 20.F);
338
339 // ----------------------------------------- Barometer -------------------------------------------
340 if (_enableBaroHgt)
341 {
342 if (gui::widgets::InputDoubleWithUnit(fmt::format("Standard deviation of the baro height bias##{}", size_t(id))
343 .c_str(),
344 configWidth, unitWidth, &_stdevBaroHeightBias, _stdevBaroHeightBiasUnits,
345 "m\0\0", 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
346 {
347 LOG_DEBUG("{}: stdevBaroHeightBias changed to: {}", nameId(), _stdevBaroHeightBias);
348 LOG_DEBUG("{}: stdevBaroHeightBiasUnits changed to: {}", nameId(), fmt::underlying(_stdevBaroHeightBiasUnits));
350 }
351 ImGui::SameLine();
352 gui::widgets::HelpMarker("Random walk");
353 if (gui::widgets::InputDoubleWithUnit(fmt::format("Standard deviation of the baro scale##{}", size_t(id))
354 .c_str(),
355 configWidth, unitWidth, &_stdevBaroHeightScale, _stdevBaroHeightScaleUnits,
356 "m/m\0\0", 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
357 {
358 LOG_DEBUG("{}: stdevBaroHeightScale changed to: {}", nameId(), _stdevBaroHeightScale);
359 LOG_DEBUG("{}: stdevBaroHeightScaleUnits changed to: {}", nameId(), fmt::underlying(_stdevBaroHeightScaleUnits));
361 }
362 ImGui::SameLine();
363 gui::widgets::HelpMarker("Random walk");
364 }
365
366 ImGui::TreePop();
367 }
368
369 // ###########################################################################################################
370 // Measurement Uncertainties 𝐑
371 // ###########################################################################################################
372
373 ImGui::SetNextItemOpen(true, ImGuiCond_FirstUseEver);
374 if (ImGui::TreeNode(fmt::format("R - Measurement noise covariance matrix##{}", size_t(id)).c_str()))
375 {
376 float curPosX = ImGui::GetCursorPosX();
377 if (ImGui::Checkbox(fmt::format("##Override R Position {}", size_t(id)).c_str(), &_gnssMeasurementUncertaintyPositionOverride))
378 {
380 }
381 if (ImGui::IsItemHovered()) { ImGui::SetTooltip("Override the position variance in the measurements with these values."); }
382 ImGui::SameLine();
383 float checkWidth = ImGui::GetCursorPosX() - curPosX;
384 if (gui::widgets::InputDouble3WithUnit(fmt::format("{} {} of the GNSS position measurements##{}",
385 NAV::to_string(_inertialIntegrator.getIntegrationFrame()),
387 ? "Variance"
388 : "Standard deviation",
389 size_t(id))
390 .c_str(),
391 configWidth - checkWidth, unitWidth, _gnssMeasurementUncertaintyPosition.data(), _gnssMeasurementUncertaintyPositionUnit, "m^2, m^2, m^2\0"
392 "m, m, m\0\0",
393 "%.2e", ImGuiInputTextFlags_CharsScientific))
394 {
395 LOG_DEBUG("{}: gnssMeasurementUncertaintyPosition changed to {}", nameId(), _gnssMeasurementUncertaintyPosition.transpose());
396 LOG_DEBUG("{}: gnssMeasurementUncertaintyPositionUnit changed to {}", nameId(), fmt::underlying(_gnssMeasurementUncertaintyPositionUnit));
398 }
399
400 if (ImGui::Checkbox(fmt::format("##Override R Velocity {}", size_t(id)).c_str(), &_gnssMeasurementUncertaintyVelocityOverride))
401 {
403 }
404 if (ImGui::IsItemHovered()) { ImGui::SetTooltip("Override the velocity variance in the measurements with these values."); }
405 ImGui::SameLine();
406 if (gui::widgets::InputDouble3WithUnit(fmt::format("{} {} of the GNSS velocity measurements##{}",
407 NAV::to_string(_inertialIntegrator.getIntegrationFrame()),
409 size_t(id))
410 .c_str(),
411 configWidth - checkWidth, unitWidth, _gnssMeasurementUncertaintyVelocity.data(), _gnssMeasurementUncertaintyVelocityUnit, "m^2/s^2\0"
412 "m/s\0\0",
413 "%.2e", ImGuiInputTextFlags_CharsScientific))
414 {
415 LOG_DEBUG("{}: gnssMeasurementUncertaintyVelocity changed to {}", nameId(), _gnssMeasurementUncertaintyVelocity);
416 LOG_DEBUG("{}: gnssMeasurementUncertaintyVelocityUnit changed to {}", nameId(), fmt::underlying(_gnssMeasurementUncertaintyVelocityUnit));
418 }
419
420 if (_enableBaroHgt)
421 {
422 if (ImGui::Checkbox(fmt::format("##Override R Baro Height {}", size_t(id)).c_str(), &_baroHeightMeasurementUncertaintyOverride))
423 {
425 }
426 if (ImGui::IsItemHovered()) { ImGui::SetTooltip("Override the barometric height variance in the measurements with this value."); }
427 ImGui::SameLine();
428 if (gui::widgets::InputDoubleWithUnit(fmt::format("{} of the barometric height measurements##{}", _barometricHeightMeasurementUncertaintyUnit == BaroHeightMeasurementUncertaintyUnit::m2 ? "Variance" : "Standard deviation",
429 size_t(id))
430 .c_str(),
432 "m\0\0",
433
434 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
435 {
436 LOG_DEBUG("{}: barometricHeightMeasurementUncertainty changed to {}", nameId(), _barometricHeightMeasurementUncertainty);
437 LOG_DEBUG("{}: barometricHeightMeasurementUncertaintyUnit changed to {}", nameId(), fmt::underlying(_barometricHeightMeasurementUncertaintyUnit));
439 }
440 }
441
442 ImGui::TreePop();
443 }
444
445 // ###########################################################################################################
446 // 𝐏 Error covariance matrix
447 // ###########################################################################################################
448
449 ImGui::SetNextItemOpen(true, ImGuiCond_FirstUseEver);
450 if (ImGui::TreeNode(fmt::format("P Error covariance matrix (init)##{}", size_t(id)).c_str()))
451 {
452 if (gui::widgets::InputDouble3WithUnit(fmt::format("Position covariance ({})##{}",
455 ? "Variance σ²"
456 : "Standard deviation σ",
457 size_t(id))
458 .c_str(),
459 configWidth, unitWidth, _initCovariancePosition.data(), _initCovariancePositionUnit, "rad^2, rad^2, m^2\0"
460 "rad, rad, m\0"
461 "m^2, m^2, m^2\0"
462 "m, m, m\0\0",
463 "%.2e", ImGuiInputTextFlags_CharsScientific))
464 {
465 LOG_DEBUG("{}: initCovariancePosition changed to {}", nameId(), _initCovariancePosition);
466 LOG_DEBUG("{}: initCovariancePositionUnit changed to {}", nameId(), fmt::underlying(_initCovariancePositionUnit));
468 }
469
470 if (gui::widgets::InputDouble3WithUnit(fmt::format("Velocity covariance ({})##{}",
472 ? "Variance σ²"
473 : "Standard deviation σ",
474 size_t(id))
475 .c_str(),
476 configWidth, unitWidth, _initCovarianceVelocity.data(), _initCovarianceVelocityUnit, "m^2/s^2\0"
477 "m/s\0\0",
478 "%.2e", ImGuiInputTextFlags_CharsScientific))
479 {
480 LOG_DEBUG("{}: initCovarianceVelocity changed to {}", nameId(), _initCovarianceVelocity);
481 LOG_DEBUG("{}: initCovarianceVelocityUnit changed to {}", nameId(), fmt::underlying(_initCovarianceVelocityUnit));
483 }
484
485 if (gui::widgets::InputDouble3WithUnit(fmt::format("Flight Angles covariance ({})##{}",
488 ? "Variance σ²"
489 : "Standard deviation σ",
490 size_t(id))
491 .c_str(),
492 configWidth, unitWidth, _initCovarianceAttitudeAngles.data(), _initCovarianceAttitudeAnglesUnit, "rad^2\0"
493 "deg^2\0"
494 "rad\0"
495 "deg\0\0",
496 "%.2e", ImGuiInputTextFlags_CharsScientific))
497 {
498 LOG_DEBUG("{}: initCovarianceAttitudeAngles changed to {}", nameId(), _initCovarianceAttitudeAngles);
499 LOG_DEBUG("{}: initCovarianceAttitudeAnglesUnit changed to {}", nameId(), fmt::underlying(_initCovarianceAttitudeAnglesUnit));
501 }
502 ImGui::SameLine();
504 ? "Angles rotating the ECEF frame into the body frame."
505 : "Angles rotating the local navigation frame into the body frame (Roll, Pitch, Yaw)");
506
507 if (gui::widgets::InputDouble3WithUnit(fmt::format("Accelerometer Bias covariance ({})##{}",
509 ? "Variance σ²"
510 : "Standard deviation σ",
511 size_t(id))
512 .c_str(),
513 configWidth, unitWidth, _initCovarianceBiasAccel.data(), _initCovarianceBiasAccelUnit, "m^2/s^4\0"
514 "m/s^2\0\0",
515 "%.2e", ImGuiInputTextFlags_CharsScientific))
516 {
517 LOG_DEBUG("{}: initCovarianceBiasAccel changed to {}", nameId(), _initCovarianceBiasAccel);
518 LOG_DEBUG("{}: initCovarianceBiasAccelUnit changed to {}", nameId(), fmt::underlying(_initCovarianceBiasAccelUnit));
520 }
521
522 if (gui::widgets::InputDouble3WithUnit(fmt::format("Gyroscope Bias covariance ({})##{}",
525 ? "Variance σ²"
526 : "Standard deviation σ",
527 size_t(id))
528 .c_str(),
529 configWidth, unitWidth, _initCovarianceBiasGyro.data(), _initCovarianceBiasGyroUnit, "rad^2/s^2\0"
530 "deg^2/s^2\0"
531 "rad/s\0"
532 "deg/s\0\0",
533 "%.2e", ImGuiInputTextFlags_CharsScientific))
534 {
535 LOG_DEBUG("{}: initCovarianceBiasGyro changed to {}", nameId(), _initCovarianceBiasGyro);
536 LOG_DEBUG("{}: initCovarianceBiasGyroUnit changed to {}", nameId(), fmt::underlying(_initCovarianceBiasGyroUnit));
538 }
539 if (_enableBaroHgt)
540 {
541 if (gui::widgets::InputDoubleWithUnit(fmt::format("Height Bias covariance ({})##{}",
543 ? "Variance σ²"
544 : "Standard deviation σ",
545 size_t(id))
546 .c_str(),
547 configWidth, unitWidth, &_initCovarianceBiasHeight, _initCovarianceBiasHeightUnit, "m^2\0"
548 "m\0\0",
549 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
550 {
551 LOG_DEBUG("{}: initCovarianceBiasHeight changed to {}", nameId(), _initCovarianceBiasHeight);
552 LOG_DEBUG("{}: initCovarianceBiasHeightUnit changed to {}", nameId(), fmt::underlying(_initCovarianceBiasHeightUnit));
554 }
555 if (gui::widgets::InputDoubleWithUnit(fmt::format("Height Scale covariance ({})##{}",
557 ? "Variance σ²"
558 : "Standard deviation σ",
559 size_t(id))
560 .c_str(),
561 configWidth, unitWidth, &_initCovarianceScaleHeight, _initCovarianceScaleHeightUnit, "m^2/m^2\0"
562 "m/m\0\0",
563 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
564 {
565 LOG_DEBUG("{}: initCovarianceScaleHeight changed to {}", nameId(), _initCovarianceScaleHeight);
566 LOG_DEBUG("{}: initCovarianceScaleHeightUnit changed to {}", nameId(), fmt::underlying(_initCovarianceScaleHeightUnit));
568 }
569 }
570
571 ImGui::TreePop();
572 }
573
574 // ###########################################################################################################
575 // IMU biases
576 // ###########################################################################################################
577
578 ImGui::SetNextItemOpen(true, ImGuiCond_FirstUseEver);
579 if (ImGui::TreeNode(fmt::format("IMU biases (init)##{}", size_t(id)).c_str()))
580 {
581 if (gui::widgets::InputDouble3WithUnit(fmt::format("Accelerometer biases##{}", size_t(id)).c_str(),
582 configWidth, unitWidth, _initBiasAccel.data(), _initBiasAccelUnit, "µg\0m/s^2\0\0",
583 "%.2e", ImGuiInputTextFlags_CharsScientific))
584 {
585 LOG_DEBUG("{}: initBiasAccel changed to {}", nameId(), _initBiasAccel.transpose());
586 LOG_DEBUG("{}: initBiasAccelUnit changed to {}", nameId(), fmt::underlying(_initBiasAccelUnit));
588 }
589 ImGui::SameLine();
590 gui::widgets::HelpMarker("In body frame coordinates");
591 if (gui::widgets::InputDouble3WithUnit(fmt::format("Gyro biases##{}", size_t(id)).c_str(),
592 configWidth, unitWidth, _initBiasGyro.data(), _initBiasGyroUnit, "rad/s\0deg/s\0\0",
593 "%.2e", ImGuiInputTextFlags_CharsScientific))
594 {
595 LOG_DEBUG("{}: initBiasGyro changed to {}", nameId(), _initBiasGyro.transpose());
596 LOG_DEBUG("{}: initBiasGyroUnit changed to {}", nameId(), fmt::underlying(_initBiasGyroUnit));
598 }
599 ImGui::SameLine();
600 gui::widgets::HelpMarker("In body frame coordinates");
601
602 ImGui::TreePop();
603 }
604
605 ImGui::SetNextItemOpen(false, ImGuiCond_FirstUseEver);
606 if (ImGui::TreeNode(fmt::format("Kalman Filter matrices##{}", size_t(id)).c_str()))
607 {
608 _kalmanFilter.showKalmanFilterMatrixViews(std::to_string(size_t(id)).c_str());
609 ImGui::TreePop();
610 }
611
612 ImGui::Separator();
613
614 if (ImGui::Checkbox(fmt::format("Rank check for Kalman filter matrices##{}", size_t(id)).c_str(), &_checkKalmanMatricesRanks))
615 {
616 LOG_DEBUG("{}: checkKalmanMatricesRanks {}", nameId(), _checkKalmanMatricesRanks);
618 }
619 }
620}
621
623{
624 LOG_TRACE("{}: called", nameId());
625
626 json j;
627
628 j["dynamicInputPins"] = _dynamicInputPins;
629 j["inertialIntegrator"] = _inertialIntegrator;
630 j["preferAccelerationOverDeltaMeasurements"] = _preferAccelerationOverDeltaMeasurements;
631 j["initalRollPitchYaw"] = _initalRollPitchYaw;
632 j["initializeStateOverExternalPin"] = _initializeStateOverExternalPin;
633
634 j["checkKalmanMatricesRanks"] = _checkKalmanMatricesRanks;
635
636 j["phiCalculationAlgorithm"] = _phiCalculationAlgorithm;
637 j["phiCalculationTaylorOrder"] = _phiCalculationTaylorOrder;
638 j["qCalculationAlgorithm"] = _qCalculationAlgorithm;
639
640 j["enableBaroHgt"] = _enableBaroHgt;
641
642 j["randomProcessAccel"] = _randomProcessAccel;
643 j["randomProcessGyro"] = _randomProcessGyro;
644 j["stdev_ra"] = _stdev_ra;
645 j["stdevAccelNoiseUnits"] = _stdevAccelNoiseUnits;
646 j["stdev_rg"] = _stdev_rg;
647 j["stdevGyroNoiseUnits"] = _stdevGyroNoiseUnits;
648 j["stdev_bad"] = _stdev_bad;
649 j["tau_bad"] = _tau_bad;
650 j["stdevAccelBiasUnits"] = _stdevAccelBiasUnits;
651 j["stdev_bgd"] = _stdev_bgd;
652 j["tau_bgd"] = _tau_bgd;
653 j["stdevGyroBiasUnits"] = _stdevGyroBiasUnits;
654 j["stdevBaroHeightBiasUnits"] = _stdevBaroHeightBiasUnits;
655 j["stdevBaroHeightBias"] = _stdevBaroHeightBias;
656 j["stdevBaroHeightScaleUnits"] = _stdevBaroHeightScaleUnits;
657 j["stdevBaroHeightScale"] = _stdevBaroHeightScale;
658
659 j["gnssMeasurementUncertaintyPositionUnit"] = _gnssMeasurementUncertaintyPositionUnit;
660 j["gnssMeasurementUncertaintyPosition"] = _gnssMeasurementUncertaintyPosition;
661 j["gnssMeasurementUncertaintyPositionOverride"] = _gnssMeasurementUncertaintyPositionOverride;
662 j["gnssMeasurementUncertaintyVelocityUnit"] = _gnssMeasurementUncertaintyVelocityUnit;
663 j["gnssMeasurementUncertaintyVelocity"] = _gnssMeasurementUncertaintyVelocity;
664 j["gnssMeasurementUncertaintyVelocityOverride"] = _gnssMeasurementUncertaintyVelocityOverride;
665 j["barometricHeightMeasurementUncertaintyUnit"] = _barometricHeightMeasurementUncertaintyUnit;
666 j["barometricHeightMeasurementUncertainty"] = _barometricHeightMeasurementUncertainty;
667 j["baroHeightMeasurementUncertaintyOverride"] = _baroHeightMeasurementUncertaintyOverride;
668
669 j["initCovariancePositionUnit"] = _initCovariancePositionUnit;
670 j["initCovariancePosition"] = _initCovariancePosition;
671 j["initCovarianceVelocityUnit"] = _initCovarianceVelocityUnit;
672 j["initCovarianceVelocity"] = _initCovarianceVelocity;
673 j["initCovarianceAttitudeAnglesUnit"] = _initCovarianceAttitudeAnglesUnit;
674 j["initCovarianceAttitudeAngles"] = _initCovarianceAttitudeAngles;
675 j["initCovarianceBiasAccelUnit"] = _initCovarianceBiasAccelUnit;
676 j["initCovarianceBiasAccel"] = _initCovarianceBiasAccel;
677 j["initCovarianceBiasGyroUnit"] = _initCovarianceBiasGyroUnit;
678 j["initCovarianceBiasGyro"] = _initCovarianceBiasGyro;
679 j["initCovarianceBiasHeightUnit"] = _initCovarianceBiasHeightUnit;
680 j["initCovarianceBiasHeight"] = _initCovarianceBiasHeight;
681 j["initCovarianceScaleHeightUnit"] = _initCovarianceScaleHeightUnit;
682 j["initCovarianceScaleHeight"] = _initCovarianceScaleHeight;
683
684 j["initBiasAccel"] = _initBiasAccel;
685 j["initBiasAccelUnit"] = _initBiasAccelUnit;
686 j["initBiasGyro"] = _initBiasGyro;
687 j["initBiasGyroUnit"] = _initBiasGyroUnit;
688
689 return j;
690}
691
693{
694 LOG_TRACE("{}: called", nameId());
695
696 if (j.contains("dynamicInputPins"))
697 {
698 gui::widgets::from_json(j.at("dynamicInputPins"), _dynamicInputPins, this);
700 }
701 if (j.contains("inertialIntegrator"))
702 {
703 j.at("inertialIntegrator").get_to(_inertialIntegrator);
704 }
705 if (j.contains("preferAccelerationOverDeltaMeasurements"))
706 {
707 j.at("preferAccelerationOverDeltaMeasurements").get_to(_preferAccelerationOverDeltaMeasurements);
708 }
709 if (j.contains("initalRollPitchYaw"))
710 {
711 j.at("initalRollPitchYaw").get_to(_initalRollPitchYaw);
712 }
713 if (j.contains("initializeStateOverExternalPin"))
714 {
715 j.at("initializeStateOverExternalPin").get_to(_initializeStateOverExternalPin);
717 }
718 if (j.contains("checkKalmanMatricesRanks"))
719 {
720 j.at("checkKalmanMatricesRanks").get_to(_checkKalmanMatricesRanks);
721 }
722
723 if (j.contains("phiCalculationAlgorithm"))
724 {
725 j.at("phiCalculationAlgorithm").get_to(_phiCalculationAlgorithm);
726 }
727 if (j.contains("phiCalculationTaylorOrder"))
728 {
729 j.at("phiCalculationTaylorOrder").get_to(_phiCalculationTaylorOrder);
730 }
731 if (j.contains("qCalculationAlgorithm"))
732 {
733 j.at("qCalculationAlgorithm").get_to(_qCalculationAlgorithm);
734 }
735 if (j.contains("enableBaroHgt"))
736 {
737 j.at("enableBaroHgt").get_to(_enableBaroHgt);
739 }
740 // ------------------------------- 𝐐 System/Process noise covariance matrix ---------------------------------
741 if (j.contains("randomProcessAccel"))
742 {
743 j.at("randomProcessAccel").get_to(_randomProcessAccel);
744 }
745 if (j.contains("randomProcessGyro"))
746 {
747 j.at("randomProcessGyro").get_to(_randomProcessGyro);
748 }
749 if (j.contains("stdev_ra"))
750 {
751 _stdev_ra = j.at("stdev_ra");
752 }
753 if (j.contains("stdevAccelNoiseUnits"))
754 {
755 j.at("stdevAccelNoiseUnits").get_to(_stdevAccelNoiseUnits);
756 }
757 if (j.contains("stdev_rg"))
758 {
759 _stdev_rg = j.at("stdev_rg");
760 }
761 if (j.contains("stdevGyroNoiseUnits"))
762 {
763 j.at("stdevGyroNoiseUnits").get_to(_stdevGyroNoiseUnits);
764 }
765 if (j.contains("stdev_bad"))
766 {
767 _stdev_bad = j.at("stdev_bad");
768 }
769 if (j.contains("tau_bad"))
770 {
771 _tau_bad = j.at("tau_bad");
772 }
773 if (j.contains("stdevAccelBiasUnits"))
774 {
775 j.at("stdevAccelBiasUnits").get_to(_stdevAccelBiasUnits);
776 }
777 if (j.contains("stdev_bgd"))
778 {
779 _stdev_bgd = j.at("stdev_bgd");
780 }
781 if (j.contains("tau_bgd"))
782 {
783 _tau_bgd = j.at("tau_bgd");
784 }
785 if (j.contains("stdevGyroBiasUnits"))
786 {
787 j.at("stdevGyroBiasUnits").get_to(_stdevGyroBiasUnits);
788 }
789 if (j.contains("stdevBaroHeightBiasUnits"))
790 {
791 j.at("stdevBaroHeightBiasUnits").get_to(_stdevBaroHeightBiasUnits);
792 }
793 if (j.contains("stdevBaroHeightBias"))
794 {
795 _stdevBaroHeightBias = j.at("stdevBaroHeightBias");
796 }
797 if (j.contains("stdevBaroHeightScaleUnits"))
798 {
799 j.at("stdevBaroHeightScaleUnits").get_to(_stdevBaroHeightScaleUnits);
800 }
801 if (j.contains("stdevBaroHeightScale"))
802 {
803 _stdevBaroHeightScale = j.at("stdevBaroHeightScale");
804 }
805
806 // -------------------------------- 𝐑 Measurement noise covariance matrix -----------------------------------
807 if (j.contains("gnssMeasurementUncertaintyPositionUnit"))
808 {
809 j.at("gnssMeasurementUncertaintyPositionUnit").get_to(_gnssMeasurementUncertaintyPositionUnit);
810 }
811 if (j.contains("gnssMeasurementUncertaintyPosition"))
812 {
813 _gnssMeasurementUncertaintyPosition = j.at("gnssMeasurementUncertaintyPosition");
814 }
815 if (j.contains("gnssMeasurementUncertaintyPositionOverride"))
816 {
817 j.at("gnssMeasurementUncertaintyPositionOverride").get_to(_gnssMeasurementUncertaintyPositionOverride);
818 }
819 if (j.contains("gnssMeasurementUncertaintyVelocityUnit"))
820 {
821 j.at("gnssMeasurementUncertaintyVelocityUnit").get_to(_gnssMeasurementUncertaintyVelocityUnit);
822 }
823 if (j.contains("gnssMeasurementUncertaintyVelocity"))
824 {
825 _gnssMeasurementUncertaintyVelocity = j.at("gnssMeasurementUncertaintyVelocity");
826 }
827 if (j.contains("gnssMeasurementUncertaintyVelocityOverride"))
828 {
829 j.at("gnssMeasurementUncertaintyVelocityOverride").get_to(_gnssMeasurementUncertaintyVelocityOverride);
830 }
831 if (j.contains("barometricHeightMeasurementUncertaintyUnit"))
832 {
833 j.at("barometricHeightMeasurementUncertaintyUnit").get_to(_barometricHeightMeasurementUncertaintyUnit);
834 }
835 if (j.contains("barometricHeightMeasurementUncertainty"))
836 {
837 _barometricHeightMeasurementUncertainty = j.at("barometricHeightMeasurementUncertainty");
838 }
839 if (j.contains("baroHeightMeasurementUncertaintyOverride"))
840 {
841 j.at("baroHeightMeasurementUncertaintyOverride").get_to(_baroHeightMeasurementUncertaintyOverride);
842 }
843 // -------------------------------------- 𝐏 Error covariance matrix -----------------------------------------
844 if (j.contains("initCovariancePositionUnit"))
845 {
846 j.at("initCovariancePositionUnit").get_to(_initCovariancePositionUnit);
847 }
848 if (j.contains("initCovariancePosition"))
849 {
850 _initCovariancePosition = j.at("initCovariancePosition");
851 }
852 if (j.contains("initCovarianceVelocityUnit"))
853 {
854 j.at("initCovarianceVelocityUnit").get_to(_initCovarianceVelocityUnit);
855 }
856 if (j.contains("initCovarianceVelocity"))
857 {
858 _initCovarianceVelocity = j.at("initCovarianceVelocity");
859 }
860 if (j.contains("initCovarianceAttitudeAnglesUnit"))
861 {
862 j.at("initCovarianceAttitudeAnglesUnit").get_to(_initCovarianceAttitudeAnglesUnit);
863 }
864 if (j.contains("initCovarianceAttitudeAngles"))
865 {
866 _initCovarianceAttitudeAngles = j.at("initCovarianceAttitudeAngles");
867 }
868 if (j.contains("initCovarianceBiasAccelUnit"))
869 {
870 j.at("initCovarianceBiasAccelUnit").get_to(_initCovarianceBiasAccelUnit);
871 }
872 if (j.contains("initCovarianceBiasAccel"))
873 {
874 _initCovarianceBiasAccel = j.at("initCovarianceBiasAccel");
875 }
876 if (j.contains("initCovarianceBiasGyroUnit"))
877 {
878 j.at("initCovarianceBiasGyroUnit").get_to(_initCovarianceBiasGyroUnit);
879 }
880 if (j.contains("initCovarianceBiasGyro"))
881 {
882 _initCovarianceBiasGyro = j.at("initCovarianceBiasGyro");
883 }
884 if (j.contains("initCovarianceBiasHeightUnit"))
885 {
886 j.at("initCovarianceBiasHeightUnit").get_to(_initCovarianceBiasHeightUnit);
887 }
888 if (j.contains("initCovarianceBiasHeight"))
889 {
890 _initCovarianceBiasHeight = j.at("initCovarianceBiasHeight");
891 }
892 if (j.contains("initCovarianceScaleHeightUnit"))
893 {
894 j.at("initCovarianceScaleHeightUnit").get_to(_initCovarianceScaleHeightUnit);
895 }
896 if (j.contains("initCovarianceScaleHeight"))
897 {
898 _initCovarianceScaleHeight = j.at("initCovarianceScaleHeight");
899 }
900
901 // ---------------------------------------- Initial IMU biases -------------------------------------------
902 if (j.contains("initBiasAccel"))
903 {
904 _initBiasAccel = j.at("initBiasAccel");
905 }
906 if (j.contains("initBiasAccelUnit"))
907 {
908 _initBiasAccelUnit = j.at("initBiasAccelUnit");
909 }
910 if (j.contains("initBiasGyro"))
911 {
912 _initBiasGyro = j.at("initBiasGyro");
913 }
914 if (j.contains("initBiasGyroUnit"))
915 {
916 _initBiasGyroUnit = j.at("initBiasGyroUnit");
917 }
918}
919
921{
922 LOG_TRACE("{}: called", nameId());
923
924 for (size_t i = _dynamicInputPins.getFirstDynamicPinIdx(); i < _dynamicInputPins.getFirstDynamicPinIdx() + _dynamicInputPins.getNumberOfDynamicPins(); i++)
925 {
926 inputPins.at(i).priority = 2; // PosVel used for initialization
927 }
928
929 _inertialIntegrator.reset();
930 _lastImuObs = nullptr;
931 _externalInitTime.reset();
933 _heightBiasTotal = 0.0;
934 _heightScaleTotal = 1.0;
935
936 _kalmanFilter.setZero();
937
938 // Initial Covariance of the attitude angles in [rad²]
939 Eigen::Vector3d variance_angles = Eigen::Vector3d::Zero();
941 {
943 variance_angles = _initCovarianceAttitudeAngles;
944 break;
946 variance_angles = deg2rad(_initCovarianceAttitudeAngles);
947 break;
949 variance_angles = _initCovarianceAttitudeAngles.array().pow(2);
950 break;
952 variance_angles = deg2rad(_initCovarianceAttitudeAngles).array().pow(2);
953 break;
954 }
955
956 // Initial Covariance of the velocity in [m²/s²]
957 Eigen::Vector3d variance_vel = Eigen::Vector3d::Zero();
959 {
961 variance_vel = _initCovarianceVelocity;
962 break;
964 variance_vel = _initCovarianceVelocity.array().pow(2);
965 break;
966 }
967
968 Eigen::Vector3d e_variance = Eigen::Vector3d::Zero(); // Initial Covariance of the position in [m²]
969 Eigen::Vector3d lla_variance = Eigen::Vector3d::Zero(); // Initial Covariance of the position in [rad² rad² m²]
971 {
973 e_variance = trafo::lla2ecef_WGS84(_initCovariancePosition.cwiseSqrt()).array().pow(2);
974 lla_variance = _initCovariancePosition;
975 break;
977 e_variance = trafo::lla2ecef_WGS84(_initCovariancePosition).array().pow(2);
978 lla_variance = _initCovariancePosition.array().pow(2);
979 break;
981 e_variance = _initCovariancePosition.array().pow(2);
982 lla_variance = (trafo::ecef2lla_WGS84(trafo::ned2ecef(_initCovariancePosition, Eigen::Vector3d{ 0, 0, 0 }))).array().pow(2);
983 break;
985 e_variance = _initCovariancePosition;
986 lla_variance = (trafo::ecef2lla_WGS84(trafo::ned2ecef(_initCovariancePosition.cwiseSqrt(), Eigen::Vector3d{ 0, 0, 0 }))).array().pow(2);
987 break;
988 }
989
990 // Initial Covariance of the accelerometer biases in [m^2/s^4]
991 Eigen::Vector3d variance_accelBias = Eigen::Vector3d::Zero();
993 {
995 variance_accelBias = _initCovarianceBiasAccel;
996 break;
998 variance_accelBias = _initCovarianceBiasAccel.array().pow(2);
999 break;
1000 }
1001
1002 // Initial Covariance of the gyroscope biases in [rad^2/s^2]
1003 Eigen::Vector3d variance_gyroBias = Eigen::Vector3d::Zero();
1005 {
1007 variance_gyroBias = _initCovarianceBiasGyro;
1008 break;
1010 variance_gyroBias = deg2rad(_initCovarianceBiasGyro.array().sqrt()).array().pow(2);
1011 break;
1013 variance_gyroBias = _initCovarianceBiasGyro.array().pow(2);
1014 break;
1016 variance_gyroBias = deg2rad(_initCovarianceBiasGyro).array().pow(2);
1017 break;
1018 }
1019
1020 // Initial Covariance of the height bias in [m^2]
1021 double variance_heightBias = 0.0;
1023 {
1025 variance_heightBias = std::pow(_initCovarianceBiasHeight, 2);
1026 break;
1028 variance_heightBias = _initCovarianceBiasHeight;
1029 break;
1030 }
1031
1032 // Initial Covariance of the height scale in [m^2/m^2]
1033 double variance_heightScale = 0.0;
1035 {
1037 variance_heightScale = std::pow(_initCovarianceScaleHeight, 2);
1038 break;
1040 variance_heightScale = _initCovarianceScaleHeight;
1041 break;
1042 }
1043
1044 // 𝐏 Error covariance matrix
1045 _kalmanFilter.P = initialErrorCovarianceMatrix_P0(variance_angles, // Flight Angles covariance
1046 variance_vel, // Velocity covariance
1048 ? lla_variance
1049 : e_variance, // Position (Lat, Lon, Alt) / ECEF covariance
1050 variance_accelBias, // Accelerometer Bias covariance
1051 variance_gyroBias, // Gyroscope Bias covariance
1052 variance_heightBias, // height bias covariance
1053 variance_heightScale); // height scale covariance
1054
1055 // Initial acceleration bias in body frame coordinates in [m/s^2]
1056 switch (_initBiasAccelUnit)
1057 {
1060 break;
1063 break;
1064 }
1065
1066 // Initial angular rate bias in body frame coordinates in [rad/s]
1067 switch (_initBiasGyroUnit)
1068 {
1071 break;
1074 break;
1075 }
1076
1077 LOG_DEBUG("{}: initialized", nameId());
1078 LOG_DATA("{}: P_0 =\n{}", nameId(), _kalmanFilter.P);
1079
1080 return true;
1081}
1082
1084{
1085 LOG_TRACE("{}: called", nameId());
1086}
1087
1089{
1090 return std::ranges::any_of(inputPins, [&insTime](const InputPin& pin) {
1091 return pin.dataIdentifier.front() == PosVel::type() && !pin.queue.empty() && pin.queue.front()->insTime == insTime;
1092 });
1093}
1094
1096{
1097 auto lckfSolution = std::make_shared<InsGnssLCKFSolution>();
1098 lckfSolution->insTime = posVelAtt.insTime;
1099 if (posVelAtt.e_CovarianceMatrix())
1100 {
1101 lckfSolution->setPosVelAttAndCov_e(posVelAtt.e_position(),
1102 posVelAtt.e_velocity(),
1103 posVelAtt.e_Quat_b(),
1104 (*posVelAtt.e_CovarianceMatrix())(all, all));
1105 }
1106 else
1107 {
1108 lckfSolution->setPosVelAtt_e(posVelAtt.e_position(), posVelAtt.e_velocity(), posVelAtt.e_Quat_b());
1109 }
1110
1111 lckfSolution->frame = _inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::NED
1114
1115 if (_lastImuObs)
1116 {
1117 lckfSolution->b_biasAccel.value = _lastImuObs->imuPos.b_quat_p() * -_inertialIntegrator.p_getLastAccelerationBias();
1118 lckfSolution->b_biasAccel.stdDev = Eigen::Vector3d{
1122 };
1123 lckfSolution->b_biasGyro.value = _lastImuObs->imuPos.b_quat_p() * -_inertialIntegrator.p_getLastAngularRateBias();
1124 lckfSolution->b_biasGyro.stdDev = Eigen::Vector3d{
1128 };
1129 }
1130 lckfSolution->heightBias = { .value = _heightBiasTotal, .stdDev = std::sqrt(_kalmanFilter.P(KFStates::HeightBias, KFStates::HeightBias)) };
1131 lckfSolution->heightScale = { .value = _heightScaleTotal, .stdDev = std::sqrt(_kalmanFilter.P(KFStates::HeightScale, KFStates::HeightScale)) };
1132 if (!hasInputPinWithSameTime(lckfSolution->insTime))
1133 {
1135 }
1136}
1137
1139{
1140 auto nodeData = queue.extract_front();
1141 if (nodeData->insTime.empty())
1142 {
1143 LOG_ERROR("{}: Can't set new imuObs__t0 because the observation has no time tag (insTime)", nameId());
1144 return;
1145 }
1146
1147 std::shared_ptr<NAV::PosVelAtt> inertialNavSol = nullptr;
1148
1149 _lastImuObs = std::static_pointer_cast<const ImuObs>(nodeData);
1150
1152 && NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(inputPins.at(INPUT_PORT_INDEX_IMU).link.getConnectedPin()->dataIdentifier, { ImuObsWDelta::type() }))
1153 {
1154 auto obs = std::static_pointer_cast<const ImuObsWDelta>(nodeData);
1155 LOG_DATA("{}: [{}] recvImuObsWDelta", nameId(), obs->insTime.toYMDHMS(GPST));
1156
1157 // Initialize biases
1159 {
1160 _inertialIntegrator.setTotalSensorBiases(obs->imuPos.p_quat_b() * -_accelBiasTotal, obs->imuPos.p_quat_b() * -_gyroBiasTotal);
1162 }
1163
1164 inertialNavSol = _inertialIntegrator.calcInertialSolutionDelta(obs->insTime, obs->dtime, obs->dvel, obs->dtheta, obs->imuPos, nameId().c_str());
1165 }
1166 else
1167 {
1168 auto obs = std::static_pointer_cast<const ImuObs>(nodeData);
1169 LOG_DATA("{}: [{}] recvImuObs", nameId(), obs->insTime.toYMDHMS(GPST));
1170
1171 // Initialize biases
1173 {
1174 _inertialIntegrator.setTotalSensorBiases(obs->imuPos.p_quat_b() * -_accelBiasTotal, obs->imuPos.p_quat_b() * -_gyroBiasTotal);
1176 }
1177
1178 inertialNavSol = _inertialIntegrator.calcInertialSolution(obs->insTime, obs->p_acceleration, obs->p_angularRate, obs->imuPos, nameId().c_str());
1179 }
1180 if (const auto& latestState = _inertialIntegrator.getLatestState();
1181 inertialNavSol && latestState && latestState->get().m.dt > 1e-8)
1182 {
1183 looselyCoupledPrediction(inertialNavSol, latestState->get().m.dt, std::static_pointer_cast<const ImuObs>(nodeData)->imuPos);
1184
1185 setSolutionPosVelAttAndCov(inertialNavSol,
1186 calcEarthRadius_N(inertialNavSol->latitude()),
1187 calcEarthRadius_E(inertialNavSol->latitude()));
1188
1189 LOG_DATA("{}: e_position = {}", nameId(), inertialNavSol->e_position().transpose());
1190 LOG_DATA("{}: e_velocity = {}", nameId(), inertialNavSol->e_velocity().transpose());
1191 LOG_DATA("{}: rollPitchYaw = {}", nameId(), rad2deg(inertialNavSol->rollPitchYaw()).transpose());
1192
1193 if (!hasInputPinWithSameTime(nodeData->insTime))
1194 {
1195 LOG_DATA("{}: [{}] Sending out predicted solution", nameId(), inertialNavSol->insTime.toYMDHMS(GPST));
1196 invokeCallbackWithPosVelAtt(*inertialNavSol);
1197 }
1198 }
1199}
1200
1202{
1203 auto obs = std::static_pointer_cast<const PosVel>(queue.extract_front());
1204 LOG_DATA("{}: [{}] recvPosVelObservation", nameId(), obs->insTime.toYMDHMS(GPST));
1205
1206 if (!_initializeStateOverExternalPin && !_inertialIntegrator.hasInitialPosition())
1207 {
1208 for (size_t i = _dynamicInputPins.getFirstDynamicPinIdx(); i < _dynamicInputPins.getFirstDynamicPinIdx() + _dynamicInputPins.getNumberOfDynamicPins(); i++)
1209 {
1210 inputPins.at(i).priority = 0; // IMU obs (prediction) should be evaluated before the PosVel obs (update)
1211 }
1212
1213 PosVelAtt posVelAtt;
1214 posVelAtt.insTime = obs->insTime;
1215 posVelAtt.setPosVelAtt_n(obs->lla_position(), obs->n_velocity(),
1217
1218 _inertialIntegrator.setInitialState(posVelAtt, nameId().c_str());
1219 LOG_DATA("{}: e_position = {}", nameId(), posVelAtt.e_position().transpose());
1220 LOG_DATA("{}: e_velocity = {}", nameId(), posVelAtt.e_velocity().transpose());
1221 LOG_DATA("{}: rollPitchYaw = {}", nameId(), rad2deg(posVelAtt.rollPitchYaw()).transpose());
1222
1223 LOG_DATA("{}: [{}] Sending out initial solution", nameId(), obs->insTime.toYMDHMS(GPST));
1224 invokeCallbackWithPosVelAtt(posVelAtt);
1225 return;
1226 }
1227
1228 if (_externalInitTime == obs->insTime) { return; }
1229 if (!_lastImuObs)
1230 {
1231 PosVelAtt posVelAtt;
1232 posVelAtt.insTime = obs->insTime;
1233 if (obs->n_CovarianceMatrix())
1234 {
1235 Eigen::Matrix<double, 10, 10> n_cov = Eigen::Matrix<double, 10, 10>::Zero();
1236 n_cov.topLeftCorner<6, 6>() = obs->n_CovarianceMatrix()->get()(Keys::PosVel<Keys::MotionModelKey>, Keys::PosVel<Keys::MotionModelKey>);
1237 posVelAtt.setPosVelAttAndCov_n(obs->lla_position(), obs->n_velocity(), _inertialIntegrator.getLatestState()->get().attitude, n_cov);
1238 }
1239 else { posVelAtt.setPosVelAtt_n(obs->lla_position(), obs->n_velocity(), _inertialIntegrator.getLatestState()->get().attitude); }
1240 _inertialIntegrator.addState(posVelAtt, nameId().c_str());
1241
1242 LOG_DATA("{}: [{}] Sending out received solution, as no IMU data yet", nameId(), obs->insTime.toYMDHMS(GPST));
1243 invokeCallbackWithPosVelAtt(posVelAtt);
1244 return;
1245 }
1246
1248}
1249
1250void NAV::LooselyCoupledKF::recvBaroHeight([[maybe_unused]] InputPin::NodeDataQueue& queue, size_t /* pinIdx */)
1251{
1252 auto obs = std::static_pointer_cast<const BaroHgt>(queue.extract_front());
1253 LOG_DATA("{}: [{}] recvPosVelObservation", nameId(), obs->insTime.toYMDHMS(GPST));
1254
1255 if (!_inertialIntegrator.hasInitialPosition())
1256 {
1257 return;
1258 }
1259
1260 if (_externalInitTime == obs->insTime) { return; }
1261 if (!_lastImuObs)
1262 {
1263 return;
1264 }
1265
1267}
1268
1270{
1271 auto posVelAtt = std::static_pointer_cast<const PosVelAtt>(queue.extract_front());
1272 inputPins.at(INPUT_PORT_INDEX_POS_VEL_ATT_INIT).queueBlocked = true;
1274
1275 LOG_DATA("{}: recvPosVelAttInit at time [{}]", nameId(), posVelAtt->insTime.toYMDHMS());
1276
1277 for (size_t i = _dynamicInputPins.getFirstDynamicPinIdx(); i < _dynamicInputPins.getFirstDynamicPinIdx() + _dynamicInputPins.getNumberOfDynamicPins(); i++)
1278 {
1279 inputPins.at(i).priority = 0; // IMU obs (prediction) should be evaluated before the PosVel obs (update)
1280 }
1281 _externalInitTime = posVelAtt->insTime;
1282
1283 _inertialIntegrator.setInitialState(*posVelAtt, nameId().c_str());
1284 LOG_DATA("{}: e_position = {}", nameId(), posVelAtt->e_position().transpose());
1285 LOG_DATA("{}: e_velocity = {}", nameId(), posVelAtt->e_velocity().transpose());
1286 LOG_DATA("{}: rollPitchYaw = {}", nameId(), rad2deg(posVelAtt->rollPitchYaw()).transpose());
1287
1288 invokeCallbackWithPosVelAtt(*posVelAtt);
1289}
1290
1291// ###########################################################################################################
1292// Kalman Filter
1293// ###########################################################################################################
1294
1295void NAV::LooselyCoupledKF::looselyCoupledPrediction(const std::shared_ptr<const PosVelAtt>& inertialNavSol, double tau_i, const ImuPos& imuPos)
1296{
1297 LOG_DATA("{}: [{}] Predicting", nameId(), inertialNavSol->insTime.toYMDHMS(GPST));
1298
1299 // ------------------------------------------- GUI Parameters ----------------------------------------------
1300
1301 // 𝜎_ra Standard deviation of the noise on the accelerometer specific-force state [m / (s^2 · √(s))]
1302 Eigen::Vector3d sigma_ra = convertUnit(_stdev_ra, _stdevAccelNoiseUnits);
1303 LOG_DATA("{}: sigma_ra = {} [m / (s^2 · √(s))]", nameId(), sigma_ra.transpose());
1304
1305 // 𝜎_rg Standard deviation of the noise on the gyro angular-rate state [rad / (s · √(s))]
1306 Eigen::Vector3d sigma_rg = convertUnit(_stdev_rg, _stdevGyroNoiseUnits);
1307 LOG_DATA("{}: sigma_rg = {} [rad / (s · √(s))]", nameId(), sigma_rg.transpose());
1308
1309 // 𝜎_bad Standard deviation of the accelerometer dynamic bias [m / s^2]
1310 Eigen::Vector3d sigma_bad = convertUnit(_stdev_bad, _stdevAccelBiasUnits);
1311 LOG_DATA("{}: sigma_bad = {} [m / s^2]", nameId(), sigma_bad.transpose());
1312
1313 // 𝜎_bgd Standard deviation of the gyro dynamic bias [rad / s]
1314 Eigen::Vector3d sigma_bgd = convertUnit(_stdev_bgd, _stdevGyroBiasUnits);
1315 LOG_DATA("{}: sigma_bgd = {} [rad / s]", nameId(), sigma_bgd.transpose());
1316
1317 // Standard deviation of the barometric height bias [m]
1318 double sigma_heightBias{};
1320 {
1321 case StdevBaroHeightBiasUnits::m: // [m]
1322 sigma_heightBias = _stdevBaroHeightBias;
1323 break;
1324 }
1325 LOG_DATA("{}: sigma_heightBias = {} [m]", nameId(), sigma_heightBias);
1326
1327 // Standard deviation of the barometric height scale [m/m]
1328 double sigma_heightScale{};
1330 {
1331 case StdevBaroHeightScaleUnits::m_m: // [m/m]
1332 sigma_heightScale = _stdevBaroHeightScale;
1333 break;
1334 }
1335
1336 // ---------------------------------------------- Prediction -------------------------------------------------
1337
1338 // Latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad, m] at the time tₖ₋₁
1339 const Eigen::Vector3d& lla_position = inertialNavSol->lla_position();
1340 LOG_DATA("{}: lla_position = {} [rad, rad, m]", nameId(), lla_position.transpose());
1341 // Prime vertical radius of curvature (East/West) [m]
1342 double R_E = calcEarthRadius_E(lla_position(0));
1343 LOG_DATA("{}: R_E = {} [m]", nameId(), R_E);
1344 // Geocentric Radius in [m]
1345 double r_eS_e = calcGeocentricRadius(lla_position(0), R_E);
1346 LOG_DATA("{}: r_eS_e = {} [m]", nameId(), r_eS_e);
1347
1348 auto p_acceleration = _inertialIntegrator.p_calcCurrentAcceleration();
1349 // Acceleration in [m/s^2], in body coordinates
1350 Eigen::Vector3d b_acceleration = p_acceleration
1351 ? imuPos.b_quat_p() * p_acceleration.value()
1352 : Eigen::Vector3d::Zero();
1353 LOG_DATA("{}: b_acceleration = {} [m/s^2]", nameId(), b_acceleration.transpose());
1354
1356 {
1357 // n_velocity (tₖ₋₁) Velocity in [m/s], in navigation coordinates, at the time tₖ₋₁
1358 const Eigen::Vector3d& n_velocity = inertialNavSol->n_velocity();
1359 LOG_DATA("{}: n_velocity = {} [m / s]", nameId(), n_velocity.transpose());
1360 // q (tₖ₋₁) Quaternion, from body to navigation coordinates, at the time tₖ₋₁
1361 const Eigen::Quaterniond& n_Quat_b = inertialNavSol->n_Quat_b();
1362 LOG_DATA("{}: n_Quat_b --> Roll, Pitch, Yaw = {} [deg]", nameId(), deg2rad(trafo::quat2eulerZYX(n_Quat_b).transpose()));
1363
1364 // Meridian radius of curvature in [m]
1365 double R_N = calcEarthRadius_N(lla_position(0));
1366 LOG_DATA("{}: R_N = {} [m]", nameId(), R_N);
1367
1368 // Conversion matrix between cartesian and curvilinear perturbations to the position
1369 Eigen::Matrix3d T_rn_p = conversionMatrixCartesianCurvilinear(lla_position, R_N, R_E);
1370 LOG_DATA("{}: T_rn_p =\n{}", nameId(), T_rn_p);
1371
1372 // Gravitation at surface level in [m/s^2]
1373 double g_0 = n_calcGravitation_EGM96(lla_position).norm();
1374
1375 // omega_in^n = omega_ie^n + omega_en^n
1376 Eigen::Vector3d n_omega_in = inertialNavSol->n_Quat_e() * InsConst::e_omega_ie
1377 + n_calcTransportRate(lla_position, n_velocity, R_N, R_E);
1378 LOG_DATA("{}: n_omega_in = {} [rad/s]", nameId(), n_omega_in.transpose());
1379
1380 // System Matrix
1381 _kalmanFilter.F = n_systemMatrix_F(n_Quat_b, b_acceleration, n_omega_in, n_velocity, lla_position, R_N, R_E, g_0, r_eS_e, _tau_bad, _tau_bgd);
1382 LOG_DATA("{}: F =\n{}", nameId(), _kalmanFilter.F);
1384 {
1385 // 2. Calculate the system noise covariance matrix Q_{k-1}
1386 _kalmanFilter.Q = n_systemNoiseCovarianceMatrix_Q(sigma_ra.array().square(), sigma_rg.array().square(),
1387 sigma_bad.array().square(), sigma_bgd.array().square(),
1388 sigma_heightBias, sigma_heightScale,
1390 _kalmanFilter.F.block<3>(KFVel, KFAtt), T_rn_p,
1391 n_Quat_b.toRotationMatrix(), tau_i);
1392 }
1393 }
1394 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1395 {
1396 // e_position (tₖ₋₁) Position in [m/s], in ECEF coordinates, at the time tₖ₋₁
1397 const Eigen::Vector3d& e_position = inertialNavSol->e_position();
1398 LOG_DATA("{}: e_position = {} [m]", nameId(), e_position.transpose());
1399 // q (tₖ₋₁) Quaternion, from body to Earth coordinates, at the time tₖ₋₁
1400 const Eigen::Quaterniond& e_Quat_b = inertialNavSol->e_Quat_b();
1401 LOG_DATA("{}: e_Quat_b = {}", nameId(), e_Quat_b);
1402
1403 // Gravitation in [m/s^2] in ECEF coordinates
1404 Eigen::Vector3d e_gravitation = trafo::e_Quat_n(lla_position(0), lla_position(1)) * n_calcGravitation_EGM96(lla_position);
1405
1406 // System Matrix
1407 _kalmanFilter.F = e_systemMatrix_F(e_Quat_b, b_acceleration, e_position, e_gravitation, r_eS_e, InsConst::e_omega_ie, _tau_bad, _tau_bgd);
1408 LOG_DATA("{}: F =\n{}", nameId(), _kalmanFilter.F);
1410 {
1411 // 2. Calculate the system noise covariance matrix Q_{k-1}
1412 _kalmanFilter.Q = e_systemNoiseCovarianceMatrix_Q(sigma_ra.array().square(), sigma_rg.array().square(),
1413 sigma_bad.array().square(), sigma_bgd.array().square(),
1414 sigma_heightBias, sigma_heightScale,
1416 _kalmanFilter.F.block<3>(KFVel, KFAtt),
1417 e_Quat_b.toRotationMatrix(), tau_i);
1418 }
1419 }
1421 {
1422 // Noise Input Matrix
1424 ? inertialNavSol->n_Quat_b()
1425 : inertialNavSol->e_Quat_b());
1426 LOG_DATA("{}: G =\n{}", nameId(), _kalmanFilter.G);
1427
1428 _kalmanFilter.W(all, all) = noiseScaleMatrix_W(sigma_ra, sigma_rg,
1429 sigma_bad, sigma_bgd,
1431 sigma_heightBias, sigma_heightScale);
1432 LOG_DATA("{}: W =\n{}", nameId(), _kalmanFilter.W(all, all));
1433 LOG_DATA("{}: G*W*G^T =\n{}", nameId(), _kalmanFilter.G(all, all) * _kalmanFilter.W(all, all) * _kalmanFilter.G(all, all).transpose());
1434
1435 // 1. Calculate the transition matrix 𝚽_{k-1}
1436 // 2. Calculate the system noise covariance matrix Q_{k-1}
1437 _kalmanFilter.calcPhiAndQWithVanLoanMethod(tau_i);
1438 }
1439 // If Q was calculated over Van Loan, then the Phi matrix was automatically calculated with the exponential matrix
1441 {
1442 auto calcPhi = [&]() {
1444 {
1445 // 1. Calculate the transition matrix 𝚽_{k-1}
1446 _kalmanFilter.calcTransitionMatrix_Phi_exp(tau_i);
1447 }
1449 {
1450 // 1. Calculate the transition matrix 𝚽_{k-1}
1451 _kalmanFilter.calcTransitionMatrix_Phi_Taylor(tau_i, static_cast<size_t>(_phiCalculationTaylorOrder));
1452 }
1453 else
1454 {
1455 LOG_CRITICAL("{}: Calculation algorithm '{}' for the system matrix Phi is not supported.", nameId(), fmt::underlying(_phiCalculationAlgorithm));
1456 }
1457 };
1458 calcPhi();
1459 }
1460 LOG_DATA("{}: KF.Phi =\n{}", nameId(), _kalmanFilter.Phi);
1461 LOG_DATA("{}: KF.Q =\n{}", nameId(), _kalmanFilter.Q);
1462
1463 LOG_DATA("{}: Q - Q^T =\n{}", nameId(), _kalmanFilter.Q(all, all) - _kalmanFilter.Q(all, all).transpose());
1464 LOG_DATA("{}: KF.P (before prediction) =\n{}", nameId(), _kalmanFilter.P);
1465
1466 // 3. Propagate the state vector estimate from x(+) and x(-)
1467 // 4. Propagate the error covariance matrix from P(+) and P(-)
1468 _kalmanFilter.predict();
1469
1470 LOG_DATA("{}: KF.x = {}", nameId(), _kalmanFilter.x.transposed());
1471 LOG_DATA("{}: KF.P (after prediction) =\n{}", nameId(), _kalmanFilter.P);
1472
1473 // Averaging of P to avoid numerical problems with symmetry (did not work)
1474 // _kalmanFilter.P = ((_kalmanFilter.P + _kalmanFilter.P.transpose()) / 2.0);
1475
1476 // LOG_DEBUG("{}: F\n{}\n", nameId(), F);
1477 // LOG_DEBUG("{}: Phi\n{}\n", nameId(), _kalmanFilter.Phi);
1478
1479 // LOG_DEBUG("{}: Q\n{}\n", nameId(), _kalmanFilter.Q);
1480 // LOG_DEBUG("{}: Q - Q^T\n{}\n", nameId(), _kalmanFilter.Q - _kalmanFilter.Q.transpose());
1481
1482 // LOG_DEBUG("{}: x\n{}\n", nameId(), _kalmanFilter.x);
1483
1484 // LOG_DEBUG("{}: P\n{}\n", nameId(), _kalmanFilter.P);
1485 // LOG_DEBUG("{}: P - P^T\n{}\n", nameId(), _kalmanFilter.P - _kalmanFilter.P.transpose());
1486
1488 {
1489 Eigen::FullPivLU<Eigen::MatrixXd> lu(_kalmanFilter.P(all, all));
1490 auto rank = lu.rank();
1491 if (rank != _kalmanFilter.P(all, all).rows())
1492 {
1493 LOG_WARN("{}: [{}] P.rank = {}", nameId(), inertialNavSol->insTime.toYMDHMS(GPST), rank);
1494 }
1495 }
1496}
1497
1498void NAV::LooselyCoupledKF::looselyCoupledUpdate(const std::shared_ptr<const PosVel>& posVelObs)
1499{
1500 INS_ASSERT_USER_ERROR(_inertialIntegrator.getLatestState().has_value(), "The update should not even trigger without an initial state.");
1501
1502 LOG_DATA("{}: [{}] Updating (lastInertial at [{}])", nameId(), posVelObs->insTime.toYMDHMS(GPST),
1503 _inertialIntegrator.getLatestState().value().get().epoch.toYMDHMS(GPST));
1504
1505 // -------------------------------------------- GUI Parameters -----------------------------------------------
1506
1507 // Latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad, m] at the time tₖ₋₁
1508 Eigen::Vector3d lla_position;
1510 {
1511 lla_position = _inertialIntegrator.getLatestState().value().get().position;
1512 }
1513 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1514 {
1515 lla_position = trafo::lla2ecef_WGS84(_inertialIntegrator.getLatestState().value().get().position);
1516 }
1517 LOG_DATA("{}: lla_position = {} [rad, rad, m]", nameId(), lla_position.transpose());
1518
1519 // ---------------------------------------------- Correction -------------------------------------------------
1520
1521 auto p_omega_ip = _inertialIntegrator.p_calcCurrentAngularRate();
1522 // Angular rate measured in units of [rad/s], and given in the body frame
1523 Eigen::Vector3d b_omega_ip = p_omega_ip
1524 ? _lastImuObs->imuPos.b_quat_p() * p_omega_ip.value()
1525 : Eigen::Vector3d::Zero();
1526 LOG_DATA("{}: b_omega_ip = {} [rad/s]", nameId(), b_omega_ip.transpose());
1527
1528 _kalmanFilter.setMeasurements(Meas);
1529
1530 // Prime vertical radius of curvature (East/West) [m]
1531 double R_E = 0.0;
1532 // Meridian radius of curvature in [m]
1533 double R_N = 0.0;
1534
1535 Eigen::Vector3d b_leverArm_InsGnss = _lastImuObs->imuPos.b_positionIMU_p();
1536
1538 {
1539 R_E = calcEarthRadius_E(lla_position(0));
1540 LOG_DATA("{}: R_E = {} [m]", nameId(), R_E);
1541 R_N = calcEarthRadius_N(lla_position(0));
1542 LOG_DATA("{}: R_N = {} [m]", nameId(), R_N);
1543
1544 // Direction Cosine Matrix from body to navigation coordinates, at the time tₖ₋₁
1545 Eigen::Matrix3d n_Dcm_b = _inertialIntegrator.getLatestState().value().get().attitude.toRotationMatrix();
1546 LOG_DATA("{}: n_Dcm_b =\n{}", nameId(), n_Dcm_b);
1547
1548 // Conversion matrix between cartesian and curvilinear perturbations to the position
1549 Eigen::Matrix3d T_rn_p = conversionMatrixCartesianCurvilinear(lla_position, R_N, R_E);
1550 LOG_DATA("{}: T_rn_p =\n{}", nameId(), T_rn_p);
1551
1552 // Skew-symmetric matrix of the Earth-rotation vector in local navigation frame axes
1553 Eigen::Matrix3d n_Omega_ie = math::skewSymmetricMatrix(_inertialIntegrator.getLatestState().value().get().attitude * InsConst::e_omega_ie);
1554 LOG_DATA("{}: n_Omega_ie =\n{}", nameId(), n_Omega_ie);
1555
1556 // 5. Calculate the measurement matrix H_k
1557 _kalmanFilter.H = n_measurementMatrix_H(T_rn_p, n_Dcm_b, b_omega_ip, b_leverArm_InsGnss, n_Omega_ie);
1558
1559 // 6. Calculate the measurement noise covariance matrix R_k
1560 _kalmanFilter.R = n_measurementNoiseCovariance_R(posVelObs, lla_position, R_N, R_E);
1561
1562 // 8. Formulate the measurement z_k
1563 _kalmanFilter.z = n_measurementInnovation_dz(posVelObs->lla_position(), _inertialIntegrator.getLatestState().value().get().position,
1564 posVelObs->n_velocity(), _inertialIntegrator.getLatestState().value().get().velocity,
1565 T_rn_p, _inertialIntegrator.getLatestState().value().get().attitude, b_leverArm_InsGnss, b_omega_ip, n_Omega_ie);
1566 }
1567 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1568 {
1569 // Direction Cosine Matrix from body to navigation coordinates, at the time tₖ₋₁
1570 Eigen::Matrix3d e_Dcm_b = _inertialIntegrator.getLatestState().value().get().attitude.toRotationMatrix();
1571 LOG_DATA("{}: e_Dcm_b =\n{}", nameId(), e_Dcm_b);
1572
1573 // Skew-symmetric matrix of the Earth-rotation vector in local navigation frame axes
1574 Eigen::Matrix3d e_Omega_ie = math::skewSymmetricMatrix(InsConst::e_omega_ie);
1575 LOG_DATA("{}: e_Omega_ie =\n{}", nameId(), e_Omega_ie);
1576
1577 // 5. Calculate the measurement matrix H_k
1578 _kalmanFilter.H = e_measurementMatrix_H(e_Dcm_b, b_omega_ip, b_leverArm_InsGnss, e_Omega_ie);
1579
1580 // 6. Calculate the measurement noise covariance matrix R_k
1582
1583 // 8. Formulate the measurement z_k
1584 _kalmanFilter.z = e_measurementInnovation_dz(posVelObs->e_position(), _inertialIntegrator.getLatestState().value().get().position,
1585 posVelObs->e_velocity(), _inertialIntegrator.getLatestState().value().get().velocity,
1586 _inertialIntegrator.getLatestState().value().get().attitude, b_leverArm_InsGnss, b_omega_ip, e_Omega_ie);
1587 }
1588
1589 LOG_DATA("{}: KF.H =\n{}", nameId(), _kalmanFilter.H);
1590 LOG_DATA("{}: KF.R =\n{}", nameId(), _kalmanFilter.R);
1591 LOG_DATA("{}: KF.z =\n{}", nameId(), _kalmanFilter.z);
1592
1594 {
1595 Eigen::FullPivLU<Eigen::MatrixXd> lu(_kalmanFilter.H(all, all) * _kalmanFilter.P(all, all) * _kalmanFilter.H(all, all).transpose() + _kalmanFilter.R(all, all));
1596 auto rank = lu.rank();
1597 if (rank != _kalmanFilter.H(all, all).rows())
1598 {
1599 LOG_WARN("{}: [{}] (HPH^T + R).rank = {}", nameId(), posVelObs->insTime.toYMDHMS(GPST), rank);
1600 }
1601 }
1602
1603 // 7. Calculate the Kalman gain matrix K_k
1604 // 9. Update the state vector estimate from x(-) to x(+)
1605 // 10. Update the error covariance matrix from P(-) to P(+)
1606 _kalmanFilter.correctWithMeasurementInnovation();
1607
1608 LOG_DATA("{}: KF.K =\n{}", nameId(), _kalmanFilter.K);
1609 LOG_DATA("{}: KF.x =\n{}", nameId(), _kalmanFilter.x);
1610 LOG_DATA("{}: KF.P =\n{}", nameId(), _kalmanFilter.P);
1611
1612 // Averaging of P to avoid numerical problems with symmetry (did not work)
1613 // _kalmanFilter.P = ((_kalmanFilter.P + _kalmanFilter.P.transpose()) / 2.0);
1614
1616 {
1617 Eigen::FullPivLU<Eigen::MatrixXd> lu(_kalmanFilter.H(all, all) * _kalmanFilter.P(all, all) * _kalmanFilter.H(all, all).transpose() + _kalmanFilter.R(all, all));
1618 auto rank = lu.rank();
1619 if (rank != _kalmanFilter.H(all, all).rows())
1620 {
1621 LOG_WARN("{}: [{}] (HPH^T + R).rank = {}", nameId(), posVelObs->insTime.toYMDHMS(GPST), rank);
1622 }
1623
1624 Eigen::FullPivLU<Eigen::MatrixXd> luP(_kalmanFilter.P(all, all));
1625 rank = luP.rank();
1626 if (rank != _kalmanFilter.P(all, all).rows())
1627 {
1628 LOG_WARN("{}: [{}] P.rank = {}", nameId(), posVelObs->insTime.toYMDHMS(GPST), rank);
1629 }
1630 }
1631
1632 // LOG_DEBUG("{}: H\n{}\n", nameId(), _kalmanFilter.H);
1633 // LOG_DEBUG("{}: R\n{}\n", nameId(), _kalmanFilter.R);
1634 // LOG_DEBUG("{}: z =\n{}", nameId(), _kalmanFilter.z.transposed());
1635
1636 // LOG_DEBUG("{}: K\n{}\n", nameId(), _kalmanFilter.K);
1637 // LOG_DEBUG("{}: x =\n{}", nameId(), _kalmanFilter.x.transposed());
1638 // LOG_DEBUG("{}: P\n{}\n", nameId(), _kalmanFilter.P);
1639
1640 // LOG_DEBUG("{}: K * z =\n{}", nameId(), (_kalmanFilter.K(all, all) * _kalmanFilter.z(all)).transpose());
1641
1642 // LOG_DEBUG("{}: P - P^T\n{}\n", nameId(), _kalmanFilter.P(all, all) - _kalmanFilter.P(all, all).transpose());
1643
1644 // Push out the new data
1645 auto lckfSolution = std::make_shared<InsGnssLCKFSolution>();
1646 lckfSolution->insTime = posVelObs->insTime;
1647 lckfSolution->positionError = _kalmanFilter.x.segment<3>(KFPos);
1648 lckfSolution->velocityError = _kalmanFilter.x.segment<3>(KFVel);
1649 lckfSolution->attitudeError = _kalmanFilter.x.segment<3>(KFAtt) * (1. / SCALE_FACTOR_ATTITUDE);
1650
1651 LOG_DATA("{}: Accumulated biases before error has been applied: b_biasAccel.value = {}, b_biasGyro.value = {}", nameId(), _inertialIntegrator.p_getLastAccelerationBias().transpose(), _inertialIntegrator.p_getLastAngularRateBias().transpose());
1652
1653 _inertialIntegrator.applySensorBiasesIncrements(_lastImuObs->imuPos.p_quat_b() * -_kalmanFilter.x.segment<3>(KFAccBias) * (1. / SCALE_FACTOR_ACCELERATION),
1654 _lastImuObs->imuPos.p_quat_b() * -_kalmanFilter.x.segment<3>(KFGyrBias) * (1. / SCALE_FACTOR_ANGULAR_RATE));
1655 lckfSolution->b_biasAccel.value = -_inertialIntegrator.p_getLastAccelerationBias();
1656 lckfSolution->b_biasAccel.stdDev = Eigen::Vector3d{
1660 };
1661 lckfSolution->b_biasGyro.value = -_inertialIntegrator.p_getLastAngularRateBias();
1662 lckfSolution->b_biasGyro.stdDev = Eigen::Vector3d{
1666 };
1667
1668 LOG_DATA("{}: Biases after error has been applied: b_biasAccel.value = {}, b_biasGyro.value = {}", nameId(), lckfSolution->b_biasAccel.value.transpose(), lckfSolution->b_biasGyro.value.transpose());
1669
1671 {
1672 lckfSolution->positionError.topRows<2>() *= 1.0 / SCALE_FACTOR_LAT_LON;
1673 lckfSolution->frame = InsGnssLCKFSolution::Frame::NED;
1674 _inertialIntegrator.applyStateErrors_n(lckfSolution->positionError,
1675 lckfSolution->velocityError,
1676 lckfSolution->attitudeError);
1677 }
1678 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1679 {
1680 lckfSolution->frame = InsGnssLCKFSolution::Frame::ECEF;
1681 _inertialIntegrator.applyStateErrors_e(lckfSolution->positionError,
1682 lckfSolution->velocityError,
1683 lckfSolution->attitudeError);
1684 }
1685
1686 setSolutionPosVelAttAndCov(lckfSolution, R_N, R_E);
1687
1688 lckfSolution->heightBias = { .value = _heightBiasTotal, .stdDev = std::sqrt(_kalmanFilter.P(KFStates::HeightBias, KFStates::HeightBias)) };
1689 lckfSolution->heightScale = { .value = _heightScaleTotal, .stdDev = std::sqrt(_kalmanFilter.P(KFStates::HeightScale, KFStates::HeightScale)) };
1690
1691 // Closed loop
1692 _kalmanFilter.x(all).setZero();
1693
1694 LOG_DATA("{}: [{}] Sending out updated solution", nameId(), lckfSolution->insTime.toYMDHMS(GPST));
1695 if (!hasInputPinWithSameTime(lckfSolution->insTime))
1696 {
1698 }
1699}
1700
1701void NAV::LooselyCoupledKF::looselyCoupledUpdate(const std::shared_ptr<const BaroHgt>& baroHgtObs)
1702{
1703 INS_ASSERT_USER_ERROR(_inertialIntegrator.getLatestState().has_value(), "The update should not even trigger without an initial state.");
1704
1705 LOG_DATA("{}: [{}] Updating (lastInertial at [{}])", nameId(), baroHgtObs->insTime.toYMDHMS(GPST), _inertialIntegrator.getLatestState().value().get().epoch.toYMDHMS(GPST));
1706
1707 // -------------------------------------------- GUI Parameters -----------------------------------------------
1708
1709 // Latitude 𝜙, longitude λ and altitude (height above ground) in [rad, rad, m] at the time tₖ₋₁
1710 Eigen::Vector3d lla_position;
1712 {
1713 lla_position = _inertialIntegrator.getLatestState().value().get().position;
1714 }
1715 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1716 {
1717 lla_position = trafo::lla2ecef_WGS84(_inertialIntegrator.getLatestState().value().get().position);
1718 }
1719 LOG_DATA("{}: lla_position = {} [rad, rad, m]", nameId(), lla_position.transpose());
1720
1721 // Baro height measurement uncertainty (Variance σ²) in [m^2]
1722 double baroHeightSigmaSquared{};
1723 if (_baroHeightMeasurementUncertaintyOverride || !baroHgtObs->baro_heightStdev.has_value())
1724 {
1726 {
1728 baroHeightSigmaSquared = std::pow(_barometricHeightMeasurementUncertainty, 2);
1729 break;
1731 baroHeightSigmaSquared = _barometricHeightMeasurementUncertainty;
1732 break;
1733 }
1734 }
1735 else
1736 {
1737 baroHeightSigmaSquared = std::pow(baroHgtObs->baro_heightStdev.value(), 2);
1738 }
1739 LOG_DATA("{}: baroHeightSigmaSquared = {} [m^2]", nameId(), baroHeightSigmaSquared);
1740
1741 // ---------------------------------------------- Correction -------------------------------------------------
1742 _kalmanFilter.setMeasurements(std::array{ KFMeas::dHgt });
1743
1744 // 5. Calculate the measurement matrix H_k
1746 {
1748 }
1749 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1750 {
1751 _kalmanFilter.H = e_measurementMatrix_H(_inertialIntegrator.getLatestState().value().get().position, lla_position(2), _heightScaleTotal);
1752 }
1753
1754 // 6. Calculate the measurement noise covariance matrix R_k (here we can use the n-Frame covariance matrix! )
1755 _kalmanFilter.R = n_measurementNoiseCovariance_R(baroHeightSigmaSquared);
1756
1757 // 8. Formulate the measurement z_k
1758 _kalmanFilter.z = n_measurementInnovation_dz(baroHgtObs->baro_height, lla_position(2), _heightBiasTotal, _heightScaleTotal);
1759
1760 LOG_DATA("{}: KF.H =\n{}", nameId(), _kalmanFilter.H);
1761 LOG_DATA("{}: KF.R =\n{}", nameId(), _kalmanFilter.R);
1762 LOG_DATA("{}: KF.z =\n{}", nameId(), _kalmanFilter.z);
1763
1765 {
1766 Eigen::FullPivLU<Eigen::MatrixXd> lu(_kalmanFilter.H(all, all) * _kalmanFilter.P(all, all) * _kalmanFilter.H(all, all).transpose() + _kalmanFilter.R(all, all));
1767 auto rank = lu.rank();
1768 if (rank != _kalmanFilter.H(all, all).rows())
1769 {
1770 LOG_WARN("{}: [{}] (HPH^T + R).rank = {}", nameId(), baroHgtObs->insTime.toYMDHMS(GPST), rank);
1771 }
1772 }
1773
1774 // 7. Calculate the Kalman gain matrix K_k
1775 // 9. Update the state vector estimate from x(-) to x(+)
1776 // 10. Update the error covariance matrix from P(-) to P(+
1777 _kalmanFilter.correctWithMeasurementInnovation();
1778
1779 LOG_DATA("{}: KF.K =\n{}", nameId(), _kalmanFilter.K);
1780 LOG_DATA("{}: KF.x =\n{}", nameId(), _kalmanFilter.x);
1781 LOG_DATA("{}: KF.P =\n{}", nameId(), _kalmanFilter.P);
1782
1783 // Averaging of P to avoid numerical problems with symmetry (did not work)
1784 // _kalmanFilter.P = ((_kalmanFilter.P + _kalmanFilter.P.transpose()) / 2.0);
1785
1787 {
1788 Eigen::FullPivLU<Eigen::MatrixXd> lu(_kalmanFilter.H(all, all) * _kalmanFilter.P(all, all) * _kalmanFilter.H(all, all).transpose() + _kalmanFilter.R(all, all));
1789 auto rank = lu.rank();
1790 if (rank != _kalmanFilter.H(all, all).rows())
1791 {
1792 LOG_WARN("{}: [{}] (HPH^T + R).rank = {}", nameId(), baroHgtObs->insTime.toYMDHMS(GPST), rank);
1793 }
1794
1795 Eigen::FullPivLU<Eigen::MatrixXd> luP(_kalmanFilter.P(all, all));
1796 rank = luP.rank();
1797 if (rank != _kalmanFilter.P(all, all).rows())
1798 {
1799 LOG_WARN("{}: [{}] P.rank = {}", nameId(), baroHgtObs->insTime.toYMDHMS(GPST), rank);
1800 }
1801 }
1802
1803 // LOG_DEBUG("{}: H\n{}\n", nameId(), _kalmanFilter.H);
1804 // LOG_DEBUG("{}: R\n{}\n", nameId(), _kalmanFilter.R);
1805 // LOG_DEBUG("{}: z =\n{}", nameId(), _kalmanFilter.z.transposed());
1806
1807 // LOG_DEBUG("{}: K\n{}\n", nameId(), _kalmanFilter.K);
1808 // LOG_DEBUG("{}: x =\n{}", nameId(), _kalmanFilter.x.transposed());
1809 // LOG_DEBUG("{}: P\n{}\n", nameId(), _kalmanFilter.P);
1810
1811 // LOG_DEBUG("{}: K * z =\n{}", nameId(), (_kalmanFilter.K(all, all) * _kalmanFilter.z(all)).transpose());
1812
1813 // LOG_DEBUG("{}: P - P^T\n{}\n", nameId(), _kalmanFilter.P(all, all) - _kalmanFilter.P(all, all).transpose());
1814
1815 // Push out the new data
1816 auto lckfSolution = std::make_shared<InsGnssLCKFSolution>();
1817 lckfSolution->insTime = baroHgtObs->insTime;
1818 lckfSolution->positionError = _kalmanFilter.x.segment<3>(KFPos);
1819 lckfSolution->velocityError = _kalmanFilter.x.segment<3>(KFVel);
1820 lckfSolution->attitudeError = _kalmanFilter.x.segment<3>(KFAtt) * (1. / SCALE_FACTOR_ATTITUDE);
1821
1822 LOG_DATA("{}: Accumulated biases before error has been applied: b_biasAccel.value = {}, b_biasGyro.value = {}", nameId(), _inertialIntegrator.p_getLastAccelerationBias().transpose(), _inertialIntegrator.p_getLastAngularRateBias().transpose());
1823
1824 _inertialIntegrator.applySensorBiasesIncrements(_lastImuObs->imuPos.p_quat_b() * -_kalmanFilter.x.segment<3>(KFAccBias) * (1. / SCALE_FACTOR_ACCELERATION),
1825 _lastImuObs->imuPos.p_quat_b() * -_kalmanFilter.x.segment<3>(KFGyrBias) * (1. / SCALE_FACTOR_ANGULAR_RATE));
1826 lckfSolution->b_biasAccel.value = -_inertialIntegrator.p_getLastAccelerationBias();
1827 lckfSolution->b_biasAccel.stdDev = Eigen::Vector3d{
1831 };
1832 lckfSolution->b_biasGyro.value = -_inertialIntegrator.p_getLastAngularRateBias();
1833 lckfSolution->b_biasGyro.stdDev = Eigen::Vector3d{
1837 };
1838
1839 LOG_DATA("{}: Biases after error has been applied: b_biasAccel.value = {}, b_biasGyro.value = {}", nameId(), lckfSolution->b_biasAccel.value.transpose(), lckfSolution->b_biasGyro.value.transpose());
1840
1842 {
1843 lckfSolution->positionError.topRows<2>() *= 1.0 / SCALE_FACTOR_LAT_LON;
1844 lckfSolution->frame = InsGnssLCKFSolution::Frame::NED;
1845 _inertialIntegrator.applyStateErrors_n(lckfSolution->positionError,
1846 lckfSolution->velocityError,
1847 lckfSolution->attitudeError);
1848 }
1849 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1850 {
1851 lckfSolution->frame = InsGnssLCKFSolution::Frame::ECEF;
1852 _inertialIntegrator.applyStateErrors_e(lckfSolution->positionError,
1853 lckfSolution->velocityError,
1854 lckfSolution->attitudeError);
1855 }
1856
1857 setSolutionPosVelAttAndCov(lckfSolution, calcEarthRadius_N(lla_position.x()), calcEarthRadius_E(lla_position.x()));
1858
1859 // Closed loop
1862 lckfSolution->heightBias = { .value = _heightBiasTotal, .stdDev = std::sqrt(_kalmanFilter.P(KFStates::HeightBias, KFStates::HeightBias)) };
1863 lckfSolution->heightScale = { .value = _heightScaleTotal, .stdDev = std::sqrt(_kalmanFilter.P(KFStates::HeightScale, KFStates::HeightScale)) };
1864 _kalmanFilter.x(all).setZero();
1865
1866 LOG_DATA("{}: [{}] Sending out updated solution", nameId(), lckfSolution->insTime.toYMDHMS(GPST));
1867 if (!hasInputPinWithSameTime(lckfSolution->insTime))
1868 {
1870 }
1871}
1872
1873void NAV::LooselyCoupledKF::setSolutionPosVelAttAndCov(const std::shared_ptr<PosVelAtt>& lckfSolution, double R_N, double R_E)
1874{
1875 Eigen::Matrix<double, 10, 9> J = Eigen::Matrix<double, 10, 9>::Zero();
1876 J.topLeftCorner<6, 6>().setIdentity();
1877
1878 Eigen::Matrix9d J_units = Eigen::Matrix9d::Identity();
1879 J_units.bottomRightCorner<3, 3>().diagonal().setConstant(std::numbers::pi_v<double> / 180.0);
1881 {
1882 const Eigen::Vector3d& lla_position = _inertialIntegrator.getLatestState().value().get().position;
1883
1884 J.bottomRightCorner<4, 3>() = trafo::covRPY2quatJacobian(_inertialIntegrator.getLatestState().value().get().attitude);
1885 J_units.topLeftCorner<3, 3>().diagonal() = 1.0
1886 / n_F_dr_dv(lla_position.x(),
1887 lla_position.z(),
1888 R_N,
1889 R_E)
1890 .diagonal()
1891 .array();
1892
1893 J_units.topLeftCorner<2, 2>().diagonal() *= 1.0 / SCALE_FACTOR_LAT_LON;
1894
1895 lckfSolution->setPosVelAttAndCov_n(lla_position,
1896 _inertialIntegrator.getLatestState().value().get().velocity,
1897 _inertialIntegrator.getLatestState().value().get().attitude,
1898 J * (J_units * _kalmanFilter.P(KFPosVelAtt, KFPosVelAtt) * J_units.transpose()) * J.transpose());
1899 }
1900 else // if (_inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::ECEF)
1901 {
1902 J.bottomRightCorner<4, 3>() = trafo::covRPY2quatJacobian(_inertialIntegrator.getLatestState().value().get().attitude);
1903
1904 lckfSolution->setPosVelAttAndCov_e(_inertialIntegrator.getLatestState().value().get().position,
1905 _inertialIntegrator.getLatestState().value().get().velocity,
1906 _inertialIntegrator.getLatestState().value().get().attitude,
1907 J * (J_units * _kalmanFilter.P(KFPosVelAtt, KFPosVelAtt) * J_units.transpose()) * J.transpose());
1908 }
1909}
1910
1911// ###########################################################################################################
1912// System matrix 𝐅
1913// ###########################################################################################################
1914
1916 NAV::LooselyCoupledKF::n_systemMatrix_F(const Eigen::Quaterniond& n_Quat_b,
1917 const Eigen::Vector3d& b_specForce_ib,
1918 const Eigen::Vector3d& n_omega_in,
1919 const Eigen::Vector3d& n_velocity,
1920 const Eigen::Vector3d& lla_position,
1921 double R_N,
1922 double R_E,
1923 double g_0,
1924 double r_eS_e,
1925 const Eigen::Vector3d& tau_bad,
1926 const Eigen::Vector3d& tau_bgd) const
1927{
1928 double latitude = lla_position(0); // Geodetic latitude of the body in [rad]
1929 double altitude = lla_position(2); // Geodetic height of the body in [m]
1930
1931 Eigen::Vector3d beta_bad = 1. / tau_bad.array(); // Gauss-Markov constant for the accelerometer 𝛽 = 1 / 𝜏 (𝜏 correlation length)
1932 Eigen::Vector3d beta_bgd = 1. / tau_bgd.array(); // Gauss-Markov constant for the gyroscope 𝛽 = 1 / 𝜏 (𝜏 correlation length)
1933
1934 // System matrix 𝐅
1935 // Math: \mathbf{F}^n = \begin{pmatrix} \mathbf{F}_{\dot{\psi},\psi}^n & \mathbf{F}_{\dot{\psi},\delta v}^n & \mathbf{F}_{\dot{\psi},\delta r}^n & \mathbf{0}_3 & \mathbf{C}_b^n \\ \mathbf{F}_{\delta \dot{v},\psi}^n & \mathbf{F}_{\delta \dot{v},\delta v}^n & \mathbf{F}_{\delta \dot{v},\delta r}^n & \mathbf{C}_b^n & \mathbf{0}_3 \\ \mathbf{0}_3 & \mathbf{F}_{\delta \dot{r},\delta v}^n & \mathbf{F}_{\delta \dot{r},\delta r}^n & \mathbf{0}_3 & \mathbf{0}_3 \\ \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 \vee -\mathbf{\beta} & \mathbf{0}_3 \\ \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 \vee -\mathbf{\beta} \end{pmatrix}
1937 F(Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), States);
1938
1939 F.block<3>(KFAtt, KFAtt) = n_F_dpsi_dpsi(n_omega_in);
1940 F.block<3>(KFAtt, KFVel) = n_F_dpsi_dv(latitude, altitude, R_N, R_E);
1941 F.block<3>(KFAtt, KFPos) = n_F_dpsi_dr(latitude, altitude, n_velocity, R_N, R_E);
1942 F.block<3>(KFAtt, KFGyrBias) = n_F_dpsi_dw(n_Quat_b.toRotationMatrix());
1943 F.block<3>(KFVel, KFAtt) = n_F_dv_dpsi(n_Quat_b * b_specForce_ib);
1944 F.block<3>(KFVel, KFVel) = n_F_dv_dv(n_velocity, latitude, altitude, R_N, R_E);
1945 F.block<3>(KFVel, KFPos) = n_F_dv_dr(n_velocity, latitude, altitude, R_N, R_E, g_0, r_eS_e);
1946 F.block<3>(KFVel, KFAccBias) = n_F_dv_df(n_Quat_b.toRotationMatrix());
1947 F.block<3>(KFPos, KFVel) = n_F_dr_dv(latitude, altitude, R_N, R_E);
1948 F.block<3>(KFPos, KFPos) = n_F_dr_dr(n_velocity, latitude, altitude, R_N, R_E);
1950 {
1951 F.block<3>(KFAccBias, KFAccBias) = n_F_df_df(_randomProcessAccel == RandomProcess::RandomWalk ? Eigen::Vector3d::Zero() : beta_bad);
1952 F.block<3>(KFGyrBias, KFGyrBias) = n_F_dw_dw(_randomProcessGyro == RandomProcess::RandomWalk ? Eigen::Vector3d::Zero() : beta_bgd);
1953 }
1954
1955 F.middleRows<3>(KFAtt) *= SCALE_FACTOR_ATTITUDE; // 𝜓' [deg / s] = 180/π * ... [rad / s]
1957
1958 // F.middleRows<3>(Vel) *= 1.; // 𝛿v' [m / s^2] = 1 * [m / s^2]
1959 // F.middleCols<3>(Vel) *= 1. / 1.;
1960
1961 F.middleRows<2>(std::array{ PosLat, PosLon }) *= SCALE_FACTOR_LAT_LON; // 𝛿ϕ' [pseudometre / s] = R0 * [rad / s]
1962 F.middleCols<2>(std::array{ PosLat, PosLon }) *= 1. / SCALE_FACTOR_LAT_LON;
1963 // F.row(PosAlt) *= 1.; // 𝛿h' [m / s] = 1 * [m / s]
1964 // F.col(PosAlt) *= 1. / 1.;
1965
1966 F.middleRows<3>(KFAccBias) *= SCALE_FACTOR_ACCELERATION; // 𝛿f' [mg / s] = 1e3 / g * [m / s^3]
1968
1969 F.middleRows<3>(KFGyrBias) *= SCALE_FACTOR_ANGULAR_RATE; // 𝛿ω' [mrad / s^2] = 1e3 * [rad / s^2]
1971
1972 return F;
1973}
1974
1976 NAV::LooselyCoupledKF::e_systemMatrix_F(const Eigen::Quaterniond& e_Quat_b,
1977 const Eigen::Vector3d& b_specForce_ib,
1978 const Eigen::Vector3d& e_position,
1979 const Eigen::Vector3d& e_gravitation,
1980 double r_eS_e,
1981 const Eigen::Vector3d& e_omega_ie,
1982 const Eigen::Vector3d& tau_bad,
1983 const Eigen::Vector3d& tau_bgd) const
1984{
1985 Eigen::Vector3d beta_bad = 1. / tau_bad.array(); // Gauss-Markov constant for the accelerometer 𝛽 = 1 / 𝜏 (𝜏 correlation length)
1986 Eigen::Vector3d beta_bgd = 1. / tau_bgd.array(); // Gauss-Markov constant for the gyroscope 𝛽 = 1 / 𝜏 (𝜏 correlation length)
1987
1988 // System matrix 𝐅
1989 // Math: \mathbf{F}^e = \begin{pmatrix} \mathbf{F}_{\dot{\psi},\psi}^n & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{C}_b^e \\ \mathbf{F}_{\delta \dot{v},\psi}^n & \mathbf{F}_{\delta \dot{v},\delta v}^n & \mathbf{F}_{\delta \dot{v},\delta r}^n & \mathbf{C}_b^e & \mathbf{0}_3 \\ \mathbf{0}_3 & \mathbf{F}_{\delta \dot{r},\delta v}^n & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 \\ \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 \vee -\mathbf{\beta} & \mathbf{0}_3 \\ \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{0}_3 \vee -\mathbf{\beta} \end{pmatrix}
1991 F(Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), States);
1992
1993 F.block<3>(KFAtt, KFAtt) = e_F_dpsi_dpsi(e_omega_ie.z());
1994 F.block<3>(KFAtt, KFGyrBias) = e_F_dpsi_dw(e_Quat_b.toRotationMatrix());
1995 F.block<3>(KFVel, KFAtt) = e_F_dv_dpsi(e_Quat_b * b_specForce_ib);
1996 F.block<3>(KFVel, KFVel) = e_F_dv_dv<double>(e_omega_ie.z());
1997 F.block<3>(KFVel, KFPos) = e_F_dv_dr(e_position, e_gravitation, r_eS_e, e_omega_ie);
1998 F.block<3>(KFVel, KFAccBias) = e_F_dv_df_b(e_Quat_b.toRotationMatrix());
2001 {
2002 F.block<3>(KFAccBias, KFAccBias) = e_F_df_df(_randomProcessAccel == RandomProcess::RandomWalk ? Eigen::Vector3d::Zero() : beta_bad);
2003 F.block<3>(KFGyrBias, KFGyrBias) = e_F_dw_dw(_randomProcessGyro == RandomProcess::RandomWalk ? Eigen::Vector3d::Zero() : beta_bgd);
2004 }
2005
2006 F.middleRows<3>(KFAtt) *= SCALE_FACTOR_ATTITUDE; // 𝜓' [deg / s] = 180/π * ... [rad / s]
2008
2009 // F.middleRows<3>(Vel) *= 1.; // 𝛿v' [m / s^2] = 1 * [m / s^2]
2010 // F.middleCols<3>(Vel) *= 1. / 1.;
2011
2012 // F.middleRows<3>(Pos) *= 1.; // 𝛿r' [m / s] = 1 * [m / s]
2013 // F.middleCols<3>(Pos) *= 1. / 1.;
2014
2015 F.middleRows<3>(KFAccBias) *= SCALE_FACTOR_ACCELERATION; // 𝛿f' [mg / s] = 1e3 / g * [m / s^3]
2017
2018 F.middleRows<3>(KFGyrBias) *= SCALE_FACTOR_ANGULAR_RATE; // 𝛿ω' [mrad / s^2] = 1e3 * [rad / s^2]
2020
2021 return F;
2022}
2023
2024// ###########################################################################################################
2025// Noise input matrix 𝐆 & Noise scale matrix 𝐖
2026// System noise covariance matrix 𝐐
2027// ###########################################################################################################
2028
2030 NAV::LooselyCoupledKF::noiseInputMatrix_G(const Eigen::Quaterniond& ien_Quat_b)
2031{
2032 // DCM matrix from body to navigation frame
2033 Eigen::Matrix3d ien_Dcm_b = ien_Quat_b.toRotationMatrix();
2034
2035 // Math: \mathbf{G}_{a} = \begin{bmatrix} -\mathbf{C}_b^{i,e,n} & 0 & 0 & 0 \\ 0 & \mathbf{C}_b^{i,e,n} & 0 & 0 \\ 0 & 0 & 0 & 0 \\ 0 & 0 & \mathbf{I}_3 & 0 \\ 0 & 0 & 0 & \mathbf{I}_3 \end{bmatrix}
2037 G(Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), States, States);
2038
2039 G.block<3>(KFAtt, KFAtt) = SCALE_FACTOR_ATTITUDE * ien_Dcm_b;
2040 G.block<3>(KFVel, KFVel) = ien_Dcm_b;
2041 G.block<3>(KFAccBias, KFAccBias) = SCALE_FACTOR_ACCELERATION * Eigen::Matrix3d::Identity();
2042 G.block<3>(KFGyrBias, KFGyrBias) = SCALE_FACTOR_ANGULAR_RATE * Eigen::Matrix3d::Identity();
2045 return G;
2046}
2047
2048Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>
2049 NAV::LooselyCoupledKF::noiseScaleMatrix_W(const Eigen::Vector3d& sigma_ra, const Eigen::Vector3d& sigma_rg,
2050 const Eigen::Vector3d& sigma_bad, const Eigen::Vector3d& sigma_bgd,
2051 const Eigen::Vector3d& tau_bad, const Eigen::Vector3d& tau_bgd,
2052 const double& sigma_heightBias, const double& sigma_heightScale)
2053{
2054 Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT> W =
2055 Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero();
2056
2057 W.diagonal() << sigma_rg.array().square(),
2058 sigma_ra.array().square(),
2059 Eigen::Vector3d::Zero(),
2060 _randomProcessAccel == RandomProcess::RandomWalk ? sigma_bad.array().square() : psd2BiasGaussMarkov(sigma_bad.array().square(), tau_bad), // S_bad
2061 _randomProcessGyro == RandomProcess::RandomWalk ? sigma_bgd.array().square() : psd2BiasGaussMarkov(sigma_bgd.array().square(), tau_bgd), // S_bgd
2062 sigma_heightBias * sigma_heightBias,
2063 sigma_heightScale * sigma_heightScale;
2064
2065 return W;
2066}
2067
2069 NAV::LooselyCoupledKF::n_systemNoiseCovarianceMatrix_Q(const Eigen::Vector3d& sigma2_ra, const Eigen::Vector3d& sigma2_rg,
2070 const Eigen::Vector3d& sigma2_bad, const Eigen::Vector3d& sigma2_bgd,
2071 const double& sigma_heightBias, const double& sigma_heightScale,
2072 const Eigen::Vector3d& tau_bad, const Eigen::Vector3d& tau_bgd,
2073 const Eigen::Matrix3d& n_F_21, const Eigen::Matrix3d& T_rn_p,
2074 const Eigen::Matrix3d& n_Dcm_b, const double& tau_s)
2075{
2076 // Math: \mathbf{Q}_{INS}^n = \begin{pmatrix} \mathbf{Q}_{11} & {\mathbf{Q}_{21}^n}^T & {\mathbf{Q}_{31}^n}^T & \mathbf{0}_3 & {\mathbf{Q}_{51}^n}^T \\ \mathbf{Q}_{21}^n & \mathbf{Q}_{22}^n & {\mathbf{Q}_{32}^n}^T & {\mathbf{Q}_{42}^n}^T & \mathbf{Q}_{25}^n \\ \mathbf{Q}_{31}^n & \mathbf{Q}_{32}^n & \mathbf{Q}_{33}^n & \mathbf{Q}_{34}^n & \mathbf{Q}_{35}^n \\ \mathbf{0}_3 & \mathbf{Q}_{42}^n & {\mathbf{Q}_{34}^n}^T & S_{bad}\tau_s\mathbf{I}_3 & \mathbf{0}_3 \\ \mathbf{Q}_{51}^n & \mathbf{Q}_{52}^n & {\mathbf{Q}_{35}^n}^T & \mathbf{0}_3 & S_{bgd}\tau_s\mathbf{I}_3 \end{pmatrix} \qquad \text{P. Groves}\,(14.80)
2077 Eigen::Vector3d S_ra = sigma2_ra * tau_s;
2078 Eigen::Vector3d S_rg = sigma2_rg * tau_s;
2079 Eigen::Vector3d S_bad = sigma2_bad.array() / tau_bad.array();
2080 Eigen::Vector3d S_bgd = sigma2_bgd.array() / tau_bgd.array();
2081
2082 Eigen::Matrix3d b_Dcm_n = n_Dcm_b.transpose();
2083
2085 Q(Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), States, States);
2086 Q.block<3>(KFAtt, KFAtt) = Q_psi_psi(S_rg, S_bgd, tau_s); // Q_11
2087 Q.block<3>(KFVel, KFAtt) = ien_Q_dv_psi(S_rg, S_bgd, n_F_21, tau_s); // Q_21
2088 Q.block<3>(KFVel, KFVel) = ien_Q_dv_dv(S_ra, S_bad, S_rg, S_bgd, n_F_21, tau_s); // Q_22
2089 Q.block<3>(KFVel, KFGyrBias) = ien_Q_dv_domega(S_bgd, n_F_21, n_Dcm_b, tau_s); // Q_25
2090 Q.block<3>(KFPos, KFAtt) = n_Q_dr_psi(S_rg, S_bgd, n_F_21, T_rn_p, tau_s); // Q_31
2091 Q.block<3>(KFPos, KFVel) = n_Q_dr_dv(S_ra, S_bad, S_rg, S_bgd, n_F_21, T_rn_p, tau_s); // Q_32
2092 Q.block<3>(KFPos, KFPos) = n_Q_dr_dr(S_ra, S_bad, S_rg, S_bgd, n_F_21, T_rn_p, tau_s); // Q_33
2093 Q.block<3>(KFPos, KFAccBias) = n_Q_dr_df(S_bgd, T_rn_p, n_Dcm_b, tau_s); // Q_34
2094 Q.block<3>(KFPos, KFGyrBias) = n_Q_dr_domega(S_bgd, n_F_21, T_rn_p, n_Dcm_b, tau_s); // Q_35
2095 Q.block<3>(KFAccBias, KFVel) = Q_df_dv(S_bad, b_Dcm_n, tau_s); // Q_42
2096 Q.block<3>(KFAccBias, KFAccBias) = Q_df_df(S_bad, tau_s); // Q_44
2097 Q.block<3>(KFGyrBias, KFAtt) = Q_domega_psi(S_bgd, b_Dcm_n, tau_s); // Q_51
2098 Q.block<3>(KFGyrBias, KFGyrBias) = Q_domega_domega(S_bgd, tau_s); // Q_55
2099
2100 Q.block<3>(KFAtt, KFVel) = Q.block<3>(KFVel, KFAtt).transpose(); // Q_21^T
2101 Q.block<3>(KFAtt, KFPos) = Q.block<3>(KFPos, KFAtt).transpose(); // Q_31^T
2102 Q.block<3>(KFVel, KFPos) = Q.block<3>(KFPos, KFVel).transpose(); // Q_32^T
2103 Q.block<3>(KFAccBias, KFPos) = Q.block<3>(KFPos, KFAccBias).transpose(); // Q_34^T
2104 Q.block<3>(KFGyrBias, KFVel) = Q.block<3>(KFVel, KFGyrBias).transpose(); // Q_25^T
2105 Q.block<3>(KFGyrBias, KFPos) = Q.block<3>(KFPos, KFGyrBias).transpose(); // Q_35^T
2106 Q.block<3>(KFVel, KFAccBias) = Q.block<3>(KFAccBias, KFVel).transpose(); // Q_42^T
2107 Q.block<3>(KFAtt, KFGyrBias) = Q.block<3>(KFGyrBias, KFAtt).transpose(); // Q_51^T
2108 Q(KFStates::HeightBias, KFStates::HeightBias) = sigma_heightBias * sigma_heightBias * tau_s;
2109 Q(KFStates::HeightScale, KFStates::HeightScale) = sigma_heightScale * sigma_heightScale * tau_s;
2110
2112 Q.middleRows<2>(std::array{ PosLat, PosLon }) *= SCALE_FACTOR_LAT_LON;
2115
2117 Q.middleCols<2>(std::array{ PosLat, PosLon }) *= SCALE_FACTOR_LAT_LON;
2120
2121 return Q;
2122}
2123
2125 NAV::LooselyCoupledKF::e_systemNoiseCovarianceMatrix_Q(const Eigen::Vector3d& sigma2_ra, const Eigen::Vector3d& sigma2_rg,
2126 const Eigen::Vector3d& sigma2_bad, const Eigen::Vector3d& sigma2_bgd,
2127 const double& sigma_heightBias, const double& sigma_heightScale,
2128 const Eigen::Vector3d& tau_bad, const Eigen::Vector3d& tau_bgd,
2129 const Eigen::Matrix3d& e_F_21,
2130 const Eigen::Matrix3d& e_Dcm_b, const double& tau_s)
2131{
2132 // Math: \mathbf{Q}_{INS}^e = \begin{pmatrix} \mathbf{Q}_{11} & {\mathbf{Q}_{21}^e}^T & {\mathbf{Q}_{31}^e}^T & \mathbf{0}_3 & {\mathbf{Q}_{51}^e}^T \\ \mathbf{Q}_{21}^e & \mathbf{Q}_{22}^e & {\mathbf{Q}_{32}^e}^T & {\mathbf{Q}_{42}^e}^T & \mathbf{Q}_{25}^e \\ \mathbf{Q}_{31}^e & \mathbf{Q}_{32}^e & \mathbf{Q}_{33}^e & \mathbf{Q}_{34}^e & \mathbf{Q}_{35}^e \\ \mathbf{0}_3 & \mathbf{Q}_{42}^e & {\mathbf{Q}_{34}^e}^T & S_{bad}\tau_s\mathbf{I}_3 & \mathbf{0}_3 \\ \mathbf{Q}_{51}^e & \mathbf{Q}_{52}^e & {\mathbf{Q}_{35}^e}^T & \mathbf{0}_3 & S_{bgd}\tau_s\mathbf{I}_3 \end{pmatrix} \qquad \text{P. Groves}\,(14.80)
2133 Eigen::Vector3d S_ra = sigma2_ra * tau_s;
2134 Eigen::Vector3d S_rg = sigma2_rg * tau_s;
2135 Eigen::Vector3d S_bad = sigma2_bad.array() / tau_bad.array();
2136 Eigen::Vector3d S_bgd = sigma2_bgd.array() / tau_bgd.array();
2137
2138 Eigen::Matrix3d b_Dcm_e = e_Dcm_b.transpose();
2139
2141 Q(Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), States, States);
2142 Q.block<3>(KFAtt, KFAtt) = Q_psi_psi(S_rg, S_bgd, tau_s); // Q_11
2143 Q.block<3>(KFVel, KFAtt) = ien_Q_dv_psi(S_rg, S_bgd, e_F_21, tau_s); // Q_21
2144 Q.block<3>(KFVel, KFVel) = ien_Q_dv_dv(S_ra, S_bad, S_rg, S_bgd, e_F_21, tau_s); // Q_22
2145 Q.block<3>(KFVel, KFGyrBias) = ien_Q_dv_domega(S_bgd, e_F_21, e_Dcm_b, tau_s); // Q_25
2146 Q.block<3>(KFPos, KFAtt) = ie_Q_dr_psi(S_rg, S_bgd, e_F_21, tau_s); // Q_31
2147 Q.block<3>(KFPos, KFVel) = ie_Q_dr_dv(S_ra, S_bad, S_rg, S_bgd, e_F_21, tau_s); // Q_32
2148 Q.block<3>(KFPos, KFPos) = ie_Q_dr_dr(S_ra, S_bad, S_rg, S_bgd, e_F_21, tau_s); // Q_33
2149 Q.block<3>(KFPos, KFAccBias) = ie_Q_dr_df(S_bgd, e_Dcm_b, tau_s); // Q_34
2150 Q.block<3>(KFPos, KFGyrBias) = ie_Q_dr_domega(S_bgd, e_F_21, e_Dcm_b, tau_s); // Q_35
2151 Q.block<3>(KFAccBias, KFVel) = Q_df_dv(S_bad, b_Dcm_e, tau_s); // Q_42
2152 Q.block<3>(KFAccBias, KFAccBias) = Q_df_df(S_bad, tau_s); // Q_44
2153 Q.block<3>(KFGyrBias, KFAtt) = Q_domega_psi(S_bgd, b_Dcm_e, tau_s); // Q_51
2154 Q.block<3>(KFGyrBias, KFGyrBias) = Q_domega_domega(S_bgd, tau_s); // Q_55
2155
2156 Q.block<3>(KFAtt, KFVel) = Q.block<3>(KFVel, KFAtt).transpose(); // Q_21^T
2157 Q.block<3>(KFAtt, KFPos) = Q.block<3>(KFPos, KFAtt).transpose(); // Q_31^T
2158 Q.block<3>(KFVel, KFPos) = Q.block<3>(KFPos, KFVel).transpose(); // Q_32^T
2159 Q.block<3>(KFAccBias, KFPos) = Q.block<3>(KFPos, KFAccBias).transpose(); // Q_34^T
2160 Q.block<3>(KFGyrBias, KFVel) = Q.block<3>(KFVel, KFGyrBias).transpose(); // Q_25^T
2161 Q.block<3>(KFGyrBias, KFPos) = Q.block<3>(KFPos, KFGyrBias).transpose(); // Q_35^T
2162 Q.block<3>(KFVel, KFAccBias) = Q.block<3>(KFAccBias, KFVel).transpose(); // Q_42^T
2163 Q.block<3>(KFAtt, KFGyrBias) = Q.block<3>(KFGyrBias, KFAtt).transpose(); // Q_51^T
2164 Q(KFStates::HeightBias, KFStates::HeightBias) = sigma_heightBias * sigma_heightBias * tau_s;
2165 Q(KFStates::HeightScale, KFStates::HeightScale) = sigma_heightScale * sigma_heightScale * tau_s;
2166
2170
2174
2175 return Q;
2176}
2177
2178// ###########################################################################################################
2179// Error covariance matrix P
2180// ###########################################################################################################
2181
2183 NAV::LooselyCoupledKF::initialErrorCovarianceMatrix_P0(const Eigen::Vector3d& variance_angles,
2184 const Eigen::Vector3d& variance_vel,
2185 const Eigen::Vector3d& variance_pos,
2186 const Eigen::Vector3d& variance_accelBias,
2187 const Eigen::Vector3d& variance_gyroBias,
2188 const double& variance_heightBias,
2189 const double& variance_heightScale) const
2190{
2191 double scaleFactorPosition = _inertialIntegrator.getIntegrationFrame() == InertialIntegrator::IntegrationFrame::NED ? SCALE_FACTOR_LAT_LON : 1.0;
2192
2193 // 𝐏 Error covariance matrix
2194 Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT> P =
2195 Eigen::Matrix<double, NAV::LooselyCoupledKF::KFStates_COUNT, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero();
2196
2197 P.diagonal() << std::pow(SCALE_FACTOR_ATTITUDE, 2) * variance_angles, // Flight Angles covariance
2198 variance_vel, // Velocity covariance
2199 std::pow(scaleFactorPosition, 2) * variance_pos(0), // Latitude/Pos X covariance
2200 std::pow(scaleFactorPosition, 2) * variance_pos(1), // Longitude/Pos Y covariance
2201 variance_pos(2), // Altitude/Pos Z covariance
2202 std::pow(SCALE_FACTOR_ACCELERATION, 2) * variance_accelBias, // Accelerometer Bias covariance
2203 std::pow(SCALE_FACTOR_ANGULAR_RATE, 2) * variance_gyroBias, // Gyroscope Bias covariance
2204 variance_heightBias, // Height Bias covariance
2205 variance_heightScale; // Height Scale covariance
2206 return { P, States };
2207}
2208
2209// ###########################################################################################################
2210// Correction
2211// ###########################################################################################################
2212
2214 NAV::LooselyCoupledKF::n_measurementMatrix_H(const Eigen::Matrix3d& T_rn_p, const Eigen::Matrix3d& n_Dcm_b, const Eigen::Vector3d& b_omega_ib, const Eigen::Vector3d& b_leverArm_InsGnss, const Eigen::Matrix3d& n_Omega_ie)
2215{
2216 // Math: \mathbf{H}_{G,k}^n = \begin{pmatrix} \mathbf{H}_{r1}^n & \mathbf{0}_3 & -\mathbf{I}_3 & \mathbf{0}_3 & \mathbf{0}_3 \\ \mathbf{H}_{v1}^n & -\mathbf{I}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{H}_{v5}^n \end{pmatrix}_k \qquad \text{P. Groves}\,(14.113)
2217 // G denotes GNSS indicated
2218
2220 H(Eigen::Matrix<double, 6, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), Meas, States);
2221
2222 // Math: \mathbf{H}_{r1}^n \approx \mathbf{\hat{T}}_{r(n)}^p \begin{bmatrix} \begin{pmatrix} \mathbf{C}_b^n \mathbf{l}_{ba}^p \end{pmatrix} \wedge \end{bmatrix} \qquad \text{P. Groves}\,(14.114)
2223 H.block<3>(dPos, KFAtt) = T_rn_p * math::skewSymmetricMatrix(n_Dcm_b * b_leverArm_InsGnss);
2224 H.block<3>(dPos, KFPos) = -Eigen::Matrix3d::Identity();
2225 // Math: \mathbf{H}_{v1}^n \approx \begin{bmatrix} \begin{Bmatrix} \mathbf{C}_b^n (\mathbf{\hat{\omega}}_{ib}^b \wedge \mathbf{l}_{ba}^b) - \mathbf{\hat{\Omega}}_{ie}^n \mathbf{C}_b^n \mathbf{l}_{ba}^b \end{Bmatrix} \wedge \end{bmatrix} \qquad \text{P. Groves}\,(14.114)
2226 H.block<3>(dVel, KFAtt) = math::skewSymmetricMatrix(n_Dcm_b * (b_omega_ib.cross(b_leverArm_InsGnss)) - n_Omega_ie * n_Dcm_b * b_leverArm_InsGnss);
2227 H.block<3>(dVel, KFVel) = -Eigen::Matrix3d::Identity();
2228 // Math: \mathbf{H}_{v5}^n = \mathbf{C}_b^n \begin{bmatrix} \mathbf{l}_{ba}^b \wedge \end{bmatrix} \qquad \text{P. Groves}\,(14.114)
2229 H.block<3>(dVel, KFGyrBias) = n_Dcm_b * math::skewSymmetricMatrix(b_leverArm_InsGnss);
2230
2231 H.middleRows<2>(std::array{ dPosLat, dPosLon }) *= SCALE_FACTOR_LAT_LON;
2232
2234 H.middleCols<2>(std::array{ PosLat, PosLon }) *= 1. / SCALE_FACTOR_LAT_LON;
2235 // H.middleCols<3>(AccBias) *= 1. / SCALE_FACTOR_ACCELERATION; // Only zero elements
2237
2238 return H;
2239}
2240
2242 NAV::LooselyCoupledKF::n_measurementMatrix_H(const double& height, const double& scale)
2243{
2245 H(Eigen::Matrix<double, 1, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), std::array{ KFMeas::dHgt }, States);
2246
2247 H(KFMeas::dHgt, PosAlt) = -scale;
2248 H(KFMeas::dHgt, HeightBias) = 1.0;
2249 H(KFMeas::dHgt, HeightScale) = height;
2250
2251 return H;
2252}
2253
2255 NAV::LooselyCoupledKF::e_measurementMatrix_H(const Eigen::Matrix3d& e_Dcm_b, const Eigen::Vector3d& b_omega_ib, const Eigen::Vector3d& b_leverArm_InsGnss, const Eigen::Matrix3d& e_Omega_ie)
2256{
2257 // Math: \mathbf{H}_{G,k}^e = \begin{pmatrix} \mathbf{H}_{r1}^e & \mathbf{0}_3 & -\mathbf{I}_3 & \mathbf{0}_3 & \mathbf{0}_3 \\ \mathbf{H}_{v1}^e & -\mathbf{I}_3 & \mathbf{0}_3 & \mathbf{0}_3 & \mathbf{H}_{v5}^e \end{pmatrix}_k \qquad \text{P. Groves}\,(14.113)
2258 // G denotes GNSS indicated
2259
2261 H(Eigen::Matrix<double, 6, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), Meas, States);
2262
2263 // Math: \mathbf{H}_{r1}^e \approx \begin{bmatrix} \begin{pmatrix} \mathbf{C}_b^e \mathbf{l}_{ba}^p \end{pmatrix} \wedge \end{bmatrix} \qquad \text{P. Groves}\,(14.114)
2264 H.block<3>(dPos, KFAtt) = math::skewSymmetricMatrix(e_Dcm_b * b_leverArm_InsGnss);
2265 H.block<3>(dPos, KFPos) = -Eigen::Matrix3d::Identity();
2266 // Math: \mathbf{H}_{v1}^e \approx \begin{bmatrix} \begin{Bmatrix} \mathbf{C}_b^e (\mathbf{\hat{\omega}}_{ib}^b \wedge \mathbf{l}_{ba}^b) - \mathbf{\hat{\Omega}}_{ie}^e \mathbf{C}_b^e \mathbf{l}_{ba}^b \end{Bmatrix} \wedge \end{bmatrix} \qquad \text{P. Groves}\,(14.114)
2267 H.block<3>(dVel, KFAtt) = math::skewSymmetricMatrix(e_Dcm_b * (b_omega_ib.cross(b_leverArm_InsGnss)) - e_Omega_ie * e_Dcm_b * b_leverArm_InsGnss);
2268 H.block<3>(dVel, KFVel) = -Eigen::Matrix3d::Identity();
2269 // Math: \mathbf{H}_{v5}^e = \mathbf{C}_b^e \begin{bmatrix} \mathbf{l}_{ba}^b \wedge \end{bmatrix} \qquad \text{P. Groves}\,(14.114)
2270 H.block<3>(dVel, KFGyrBias) = e_Dcm_b * math::skewSymmetricMatrix(b_leverArm_InsGnss);
2271
2273 // H.middleCols<3>(AccBias) *= 1. / SCALE_FACTOR_ACCELERATION; // Only zero elements
2275
2276 return H;
2277}
2278
2280 NAV::LooselyCoupledKF::e_measurementMatrix_H(const Eigen::Vector3d& e_positionEstimate, const double& height, const double& scale)
2281{
2283 H(Eigen::Matrix<double, 1, NAV::LooselyCoupledKF::KFStates_COUNT>::Zero(), std::array{ KFMeas::dHgt }, States);
2284
2285 H(KFMeas::dHgt, KFPos) = -scale * e_positionEstimate.normalized().transpose();
2286 H(KFMeas::dHgt, HeightBias) = 1.0;
2287 H(KFMeas::dHgt, HeightScale) = height;
2288
2289 return H;
2290}
2291
2293 NAV::LooselyCoupledKF::n_measurementNoiseCovariance_R(const std::shared_ptr<const PosVel>& posVelObs,
2294 const Eigen::Vector3d& lla_position,
2295 double R_N,
2296 double R_E) const
2297{
2298 // GNSS measurement uncertainty for the position (Variance σ²) in [m^2]
2299 Eigen::Vector3d gnssSigmaSquaredPosition = Eigen::Vector3d::Zero();
2301 {
2303 gnssSigmaSquaredPosition = _gnssMeasurementUncertaintyPosition.array().pow(2);
2304 break;
2306 gnssSigmaSquaredPosition = _gnssMeasurementUncertaintyPosition;
2307 break;
2308 }
2309 // GNSS measurement uncertainty for the velocity (Variance σ²) in [m^2/s^2]
2310 Eigen::Vector3d gnssSigmaSquaredVelocity = Eigen::Vector3d::Zero();
2312 {
2314 gnssSigmaSquaredVelocity = _gnssMeasurementUncertaintyVelocity.array().pow(2);
2315 break;
2317 gnssSigmaSquaredVelocity = _gnssMeasurementUncertaintyVelocity;
2318 break;
2319 }
2320
2321 KeyedMatrix<double, KFMeas, KFMeas, 6, 6> R(Eigen::Matrix<double, 6, 6>::Zero(), Meas);
2322
2324 && posVelObs->n_CovarianceMatrix() && posVelObs->n_CovarianceMatrix()->get().hasRows(Keys::PosVel<Keys::MotionModelKey>))
2325 {
2326 R(all, all) = posVelObs->n_CovarianceMatrix()->get()(Keys::PosVel<Keys::MotionModelKey>, Keys::PosVel<Keys::MotionModelKey>);
2327 }
2329 && posVelObs->n_CovarianceMatrix() && posVelObs->n_CovarianceMatrix()->get().hasRows(Keys::Pos<Keys::MotionModelKey>))
2330 {
2331 R.block<3>(dPos, dPos) = posVelObs->n_CovarianceMatrix()->get()(Keys::Pos<Keys::MotionModelKey>, Keys::Pos<Keys::MotionModelKey>);
2332 R.block<3>(dVel, dVel).diagonal() = gnssSigmaSquaredVelocity;
2333 }
2335 && posVelObs->n_CovarianceMatrix() && posVelObs->n_CovarianceMatrix()->get().hasRows(Keys::Vel<Keys::MotionModelKey>))
2336 {
2337 R.block<3>(dPos, dPos).diagonal() = gnssSigmaSquaredPosition;
2338 R.block<3>(dVel, dVel) = posVelObs->n_CovarianceMatrix()->get()(Keys::Vel<Keys::MotionModelKey>, Keys::Vel<Keys::MotionModelKey>);
2339 }
2340 else // if (_gnssMeasurementUncertaintyPositionOverride && _gnssMeasurementUncertaintyVelocityOverride)
2341 {
2342 R.block<3>(dPos, dPos).diagonal() = gnssSigmaSquaredPosition;
2343 R.block<3>(dVel, dVel).diagonal() = gnssSigmaSquaredVelocity;
2344 }
2345
2346 // transform NED covariance into LLA covariance
2347 Eigen::Matrix6d J = Eigen::Matrix6d::Identity();
2348 J.topLeftCorner<3, 3>() = n_F_dr_dv(lla_position.x(), lla_position.z(), R_N, R_E);
2349 R(all, all) = J * R(all, all) * J.transpose();
2350
2351 // scale units
2352 R.middleRows<2>(std::array{ dPosLat, dPosLon }) *= SCALE_FACTOR_LAT_LON;
2353 R.middleCols<2>(std::array{ dPosLat, dPosLon }) *= SCALE_FACTOR_LAT_LON;
2354
2355 return R;
2356}
2357
2360{
2361 KeyedMatrix<double, KFMeas, KFMeas, 1, 1> R(Eigen::Matrix<double, 1, 1>::Zero(), std::array{ KFMeas::dHgt });
2362 R(KFMeas::dHgt, KFMeas::dHgt) = baroVarianceHeight;
2363
2364 return R;
2365}
2366
2368 NAV::LooselyCoupledKF::e_measurementNoiseCovariance_R(const std::shared_ptr<const PosVel>& posVelObs) const
2369{
2370 // GNSS measurement uncertainty for the position (Variance σ²) in [m^2]
2371 Eigen::Vector3d gnssSigmaSquaredPosition = Eigen::Vector3d::Zero();
2373 {
2375 gnssSigmaSquaredPosition = _gnssMeasurementUncertaintyPosition.array().pow(2);
2376 break;
2378 gnssSigmaSquaredPosition = _gnssMeasurementUncertaintyPosition;
2379 break;
2380 }
2381 // GNSS measurement uncertainty for the velocity (Variance σ²) in [m^2/s^2]
2382 Eigen::Vector3d gnssSigmaSquaredVelocity = Eigen::Vector3d::Zero();
2384 {
2386 gnssSigmaSquaredVelocity = _gnssMeasurementUncertaintyVelocity.array().pow(2);
2387 break;
2389 gnssSigmaSquaredVelocity = _gnssMeasurementUncertaintyVelocity;
2390 break;
2391 }
2392
2393 KeyedMatrix<double, KFMeas, KFMeas, 6, 6> R(Eigen::Matrix<double, 6, 6>::Zero(), Meas);
2394
2396 && posVelObs->e_CovarianceMatrix() && posVelObs->e_CovarianceMatrix()->get().hasRows(Keys::PosVel<Keys::MotionModelKey>))
2397 {
2398 R(all, all) = posVelObs->e_CovarianceMatrix()->get()(Keys::PosVel<Keys::MotionModelKey>, Keys::PosVel<Keys::MotionModelKey>);
2399 }
2401 && posVelObs->e_CovarianceMatrix() && posVelObs->e_CovarianceMatrix()->get().hasRows(Keys::Pos<Keys::MotionModelKey>))
2402 {
2403 R.block<3>(dPos, dPos) = posVelObs->e_CovarianceMatrix()->get()(Keys::Pos<Keys::MotionModelKey>, Keys::Pos<Keys::MotionModelKey>);
2404 R.block<3>(dVel, dVel).diagonal() = gnssSigmaSquaredVelocity;
2405 }
2407 && posVelObs->e_CovarianceMatrix() && posVelObs->e_CovarianceMatrix()->get().hasRows(Keys::Vel<Keys::MotionModelKey>))
2408 {
2409 R.block<3>(dPos, dPos).diagonal() = gnssSigmaSquaredPosition;
2410 R.block<3>(dVel, dVel) = posVelObs->e_CovarianceMatrix()->get()(Keys::Vel<Keys::MotionModelKey>, Keys::Vel<Keys::MotionModelKey>);
2411 }
2412 else // if (_gnssMeasurementUncertaintyPositionOverride && _gnssMeasurementUncertaintyVelocityOverride)
2413 {
2414 R.block<3>(dPos, dPos).diagonal() = gnssSigmaSquaredPosition;
2415 R.block<3>(dVel, dVel).diagonal() = gnssSigmaSquaredVelocity;
2416 }
2417
2418 return R;
2419}
2420
2422 NAV::LooselyCoupledKF::n_measurementInnovation_dz(const Eigen::Vector3d& lla_positionMeasurement, const Eigen::Vector3d& lla_positionEstimate,
2423 const Eigen::Vector3d& n_velocityMeasurement, const Eigen::Vector3d& n_velocityEstimate,
2424 const Eigen::Matrix3d& T_rn_p, const Eigen::Quaterniond& n_Quat_b, const Eigen::Vector3d& b_leverArm_InsGnss,
2425 const Eigen::Vector3d& b_omega_ib, const Eigen::Matrix3d& n_Omega_ie)
2426{
2427 // Math: \delta\mathbf{z}_{G,k}^{n-} = \begin{pmatrix} \mathbf{\hat{p}}_{aG} - \mathbf{\hat{p}}_b - \mathbf{\hat{T}}_{r(n)}^p \mathbf{C}_b^n \mathbf{l}_{ba}^b \\ \mathbf{\hat{v}}_{eaG}^n - \mathbf{\hat{v}}_{eb}^n - \mathbf{C}_b^n (\mathbf{\hat{\omega}}_{ib}^b \wedge \mathbf{l}_{ba}^b) + \mathbf{\hat{\Omega}}_{ie}^n \mathbf{C}_b^n \mathbf{l}_{ba}^b \end{pmatrix}_k \qquad \text{P. Groves}\,(14.103)
2428 Eigen::Vector3d deltaLLA = lla_positionMeasurement - lla_positionEstimate - T_rn_p * (n_Quat_b * b_leverArm_InsGnss);
2429 Eigen::Vector3d deltaVel = n_velocityMeasurement - n_velocityEstimate - n_Quat_b * (b_omega_ib.cross(b_leverArm_InsGnss)) + n_Omega_ie * (n_Quat_b * b_leverArm_InsGnss);
2430
2431 deltaLLA.topRows<2>() *= SCALE_FACTOR_LAT_LON;
2432
2433 Eigen::Matrix<double, 6, 1> innovation;
2434 innovation << deltaLLA, deltaVel;
2435
2436 return { innovation, Meas };
2437}
2438
2440 NAV::LooselyCoupledKF::n_measurementInnovation_dz(const double& baroheight, const double& height, const double& heightbias, const double& heightscale)
2441{
2442 Eigen::Matrix<double, 1, 1> innovation;
2443 innovation << baroheight - (height * heightscale + heightbias);
2444
2445 return { innovation, std::array{ KFMeas::dHgt } };
2446}
2447
2449 NAV::LooselyCoupledKF::e_measurementInnovation_dz(const Eigen::Vector3d& e_positionMeasurement, const Eigen::Vector3d& e_positionEstimate,
2450 const Eigen::Vector3d& e_velocityMeasurement, const Eigen::Vector3d& e_velocityEstimate,
2451 const Eigen::Quaterniond& e_Quat_b, const Eigen::Vector3d& b_leverArm_InsGnss,
2452 const Eigen::Vector3d& b_omega_ib, const Eigen::Matrix3d& e_Omega_ie)
2453{
2454 // Math: \delta\mathbf{z}_{G,k}^{e-} = \begin{pmatrix} \mathbf{\hat{r}}_{eaG}^e - \mathbf{\hat{r}}_{eb}^e - \mathbf{C}_b^e \mathbf{l}_{ba}^b \\ \mathbf{\hat{v}}_{eaG}^e - \mathbf{\hat{v}}_{eb}^e - \mathbf{C}_b^e (\mathbf{\hat{\omega}}_{ib}^b \wedge \mathbf{l}_{ba}^b) + \mathbf{\hat{\Omega}}_{ie}^e \mathbf{C}_b^e \mathbf{l}_{ba}^b \end{pmatrix}_k \qquad \text{P. Groves}\,(14.102)
2455 Eigen::Vector3d deltaPos = e_positionMeasurement - e_positionEstimate - e_Quat_b * b_leverArm_InsGnss;
2456 Eigen::Vector3d deltaVel = e_velocityMeasurement - e_velocityEstimate - e_Quat_b * (b_omega_ib.cross(b_leverArm_InsGnss)) + e_Omega_ie * (e_Quat_b * b_leverArm_InsGnss);
2457
2458 Eigen::Matrix<double, 6, 1> innovation;
2459 innovation << deltaPos, deltaVel;
2460
2461 return { innovation, Meas };
2462}
2463
2464std::ostream& operator<<(std::ostream& os, const NAV::LooselyCoupledKF::KFStates& obj)
2465{
2466 return os << fmt::format("{}", obj);
2467}
2468std::ostream& operator<<(std::ostream& os, const NAV::LooselyCoupledKF::KFMeas& obj)
2469{
2470 return os << fmt::format("{}", obj);
2471}
Assertion helpers.
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
Holds all Constants.
Error Equations for the ECEF frame.
Vector space operations.
Functions concerning the ellipsoid model.
Save/Load the Nodes.
nlohmann::json json
json namespace
Different Gravity Models.
Text Help Marker (?) with Tooltip.
Inertial Navigation Helper Functions.
Data storage class for one VectorNavImu observation.
Defines Widgets which allow the input of values and the selection of the unit.
Loosely-coupled Kalman Filter INS/GNSS errors.
Error Equations for the local navigation frame.
Utility class for logging to console and file.
#define LOG_CRITICAL(...)
Critical Event, which causes the program to work entirely and throws an exception.
Definition Logger.hpp:75
#define LOG_DEBUG
Debug information. Should not be called on functions which receive observations (spamming)
Definition Logger.hpp:67
#define LOG_DATA
All output which occurs repeatedly every time observations are received.
Definition Logger.hpp:29
#define LOG_ERROR
Error occurred, which stops part of the program to work, but not everything.
Definition Logger.hpp:73
#define LOG_WARN
Error occurred, but a fallback option exists and program continues to work normally.
Definition Logger.hpp:71
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Definition Logger.hpp:65
constexpr double SCALE_FACTOR_LAT_LON
Scale factor to convert the latitude and longitude error.
constexpr double SCALE_FACTOR_ANGULAR_RATE
Scale factor to convert the angular rate error.
constexpr double SCALE_FACTOR_ATTITUDE
Scale factor to convert the attitude error.
constexpr double SCALE_FACTOR_ACCELERATION
Scale factor to convert the acceleration error.
Kalman Filter class for the loosely coupled INS/GNSS integration.
Simple Math functions.
Utility class which specifies available nodes.
Pin class.
Position, Velocity and Attitude Storage Class.
Position and Velocity Storage Class.
General process Noise definitions.
static std::string type()
Returns the type of the data class.
Definition BaroHgt.hpp:28
static std::string type()
Returns the type of the data class.
static std::string type()
Returns the type of the data class.
Definition ImuObs.hpp:33
IMU Position.
Definition ImuPos.hpp:26
const Eigen::Quaterniond & b_quat_p() const
Quaternion from IMU platform frame to body frame.
Definition ImuPos.hpp:35
@ ECEF
Earth-Centered Earth-Fixed frame.
Input pins of nodes.
Definition Pin.hpp:491
TsDeque< std::shared_ptr< const NAV::NodeData > > NodeDataQueue
Node data queue type.
Definition Pin.hpp:707
bool(*)(const Node *, const InputPin &) FlowFirableCheckFunc
Function type to call when checking if a pin is firable.
Definition Pin.hpp:725
NodeDataQueue queue
Queue with received data.
Definition Pin.hpp:743
static constexpr double pseudometre
Conversion factor between latitude and longitude in [rad] to [pseudometre].
Definition Constants.hpp:31
static constexpr double G_NORM
Standard gravity in [m / s^2].
Definition Constants.hpp:40
static const Eigen::Vector3< double > e_omega_ie
ω_ie_e = ω_ie_i Nominal mean angular velocity of the Earth in [rad/s], in earth coordinates
@ NED
Local North-East-Down frame.
@ ECEF
Earth-Centered Earth-Fixed frame.
static std::string type()
Returns the type of the data class.
The class is responsible for all time-related tasks.
Definition InsTime.hpp:710
Static sized KeyedMatrix.
Static sized KeyedVector.
InitCovarianceScaleHeight _initCovarianceScaleHeightUnit
Gui selection for the Unit of the initial covariance for the height scale.
KFStates
State Keys of the Kalman filter.
@ HeightScale
Baro Height Scale.
@ GyrBiasX
Gyroscope Bias X.
@ HeightBias
Baro Height Bias.
@ AccBiasZ
Accelerometer Bias Z.
@ GyrBiasZ
Gyroscope Bias Z.
@ GyrBiasY
Gyroscope Bias Y.
@ AccBiasX
Accelerometer Bias X.
@ AccBiasY
Accelerometer Bias Y.
Units::ImuAccelerometerFilterNoiseUnits _stdevAccelNoiseUnits
Gui selection for the Unit of the input stdev_ra parameter.
StdevBaroHeightScaleUnits _stdevBaroHeightScaleUnits
Gui selection for the Unit of the barometric height scale uncertainty.
RandomProcess _randomProcessAccel
Random Process used to estimate the accelerometer biases.
static KeyedMatrix< double, KFMeas, KFStates, 6, 17 > e_measurementMatrix_H(const Eigen::Matrix3d &e_Dcm_b, const Eigen::Vector3d &b_omega_ib, const Eigen::Vector3d &b_leverArm_InsGnss, const Eigen::Matrix3d &e_Omega_ie)
Measurement matrix for GNSS measurements at timestep k, represented in Earth frame coordinates.
json save() const override
Saves the node into a json object.
InitBiasAccelUnit _initBiasAccelUnit
Gui selection for the unit of the initial accelerometer biases.
InitCovarianceVelocityUnit _initCovarianceVelocityUnit
Gui selection for the Unit of the initial covariance for the velocity.
bool _preferAccelerationOverDeltaMeasurements
Prefer the raw acceleration measurements over the deltaVel & deltaTheta values.
static void pinAddCallback(Node *node)
Function to call to add a new pin.
Eigen::Vector3d _initBiasAccel
GUI selection of the initial accelerometer biases.
static KeyedVector< double, KFMeas, 6 > n_measurementInnovation_dz(const Eigen::Vector3d &lla_positionMeasurement, const Eigen::Vector3d &lla_positionEstimate, const Eigen::Vector3d &n_velocityMeasurement, const Eigen::Vector3d &n_velocityEstimate, const Eigen::Matrix3d &T_rn_p, const Eigen::Quaterniond &n_Quat_b, const Eigen::Vector3d &b_leverArm_InsGnss, const Eigen::Vector3d &b_omega_ib, const Eigen::Matrix3d &n_Omega_ie)
Measurement innovation vector 𝜹𝐳
Eigen::Vector3d _gnssMeasurementUncertaintyVelocity
GUI selection of the GNSS NED velocity measurement uncertainty (standard deviation σ or Variance σ²)
StdevBaroHeightBiasUnits _stdevBaroHeightBiasUnits
Gui selection for the Unit of the barometric height bias uncertainty.
PhiCalculationAlgorithm _phiCalculationAlgorithm
GUI option for the Phi calculation algorithm.
int _phiCalculationTaylorOrder
GUI option for the order of the Taylor polynom to calculate the Phi matrix.
Eigen::Vector3d _initCovariancePosition
GUI selection of the initial covariance diagonal values for position (standard deviation σ or Varianc...
static std::string category()
String representation of the class category.
static const std::vector< KFMeas > dPos
All position difference keys.
void updateInputPins()
Update the input pins depending on the GUI.
KeyedMatrix< double, KFMeas, KFMeas, 6, 6 > e_measurementNoiseCovariance_R(const std::shared_ptr< const PosVel > &posVelObs) const
Measurement noise covariance matrix 𝐑
static KeyedVector< double, KFMeas, 6 > e_measurementInnovation_dz(const Eigen::Vector3d &e_positionMeasurement, const Eigen::Vector3d &e_positionEstimate, const Eigen::Vector3d &e_velocityMeasurement, const Eigen::Vector3d &e_velocityEstimate, const Eigen::Quaterniond &e_Quat_b, const Eigen::Vector3d &b_leverArm_InsGnss, const Eigen::Vector3d &b_omega_ib, const Eigen::Matrix3d &e_Omega_ie)
Measurement innovation vector 𝜹𝐳
KeyedMatrix< double, KFMeas, KFMeas, 6, 6 > n_measurementNoiseCovariance_R(const std::shared_ptr< const PosVel > &posVelObs, const Eigen::Vector3d &lla_position, double R_N, double R_E) const
Measurement noise covariance matrix 𝐑
double _heightScaleTotal
Accumulator for height scale [m/m].
void recvImuObservation(InputPin::NodeDataQueue &queue, size_t pinIdx)
Receive Function for the IMU observation.
static const std::vector< KFStates > KFAccBias
All acceleration bias keys.
GnssMeasurementUncertaintyVelocityUnit _gnssMeasurementUncertaintyVelocityUnit
Gui selection for the Unit of the GNSS measurement uncertainty for the velocity.
void looselyCoupledUpdate(const std::shared_ptr< const PosVel > &posVelObs)
Updates the predicted state from the InertialNavSol with the PosVel observation.
Eigen::Vector3d _initCovarianceVelocity
GUI selection of the initial covariance diagonal values for velocity (standard deviation σ or Varianc...
static KeyedMatrix< double, KFStates, KFStates, 17, 17 > noiseInputMatrix_G(const Eigen::Quaterniond &ien_Quat_b)
Calculates the noise input matrix 𝐆
bool hasInputPinWithSameTime(const InsTime &insTime) const
Checks wether there is an input pin with the same time.
Eigen::Vector3d _initCovarianceBiasGyro
GUI selection of the initial covariance diagonal values for gyroscope biases (standard deviation σ or...
bool _gnssMeasurementUncertaintyPositionOverride
Whether to override the position uncertainty or use the one included in the measurement.
Units::ImuGyroscopeFilterNoiseUnits _stdevGyroNoiseUnits
Gui selection for the Unit of the input stdev_rg parameter.
Eigen::Vector3d _gnssMeasurementUncertaintyPosition
GUI selection of the GNSS position measurement uncertainty (standard deviation σ or Variance σ²)....
static constexpr size_t INPUT_PORT_INDEX_POS_VEL_ATT_INIT
Flow (PosVelAtt)
~LooselyCoupledKF() override
Destructor.
QCalculationAlgorithm _qCalculationAlgorithm
GUI option for the Q calculation algorithm.
@ rad_rad_m
Standard deviation LatLonAlt [rad, rad, m].
@ rad2_rad2_m2
Variance LatLonAlt^2 [rad^2, rad^2, m^2].
static const std::vector< KFStates > KFVel
All velocity keys.
bool _initializeStateOverExternalPin
Whether to initialize the state over an external pin.
Eigen::Vector3d _tau_bgd
Correlation length of the gyro dynamic bias in [s].
double _initCovarianceBiasHeight
GUI selection of the initial covariance diagonal values for the height bias (standard deviation σ or ...
bool _checkKalmanMatricesRanks
Check the rank of the Kalman matrices every iteration (computational expensive)
Units::ImuAccelerometerFilterBiasUnits _stdevAccelBiasUnits
Gui selection for the Unit of the input variance_bad parameter.
GnssMeasurementUncertaintyPositionUnit _gnssMeasurementUncertaintyPositionUnit
Gui selection for the Unit of the GNSS measurement uncertainty for the position.
double _stdevBaroHeightBias
Uncertainty of the barometric height bias.
static const std::vector< KFStates > KFAtt
All attitude keys.
KeyedKalmanFilterD< KFStates, KFMeas > _kalmanFilter
Kalman Filter representation.
InitBiasGyroUnit _initBiasGyroUnit
Gui selection for the unit of the initial gyroscope biases.
double _initCovarianceScaleHeight
GUI selection of the initial covariance diagonal values for the height scale (standard deviation σ or...
static const std::vector< KFMeas > dVel
All velocity difference keys.
Eigen::Vector3d _accelBiasTotal
Accumulator for acceleration bias [m/s²].
void recvPosVelAttInit(InputPin::NodeDataQueue &queue, size_t pinIdx)
Receive Function for the PosVelAtt observation.
std::shared_ptr< const ImuObs > _lastImuObs
Last received IMU observation (to get ImuPos)
InitCovarianceBiasAccelUnit _initCovarianceBiasAccelUnit
Gui selection for the Unit of the initial covariance for the accelerometer biases.
InitCovariancePositionUnit _initCovariancePositionUnit
Gui selection for the Unit of the initial covariance for the position.
gui::widgets::DynamicInputPins _dynamicInputPins
Dynamic input pins.
Eigen::Vector3d _stdev_rg
𝜎_rg Standard deviation of the noise on the gyro angular-rate measurements
static const std::vector< KFStates > KFPosVelAtt
All position, velocity and attitude keys.
void recvBaroHeight(InputPin::NodeDataQueue &queue, size_t pinIdx)
Receive Function for the BaroHgt observation.
InsTime _externalInitTime
Time from the external init.
static constexpr size_t OUTPUT_PORT_INDEX_SOLUTION
Flow (InsGnssLCKFSolution)
static constexpr size_t INPUT_PORT_INDEX_IMU
Flow (ImuObs)
void deinitialize() override
Deinitialize the node.
void setSolutionPosVelAttAndCov(const std::shared_ptr< PosVelAtt > &lckfSolution, double R_N, double R_E)
Sets the covariance matrix P of the LCKF (and does the necessary unit conversions)
Eigen::Vector3d _stdev_bad
𝜎²_bad Variance of the accelerometer dynamic bias
InertialIntegrator _inertialIntegrator
Inertial Integrator.
void restore(const json &j) override
Restores the node from a json object.
void invokeCallbackWithPosVelAtt(const PosVelAtt &posVelAtt)
Invoke the callback with a PosVelAtt solution (without LCKF specific output)
KeyedMatrix< double, KFStates, KFStates, 17, 17 > e_systemMatrix_F(const Eigen::Quaterniond &e_Quat_b, const Eigen::Vector3d &b_specForce_ib, const Eigen::Vector3d &e_position, const Eigen::Vector3d &e_gravitation, double r_eS_e, const Eigen::Vector3d &e_omega_ie, const Eigen::Vector3d &tau_bad, const Eigen::Vector3d &tau_bgd) const
Calculates the system matrix 𝐅 for the ECEF frame.
void looselyCoupledPrediction(const std::shared_ptr< const PosVelAtt > &inertialNavSol, double tau_i, const ImuPos &imuPos)
Predicts the state from the InertialNavSol.
KFMeas
Measurement Keys of the Kalman filter.
@ dPosLat
Latitude difference.
@ dPosLon
Longitude difference.
@ dHgt
height difference
BaroHeightMeasurementUncertaintyUnit _barometricHeightMeasurementUncertaintyUnit
Gui selection for the Unit of the barometric height measurement uncertainty.
double _stdevBaroHeightScale
Uncertainty of the barometric height scale.
KeyedMatrix< double, KFStates, KFStates, 17, 17 > initialErrorCovarianceMatrix_P0(const Eigen::Vector3d &variance_angles, const Eigen::Vector3d &variance_vel, const Eigen::Vector3d &variance_pos, const Eigen::Vector3d &variance_accelBias, const Eigen::Vector3d &variance_gyroBias, const double &variance_heightBias, const double &variance_heightScale) const
Initial error covariance matrix P_0.
double _heightBiasTotal
Accumulator for height bias [m].
void recvPosVelObservation(InputPin::NodeDataQueue &queue, size_t pinIdx)
Receive Function for the PosVel observation.
bool _baroHeightMeasurementUncertaintyOverride
Whether to override the barometric height uncertainty or use the one included in the measurement.
static std::string typeStatic()
String representation of the class type.
bool _gnssMeasurementUncertaintyVelocityOverride
Whether to override the velocity uncertainty or use the one included in the measurement.
Units::ImuGyroscopeFilterBiasUnits _stdevGyroBiasUnits
Gui selection for the Unit of the input variance_bad parameter.
static const std::vector< KFStates > KFPos
All position keys.
Eigen::Vector3d _stdev_ra
𝜎_ra Standard deviation of the noise on the accelerometer specific-force measurements
Eigen::Vector3d _tau_bad
Correlation length of the accelerometer dynamic bias in [s].
KeyedMatrix< double, KFStates, KFStates, 17, 17 > n_systemMatrix_F(const Eigen::Quaterniond &n_Quat_b, const Eigen::Vector3d &b_specForce_ib, const Eigen::Vector3d &n_omega_in, const Eigen::Vector3d &n_velocity, const Eigen::Vector3d &lla_position, double R_N, double R_E, double g_0, double r_eS_e, const Eigen::Vector3d &tau_bad, const Eigen::Vector3d &tau_bgd) const
Calculates the system matrix 𝐅 for the local navigation frame.
InitCovarianceBiasGyroUnit _initCovarianceBiasGyroUnit
Gui selection for the Unit of the initial covariance for the gyroscope biases.
static void pinDeleteCallback(Node *node, size_t pinIdx)
Function to call to delete a pin.
std::string type() const override
String representation of the class type.
static const std::vector< KFStates > KFGyrBias
All gyroscope bias keys.
std::array< double, 3 > _initalRollPitchYaw
Roll, Pitch and Yaw angles in [deg] used for initialization if not taken from separate pin.
LooselyCoupledKF()
Default constructor.
static KeyedMatrix< double, KFStates, KFStates, 17, 17 > e_systemNoiseCovarianceMatrix_Q(const Eigen::Vector3d &sigma2_ra, const Eigen::Vector3d &sigma2_rg, const Eigen::Vector3d &sigma2_bad, const Eigen::Vector3d &sigma2_bgd, const double &sigma_heightBias, const double &sigma_heightScale, const Eigen::Vector3d &tau_bad, const Eigen::Vector3d &tau_bgd, const Eigen::Matrix3d &e_F_21, const Eigen::Matrix3d &e_Dcm_b, const double &tau_s)
System noise covariance matrix 𝐐_{k-1}.
double _barometricHeightMeasurementUncertainty
GUI selection of the barometric height measurement uncertainty (standard deviation σ or Variance σ²)
static KeyedMatrix< double, KFMeas, KFStates, 6, 17 > n_measurementMatrix_H(const Eigen::Matrix3d &T_rn_p, const Eigen::Matrix3d &n_Dcm_b, const Eigen::Vector3d &b_omega_ib, const Eigen::Vector3d &b_leverArm_InsGnss, const Eigen::Matrix3d &n_Omega_ie)
Measurement matrix for GNSS measurements at timestep k, represented in navigation coordinates.
Eigen::Vector3d _gyroBiasTotal
Accumulator gyro bias [rad/s].
bool _initialSensorBiasesApplied
Whether the accumulated biases have been initialized in the 'inertialIntegrator'.
RandomProcess _randomProcessGyro
Random Process used to estimate the gyroscope biases.
Eigen::Vector3d _initCovarianceBiasAccel
GUI selection of the initial covariance diagonal values for accelerometer biases (standard deviation ...
void guiConfig() override
ImGui config window which is shown on double click.
bool initialize() override
Initialize the node.
bool _enableBaroHgt
Whether to enable barometric height (including the corresponding pin)
Eigen::Vector3d _initCovarianceAttitudeAngles
GUI selection of the initial covariance diagonal values for attitude angles (standard deviation σ or ...
Eigen::Matrix< double, 17, 17 > noiseScaleMatrix_W(const Eigen::Vector3d &sigma_ra, const Eigen::Vector3d &sigma_rg, const Eigen::Vector3d &sigma_bad, const Eigen::Vector3d &sigma_bgd, const Eigen::Vector3d &tau_bad, const Eigen::Vector3d &tau_bgd, const double &sigma_heightBias, const double &sigma_heightScale)
Calculates the noise scale matrix 𝐖
Eigen::Vector3d _stdev_bgd
𝜎²_bgd Variance of the gyro dynamic bias
Eigen::Vector3d _initBiasGyro
GUI selection of the initial gyroscope biases.
InitCovarianceAttitudeAnglesUnit _initCovarianceAttitudeAnglesUnit
Gui selection for the Unit of the initial covariance for the attitude angles.
static KeyedMatrix< double, KFStates, KFStates, 17, 17 > n_systemNoiseCovarianceMatrix_Q(const Eigen::Vector3d &sigma2_ra, const Eigen::Vector3d &sigma2_rg, const Eigen::Vector3d &sigma2_bad, const Eigen::Vector3d &sigma2_bgd, const double &sigma_heightBias, const double &sigma_heightScale, const Eigen::Vector3d &tau_bad, const Eigen::Vector3d &tau_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const Eigen::Matrix3d &n_Dcm_b, const double &tau_s)
System noise covariance matrix 𝐐_{k-1}.
InitCovarianceBiasHeightUnit _initCovarianceBiasHeightUnit
Gui selection for the Unit of the initial covariance for the height bias.
InsTime insTime
Time at which the message was received.
Definition NodeData.hpp:123
ImVec2 _guiConfigDefaultWindowSize
Definition Node.hpp:522
Node(std::string name)
Constructor.
Definition Node.cpp:29
std::vector< InputPin > inputPins
List of input pins.
Definition Node.hpp:509
OutputPin * CreateOutputPin(const char *name, Pin::Type pinType, const std::vector< std::string > &dataIdentifier, OutputPin::PinData data=static_cast< void * >(nullptr), int idx=-1)
Create an Output Pin object.
Definition Node.cpp:278
std::string nameId() const
Node name and id.
Definition Node.cpp:323
std::string name
Name of the Node.
Definition Node.hpp:507
InputPin * CreateInputPin(const char *name, Pin::Type pinType, const std::vector< std::string > &dataIdentifier={}, InputPin::Callback callback=static_cast< InputPin::FlowFirableCallbackFunc >(nullptr), InputPin::FlowFirableCheckFunc firable=nullptr, int priority=0, int idx=-1)
Create an Input Pin object.
Definition Node.cpp:252
void invokeCallbacks(size_t portIndex, const std::shared_ptr< const NodeData > &data)
Calls all registered callbacks on the specified output port.
Definition Node.cpp:179
bool DeleteInputPin(size_t pinIndex)
Deletes the input pin. Invalidates the pin reference given.
Definition Node.cpp:310
bool _hasConfig
Flag if the config window should be shown.
Definition Node.hpp:525
std::vector< std::string > dataIdentifier
One or multiple Data Identifiers (Unique name which is used for data flows)
Definition Pin.hpp:305
Position, Velocity and Attitude Storage Class.
Definition PosVelAtt.hpp:25
void setPosVelAtt_n(const Eigen::MatrixBase< DerivedP > &lla_position, const Eigen::MatrixBase< DerivedV > &n_velocity, const Eigen::QuaternionBase< DerivedA > &n_Quat_b)
Set the position, velocity and attitude.
void setPosVelAttAndCov_n(const Eigen::MatrixBase< DerivedP > &lla_position, const Eigen::MatrixBase< DerivedV > &n_velocity, const Eigen::QuaternionBase< DerivedA > &n_Quat_b, const Eigen::MatrixBase< Derived > &n_covarianceMatrix)
Set the position, velocity, attitude and the covariance matrix.
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
Eigen::Vector3d rollPitchYaw() const
Returns the Roll, Pitch and Yaw angles in [rad].
const Eigen::Quaterniond & e_Quat_b() const
Returns the Quaternion from body to Earth-fixed frame.
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
const Eigen::Vector3d & e_velocity() const
Returns the velocity in [m/s], in earth coordinates.
Definition PosVel.hpp:208
std::optional< std::reference_wrapper< const KeyedMatrixXd< Keys::MotionModelKey, Keys::MotionModelKey > > > e_CovarianceMatrix() const
Returns the Covariance matrix in ECEF frame.
Definition Pos.hpp:272
const Eigen::Vector3d & e_position() const
Returns the coordinates in [m].
Definition Pos.hpp:249
auto & front()
Returns a reference to the first element in the container.
Definition TsDeque.hpp:198
auto extract_front()
Returns a copy of the first element in the container and removes it from the container.
Definition TsDeque.hpp:494
bool empty() const noexcept
Checks if the container has no elements, i.e. whether 'begin() == end()'.
Definition TsDeque.hpp:275
static float windowFontRatio()
Ratio to multiply for GUI window elements.
decltype(auto) middleCols(std::span< const ColKeyType > colKeys) const
Gets the values for the col keys.
decltype(auto) block(std::span< const RowKeyType > rowKeys, std::span< const ColKeyType > colKeys) const
Gets the values for the row and col keys.
decltype(auto) middleRows(std::span< const RowKeyType > rowKeys) const
Gets the values for the row keys.
ImGui extensions.
Matrix< double, 6, 6 > Matrix6d
Double 6x6 Eigen::Matrix.
Definition Eigen.hpp:37
Matrix< double, 9, 9 > Matrix9d
Double 9x9 Eigen::Matrix.
Definition Eigen.hpp:40
bool InputIntL(const char *label, int *v, int v_min, int v_max, int step, int step_fast, ImGuiInputTextFlags flags)
Shows a value limited InputText GUI element for 'int'.
Definition imgui_ex.cpp:242
bool DragDouble(const char *label, double *v, float v_speed, double v_min, double v_max, const char *format, ImGuiSliderFlags flags)
Shows a Drag GUI element for 'double'.
Definition imgui_ex.cpp:19
constexpr std::array< StateKeyType, 3 > Pos
All position keys.
constexpr std::array< StateKeyType, 6 > PosVel
Vector with all position and velocity keys.
constexpr std::array< StateKeyType, 3 > Vel
All velocity keys.
bool NodeDataTypeAnyIsChildOf(const std::vector< std::string > &childTypes, const std::vector< std::string > &parentTypes)
Checks if any of the provided child types is a child of any of the provided parent types.
void ApplyChanges()
Signals that there have been changes to the flow.
InputWithUnitChange InputDoubleWithUnit(const char *label, float itemWidth, float unitWidth, double *v, U &combo_current_item, const char *combo_items_separated_by_zeros, double step=0.0, double step_fast=0.0, const char *format="%.6f", ImGuiInputTextFlags flags=0, int combo_popup_max_height_in_items=-1)
Shows an InputText GUI element to modify the provided value and also set its unit.
@ InputWithUnitChange_Unit
The Unit changed.
@ InputWithUnitChange_Input
The Input changed.
InputWithUnitChange InputDouble3WithUnit(const char *label, float itemWidth, float unitWidth, double v[3], U &combo_current_item, const char *combo_items_separated_by_zeros, const char *format="%.6f", ImGuiInputTextFlags flags=0, int combo_popup_max_height_in_items=-1)
Shows an InputText GUI element to modify the provided value and also set its unit.
void from_json(const json &j, DynamicInputPins &obj, Node *node)
Converts the provided json object into a node object.
void HelpMarker(const char *desc, const char *symbol="(?)")
Text Help Marker, e.g. '(?)', with Tooltip.
InputWithUnitChange InputDouble3LWithUnit(const char *label, float itemWidth, float unitWidth, double v[3], double v_min, double v_max, U &combo_current_item, const char *combo_items_separated_by_zeros, const char *format="%.6f", ImGuiInputTextFlags flags=0, int combo_popup_max_height_in_items=-1)
Shows an InputText GUI element to modify the provided value and also set its unit.
Eigen::Matrix< typename Derived::Scalar, 3, 3 > skewSymmetricMatrix(const Eigen::MatrixBase< Derived > &a)
Calculates the skew symmetric matrix of the given vector. This is needed to perform the cross product...
Definition Math.hpp:99
Eigen::Vector3< typename Derived::Scalar > ecef2lla_WGS84(const Eigen::MatrixBase< Derived > &e_position)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.
Eigen::Quaternion< Scalar > e_Quat_n(const Scalar &latitude, const Scalar &longitude)
Quaternion for rotations from navigation to Earth-fixed frame.
Eigen::Matrix< typename Derived::Scalar, 4, 3 > covRPY2quatJacobian(const Eigen::QuaternionBase< Derived > &n_quat_b)
Calculates the Jacobian to convert an attitude represented in Euler angels (roll, pitch,...
Eigen::Vector3< typename Derived::Scalar > quat2eulerZYX(const Eigen::QuaternionBase< Derived > &q)
Converts the quaternion to Euler rotation angles with rotation sequence ZYX.
Eigen::Vector3< typename DerivedA::Scalar > ned2ecef(const Eigen::MatrixBase< DerivedA > &n_position, const Eigen::MatrixBase< DerivedB > &lla_position_ref)
Converts local NED coordinates into ECEF coordinates.
Eigen::Vector3< typename Derived::Scalar > lla2ecef_WGS84(const Eigen::MatrixBase< Derived > &lla_position)
Converts latitude, longitude and altitude into Earth-centered-Earth-fixed coordinates using WGS84.
Eigen::Quaternion< Scalar > n_Quat_b(Scalar roll, Scalar pitch, Scalar yaw)
Quaternion for rotations from body to navigation frame.
KeyedMatrixX< T, KeyType, KeyType > e_systemMatrix_F(const Eigen::Vector3d &ps_f_ip, const Eigen::Vector3d &ps_omega_ip, const Eigen::Quaterniond &b_quat_p, const Eigen::Vector3< T > &e_gravitation, const T &r_eS_e, std::optional< double > tau_bad, std::optional< double > tau_bgd, const Eigen::Vector3< T > &e_position, const Eigen::Quaternion< T > &e_quat_b, const Eigen::Vector3< T > &p_accelBias, const Eigen::Vector3< T > &p_gyroBias, const Eigen::Vector3< T > &p_accelScale, const Eigen::Vector3< T > &p_gyroScale, const Eigen::Quaternion< T > &p_quatAccel_ps, const Eigen::Quaternion< T > &p_quatGyro_ps, const PosVelAttDerivativeConstants &config, bool accelBiases, bool gyroBiases, bool accelScaleFactor, bool gyroScaleFactor, bool accelMisalignment, bool gyroMisalignment)
Calculate the linearized system matrix in Earth frame coordinates.
@ GPST
GPS Time.
Eigen::Matrix3d n_F_dv_df(const Eigen::Matrix3d &n_Dcm_b)
Calculates the matrix 𝐅_𝜓'_𝛿f.
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dv_df_b(const Eigen::MatrixBase< Derived > &e_Dcm_b)
Calculates the matrix 𝐅_𝜓'_𝛿f_b.
Eigen::Matrix3d ie_Q_dr_domega(const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const Eigen::Matrix3d &ie_Dcm_b, const double &tau_s)
Submatrix 𝐐_35 of the system noise covariance matrix 𝐐
Eigen::Matrix3d n_F_dpsi_dr(double latitude, double height, const Eigen::Vector3d &n_velocity, double R_N, double R_E)
Calculates the matrix 𝐅_𝜓'_𝛿r.
Eigen::Matrix3d ie_Q_dr_df(const Eigen::Vector3d &S_bad, const Eigen::Matrix3d &ie_Dcm_b, const double &tau_s)
Submatrix 𝐐_34 of the system noise covariance matrix 𝐐
Eigen::Matrix3< T > e_F_dr_dv()
Calculates the matrix 𝐅_𝛿r'_𝛿v.
Eigen::Matrix3d n_F_dpsi_dv(double latitude, double height, double R_N, double R_E)
Calculates the matrix 𝐅_𝜓'_𝛿v.
Eigen::Matrix3d Q_domega_psi(const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &b_Dcm_ien, const double &tau_s)
Submatrix 𝐐_51 of the system noise covariance matrix 𝐐
Eigen::Matrix3d Q_df_df(const Eigen::Vector3d &S_bad, const double &tau_s)
Submatrix 𝐐_44 of the system noise covariance matrix 𝐐
Scalar calcEarthRadius_N(const Scalar &latitude, const Scalar &a=InsConst::WGS84::a, const Scalar &e_squared=InsConst::WGS84::e_squared)
Calculates the North/South (meridian) earth radius.
Definition Ellipsoid.hpp:42
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
Eigen::Vector3< typename DerivedA::Scalar > n_calcTransportRate(const Eigen::MatrixBase< DerivedA > &lla_position, const Eigen::MatrixBase< DerivedB > &n_velocity, const auto &R_N, const auto &R_E)
Calculates the transport rate ω_en_n (rotation rate of the Earth frame relative to the navigation fra...
Definition Functions.hpp:39
Eigen::Matrix3d n_F_dr_dv(double latitude, double height, double R_N, double R_E)
Calculates the matrix 𝐅_𝛿r'_𝛿v.
Eigen::Matrix3d ien_Q_dv_dv(const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ien_F_21, const double &tau_s)
Submatrix 𝐐_22 of the system noise covariance matrix 𝐐
bool InertialIntegratorGui(const char *label, InertialIntegrator &integrator, bool &preferAccelerationOverDeltaMeasurements, float width)
Shows a GUI for advanced configuration of the InertialIntegrator.
Eigen::Matrix< typename Derived1::Scalar, 3, 3 > e_F_dv_dr(const Eigen::MatrixBase< Derived1 > &e_position, const Eigen::MatrixBase< Derived2 > &e_gravitation, const T &r_eS_e, const Eigen::Vector3d &e_omega_ie)
Calculates the matrix 𝐅_𝛿v'_𝛿r.
Eigen::Matrix3< T > e_F_dv_dv(double omega_ie)
Calculates the matrix 𝐅_𝛿v'_𝛿v.
Eigen::Matrix3d ie_Q_dr_psi(const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const double &tau_s)
Submatrix 𝐐_31 of the system noise covariance matrix 𝐐
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dw_dw(const Eigen::MatrixBase< Derived > &beta_omega)
Calculates the matrix 𝐅_𝛿ω'_𝛿ω
Eigen::Matrix3d n_F_dv_dr(const Eigen::Vector3d &n_velocity, double latitude, double height, double R_N, double R_E, double g_0, double r_eS_e)
Calculates the matrix 𝐅_𝛿v'_𝛿r.
Eigen::Matrix3d n_Q_dr_dv(const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const double &tau_s)
Submatrix 𝐐_32 of the system noise covariance matrix 𝐐
Eigen::Matrix3d n_F_dpsi_dw(const Eigen::Matrix3d &n_Dcm_b)
Calculates the matrix 𝐅_𝜓'_𝛿ω
Eigen::Matrix3d n_F_dw_dw(const Eigen::Vector3d &beta_omega)
Calculates the matrix 𝐅_𝛿ω'_𝛿ω
Scalar calcGeocentricRadius(const Scalar &latitude, const Scalar &R_E, const Scalar &e_squared=InsConst::WGS84::e_squared)
r_eS^e The distance of a point on the Earth's surface from the center of the Earth
Definition Ellipsoid.hpp:29
Eigen::Matrix3d n_F_dv_dpsi(const Eigen::Vector3d &n_force_ib)
Calculates the matrix 𝐅_𝛿v'_𝜓
Eigen::Matrix3d Q_df_dv(const Eigen::Vector3d &S_bad, const Eigen::Matrix3d &b_Dcm_ien, const double &tau_s)
Submatrix 𝐐_42 of the system noise covariance matrix 𝐐
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dv_dpsi(const Eigen::MatrixBase< Derived > &e_force_ib)
Calculates the matrix 𝐅_𝛿v'_𝜓
Eigen::Matrix3d Q_psi_psi(const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const double &tau_s)
Submatrix 𝐐_11 of the system noise covariance matrix 𝐐
Eigen::Matrix3d n_Q_dr_df(const Eigen::Vector3d &S_bad, const Eigen::Matrix3d &T_rn_p, const Eigen::Matrix3d &n_Dcm_b, const double &tau_s)
Submatrix 𝐐_34 of the system noise covariance matrix 𝐐
Eigen::Vector3d psd2BiasGaussMarkov(const Eigen::Vector3d &sigma2_bd, const Eigen::Vector3d &tau_bd)
u_bias^2 Power Spectral Density of the bias for a Gauss-Markov random process
Eigen::Matrix3< T > e_F_dpsi_dpsi(const T &omega_ie)
Calculates the matrix 𝐅_𝜓'_𝜓
double convertUnit(const double &value, Units::PositionUncertaintyUnits unit)
Converts the value depending on the unit provided.
Definition Units.cpp:135
Eigen::Matrix3d n_F_df_df(const Eigen::Vector3d &beta_a)
Calculates the matrix 𝐅_𝛿f'_𝛿f.
Eigen::Matrix3d n_F_dpsi_dpsi(const Eigen::Vector3d &n_omega_in)
Calculates the matrix 𝐅_𝜓'_𝜓
Eigen::Vector3< typename Derived::Scalar > n_calcGravitation_EGM96(const Eigen::MatrixBase< Derived > &lla_position, size_t ndegree=10)
Calculates the gravitation (acceleration due to mass attraction of the Earth) at the WGS84 reference ...
Definition Gravity.hpp:137
Eigen::Matrix3d Q_domega_domega(const Eigen::Vector3d &S_bgd, const double &tau_s)
Submatrix 𝐐_55 of the system noise covariance matrix 𝐐
constexpr auto deg2rad(const T &deg)
Convert Degree to Radians.
Definition Units.hpp:21
Eigen::Matrix3d n_F_dr_dr(const Eigen::Vector3d &n_velocity, double latitude, double height, double R_N, double R_E)
Calculates the matrix 𝐅_𝛿r'_𝛿r.
Eigen::Matrix3d n_Q_dr_psi(const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const double &tau_s)
Submatrix 𝐐_31 of the system noise covariance matrix 𝐐
std::string MakeComboItems()
Units separated by '\0' and terminated by double '\0'.
static const internal::all_t all
Used to request all rows or columns in KeyedMatrices.
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_dpsi_dw(const Eigen::MatrixBase< Derived > &e_Dcm_b)
Calculates the matrix 𝐅_𝜓'_𝛿ω
Eigen::Matrix3d ie_Q_dr_dv(const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const double &tau_s)
Submatrix 𝐐_32 of the system noise covariance matrix 𝐐
Eigen::Matrix3d n_Q_dr_domega(const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const Eigen::Matrix3d &n_Dcm_b, const double &tau_s)
Submatrix 𝐐_35 of the system noise covariance matrix 𝐐
Eigen::Matrix3d ien_Q_dv_psi(const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ien_F_21, const double &tau_s)
Submatrix 𝐐_21 of the system noise covariance matrix 𝐐
Eigen::Matrix3d ie_Q_dr_dr(const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const double &tau_s)
Submatrix 𝐐_33 of the system noise covariance matrix 𝐐
Eigen::Matrix3< typename Derived::Scalar > conversionMatrixCartesianCurvilinear(const Eigen::MatrixBase< Derived > &lla_position, const typename Derived::Scalar &R_N, const typename Derived::Scalar &R_E)
Conversion matrix between cartesian and curvilinear perturbations to the position.
Definition Ellipsoid.hpp:71
Eigen::Matrix3d n_Q_dr_dr(const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const double &tau_s)
Submatrix 𝐐_33 of the system noise covariance matrix 𝐐
Eigen::Matrix< typename Derived::Scalar, 3, 3 > e_F_df_df(const Eigen::MatrixBase< Derived > &beta_a)
Calculates the matrix 𝐅_𝛿f'_𝛿f.
Eigen::Matrix3d n_F_dv_dv(const Eigen::Vector3d &n_velocity, double latitude, double height, double R_N, double R_E)
Calculates the matrix 𝐅_𝛿v'_𝛿v.
std::ostream & operator<<(std::ostream &os, const SatelliteSystem &satSys)
Stream insertion operator overload.
Eigen::Matrix3d ien_Q_dv_domega(const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ien_F_21, const Eigen::Matrix3d &ien_Dcm_b, const double &tau_s)
Submatrix 𝐐_25 of the system noise covariance matrix 𝐐
constexpr auto rad2deg(const T &rad)
Convert Radians to Degree.
Definition Units.hpp:39
Scalar calcEarthRadius_E(const Scalar &latitude, const Scalar &a=InsConst::WGS84::a, const Scalar &e_squared=InsConst::WGS84::e_squared)
Calculates the East/West (prime vertical) earth radius.
Definition Ellipsoid.hpp:58
Type of the data on the Pin.
Definition Pin.hpp:47
@ Flow
NodeData Trigger.
Definition Pin.hpp:52