kalman.cpp
Go to the documentation of this file.
1 
8 #include <iostream>
9 #include <stdexcept>
10 
11 #include "kalman.hpp"
12 
14  double dt,
15  const Eigen::MatrixXd& A,
16  const Eigen::MatrixXd& C,
17  const Eigen::MatrixXd& Q,
18  const Eigen::MatrixXd& R,
19  const Eigen::MatrixXd& P)
20  : A(A), C(C), Q(Q), R(R), P0(P),
21  m(C.rows()), n(A.rows()), dt(dt), initialized(false),
22  I(n, n), x_hat(n), x_hat_new(n)
23 {
24  I.setIdentity();
25 }
26 
28 
29 void KalmanFilter::init(double t0, const Eigen::VectorXd& x0) {
30  x_hat = x0;
31  P = P0;
32  this->t0 = t0;
33  t = t0;
34  initialized = true;
35 
36 }
37 
39  x_hat.setZero();
40  P = P0;
41  t0 = 0;
42  t = t0;
43  initialized = true;
44 }
45 
46 void KalmanFilter::update(const Eigen::VectorXd& y) {
47 
48  if(!initialized)
49  throw std::runtime_error("Filter is not initialized!");
50 
51  x_hat_new = A * x_hat;
52  P = A*P*A.transpose() + Q;
53  K = P*C.transpose()*(C*P*C.transpose() + R).inverse();
54 
55  x_hat_new += K * (y - C*x_hat_new);
56  P = (I - K*C)*P;
57  x_hat = x_hat_new;
58 
59  t += dt;
60 }
61 
62 void KalmanFilter::changeStates(const Eigen::VectorXd& new_states) {
63 
64  if(!initialized)
65  throw std::runtime_error("Filter is not initialized!");
66  if(x_hat.size() != new_states.size())
67  throw std::runtime_error("State vectors do not have the same size");
68  x_hat = new_states;
69 }
70 
71 void KalmanFilter::update(const Eigen::VectorXd& y, double dt, const Eigen::MatrixXd A) {
72 
73  this->A = A;
74  this->dt = dt;
75  update(y);
76 }
77 
78 void KalmanFilter::update(const Eigen::VectorXd& y, double dt) {
79 
80  this->dt = dt;
81  update(y);
82 }
83 
84 
Eigen::MatrixXd C
Definition: kalman.hpp:28
Eigen::MatrixXd Q
Definition: kalman.hpp:28
Eigen::VectorXd x_hat
Definition: kalman.hpp:94
bool initialized
Definition: kalman.hpp:88
Eigen::MatrixXd I
Definition: kalman.hpp:91
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
void init()
Definition: kalman.cpp:38
double t
Definition: kalman.hpp:82
Eigen::VectorXd x_hat_new
Definition: kalman.hpp:94
Eigen::MatrixXd K
Definition: kalman.hpp:28
KalmanFilter()
Definition: kalman.cpp:27
double dt
Definition: kalman.hpp:85
void changeStates(const Eigen::VectorXd &new_states)
Definition: kalman.cpp:62
Eigen::MatrixXd P
Definition: kalman.hpp:28
Eigen::MatrixXd A
Definition: kalman.hpp:28
void update(const Eigen::VectorXd &y)
Definition: kalman.cpp:46
Eigen::MatrixXd R
Definition: kalman.hpp:28
Eigen::MatrixXd P0
Definition: kalman.hpp:28
double t0
Definition: kalman.hpp:82


datmo
Author(s): Kostas Konstantinidis
autogenerated on Tue May 2 2023 02:58:06