16#include <boost/math/distributions/chi_squared.hpp>
35template<
typename Scalar,
typename StateKeyType,
typename MeasKeyType>
45 KeyedKalmanFilter(
const std::vector<StateKeyType>& stateKeys,
const std::vector<MeasKeyType>& measKeys)
47 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
49 std::unordered_set<MeasKeyType> measSet = { measKeys.begin(), measKeys.end() };
52 auto n =
static_cast<int>(stateKeys.size());
53 auto m =
static_cast<int>(measKeys.size());
68 I = Eigen::MatrixX<Scalar>::Identity(n, n);
75 P(all, all).setZero();
76 F(all, all).setZero();
77 Phi(all, all).setZero();
78 G(all, all).setZero();
79 W(all, all).setZero();
80 Q(all, all).setZero();
82 H(all, all).setZero();
83 R(all, all).setZero();
84 S(all, all).setZero();
85 K(all, all).setZero();
94 x(all) =
Phi(all, all) *
x(all);
97 P(all, all) =
Phi(all, all) *
P(all, all) *
Phi(all, all).transpose() +
Q(all, all);
106 S(all, all) =
H(all, all) *
P(all, all) *
H(all, all).transpose() +
R(all, all);
109 K(all, all) =
P(all, all) *
H(all, all).transpose() *
S(all, all).inverse();
112 x(all) =
x(all) +
K(all, all) * (
z(all) -
H(all, all) *
x(all));
115 P(all, all) = (I -
K(all, all) *
H(all, all)) *
P(all, all);
125 S(all, all) =
H(all, all) *
P(all, all) *
H(all, all).transpose() +
R(all, all);
128 K(all, all) =
P(all, all) *
H(all, all).transpose() *
S(all, all).inverse();
131 x(all) =
x(all) +
K(all, all) *
z(all);
137 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();
142 [[nodiscard]]
bool hasState(
const StateKeyType& stateKey)
const {
return x.hasRow(stateKey); }
145 [[nodiscard]]
bool hasStates(
const std::vector<StateKeyType>& stateKeys)
const {
return x.hasStates(stateKeys); }
148 [[nodiscard]]
bool hasAnyStates(
const std::vector<StateKeyType>& stateKeys)
const {
return x.hasAnyStates(stateKeys); }
156 void addStates(
const std::vector<StateKeyType>& stateKeys)
158 INS_ASSERT_USER_ERROR(!
x.hasAnyRows(stateKeys),
"You cannot add a state key which is already in the Kalman filter.");
159 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
162 auto n =
x(all).rows() +
static_cast<int>(stateKeys.size());
164 x.addRows(stateKeys);
165 P.addRowsCols(stateKeys, stateKeys);
166 F.addRowsCols(stateKeys, stateKeys);
167 Phi.addRowsCols(stateKeys, stateKeys);
168 G.addRowsCols(stateKeys, stateKeys);
169 W.addRowsCols(stateKeys, stateKeys);
170 Q.addRowsCols(stateKeys, stateKeys);
171 H.addCols(stateKeys);
172 K.addRows(stateKeys);
173 I = Eigen::MatrixX<Scalar>::Identity(n, n);
184 INS_ASSERT_USER_ERROR(
x.hasRows(stateKeys),
"Not all state keys you are trying to remove are in the Kalman filter.");
185 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
188 auto n =
x.rows() -
static_cast<int>(stateKeys.size());
190 x.removeRows(stateKeys);
191 P.removeRowsCols(stateKeys, stateKeys);
192 F.removeRowsCols(stateKeys, stateKeys);
193 Phi.removeRowsCols(stateKeys, stateKeys);
194 G.removeRowsCols(stateKeys, stateKeys);
195 W.removeRowsCols(stateKeys, stateKeys);
196 Q.removeRowsCols(stateKeys, stateKeys);
197 H.removeCols(stateKeys);
198 K.removeRows(stateKeys);
199 I = Eigen::MatrixX<Scalar>::Identity(n, n);
205 void replaceState(
const StateKeyType& oldKey,
const StateKeyType& newKey)
207 x.replaceRowKey(oldKey, newKey);
208 P.replaceRowKey(oldKey, newKey);
209 P.replaceColKey(oldKey, newKey);
210 F.replaceRowKey(oldKey, newKey);
211 F.replaceColKey(oldKey, newKey);
212 Phi.replaceRowKey(oldKey, newKey);
213 Phi.replaceColKey(oldKey, newKey);
214 G.replaceRowKey(oldKey, newKey);
215 G.replaceColKey(oldKey, newKey);
216 W.replaceRowKey(oldKey, newKey);
217 W.replaceColKey(oldKey, newKey);
218 Q.replaceRowKey(oldKey, newKey);
219 Q.replaceColKey(oldKey, newKey);
220 H.replaceColKey(oldKey, newKey);
221 K.replaceRowKey(oldKey, newKey);
228 std::unordered_set<MeasKeyType> measSet = { measKeys.begin(), measKeys.end() };
231 auto n =
static_cast<int>(
x.rows());
232 auto m =
static_cast<int>(measKeys.size());
234 const auto& stateKeys =
x.rowKeys();
251 INS_ASSERT_USER_ERROR(
z.hasRows(measKeys),
"Not all measurement keys you are trying to remove are in the Kalman filter.");
252 std::unordered_set<MeasKeyType> measurementSet = { measKeys.begin(), measKeys.end() };
253 INS_ASSERT_USER_ERROR(measurementSet.size() == measKeys.size(),
"Each measurement key must be unique");
255 z.removeRows(measKeys);
256 H.removeRows(measKeys);
257 R.removeRowsCols(measKeys, measKeys);
258 S.removeRowsCols(measKeys, measKeys);
259 K.removeCols(measKeys);
282 INS_ASSERT_USER_ERROR(
F.rowKeys() ==
Phi.rowKeys(),
"The system model matrix F and the state transition matrix ๐ฝ need to have the same keys.");
293 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 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)");
304 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.");
305 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.");
308 this->
Phi(all, all) =
Phi;
309 this->
Q(all, all) =
Q;
318 INS_ASSERT_USER_ERROR(!_savedPreUpdate.
saved,
"Cannot save the pre-update without restoring or discarding the old one first.");
319 _savedPreUpdate.
saved =
true;
321 _savedPreUpdate.
x =
x;
322 _savedPreUpdate.
P =
P;
323 _savedPreUpdate.
Phi =
Phi;
324 _savedPreUpdate.
Q =
Q;
325 _savedPreUpdate.
z =
z;
326 _savedPreUpdate.
H =
H;
327 _savedPreUpdate.
R =
R;
328 _savedPreUpdate.
S =
S;
329 _savedPreUpdate.
K =
K;
331 _savedPreUpdate.
F =
F;
332 _savedPreUpdate.
G =
G;
333 _savedPreUpdate.
W =
W;
340 _savedPreUpdate.
saved =
false;
342 x = _savedPreUpdate.
x;
343 P = _savedPreUpdate.
P;
344 Phi = _savedPreUpdate.
Phi;
345 Q = _savedPreUpdate.
Q;
346 z = _savedPreUpdate.
z;
347 H = _savedPreUpdate.
H;
348 R = _savedPreUpdate.
R;
349 S = _savedPreUpdate.
S;
350 K = _savedPreUpdate.
K;
352 F = _savedPreUpdate.
F;
353 G = _savedPreUpdate.
G;
354 W = _savedPreUpdate.
W;
360 _savedPreUpdate.
saved =
false;
384 if (
z.rows() == 0) {
return ret; }
385 S(all, all) =
H(all, all) *
P(all, all) *
H(all, all).transpose() +
R(all, all);
387 ret.NIS = std::abs(
z(all).transpose() *
S(all, all).inverse() *
z(all));
389 boost::math::chi_squared dist(
static_cast<double>(
z.rows()));
391 ret.r2 = boost::math::quantile(dist, 1.0 - _alphaNIS);
393 ret.triggered = ret.NIS >= ret.r2;
397 LOG_DEBUG(
"{}: NIS test triggered because: NIS = {:.3f} > {:.3f} = r2", nameId, ret.NIS, ret.r2);
401 LOG_DATA(
"{}: NIS test passed: NIS = {:.3f} <= {:.3f} = r2", nameId, ret.NIS, ret.r2);
413 bool changed =
false;
415 changed |= ImGui::Checkbox(fmt::format(
"Enable outlier NIS check##{}",
id).c_str(), &_checkNIS);
417 gui::widgets::HelpMarker(
"If the check has too many false positives, try increasing the process noise.");
421 double alpha = _alphaNIS * 100.0;
422 ImGui::SetNextItemWidth(width - ImGui::GetStyle().IndentSpacing);
423 if (ImGui::DragDouble(fmt::format(
"NIS alpha (failure rate)##{}",
id).c_str(), &alpha, 1.0F, 0.0, 100.0,
"%.2f %%"))
425 _alphaNIS = alpha / 100.0;
438 ImGui::PushFont(Application::MonoFont());
439 float matrixTableHeight = ImGui::GetTextLineHeightWithSpacing() *
static_cast<float>(nRows + 1);
440 float vectorTableHeight = ImGui::GetTextLineHeightWithSpacing() *
static_cast<float>(nRows);
443 if (ImGui::TreeNode(fmt::format(
"x - State vector##{}",
id).c_str()))
445 gui::widgets::KeyedVectorView(fmt::format(
"Kalman Filter x##{}",
id).c_str(), &
x, vectorTableHeight);
448 if (ImGui::TreeNode(fmt::format(
"P - Error covariance matrix##{}",
id).c_str()))
450 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter P##{}",
id).c_str(), &
P, matrixTableHeight);
453 if (ImGui::TreeNode(fmt::format(
"Phi - State transition matrix##{}",
id).c_str()))
455 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter Phi##{}",
id).c_str(), &
Phi, matrixTableHeight);
458 if (ImGui::TreeNode(fmt::format(
"Q System/Process noise covariance matrix##{}",
id).c_str()))
460 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter Q##{}",
id).c_str(), &
Q, matrixTableHeight);
463 if (ImGui::TreeNode(fmt::format(
"z - Measurement vector##{}",
id).c_str()))
465 gui::widgets::KeyedVectorView(fmt::format(
"Kalman Filter z##{}",
id).c_str(), &
z, vectorTableHeight);
468 if (ImGui::TreeNode(fmt::format(
"H - Measurement sensitivity matrix##{}",
id).c_str()))
470 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter H##{}",
id).c_str(), &
H, matrixTableHeight);
473 if (ImGui::TreeNode(fmt::format(
"R - Measurement noise covariance matrix##{}",
id).c_str()))
475 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter R##{}",
id).c_str(), &
R, matrixTableHeight);
478 if (ImGui::TreeNode(fmt::format(
"S - Measurement prediction covariance matrix##{}",
id).c_str()))
480 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter S##{}",
id).c_str(), &
S, matrixTableHeight);
483 if (ImGui::TreeNode(fmt::format(
"K - Kalman gain matrix##{}",
id).c_str()))
485 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter K##{}",
id).c_str(), &
K, matrixTableHeight);
488 if (ImGui::TreeNode(fmt::format(
"F - System model matrix##{}",
id).c_str()))
490 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter F##{}",
id).c_str(), &
F, matrixTableHeight);
493 if (ImGui::TreeNode(fmt::format(
"G - Noise input matrix##{}",
id).c_str()))
495 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter G##{}",
id).c_str(), &
G, matrixTableHeight);
498 if (ImGui::TreeNode(fmt::format(
"W - Noise scale matrix##{}",
id).c_str()))
500 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter W##{}",
id).c_str(), &
W, matrixTableHeight);
531 SavedPreUpdate _savedPreUpdate;
534 bool _checkNIS =
true;
537 double _alphaNIS = 0.05;
545 {
"checkNIS", obj._checkNIS },
546 {
"alphaNIS", obj._alphaNIS },
554 if (j.contains(
"checkNIS")) { j.at(
"checkNIS").get_to(obj._checkNIS); }
555 if (j.contains(
"alphaNIS")) { j.at(
"alphaNIS").get_to(obj._alphaNIS); }
562template<
typename StateKeyType,
typename MeasKeyType>
570template<
typename Scalar,
typename RowKeyType,
typename ColKeyType,
int Rows,
int Cols>
571KeyedMatrix<Scalar, RowKeyType, ColKeyType, Rows, Cols> transitionMatrix_Phi_Taylor(
const KeyedMatrix<Scalar, RowKeyType, ColKeyType, Rows, Cols>& F, Scalar tau_s,
size_t order)
574 Eigen::Matrix<Scalar, Rows, Cols> Phi;
576 if constexpr (Rows == Eigen::Dynamic)
578 Phi = Eigen::Matrix<Scalar, Rows, Cols>::Identity(F.
rows(), F.
cols());
582 Phi = Eigen::Matrix<Scalar, Rows, Cols>::Identity();
586 for (
size_t i = 1; i <= order; i++)
588 Eigen::Matrix<Scalar, Rows, Cols> Fpower = F(all, all);
591 for (
size_t j = 1; j < i; j++)
594 Fpower *= F(all, all);
598 Phi += (Fpower * std::pow(tau_s, i)) / math::factorial(i);
610template<
typename Scalar,
typename RowKeyType,
typename ColKeyType,
int Rows,
int Cols>
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
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.
#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
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
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:37
KeyedMatrixX< Scalar, MeasKeyType, StateKeyType > H
๐ Measurement sensitivity matrix (m x n)
Definition KeyedKalmanFilter.hpp:267
bool showKalmanFilterGUI(const char *id, float width=0.0F)
Shows GUI elements for the Kalman Filter.
Definition KeyedKalmanFilter.hpp:411
void calcPhiAndQWithVanLoanMethod(Scalar dt)
Numerical Method to calculate the State transition matrix ๐ฝ and System/Process noise covariance matri...
Definition KeyedKalmanFilter.hpp:301
void replaceState(const StateKeyType &oldKey, const StateKeyType &newKey)
Replace the old with the new key.
Definition KeyedKalmanFilter.hpp:205
KeyedVectorX< Scalar, MeasKeyType > z
๐ณ Measurement vector (m x 1)
Definition KeyedKalmanFilter.hpp:266
void discardPreUpdate()
Discards the saved xฬ, ๐, ๐ณ, ๐, ๐ a-priori (pre-update)
Definition KeyedKalmanFilter.hpp:357
bool isPreUpdateSaved() const
Whether a pre-update was saved.
Definition KeyedKalmanFilter.hpp:313
bool hasState(const StateKeyType &stateKey) const
Checks if the filter has the key.
Definition KeyedKalmanFilter.hpp:142
void removeState(const StateKeyType &stateKey)
Remove a state from the filter.
Definition KeyedKalmanFilter.hpp:178
friend void from_json(const json &j, KeyedKalmanFilter< Scalar, StateKeyType, MeasKeyType > &obj)
Converts the provided json object into a node object.
Definition KeyedKalmanFilter.hpp:552
auto checkForOutliersNIS(const std::string &nameId)
Performs the Normalized Innovation Squared (NIS) test on the measurement innovation ๐น๐ณ
Definition KeyedKalmanFilter.hpp:381
void setMeasurements(const std::vector< MeasKeyType > &measKeys)
Sets the measurement keys and initializes matrices z, H, R, S, K with Zero.
Definition KeyedKalmanFilter.hpp:226
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > S
๐ฆ Measurement prediction covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:269
KeyedMatrixX< Scalar, StateKeyType, MeasKeyType > K
๐ Kalman gain matrix (n x m)
Definition KeyedKalmanFilter.hpp:270
friend void to_json(json &j, const KeyedKalmanFilter< Scalar, StateKeyType, MeasKeyType > &obj)
Converts the provided object into json.
Definition KeyedKalmanFilter.hpp:542
KeyedVectorX< Scalar, StateKeyType > x
xฬ State vector (n x 1)
Definition KeyedKalmanFilter.hpp:262
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > W
๐ Noise scale matrix (o x o)
Definition KeyedKalmanFilter.hpp:274
bool hasStates(const std::vector< StateKeyType > &stateKeys) const
Checks if the filter has the keys.
Definition KeyedKalmanFilter.hpp:145
KeyedKalmanFilter(const std::vector< StateKeyType > &stateKeys, const std::vector< MeasKeyType > &measKeys)
Constructor.
Definition KeyedKalmanFilter.hpp:45
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > F
๐
System model matrix (n x n)
Definition KeyedKalmanFilter.hpp:272
void removeMeasurement(const MeasKeyType &measKey)
Remove a measurement from the filter.
Definition KeyedKalmanFilter.hpp:245
void showKalmanFilterMatrixViews(const char *id, int nRows=-2)
Shows ImGui Tree nodes for all matrices.
Definition KeyedKalmanFilter.hpp:436
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Q
๐ System/Process noise covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:265
void addState(const StateKeyType &stateKey)
Add a new state to the filter.
Definition KeyedKalmanFilter.hpp:152
bool hasAnyStates(const std::vector< StateKeyType > &stateKeys) const
Checks if the filter has any of the provided keys.
Definition KeyedKalmanFilter.hpp:148
void restorePreUpdate()
Restores the saved xฬ, ๐, ๐ณ, ๐, ๐ a-priori (pre-update)
Definition KeyedKalmanFilter.hpp:337
void removeMeasurements(const std::vector< MeasKeyType > &measKeys)
Remove measurements from the filter.
Definition KeyedKalmanFilter.hpp:249
void setZero()
Sets all Vectors and matrices to 0.
Definition KeyedKalmanFilter.hpp:72
void addStates(const std::vector< StateKeyType > &stateKeys)
Add new states to the filter.
Definition KeyedKalmanFilter.hpp:156
void correctWithMeasurementInnovation()
Do a Measurement Update with a Measurement Innovation ๐น๐ณ
Definition KeyedKalmanFilter.hpp:123
void predict()
Do a Time Update.
Definition KeyedKalmanFilter.hpp:91
void removeStates(const std::vector< StateKeyType > &stateKeys)
Remove states from the filter.
Definition KeyedKalmanFilter.hpp:182
bool isNISenabled() const
Whether the NIS check should be performed.
Definition KeyedKalmanFilter.hpp:364
void calcTransitionMatrix_Phi_exp(Scalar tau)
Calculates the state transition matrix ๐ฝ using the exponential matrix.
Definition KeyedKalmanFilter.hpp:291
void calcTransitionMatrix_Phi_Taylor(Scalar tau, size_t order)
Calculates the state transition matrix ๐ฝ limited to specified order in ๐
๐โ
Definition KeyedKalmanFilter.hpp:280
void savePreUpdate()
Saves xฬ, ๐, ๐ณ, ๐, ๐ a-priori (pre-update)
Definition KeyedKalmanFilter.hpp:316
void correct()
Do a Measurement Update with a Measurement ๐ณ
Definition KeyedKalmanFilter.hpp:104
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Phi
๐ฝ State transition matrix (n x n)
Definition KeyedKalmanFilter.hpp:264
KeyedKalmanFilter()=default
Default Constructor.
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > R
๐ = ๐ธ{๐ฐโ๐ฐโแต} Measurement noise covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:268
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > P
๐ Error covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:263
const SavedPreUpdate & savedPreUpdate() const
Accesses the saved pre-update matrices.
Definition KeyedKalmanFilter.hpp:526
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > G
๐ Noise input matrix (n x o)
Definition KeyedKalmanFilter.hpp:273
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
Normalized Innovation Squared (NIS) test results.
Definition KeyedKalmanFilter.hpp:368
double NIS
Normalized Innovation Squared (NIS)
Definition KeyedKalmanFilter.hpp:370
bool triggered
Whether the test triggered.
Definition KeyedKalmanFilter.hpp:369
double r2
Upper boundary of one-sided acceptance interval.
Definition KeyedKalmanFilter.hpp:371
Saved pre-update state and measurement.
Definition KeyedKalmanFilter.hpp:507
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > F
๐
System model matrix (n x n)
Definition KeyedKalmanFilter.hpp:520
KeyedMatrixX< Scalar, MeasKeyType, StateKeyType > H
๐ Measurement sensitivity matrix (m x n)
Definition KeyedKalmanFilter.hpp:515
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Q
๐ System/Process noise covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:513
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > G
๐ Noise input matrix (n x o)
Definition KeyedKalmanFilter.hpp:521
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > P
๐ Error covariance matrix (n x n)
Definition KeyedKalmanFilter.hpp:511
KeyedMatrixX< Scalar, StateKeyType, MeasKeyType > K
Definition KeyedKalmanFilter.hpp:518
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > Phi
๐ฝ State transition matrix (n x n)
Definition KeyedKalmanFilter.hpp:512
bool saved
Flag whether the state was saved.
Definition KeyedKalmanFilter.hpp:508
KeyedVectorX< Scalar, MeasKeyType > z
๐ณ Measurement vector (m x 1)
Definition KeyedKalmanFilter.hpp:514
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > R
๐ = ๐ธ{๐ฐโ๐ฐโแต} Measurement noise covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:516
KeyedMatrixX< Scalar, StateKeyType, StateKeyType > W
๐ Noise scale matrix (o x o)
Definition KeyedKalmanFilter.hpp:522
KeyedVectorX< Scalar, StateKeyType > x
xฬ State vector (n x 1)
Definition KeyedKalmanFilter.hpp:510
KeyedMatrixX< Scalar, MeasKeyType, MeasKeyType > S
๐ฆ Measurement prediction covariance matrix (m x m)
Definition KeyedKalmanFilter.hpp:517
Matrix which can be accessed by keys.