Optimize correct

This commit is contained in:
Milo Priegnitz
2024-07-15 17:25:15 +02:00
committed by dario
parent ee10ce1189
commit d5914f2d1c
3 changed files with 13 additions and 12 deletions

View File

@@ -2,6 +2,7 @@
#include <sta/math/linalg/linalg.hpp>
#include <sta/debug/debug.hpp>
#include <sta/debug/assert.hpp>
#include <sta/debug/profile.hpp>
namespace sta
{
@@ -30,9 +31,9 @@ KalmanState KalmanFilter::predict(KalmanState state, matrix u)
{
// Predict step implementation
// Update the state based on the system dynamics
state.x = F_ * state.x + B_ * u;
state.x = (F_ * state.x) + (B_ * u);
// Update the error covariance matrix
state.error = F_ * state.error * F_.T() + Q_;
state.error = F_ *( state.error * F_.T()) + Q_;
return state;
}
@@ -40,11 +41,13 @@ KalmanState KalmanFilter::correct(KalmanState state, matrix z)
{
// Correct step implementation
// Calculate the Kalman gain
matrix K = state.error * H_.T() * linalg::inv(H_ * state.error * H_.T() + R_);
K.show_serial();
matrix K;
{
K = state.error * H_.T() * linalg::inv(H_ * state.error * H_.T() + R_);
}
// Update the state based on the measurement
state.x = state.x + K * (z - H_ * state.x); //TODO check transpose
state.x.show_serial();
// Update the error covariance matrix
state.error = (identity_ - K * H_) * state.error;
return state;
@@ -55,12 +58,11 @@ KalmanState KalmanFilter::correct(KalmanState state, matrix z, matrix H, matrix
// Correct step implementation
// Calculate the Kalman gain
matrix K = state.error * H.T() * linalg::inv(H * state.error * H.T() + R);
K.show_serial();
// Update the state based on the measurement
state.x = state.x + K * (z - H * state.x); //TODO check transpose
state.x.show_serial();
// Update the error covariance matrix
state.error = (matrix::eye(state.x.get_rows()) - K * H) * state.error;
//state.error = (matrix::eye(state.x.get_rows()) - K * H) * state.error;
state.error = (identity_ - K * H) * state.error;
return state;
}