0.3.0
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Modules Pages Concepts
KeyedKalmanFilter.hpp
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
13
14#pragma once
15
16#include <boost/math/distributions/chi_squared.hpp>
17#include <imgui.h>
18
22#include "util/Eigen.hpp"
23#include "util/Json.hpp"
28#include "util/Logger.hpp"
29
30namespace NAV
31{
36template<typename Scalar, typename StateKeyType, typename MeasKeyType>
38{
39 public:
41 KeyedKalmanFilter() = default;
42
46 KeyedKalmanFilter(const std::vector<StateKeyType>& stateKeys, const std::vector<MeasKeyType>& measKeys)
47 {
48 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
49 INS_ASSERT_USER_ERROR(stateSet.size() == stateKeys.size(), "Each state key must be unique");
50 std::unordered_set<MeasKeyType> measSet = { measKeys.begin(), measKeys.end() };
51 INS_ASSERT_USER_ERROR(measSet.size() == measKeys.size(), "Each measurement key must be unique");
52
53 auto n = static_cast<int>(stateKeys.size());
54 auto m = static_cast<int>(measKeys.size());
55
56 x = KeyedVectorX<Scalar, StateKeyType>(Eigen::VectorX<Scalar>::Zero(n), stateKeys);
57 P = KeyedMatrixX<Scalar, StateKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(n, n), stateKeys);
58 F = KeyedMatrixX<Scalar, StateKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(n, n), stateKeys);
59 Phi = KeyedMatrixX<Scalar, StateKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(n, n), stateKeys);
60
61 G = KeyedMatrixX<Scalar, StateKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(n, n), stateKeys);
62 W = KeyedMatrixX<Scalar, StateKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(n, n), stateKeys);
63 Q = KeyedMatrixX<Scalar, StateKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(n, n), stateKeys);
64 z = KeyedVectorX<Scalar, MeasKeyType>(Eigen::VectorX<Scalar>::Zero(m), measKeys);
65 H = KeyedMatrixX<Scalar, MeasKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(m, n), measKeys, stateKeys);
66 R = KeyedMatrixX<Scalar, MeasKeyType, MeasKeyType>(Eigen::MatrixX<Scalar>::Zero(m, m), measKeys, measKeys);
67 S = KeyedMatrixX<Scalar, MeasKeyType, MeasKeyType>(Eigen::MatrixX<Scalar>::Zero(m, m), measKeys, measKeys);
68 K = KeyedMatrixX<Scalar, StateKeyType, MeasKeyType>(Eigen::MatrixX<Scalar>::Zero(n, m), stateKeys, measKeys);
69 I = Eigen::MatrixX<Scalar>::Identity(n, n);
70 }
71
73 void setZero()
74 {
75 x(all).setZero(); // x̂ State vector
76 P(all, all).setZero(); // 𝐏 Error covariance matrix
77 F(all, all).setZero(); // 𝐅 System model matrix (n x n)
78 Phi(all, all).setZero(); // 𝚽 State transition matrix
79 G(all, all).setZero(); // 𝐆 Noise input matrix (n x o)
80 W(all, all).setZero(); // 𝐖 Noise scale matrix (o x o)
81 Q(all, all).setZero(); // 𝐐 System/Process noise covariance matrix
82 z(all).setZero(); // 𝐳 Measurement vector
83 H(all, all).setZero(); // 𝐇 Measurement sensitivity Matrix
84 R(all, all).setZero(); // 𝐑 = 𝐸{𝐰ₘ𝐰ₘᵀ} Measurement noise covariance matrix
85 S(all, all).setZero(); // 𝗦 Measurement prediction covariance matrix
86 K(all, all).setZero(); // 𝐊 Kalman gain matrix
87 }
88
92 void predict()
93 {
94 // Math: \mathbf{\hat{x}}_k^- = \mathbf{\Phi}_{k-1}\mathbf{\hat{x}}_{k-1}^+ \qquad \text{P. Groves}\,(3.14)
95 x(all) = Phi(all, all) * x(all);
96
97 // Math: \mathbf{P}_k^- = \mathbf{\Phi}_{k-1} P_{k-1}^+ \mathbf{\Phi}_{k-1}^T + \mathbf{Q}_{k-1} \qquad \text{P. Groves}\,(3.15)
98 P(all, all) = Phi(all, all) * P(all, all) * Phi(all, all).transpose() + Q(all, all);
99 }
100
105 void correct()
106 {
107 S(all, all) = H(all, all) * P(all, all) * H(all, all).transpose() + R(all, all);
108
109 // Math: \mathbf{K}_k = \mathbf{P}_k^- \mathbf{H}_k^T (\mathbf{H}_k \mathbf{P}_k^- \mathbf{H}_k^T + R_k)^{-1} \qquad \text{P. Groves}\,(3.21)
110 K(all, all) = P(all, all) * H(all, all).transpose() * S(all, all).inverse();
111
112 // Math: x^k+=x^k+Kk(zkHkx^k)=x^k+Kkδzk \qquad \text{P. Groves}\,(3.24)
113 x(all) = x(all) + K(all, all) * (z(all) - H(all, all) * x(all));
114
115 // Math: \mathbf{P}_k^+ = (\mathbf{I} - \mathbf{K}_k \mathbf{H}_k) \mathbf{P}_k^- \qquad \text{P. Groves}\,(3.25)
116 P(all, all) = (I - K(all, all) * H(all, all)) * P(all, all);
117 }
118
125 {
126 S(all, all) = H(all, all) * P(all, all) * H(all, all).transpose() + R(all, all);
127
128 // Math: \mathbf{K}_k = \mathbf{P}_k^- \mathbf{H}_k^T (\mathbf{H}_k \mathbf{P}_k^- \mathbf{H}_k^T + R_k)^{-1} \qquad \text{P. Groves}\,(3.21)
129 K(all, all) = P(all, all) * H(all, all).transpose() * S(all, all).inverse();
130
131 // Math: x^k+=x^k+Kk(zkh(x^k))=x^k+Kkδzk \qquad \text{P. Groves}\,(3.24)
132 x(all) = x(all) + K(all, all) * z(all);
133
134 // Math: \mathbf{P}_k^+ = (\mathbf{I} - \mathbf{K}_k \mathbf{H}_k) \mathbf{P}_k^- \qquad \text{P. Groves}\,(3.25)
135 // P(all, all) = (I - K(all, all) * H(all, all)) * P(all, all);
136
137 // Math: \mathbf{P}_k^+ = (\mathbf{I} - \mathbf{K}_k \mathbf{H}_k) \mathbf{P}_k^- (\mathbf{I} - \mathbf{K}_k \mathbf{H}_k)^T + \mathbf{K}_k \mathbf{R}_k \mathbf{K}_k^T \qquad \text{Brown & Hwang}\,(p. 145, eq. 4.2.11)
138 P(all, all) = (I - K(all, all) * H(all, all)) * P(all, all) * (I - K(all, all) * H(all, all)).transpose() + K(all, all) * R(all, all) * K(all, all).transpose();
139 }
140
143 [[nodiscard]] bool hasState(const StateKeyType& stateKey) const { return x.hasRow(stateKey); }
146 [[nodiscard]] bool hasStates(const std::vector<StateKeyType>& stateKeys) const { return x.hasStates(stateKeys); }
149 [[nodiscard]] bool hasAnyStates(const std::vector<StateKeyType>& stateKeys) const { return x.hasAnyStates(stateKeys); }
150
153 void addState(const StateKeyType& stateKey) { addStates({ stateKey }); }
154
157 void addStates(const std::vector<StateKeyType>& stateKeys)
158 {
159 INS_ASSERT_USER_ERROR(!x.hasAnyRows(stateKeys), "You cannot add a state key which is already in the Kalman filter.");
160 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
161 INS_ASSERT_USER_ERROR(stateSet.size() == stateKeys.size(), "Each state key must be unique");
162
163 auto n = x(all).rows() + static_cast<int>(stateKeys.size());
164
165 x.addRows(stateKeys);
166 P.addRowsCols(stateKeys, stateKeys);
167 F.addRowsCols(stateKeys, stateKeys);
168 Phi.addRowsCols(stateKeys, stateKeys);
169 G.addRowsCols(stateKeys, stateKeys);
170 W.addRowsCols(stateKeys, stateKeys);
171 Q.addRowsCols(stateKeys, stateKeys);
172 H.addCols(stateKeys);
173 K.addRows(stateKeys);
174 I = Eigen::MatrixX<Scalar>::Identity(n, n);
175 }
176
179 void removeState(const StateKeyType& stateKey) { removeStates({ stateKey }); }
180
183 void removeStates(const std::vector<StateKeyType>& stateKeys)
184 {
185 INS_ASSERT_USER_ERROR(x.hasRows(stateKeys), "Not all state keys you are trying to remove are in the Kalman filter.");
186 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
187 INS_ASSERT_USER_ERROR(stateSet.size() == stateKeys.size(), "Each state key must be unique");
188
189 auto n = x.rows() - static_cast<int>(stateKeys.size());
190
191 x.removeRows(stateKeys);
192 P.removeRowsCols(stateKeys, stateKeys);
193 F.removeRowsCols(stateKeys, stateKeys);
194 Phi.removeRowsCols(stateKeys, stateKeys);
195 G.removeRowsCols(stateKeys, stateKeys);
196 W.removeRowsCols(stateKeys, stateKeys);
197 Q.removeRowsCols(stateKeys, stateKeys);
198 H.removeCols(stateKeys);
199 K.removeRows(stateKeys);
200 I = Eigen::MatrixX<Scalar>::Identity(n, n);
201 }
202
206 void replaceState(const StateKeyType& oldKey, const StateKeyType& newKey)
207 {
208 x.replaceRowKey(oldKey, newKey);
209 P.replaceRowKey(oldKey, newKey);
210 P.replaceColKey(oldKey, newKey);
211 F.replaceRowKey(oldKey, newKey);
212 F.replaceColKey(oldKey, newKey);
213 Phi.replaceRowKey(oldKey, newKey);
214 Phi.replaceColKey(oldKey, newKey);
215 G.replaceRowKey(oldKey, newKey);
216 G.replaceColKey(oldKey, newKey);
217 W.replaceRowKey(oldKey, newKey);
218 W.replaceColKey(oldKey, newKey);
219 Q.replaceRowKey(oldKey, newKey);
220 Q.replaceColKey(oldKey, newKey);
221 H.replaceColKey(oldKey, newKey);
222 K.replaceRowKey(oldKey, newKey);
223 }
224
227 void setMeasurements(const std::vector<MeasKeyType>& measKeys)
228 {
229 std::unordered_set<MeasKeyType> measSet = { measKeys.begin(), measKeys.end() };
230 INS_ASSERT_USER_ERROR(measSet.size() == measKeys.size(), "Each measurement key must be unique");
231
232 auto n = static_cast<int>(x.rows());
233 auto m = static_cast<int>(measKeys.size());
234
235 const auto& stateKeys = x.rowKeys();
236
237 z = KeyedVectorX<Scalar, MeasKeyType>(Eigen::VectorX<Scalar>::Zero(m), measKeys);
238 H = KeyedMatrixX<Scalar, MeasKeyType, StateKeyType>(Eigen::MatrixX<Scalar>::Zero(m, n), measKeys, stateKeys);
239 R = KeyedMatrixX<Scalar, MeasKeyType, MeasKeyType>(Eigen::MatrixX<Scalar>::Zero(m, m), measKeys, measKeys);
240 S = KeyedMatrixX<Scalar, MeasKeyType, MeasKeyType>(Eigen::MatrixX<Scalar>::Zero(m, m), measKeys, measKeys);
241 K = KeyedMatrixX<Scalar, StateKeyType, MeasKeyType>(Eigen::MatrixX<Scalar>::Zero(n, m), stateKeys, measKeys);
242 }
243
246 void addMeasurement(const MeasKeyType& measKey) { addMeasurements({ measKey }); }
247
250 void addMeasurements(const std::vector<MeasKeyType>& measKeys)
251 {
252 INS_ASSERT_USER_ERROR(!z.hasAnyRows(measKeys), "A measurement keys you are trying to add was already in the Kalman filter.");
253 std::unordered_set<MeasKeyType> measurementSet = { measKeys.begin(), measKeys.end() };
254 INS_ASSERT_USER_ERROR(measurementSet.size() == measKeys.size(), "Each measurement key must be unique");
255
256 z.addRows(measKeys);
257 H.addRows(measKeys);
258 R.addRowsCols(measKeys, measKeys);
259 S.addRowsCols(measKeys, measKeys);
260 K.addCols(measKeys);
261 }
262
265 void removeMeasurement(const MeasKeyType& measKey) { removeMeasurements({ measKey }); }
266
269 void removeMeasurements(const std::vector<MeasKeyType>& measKeys)
270 {
271 INS_ASSERT_USER_ERROR(z.hasRows(measKeys), "Not all measurement keys you are trying to remove are in the Kalman filter.");
272 std::unordered_set<MeasKeyType> measurementSet = { measKeys.begin(), measKeys.end() };
273 INS_ASSERT_USER_ERROR(measurementSet.size() == measKeys.size(), "Each measurement key must be unique");
274
275 z.removeRows(measKeys);
276 H.removeRows(measKeys);
277 R.removeRowsCols(measKeys, measKeys);
278 S.removeRowsCols(measKeys, measKeys);
279 K.removeCols(measKeys);
280 }
281
291
295
300 void calcTransitionMatrix_Phi_Taylor(Scalar tau, size_t order)
301 {
302 INS_ASSERT_USER_ERROR(F.rowKeys() == Phi.rowKeys(), "The system model matrix F and the state transition matrix 𝚽 need to have the same keys.");
303
304 Phi = transitionMatrix_Phi_Taylor(F, tau, order);
305 }
306
312 {
313 INS_ASSERT_USER_ERROR(F.rowKeys() == Phi.rowKeys(), "The system model matrix F and the state transition matrix 𝚽 need to have the same keys.");
314
316 }
317
322 {
323 INS_ASSERT_USER_ERROR(G.colKeys() == W.rowKeys(), "The columns of the noise input matrix G and rows of the noise scale matrix W must match. (G * W * G^T)");
324 INS_ASSERT_USER_ERROR(G.rowKeys() == Q.rowKeys(), "The rows of the noise input matrix G and the System/Process noise covariance matrix Q must match.");
325 INS_ASSERT_USER_ERROR(G.colKeys() == Q.colKeys(), "The cols of the noise input matrix G and the System/Process noise covariance matrix Q must match.");
326
327 auto [Phi, Q] = NAV::calcPhiAndQWithVanLoanMethod(F(all, all), G(all, all), W(all, all), dt);
328 this->Phi(all, all) = Phi;
329 this->Q(all, all) = Q;
330 }
331
333 [[nodiscard]] bool isPreUpdateSaved() const { return _savedPreUpdate.saved; }
334
337 {
338 INS_ASSERT_USER_ERROR(!_savedPreUpdate.saved, "Cannot save the pre-update without restoring or discarding the old one first.");
339 _savedPreUpdate.saved = true;
340
350
354 }
355
358 {
359 INS_ASSERT_USER_ERROR(_savedPreUpdate.saved, "Cannot restore the pre-update without saving one first.");
360 _savedPreUpdate.saved = false;
361
371
375 }
378 {
379 INS_ASSERT_USER_ERROR(_savedPreUpdate.saved, "Cannot discard the pre-update without saving one first.");
380 _savedPreUpdate.saved = false;
381 }
382
384 [[nodiscard]] bool isNISenabled() const { return _checkNIS; }
385
388 {
389 bool triggered = false;
390 double NIS = 0.0;
391 double r2 = 0.0;
392 };
393
401 [[nodiscard]] auto checkForOutliersNIS([[maybe_unused]] const std::string& nameId)
402 {
403 NISResult ret{};
404 if (z.rows() == 0) { return ret; }
405 S(all, all) = H(all, all) * P(all, all) * H(all, all).transpose() + R(all, all);
406
407 ret.NIS = std::abs(z(all).transpose() * S(all, all).inverse() * z(all));
408
409 boost::math::chi_squared dist(static_cast<double>(z.rows()));
410
411 ret.r2 = boost::math::quantile(dist, 1.0 - _alphaNIS);
412
413 ret.triggered = ret.NIS >= ret.r2;
414
415 if (ret.triggered)
416 {
417 LOG_TRACE("{}: NIS test triggered because: NIS = {:.3f} > {:.3f} = r2", nameId, ret.NIS, ret.r2);
418 }
419 else
420 {
421 LOG_DATA("{}: NIS test passed: NIS = {:.3f} <= {:.3f} = r2", nameId, ret.NIS, ret.r2);
422 }
423
424 return ret;
425 }
426
431 bool showKalmanFilterGUI(const char* id, float width = 0.0F)
432 {
433 bool changed = false;
434
435 changed |= ImGui::Checkbox(fmt::format("Enable outlier NIS check##{}", id).c_str(), &_checkNIS);
436 ImGui::SameLine();
437 gui::widgets::HelpMarker("If the check has too many false positives, try increasing the process noise.");
438
439 if (_checkNIS)
440 {
441 double alpha = _alphaNIS * 100.0;
442 ImGui::SetNextItemWidth(width - ImGui::GetStyle().IndentSpacing);
443 if (ImGui::DragDouble(fmt::format("NIS alpha (failure rate)##{}", id).c_str(), &alpha, 1.0F, 0.0, 100.0, "%.2f %%"))
444 {
445 _alphaNIS = alpha / 100.0;
446 changed = true;
447 }
448 }
449
450 return changed;
451 }
452
456 void showKalmanFilterMatrixViews(const char* id, int nRows = -2)
457 {
458 ImGui::PushFont(Application::MonoFont());
459 float matrixTableHeight = ImGui::GetTextLineHeightWithSpacing() * static_cast<float>(nRows + 1);
460 float vectorTableHeight = ImGui::GetTextLineHeightWithSpacing() * static_cast<float>(nRows);
461 ImGui::PopFont();
462
463 if (ImGui::TreeNode(fmt::format("x - State vector##{}", id).c_str()))
464 {
465 gui::widgets::KeyedVectorView(fmt::format("Kalman Filter x##{}", id).c_str(), &x, vectorTableHeight);
466 ImGui::TreePop();
467 }
468 if (ImGui::TreeNode(fmt::format("P - Error covariance matrix##{}", id).c_str()))
469 {
470 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter P##{}", id).c_str(), &P, matrixTableHeight);
471 ImGui::TreePop();
472 }
473 if (ImGui::TreeNode(fmt::format("Phi - State transition matrix##{}", id).c_str()))
474 {
475 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter Phi##{}", id).c_str(), &Phi, matrixTableHeight);
476 ImGui::TreePop();
477 }
478 if (ImGui::TreeNode(fmt::format("Q System/Process noise covariance matrix##{}", id).c_str()))
479 {
480 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter Q##{}", id).c_str(), &Q, matrixTableHeight);
481 ImGui::TreePop();
482 }
483 if (ImGui::TreeNode(fmt::format("z - Measurement vector##{}", id).c_str()))
484 {
485 gui::widgets::KeyedVectorView(fmt::format("Kalman Filter z##{}", id).c_str(), &z, vectorTableHeight);
486 ImGui::TreePop();
487 }
488 if (ImGui::TreeNode(fmt::format("H - Measurement sensitivity matrix##{}", id).c_str()))
489 {
490 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter H##{}", id).c_str(), &H, matrixTableHeight);
491 ImGui::TreePop();
492 }
493 if (ImGui::TreeNode(fmt::format("R - Measurement noise covariance matrix##{}", id).c_str()))
494 {
495 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter R##{}", id).c_str(), &R, matrixTableHeight);
496 ImGui::TreePop();
497 }
498 if (ImGui::TreeNode(fmt::format("S - Measurement prediction covariance matrix##{}", id).c_str()))
499 {
500 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter S##{}", id).c_str(), &S, matrixTableHeight);
501 ImGui::TreePop();
502 }
503 if (ImGui::TreeNode(fmt::format("K - Kalman gain matrix##{}", id).c_str()))
504 {
505 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter K##{}", id).c_str(), &K, matrixTableHeight);
506 ImGui::TreePop();
507 }
508 if (ImGui::TreeNode(fmt::format("F - System model matrix##{}", id).c_str()))
509 {
510 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter F##{}", id).c_str(), &F, matrixTableHeight);
511 ImGui::TreePop();
512 }
513 if (ImGui::TreeNode(fmt::format("G - Noise input matrix##{}", id).c_str()))
514 {
515 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter G##{}", id).c_str(), &G, matrixTableHeight);
516 ImGui::TreePop();
517 }
518 if (ImGui::TreeNode(fmt::format("W - Noise scale matrix##{}", id).c_str()))
519 {
520 gui::widgets::KeyedMatrixView(fmt::format("Kalman Filter W##{}", id).c_str(), &W, matrixTableHeight);
521 ImGui::TreePop();
522 }
523 }
524
544
546 [[nodiscard]] const SavedPreUpdate& savedPreUpdate() const { return _savedPreUpdate; }
547
548 private:
549 Eigen::MatrixXd I;
550
552
554 bool _checkNIS = true;
555
557 double _alphaNIS = 0.05;
558
563 {
564 j = json{
565 { "checkNIS", obj._checkNIS },
566 { "alphaNIS", obj._alphaNIS },
567 };
568 }
573 {
574 if (j.contains("checkNIS")) { j.at("checkNIS").get_to(obj._checkNIS); }
575 if (j.contains("alphaNIS")) { j.at("alphaNIS").get_to(obj._alphaNIS); }
576 }
577};
578
582template<typename StateKeyType, typename MeasKeyType>
584
590template<typename Scalar, typename RowKeyType, typename ColKeyType, int Rows, int Cols>
592{
593 // Transition matrix 𝚽
594 Eigen::Matrix<Scalar, Rows, Cols> Phi;
595
596 if constexpr (Rows == Eigen::Dynamic)
597 {
598 Phi = Eigen::Matrix<Scalar, Rows, Cols>::Identity(F.rows(), F.cols());
599 }
600 else
601 {
602 Phi = Eigen::Matrix<Scalar, Rows, Cols>::Identity();
603 }
604 // std::cout << "Phi = I";
605
606 for (size_t i = 1; i <= order; i++)
607 {
608 Eigen::Matrix<Scalar, Rows, Cols> Fpower = F(all, all);
609 // std::cout << " + (F";
610
611 for (size_t j = 1; j < i; j++) // F^j
612 {
613 // std::cout << "*F";
614 Fpower *= F(all, all);
615 }
616 // std::cout << "*tau_s^" << i << ")";
617 // std::cout << "/" << math::factorial(i);
618 Phi += (Fpower * std::pow(tau_s, i)) / math::factorial(i);
619 }
620 // std::cout << "\n";
621
622 return { Phi, F.rowKeys(), F.colKeys() };
623}
624
630template<typename Scalar, typename RowKeyType, typename ColKeyType, int Rows, int Cols>
632{
633 // Transition matrix 𝚽
634 return { (F(all, all) * tau_s).exp(), F.rowKeys(), F.colKeys() };
635}
636
637} // namespace NAV
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
Vector space operations.
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
Text Help Marker (?) with Tooltip.
The class is responsible for all time-related tasks.
Defines how to save certain datatypes to json.
Utility class for logging to console and file.
#define LOG_DATA
All output which occurs repeatedly every time observations are received.
Definition Logger.hpp:29
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Definition Logger.hpp:65
Derived::PlainObject transitionMatrix_Phi_exp(const Eigen::MatrixBase< Derived > &F, typename Derived::Scalar tau_s)
Calculates the state transition matrix 𝚽 using the exponential matrix.
Definition KalmanFilter.hpp:235
Derived::PlainObject transitionMatrix_Phi_Taylor(const Eigen::MatrixBase< Derived > &F, double tau_s, size_t order)
Calculates the state transition matrix 𝚽 limited to specified order in 𝐅𝜏ₛ
Definition KalmanFilter.hpp:195
Simple Math functions.
Van Loan Method loan1978.
std::pair< typename DerivedF::PlainObject, typename DerivedF::PlainObject > calcPhiAndQWithVanLoanMethod(const Eigen::MatrixBase< DerivedF > &F, const Eigen::MatrixBase< DerivedG > &G, const Eigen::MatrixBase< DerivedW > &W, typename DerivedF::Scalar dt)
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matri...
Definition VanLoan.hpp:62
Keyed Kalman Filter class.
Definition KeyedKalmanFilter.hpp:38
Eigen::MatrixXd I
𝑰 Identity matrix (n x n)
Definition KeyedKalmanFilter.hpp:549
KeyedMatrixX< Scalar, MeasKeyType, StateKeyType > H
𝐇 Measurement sensitivity matrix (m x n)
Definition KeyedKalmanFilter.hpp:287
bool showKalmanFilterGUI(const char *id, float width=0.0F)
Shows GUI elements for the Kalman Filter.
Definition KeyedKalmanFilter.hpp:431
void calcPhiAndQWithVanLoanMethod(Scalar dt)
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matri...
Definition KeyedKalmanFilter.hpp:321
void replaceState(const StateKeyType &oldKey, const StateKeyType &newKey)
Replace the old with the new key.
Definition KeyedKalmanFilter.hpp:206
bool _checkNIS
Normalized Innovation Squared (NIS) test.
Definition KeyedKalmanFilter.hpp:554
KeyedVectorX< Scalar, MeasKeyType > z
𝐳 Measurement vector (m x 1)
Definition KeyedKalmanFilter.hpp:286
void discardPreUpdate()
Discards the saved x̂, 𝐏, 𝐳, 𝐇, 𝐑 a-priori (pre-update)
Definition KeyedKalmanFilter.hpp:377
double _alphaNIS
NIS Test Hypothesis testing failure rate (probability that H_0 is accepted is (1 - alpha))
Definition KeyedKalmanFilter.hpp:557
bool isPreUpdateSaved() const
Whether a pre-update was saved.
Definition KeyedKalmanFilter.hpp:333
bool hasState(const StateKeyType &stateKey) const
Checks if the filter has the key.
Definition KeyedKalmanFilter.hpp:143
void removeState(const StateKeyType &stateKey)
Remove a state from the filter.
Definition KeyedKalmanFilter.hpp:179
friend void from_json(const json &j, KeyedKalmanFilter< Scalar, StateKeyType, MeasKeyType > &obj)
Converts the provided json object into a node object.
Definition KeyedKalmanFilter.hpp:572
auto checkForOutliersNIS(const std::string &nameId)
Performs the Normalized Innovation Squared (NIS) test on the measurement innovation 𝜹𝐳
Definition KeyedKalmanFilter.hpp:401
void setMeasurements(const std::vector< MeasKeyType > &measKeys)
Sets the measurement keys and initializes matrices z, H, R, S, K with Zero.
Definition KeyedKalmanFilter.hpp:227
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > S
𝗦 Measurement prediction covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:289
KeyedMatrixX< Scalar, StateKeyType, MeasKeyType > K
𝐊 Kalman gain matrix (n x m)
Definition KeyedKalmanFilter.hpp:290
friend void to_json(json &j, const KeyedKalmanFilter< Scalar, StateKeyType, MeasKeyType > &obj)
Converts the provided object into json.
Definition KeyedKalmanFilter.hpp:562
KeyedVectorX< Scalar, StateKeyType > x
x̂ State vector (n x 1)
Definition KeyedKalmanFilter.hpp:282
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > W
𝐖 Noise scale matrix (o x o)
Definition KeyedKalmanFilter.hpp:294
void addMeasurement(const MeasKeyType &measKey)
Add a measurement to the filter.
Definition KeyedKalmanFilter.hpp:246
bool hasStates(const std::vector< StateKeyType > &stateKeys) const
Checks if the filter has the keys.
Definition KeyedKalmanFilter.hpp:146
KeyedKalmanFilter(const std::vector< StateKeyType > &stateKeys, const std::vector< MeasKeyType > &measKeys)
Constructor.
Definition KeyedKalmanFilter.hpp:46
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > F
𝐅 System model matrix (n x n)
Definition KeyedKalmanFilter.hpp:292
void removeMeasurement(const MeasKeyType &measKey)
Remove a measurement from the filter.
Definition KeyedKalmanFilter.hpp:265
void showKalmanFilterMatrixViews(const char *id, int nRows=-2)
Shows ImGui Tree nodes for all matrices.
Definition KeyedKalmanFilter.hpp:456
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Q
𝐐 System/Process noise covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:285
void addMeasurements(const std::vector< MeasKeyType > &measKeys)
Add measurements to the filter.
Definition KeyedKalmanFilter.hpp:250
void addState(const StateKeyType &stateKey)
Add a new state to the filter.
Definition KeyedKalmanFilter.hpp:153
bool hasAnyStates(const std::vector< StateKeyType > &stateKeys) const
Checks if the filter has any of the provided keys.
Definition KeyedKalmanFilter.hpp:149
void restorePreUpdate()
Restores the saved x̂, 𝐏, 𝐳, 𝐇, 𝐑 a-priori (pre-update)
Definition KeyedKalmanFilter.hpp:357
void removeMeasurements(const std::vector< MeasKeyType > &measKeys)
Remove measurements from the filter.
Definition KeyedKalmanFilter.hpp:269
void setZero()
Sets all Vectors and matrices to 0.
Definition KeyedKalmanFilter.hpp:73
void addStates(const std::vector< StateKeyType > &stateKeys)
Add new states to the filter.
Definition KeyedKalmanFilter.hpp:157
void correctWithMeasurementInnovation()
Do a Measurement Update with a Measurement Innovation 𝜹𝐳
Definition KeyedKalmanFilter.hpp:124
void predict()
Do a Time Update.
Definition KeyedKalmanFilter.hpp:92
void removeStates(const std::vector< StateKeyType > &stateKeys)
Remove states from the filter.
Definition KeyedKalmanFilter.hpp:183
bool isNISenabled() const
Whether the NIS check should be performed.
Definition KeyedKalmanFilter.hpp:384
void calcTransitionMatrix_Phi_exp(Scalar tau)
Calculates the state transition matrix 𝚽 using the exponential matrix.
Definition KeyedKalmanFilter.hpp:311
void calcTransitionMatrix_Phi_Taylor(Scalar tau, size_t order)
Calculates the state transition matrix 𝚽 limited to specified order in 𝐅𝜏ₛ
Definition KeyedKalmanFilter.hpp:300
void savePreUpdate()
Saves x̂, 𝐏, 𝐳, 𝐇, 𝐑 a-priori (pre-update)
Definition KeyedKalmanFilter.hpp:336
void correct()
Do a Measurement Update with a Measurement 𝐳
Definition KeyedKalmanFilter.hpp:105
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Phi
𝚽 State transition matrix (n x n)
Definition KeyedKalmanFilter.hpp:284
KeyedKalmanFilter()=default
Default Constructor.
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > R
𝐑 = 𝐸{𝐰ₘ𝐰ₘᵀ} Measurement noise covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:288
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > P
𝐏 Error covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:283
const SavedPreUpdate & savedPreUpdate() const
Accesses the saved pre-update matrices.
Definition KeyedKalmanFilter.hpp:546
SavedPreUpdate _savedPreUpdate
Saved pre-update state and measurement.
Definition KeyedKalmanFilter.hpp:551
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > G
𝐆 Noise input matrix (n x o)
Definition KeyedKalmanFilter.hpp:293
Dynamic sized KeyedMatrix.
Definition KeyedMatrix.hpp:2055
Static sized KeyedMatrix.
Definition KeyedMatrix.hpp:1910
Dynamic sized KeyedVector.
Definition KeyedMatrix.hpp:1569
const std::vector< ColKeyType > & colKeys() const
Returns the col keys.
Definition KeyedMatrix.hpp:221
decltype(auto) cols() const
Return the cols of the underlying Eigen matrix.
Definition KeyedMatrix.hpp:218
decltype(auto) rows() const
Return the rows of the underlying Eigen matrix.
Definition KeyedMatrix.hpp:74
const std::vector< RowKeyType > & rowKeys() const
Returns the row keys.
Definition KeyedMatrix.hpp:77
ImGui extensions.
Widgets related to KeyedMatrices.
Normalized Innovation Squared (NIS) test results.
Definition KeyedKalmanFilter.hpp:388
double NIS
Normalized Innovation Squared (NIS)
Definition KeyedKalmanFilter.hpp:390
bool triggered
Whether the test triggered.
Definition KeyedKalmanFilter.hpp:389
double r2
Upper boundary of one-sided acceptance interval.
Definition KeyedKalmanFilter.hpp:391
Saved pre-update state and measurement.
Definition KeyedKalmanFilter.hpp:527
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > F
𝐅 System model matrix (n x n)
Definition KeyedKalmanFilter.hpp:540
KeyedMatrixX< Scalar, MeasKeyType, StateKeyType > H
𝐇 Measurement sensitivity matrix (m x n)
Definition KeyedKalmanFilter.hpp:535
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Q
𝐐 System/Process noise covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:533
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > G
𝐆 Noise input matrix (n x o)
Definition KeyedKalmanFilter.hpp:541
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > P
𝐏 Error covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:531
KeyedMatrixX< Scalar, StateKeyType, MeasKeyType > K
Definition KeyedKalmanFilter.hpp:538
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Phi
𝚽 State transition matrix (n x n)
Definition KeyedKalmanFilter.hpp:532
bool saved
Flag whether the state was saved.
Definition KeyedKalmanFilter.hpp:528
KeyedVectorX< Scalar, MeasKeyType > z
𝐳 Measurement vector (m x 1)
Definition KeyedKalmanFilter.hpp:534
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > R
𝐑 = 𝐸{𝐰ₘ𝐰ₘᵀ} Measurement noise covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:536
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > W
𝐖 Noise scale matrix (o x o)
Definition KeyedKalmanFilter.hpp:542
KeyedVectorX< Scalar, StateKeyType > x
x̂ State vector (n x 1)
Definition KeyedKalmanFilter.hpp:530
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > S
𝗦 Measurement prediction covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:537
Matrix which can be accessed by keys.