16#include <boost/math/distributions/chi_squared.hpp>
36template<
typename Scalar,
typename StateKeyType,
typename MeasKeyType>
46 KeyedKalmanFilter(
const std::vector<StateKeyType>& stateKeys,
const std::vector<MeasKeyType>& measKeys)
48 std::unordered_set<StateKeyType> stateSet = { stateKeys.begin(), stateKeys.end() };
50 std::unordered_set<MeasKeyType> measSet = { measKeys.begin(), measKeys.end() };
53 auto n =
static_cast<int>(stateKeys.size());
54 auto m =
static_cast<int>(measKeys.size());
69 I = Eigen::MatrixX<Scalar>::Identity(n, n);
46 KeyedKalmanFilter(
const std::vector<StateKeyType>& stateKeys,
const std::vector<MeasKeyType>& measKeys) {
…}
76 P(all, all).setZero();
77 F(all, all).setZero();
78 Phi(all, all).setZero();
79 G(all, all).setZero();
80 W(all, all).setZero();
81 Q(all, all).setZero();
83 H(all, all).setZero();
84 R(all, all).setZero();
85 S(all, all).setZero();
86 K(all, all).setZero();
95 x(all) =
Phi(all, all) *
x(all);
98 P(all, all) =
Phi(all, all) *
P(all, all) *
Phi(all, all).transpose() +
Q(all, all);
107 S(all, all) =
H(all, all) *
P(all, all) *
H(all, all).transpose() +
R(all, all);
110 K(all, all) =
P(all, all) *
H(all, all).transpose() *
S(all, all).inverse();
113 x(all) =
x(all) +
K(all, all) * (
z(all) -
H(all, all) *
x(all));
116 P(all, all) = (
I -
K(all, all) *
H(all, all)) *
P(all, all);
126 S(all, all) =
H(all, all) *
P(all, all) *
H(all, all).transpose() +
R(all, all);
129 K(all, all) =
P(all, all) *
H(all, all).transpose() *
S(all, all).inverse();
132 x(all) =
x(all) +
K(all, all) *
z(all);
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();
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); }
157 void addStates(
const std::vector<StateKeyType>& stateKeys)
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() };
163 auto n =
x(all).rows() +
static_cast<int>(stateKeys.size());
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);
157 void addStates(
const std::vector<StateKeyType>& stateKeys) {
…}
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() };
189 auto n =
x.rows() -
static_cast<int>(stateKeys.size());
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);
206 void replaceState(
const StateKeyType& oldKey,
const StateKeyType& newKey)
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);
206 void replaceState(
const StateKeyType& oldKey,
const StateKeyType& newKey) {
…}
229 std::unordered_set<MeasKeyType> measSet = { measKeys.begin(), measKeys.end() };
232 auto n =
static_cast<int>(
x.rows());
233 auto m =
static_cast<int>(measKeys.size());
235 const auto& stateKeys =
x.rowKeys();
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");
258 R.addRowsCols(measKeys, measKeys);
259 S.addRowsCols(measKeys, measKeys);
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");
275 z.removeRows(measKeys);
276 H.removeRows(measKeys);
277 R.removeRowsCols(measKeys, measKeys);
278 S.removeRowsCols(measKeys, measKeys);
279 K.removeCols(measKeys);
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.");
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.");
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.");
328 this->
Phi(all, all) =
Phi;
329 this->
Q(all, all) =
Q;
404 if (
z.rows() == 0) {
return ret; }
405 S(all, all) =
H(all, all) *
P(all, all) *
H(all, all).transpose() +
R(all, all);
407 ret.NIS = std::abs(
z(all).transpose() *
S(all, all).inverse() *
z(all));
409 boost::math::chi_squared dist(
static_cast<double>(
z.rows()));
411 ret.r2 = boost::math::quantile(dist, 1.0 -
_alphaNIS);
413 ret.triggered = ret.NIS >= ret.r2;
417 LOG_TRACE(
"{}: NIS test triggered because: NIS = {:.3f} > {:.3f} = r2", nameId, ret.NIS, ret.r2);
421 LOG_DATA(
"{}: NIS test passed: NIS = {:.3f} <= {:.3f} = r2", nameId, ret.NIS, ret.r2);
433 bool changed =
false;
435 changed |= ImGui::Checkbox(fmt::format(
"Enable outlier NIS check##{}",
id).c_str(), &
_checkNIS);
437 gui::widgets::HelpMarker(
"If the check has too many false positives, try increasing the process noise.");
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 %%"))
458 ImGui::PushFont(Application::MonoFont());
459 float matrixTableHeight = ImGui::GetTextLineHeightWithSpacing() *
static_cast<float>(nRows + 1);
460 float vectorTableHeight = ImGui::GetTextLineHeightWithSpacing() *
static_cast<float>(nRows);
463 if (ImGui::TreeNode(fmt::format(
"x - State vector##{}",
id).c_str()))
465 gui::widgets::KeyedVectorView(fmt::format(
"Kalman Filter x##{}",
id).c_str(), &
x, vectorTableHeight);
468 if (ImGui::TreeNode(fmt::format(
"P - Error covariance matrix##{}",
id).c_str()))
470 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter P##{}",
id).c_str(), &
P, matrixTableHeight);
473 if (ImGui::TreeNode(fmt::format(
"Phi - State transition matrix##{}",
id).c_str()))
475 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter Phi##{}",
id).c_str(), &
Phi, matrixTableHeight);
478 if (ImGui::TreeNode(fmt::format(
"Q System/Process noise covariance matrix##{}",
id).c_str()))
480 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter Q##{}",
id).c_str(), &
Q, matrixTableHeight);
483 if (ImGui::TreeNode(fmt::format(
"z - Measurement vector##{}",
id).c_str()))
485 gui::widgets::KeyedVectorView(fmt::format(
"Kalman Filter z##{}",
id).c_str(), &
z, vectorTableHeight);
488 if (ImGui::TreeNode(fmt::format(
"H - Measurement sensitivity matrix##{}",
id).c_str()))
490 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter H##{}",
id).c_str(), &
H, matrixTableHeight);
493 if (ImGui::TreeNode(fmt::format(
"R - Measurement noise covariance matrix##{}",
id).c_str()))
495 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter R##{}",
id).c_str(), &
R, matrixTableHeight);
498 if (ImGui::TreeNode(fmt::format(
"S - Measurement prediction covariance matrix##{}",
id).c_str()))
500 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter S##{}",
id).c_str(), &
S, matrixTableHeight);
503 if (ImGui::TreeNode(fmt::format(
"K - Kalman gain matrix##{}",
id).c_str()))
505 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter K##{}",
id).c_str(), &
K, matrixTableHeight);
508 if (ImGui::TreeNode(fmt::format(
"F - System model matrix##{}",
id).c_str()))
510 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter F##{}",
id).c_str(), &
F, matrixTableHeight);
513 if (ImGui::TreeNode(fmt::format(
"G - Noise input matrix##{}",
id).c_str()))
515 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter G##{}",
id).c_str(), &
G, matrixTableHeight);
518 if (ImGui::TreeNode(fmt::format(
"W - Noise scale matrix##{}",
id).c_str()))
520 gui::widgets::KeyedMatrixView(fmt::format(
"Kalman Filter W##{}",
id).c_str(), &
W, matrixTableHeight);
574 if (j.contains(
"checkNIS")) { j.at(
"checkNIS").get_to(obj.
_checkNIS); }
575 if (j.contains(
"alphaNIS")) { j.at(
"alphaNIS").get_to(obj.
_alphaNIS); }
582template<
typename StateKeyType,
typename MeasKeyType>
590template<
typename Scalar,
typename RowKeyType,
typename ColKeyType,
int Rows,
int Cols>
591KeyedMatrix<Scalar, RowKeyType, ColKeyType, Rows, Cols> transitionMatrix_Phi_Taylor(
const KeyedMatrix<Scalar, RowKeyType, ColKeyType, Rows, Cols>& F, Scalar tau_s,
size_t order)
594 Eigen::Matrix<Scalar, Rows, Cols> Phi;
596 if constexpr (Rows == Eigen::Dynamic)
598 Phi = Eigen::Matrix<Scalar, Rows, Cols>::Identity(F.
rows(), F.
cols());
602 Phi = Eigen::Matrix<Scalar, Rows, Cols>::Identity();
606 for (
size_t i = 1; i <= order; i++)
608 Eigen::Matrix<Scalar, Rows, Cols> Fpower = F(all, all);
611 for (
size_t j = 1; j < i; j++)
614 Fpower *= F(all, all);
618 Phi += (Fpower * std::pow(tau_s, i)) / math::factorial(i);
591KeyedMatrix<Scalar, RowKeyType, ColKeyType, Rows, Cols> transitionMatrix_Phi_Taylor(
const KeyedMatrix<Scalar, RowKeyType, ColKeyType, Rows, Cols>& F, Scalar tau_s,
size_t order) {
…}
630template<
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.
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
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
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.