mirror of
https://git.intern.spaceteamaachen.de/ALPAKA/sta-peak.git
synced 2025-06-11 18:35:59 +00:00
Optimize correct
This commit is contained in:
parent
918ca9ef9c
commit
ca62dab64c
@ -78,7 +78,7 @@ public:
|
||||
* @param R The measurement noise covariance matrix.
|
||||
* @return The corrected state of the Kalman filter.
|
||||
*/
|
||||
static KalmanState correct(KalmanState state, matrix z, matrix H, matrix R);
|
||||
KalmanState correct(KalmanState state, matrix z, matrix H, matrix R);
|
||||
};
|
||||
|
||||
} // namespace math
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include <cmath>
|
||||
#include <sta/debug/debug.hpp>
|
||||
#include <sta/debug/assert.hpp>
|
||||
#include <sta/debug/profile.hpp>
|
||||
|
||||
namespace sta{
|
||||
|
||||
@ -13,7 +14,6 @@ namespace linalg {
|
||||
|
||||
|
||||
matrix dot(matrix a, matrix b) {
|
||||
|
||||
STA_ASSERT_MSG(a.get_cols() == b.get_rows(), "Matrix dimension mismatch");
|
||||
|
||||
uint8_t k = a.get_cols();
|
||||
@ -115,7 +115,6 @@ matrix skew_symmetric(matrix m) {
|
||||
|
||||
};
|
||||
matrix add(matrix a, matrix b) {
|
||||
|
||||
STA_ASSERT_MSG( a.get_rows() == b.get_rows() && a.get_cols() == b.get_cols(), "Matrix dimensions mismatch!" );
|
||||
|
||||
matrix output = a.clone();
|
||||
@ -138,7 +137,7 @@ matrix subtract(matrix a, matrix b) {
|
||||
return output;
|
||||
};
|
||||
matrix dot(matrix m, float s) {
|
||||
|
||||
|
||||
float size = m.get_size();
|
||||
|
||||
matrix output = m.clone();
|
||||
|
Loading…
x
Reference in New Issue
Block a user