state-observation 1.7.0
Loading...
Searching...
No Matches
linear-kalman-filter.hpp
Go to the documentation of this file.
1
20#ifndef STATEOBSERVER_LINEARKALMANFILTERHPP
21#define STATEOBSERVER_LINEARKALMANFILTERHPP
22
23#include <state-observation/api.h>
25
26namespace stateObservation
27{
28
48{
49public:
55
58
60 typedef Matrix Bmatrix;
61
63 typedef Matrix Dmatrix;
64
66 virtual void setB(const Bmatrix & B);
67
69 virtual void clearB();
70
72 virtual void setD(const Dmatrix & D);
73
75 virtual void clearD();
76
79
82
85
87 bool checkBmatrix(const Bmatrix &) const;
88
91
94
97
99 bool checkDmatrix(const Dmatrix &) const;
100
104 virtual void setStateSize(Index n);
105
109 virtual void setMeasureSize(Index m);
110
114 virtual void setInputSize(Index p);
115
116protected:
119
122
125
128
129public:
131};
132
133} // namespace stateObservation
134
135#endif // STATEOBSERVER_LINEARKALMANFILTERHPP
It mostly implements the equations of Kalman filtering It is suitablle by derivation to be used incas...
Definition kalman-filter-base.hpp:51
The class of a Linear Kalman filter.
Definition linear-kalman-filter.hpp:48
virtual void setD(const Dmatrix &D)
Set the value of the input-measurement matrix.
virtual void setB(const Bmatrix &B)
Set the value of the input-state matrix.
Matrix d_
The container of the Input-State matrix.
Definition linear-kalman-filter.hpp:124
Dmatrix getDmatrixConstant(double c) const
Get a matrix having the size of the D matrix having "c" values.
virtual void clearB()
Clear the value of the input-state Matrix.
bool checkDmatrix(const Dmatrix &) const
checks whether or not a matrix has the dimensions of the D matrix
LinearKalmanFilter(Index n, Index m, Index p=0)
Definition linear-kalman-filter.hpp:54
Dmatrix getDmatrixRandom() const
Get a matrix having the size of the D matrix having random values.
Bmatrix getBmatrixZero() const
Get a matrix having the size of the B matrix having zero values.
Bmatrix getBmatrixRandom() const
Get a matrix having the size of the B matrix having random values.
virtual void clearD()
Clear the value of the input-measurement matrix.
virtual void setMeasureSize(Index m)
virtual StateVector prediction_(TimeIndex k)
The implementation of the (linear) prediction (state dynamics)
Dmatrix getDmatrixZero() const
Get a matrix having the size of the D matrix having zero values.
virtual void setStateSize(Index n)
Matrix Bmatrix
The type of the matrix linking the input to the state.
Definition linear-kalman-filter.hpp:60
LinearKalmanFilter()
Default constructor.
Definition linear-kalman-filter.hpp:57
virtual void setInputSize(Index p)
virtual MeasureVector simulateSensor_(const StateVector &x, TimeIndex k)
The implementation of the (linear) measurement (state dynamics)
bool checkBmatrix(const Bmatrix &) const
checks whether or not a matrix has the dimensions of the B matrix
Bmatrix getBmatrixConstant(double c) const
Get a matrix having the size of the B matrix having "c" values.
Matrix Dmatrix
The type of the matrix linking the input to the measurement.
Definition linear-kalman-filter.hpp:63
Matrix b_
The container of the Input-Measurement matrix.
Definition linear-kalman-filter.hpp:127
Vector StateVector
StateVector is the type of state vector.
Definition observer-base.hpp:42
Vector MeasureVector
MeasureVector is the type of measurements vector.
Definition observer-base.hpp:45
Defines the base class of a Kalman filter.
Definition bidim-elastic-inv-pendulum-dyn-sys.hpp:21
long int TimeIndex
Definition definitions.hpp:139
Eigen::MatrixXd Matrix
Dynamic sized Matrix.
Definition definitions.hpp:100
Eigen::Index Index
Definition definitions.hpp:138