#include <kfilter.hpp>
Inheritance diagram for Kalman::KFilter< T, BEG, OQ, OVR, DBG >:
Public Types | |
typedef T | type |
Type of objects contained in matrices and vectors. | |
typedef KVector< T, BEG, DBG > | Vector |
Vector type. | |
typedef KMatrix< T, BEG, DBG > | Matrix |
Matrix type. | |
enum | { beg = BEG } |
Public Member Functions | |
virtual | ~KFilter ()=0 |
Virtual destructor. | |
void | init (Vector &x_, Matrix &P_) |
Sets initial conditions for the Kalman Filter. | |
Dimension Accessor Functions | |
K_UINT_32 | getSizeX () const |
Returns the size of the state vector. | |
K_UINT_32 | getSizeU () const |
Returns the size of the input vector. | |
K_UINT_32 | getSizeW () const |
Returns the size of the process noise vector. | |
K_UINT_32 | getSizeZ () const |
Returns the size of the measurement vector. | |
K_UINT_32 | getSizeV () const |
Returns the size of the measurement noise vector. | |
Resizing Functions | |
These functions allow to change the dimensions of all matrices and vectors, thus implementing a Variable-Dimension Extended Kalman Filter. They do nothing if the new size is the same as the old one.
| |
void | setDim (K_UINT_32 n_, K_UINT_32 nu_, K_UINT_32 nw_, K_UINT_32 m_, K_UINT_32 nv_) |
Sets all dimensions at once. | |
void | setSizeX (K_UINT_32 n_) |
Sets the size of the state vector. | |
void | setSizeU (K_UINT_32 nu_) |
Sets the size of the input vector. | |
void | setSizeW (K_UINT_32 nw_) |
Sets the size of the process noise vector. | |
void | setSizeZ (K_UINT_32 m_) |
Sets the size of the measurement vector. | |
void | setSizeV (K_UINT_32 nv_) |
Sets the size of the measurement noise vector. | |
Kalman Filter Functions | |
These functions allow to get the results from the Kalman filtering algorithm. Before any of these can be called, all dimensions must have been set properly at least once and init() must have been called, also at least once. Each time the user want to resize some vectors, the corresponding resizing functions must be called again before being able to call one of the functions in this section. init() must also be called again if n or nw has changed. init() can also be called solely to reset the filter. | |
void | step (Vector &u_, const Vector &z_) |
Makes one prediction-correction step. | |
void | timeUpdateStep (Vector &u_) |
Makes one prediction step. | |
void | measureUpdateStep (const Vector &z_) |
Makes one correction step. | |
const Vector & | predict (Vector &u_) |
Returns the predicted state vector (a priori state estimate). | |
const Vector & | simulate () |
Returns the predicted measurement vector. | |
const Vector & | getX () const |
Returns the corrected state (a posteriori state estimate). | |
const Matrix & | calculateP () const |
Returns the a posteriori error covariance estimate matrix. | |
Protected Member Functions | |
virtual void | makeBaseB () |
Virtual pre-creator of B. | |
virtual void | makeB () |
Virtual creator of B. | |
void | NoModification () |
Allows optimizations on some calculations. | |
Matrix Pre-Creators | |
Theses functions have been designed to be overridden by derived classes if necessary. Their role is to fill in the parts of the Kalman matrices that don't change between iterations. That is to say, these functions should only set constant values inside matrices that don't depend on x or u. They will all be called at least once, before the calls to their corresponding matrix (not pre-) creators. In fact, they are called once per resize (not necessarily at the moment of the resize though), including while the matrices are first allocated.
| |
virtual void | makeBaseA () |
Virtual pre-creator of A. | |
virtual void | makeBaseW () |
Virtual pre-creator of W. | |
virtual void | makeBaseQ () |
Virtual pre-creator of Q. | |
virtual void | makeBaseH () |
Virtual pre-creator of H. | |
virtual void | makeBaseV () |
Virtual pre-creator of V. | |
virtual void | makeBaseR () |
Virtual pre-creator of R. | |
Matrix Creators | |
Theses functions have been designed to be overridden by derived classes if necessary. Their role is to fill in the parts of the Kalman matrices that change between iterations. That is to say, these functions should set values inside matrices that depend on x or u.
These functions can suppose that their corresponding matrix pre-creator has been called at least once before. Also,
| |
virtual void | makeCommonProcess () |
Optional function used to precalculate common values for process. | |
virtual void | makeA () |
Virtual creator of A. | |
virtual void | makeW () |
Virtual creator of W. | |
virtual void | makeQ () |
Virtual creator of Q. | |
virtual void | makeCommonMeasure () |
Optional function used to precalculate common values for measurement. | |
virtual void | makeH () |
Virtual creator of H. | |
virtual void | makeV () |
Virtual creator of V. | |
virtual void | makeR () |
Virtual creator of R. | |
virtual void | makeDZ () |
Hook-up function to modify innovation vector. | |
Protected Attributes | |
Matrix | B |
Input matrix. | |
Kalman Vectors and Matrices | |
Vector | x |
Corrected state vector. | |
Vector | u |
Input vector. | |
Vector | z |
Predicted measurement vector. | |
Vector | dz |
Innovation vector. | |
Matrix | A |
A jacobian matrix. | |
Matrix | W |
A jacobian matrix. | |
Matrix | Q |
Process noise covariance matrix. | |
Matrix | H |
A jacobian matrix. | |
Matrix | V |
A jacobian matrix. | |
Matrix | R |
Measurement noise covariance matrix. | |
Kalman Dimensions | |
| |
K_UINT_32 | n |
Size of the state vector. | |
K_UINT_32 | nu |
Size of the input vector. | |
K_UINT_32 | nw |
Size of the process noise vector. | |
K_UINT_32 | m |
Size of the measurement vector. | |
K_UINT_32 | nv |
Size of the measurement noise vector. |
EKFilter
. You should really read all the documentation of EKFilter
before reading this. EKFilter
template class.
where is the (known) input vector fed to the process and is the (unknown) process noise vector due to uncertainty and process modeling errors. Further suppose that the (known) process noise covariance matrix is :
Now, let's assume a (known) measurement vector , which depends on the current state in the form of a linear function (to model) :
where is the (unknown) measurement noise vector with a (known) covariance matrix :
Suppose that we have an estimate of the previous state , called a corrected state or an a posteriori state estimate. We can build a predicted state (also called an a priori state estimate) by using :
since the input is known and the process noise, unknown. With this predicted state, we can get a predicted measurement vector by using :
since the measurement noise is unknown.
makeProcess()
and makeMeasure()
have already been overridden, and cannot be ovverridden again. However, there is a new matrix to create : B. This means there are two new virtual functions that can be overridden : makeBaseB()
and makeB()
. EKFilter
|
|
|
Sets all dimensions at once.
This function simply calls the
|
|
Sets the size of the state vector.
|
|
Sets the size of the process noise vector.
|
|
Sets initial conditions for the Kalman Filter. This function allows to set an initial state estimate vector and an initial error covariance matrix estimate. This must be called at least once, after all dimensioning functions and before any other function. However, it can also be called anytime to reset or modify x or P.
|
|
Makes one prediction-correction step.
This is the main
|
|
Makes one prediction step.
This function first resizes any matrix who needs it. Then, it proceeds to the time update phase, using the input vector
|
|
Makes one correction step.
First, this function resizes any matrix who needs it. If
|
|
Returns the predicted state vector (a priori state estimate).
This function is used to predict a future state. First, it resizes any matrix who needs it. Then, it does a partial time update, in the sense that only x is updated, not P. This also means that only the following virtual functions should be called :
|
|
Returns the predicted measurement vector.
This function is used to predict a future measurement. First, it resizes any matrix who needs it. Then, it does a partial measure update, in the sense that only z is calculated : x and P are not updated. This also means that only the following virtual functions should be called :
|
|
Returns the a posteriori error covariance estimate matrix.
|
|
Allows optimizations on some calculations.
By default, the EKFilter template class suppose that matrix pre-creators and creators modify all matrices. However, if it could suppose that some of these functions do not modify anything, some calculations could be optimized away. The |
|
Virtual pre-creator of Q.
|
|
Virtual pre-creator of V.
|
|
Virtual pre-creator of R.
|
|
Optional function used to precalculate common values for process.
If complex calculations are needed for more than one of
|
|
Virtual creator of Q.
|
|
Optional function used to precalculate common values for measurement.
If complex calculations are needed for more than one of
|
|
Virtual creator of V.
|
|
Virtual creator of R.
|
|
Hook-up function to modify innovation vector. This function should rarely be overridden ; this is more of a hack than anything else. In fact, this is used to perform adjustements on the result of substracting the predicted measurement vector to the real measurement vector. This is needed, for example, when measures include angles. It may be mandatory that the difference of the two angles be in a certain range, like . |
|
Corrected state vector.
This is an n-sized vector. Derived classes should modify it only through |
|
Input vector. This is an nu-sized vector. Derived classes should never modify it. |
|
Predicted measurement vector.
This is an m-sized vector. Derived classes should modify it only through |
|
Innovation vector.
This is an m-sized vector. Derived classes should modify it only through |
|
A jacobian matrix. This is an n by n jacobian matrix of partial derivatives, defined as follow :
Derived classes should modify it only through |
|
A jacobian matrix. This is an n by nw jacobian matrix of partial derivatives, defined as follow :
Derived classes should modify it only through |
|
Process noise covariance matrix. This is the nw by nw covariance matrix of w, that is :
Derived classes should modify it only through |
|
A jacobian matrix. This is an m by n jacobian matrix of partial derivatives, defined as follow :
Derived classes should modify it only through |
|
A jacobian matrix. This is an m by nv jacobian matrix of partial derivatives, defined as follow :
Derived classes should modify it only through |
|
Measurement noise covariance matrix. This is the nv by nv covariance matrix of v, that is :
Derived classes should modify it only through |