stateObservation::LinearKalmanFilter Class Reference

The class of a Linear Kalman filter. More...

#include <state-observation/observer/linear-kalman-filter.hpp>

Inheritance diagram for stateObservation::LinearKalmanFilter:
Collaboration diagram for stateObservation::LinearKalmanFilter:

Public Types

typedef Matrix Bmatrix
 The type of the matrix linking the input to the state. More...
 
typedef Matrix Dmatrix
 The type of the matrix linking the input to the measurement. More...
 
- Public Types inherited from stateObservation::KalmanFilterBase
typedef Matrix Amatrix
 The type of the jacobian df/dx. More...
 
typedef Matrix Cmatrix
 The type of the jacobian dh/dx. More...
 
typedef Matrix Qmatrix
 The type of the covariance matrix of the process noise v. More...
 
typedef Matrix Rmatrix
 The type of the covariance matrix of the measurement noise w. More...
 
typedef Matrix Pmatrix
 The type of the covariance matrix of the state estimation error. More...
 
typedef Eigen::LLT< PmatrixLLTPMatrix
 
typedef Vector StateVectorTan
 StateVector is the type of state tangent vector. More...
 
typedef Vector MeasureVectorTan
 MeasureVector is the type of measurement tanegnt vector. More...
 
- Public Types inherited from stateObservation::ObserverBase
typedef Vector StateVector
 StateVector is the type of state vector. More...
 
typedef Vector MeasureVector
 MeasureVector is the type of measurements vector. More...
 
typedef Vector InputVector
 InputVector is the type of the input vector. More...
 

Public Member Functions

 LinearKalmanFilter (Index n, Index m, Index p=0)
 
 LinearKalmanFilter ()
 Default constructor. More...
 
virtual void setB (const Bmatrix &B)
 Set the value of the input-state matrix. More...
 
virtual void clearB ()
 Clear the value of the input-state Matrix. More...
 
virtual void setD (const Dmatrix &D)
 Set the value of the input-measurement matrix. More...
 
virtual void clearD ()
 Clear the value of the input-measurement matrix. More...
 
Bmatrix getBmatrixConstant (double c) const
 Get a matrix having the size of the B matrix having "c" values. More...
 
Bmatrix getBmatrixRandom () const
 Get a matrix having the size of the B matrix having random values. More...
 
Bmatrix getBmatrixZero () const
 Get a matrix having the size of the B matrix having zero values. More...
 
bool checkBmatrix (const Bmatrix &) const
 checks whether or not a matrix has the dimensions of the B matrix More...
 
Dmatrix getDmatrixConstant (double c) const
 Get a matrix having the size of the D matrix having "c" values. More...
 
Dmatrix getDmatrixRandom () const
 Get a matrix having the size of the D matrix having random values. More...
 
Dmatrix getDmatrixZero () const
 Get a matrix having the size of the D matrix having zero values. More...
 
bool checkDmatrix (const Dmatrix &) const
 checks whether or not a matrix has the dimensions of the D matrix More...
 
virtual void setStateSize (Index n)
 
virtual void setMeasureSize (Index m)
 
virtual void setInputSize (Index p)
 
- Public Member Functions inherited from stateObservation::KalmanFilterBase
 KalmanFilterBase ()
 Default constructor. More...
 
 KalmanFilterBase (Index n, Index m, Index p=0)
 
 KalmanFilterBase (Index n, Index nt, Index m, Index mt, Index p)
 
virtual void setA (const Amatrix &A)
 Set the value of the jacobian df/dx. More...
 
virtual Matrix getA () const
 
virtual void clearA ()
 Clear the jacobian df/dx. More...
 
virtual void setC (const Cmatrix &C)
 Set the value of the Jacobian dh/dx. More...
 
virtual Matrix getC () const
 
virtual void clearC ()
 Clear the jacobian dh/dx. More...
 
virtual void setR (const Rmatrix &R)
 Set the measurement noise covariance matrix. More...
 
void setMeasurementCovariance (const Rmatrix &R)
 
virtual Matrix getR () const
 Set the measurement noise covariance matrix. More...
 
Matrix getMeasurementCovariance () const
 
virtual void clearR ()
 Clear the measurement noise covariance matrix. More...
 
virtual void setQ (const Qmatrix &Q)
 Set the process noise covariance matrix. More...
 
void setProcessCovariance (const Qmatrix &Q)
 
virtual Matrix getQ () const
 Set the process noise covariance matrix. More...
 
Matrix getProcessCovariance () const
 
virtual void clearQ ()
 Clear the process noise covariance matrix. More...
 
virtual void setStateCovariance (const Pmatrix &P)
 Set the covariance matrix of the current time state estimation error. More...
 
virtual void clearStates ()
 clears the state and the state covariance More...
 
virtual void clearStateCovariance ()
 
virtual Pmatrix getStateCovariance () const
 Get the covariance matrix of the current time state estimation. More...
 
virtual void reset ()
 Resets all the observer. More...
 
Amatrix getAmatrixConstant (double c) const
 Get a matrix having the size of the A matrix having "c" values. More...
 
Amatrix getAmatrixRandom () const
 Get a matrix having the size of the A matrix having random values. More...
 
Amatrix getAmatrixZero () const
 Get a matrix having the size of the A matrix having zero values. More...
 
Amatrix getAmatrixIdentity () const
 Get an identity matrix having the size of the A matrix. More...
 
bool checkAmatrix (const Amatrix &) const
 checks whether or not a matrix has the dimensions of the A matrix More...
 
Cmatrix getCmatrixConstant (double c) const
 Get a matrix having the size of the C matrix having "c" values. More...
 
Cmatrix getCmatrixRandom () const
 Get a matrix having the size of the C matrix having random values. More...
 
Cmatrix getCmatrixZero () const
 Get a matrix having the size of the C matrix having zero values. More...
 
bool checkCmatrix (const Cmatrix &) const
 checks whether or not a matrix has the dimensions of the C matrix More...
 
Qmatrix getQmatrixConstant (double c) const
 Get a matrix having the size of the Q matrix having "c" values. More...
 
Qmatrix getQmatrixRandom () const
 Get a matrix having the size of the Q matrix having random values. More...
 
Qmatrix getQmatrixZero () const
 Get a matrix having the size of the Q matrix having zero values. More...
 
Qmatrix getQmatrixIdentity () const
 Get an identity matrix having the size of the Q matrix. More...
 
bool checkQmatrix (const Qmatrix &) const
 checks whether or not a matrix has the dimensions of the Q matrix More...
 
Rmatrix getRmatrixConstant (double c) const
 Get a matrix having the size of the R matrix having "c" values. More...
 
Rmatrix getRmatrixRandom () const
 Get a matrix having the size of the R matrix having random values. More...
 
Rmatrix getRmatrixZero () const
 Get a matrix having the size of the R matrix having zero values. More...
 
Rmatrix getRmatrixIdentity () const
 Get an identity matrix having the size of the R matrix. More...
 
bool checkRmatrix (const Rmatrix &) const
 checks whether or not a matrix has the dimensions of the R matrix More...
 
Pmatrix getPmatrixConstant (double c) const
 Get a matrix having the size of the P matrix having "c" values. More...
 
Pmatrix getPmatrixRandom () const
 Get a matrix having the size of the P matrix having random values. More...
 
Pmatrix getPmatrixZero () const
 Get a matrix having the size of the P matrix having zero values. More...
 
Pmatrix getPmatrixIdentity () const
 Get an identity matrix having the size of the P matrix. More...
 
bool checkPmatrix (const Pmatrix &) const
 Checks whether or not a matrix has the dimensions of the P matrix. More...
 
virtual StateVectorTan stateTangentVectorConstant (double c) const
 Gives a vector of state tangent vector size having duplicated "c" value. More...
 
virtual StateVectorTan stateTangentVectorRandom () const
 Gives a vector of state tangent vector size having random values. More...
 
virtual StateVectorTan stateTangentVectorZero () const
 Gives a vector of state tangent vector size having zero values. More...
 
virtual bool checkStateTangentVector (const StateVectorTan &v) const
 Tells whether or not the vector has the dimensions of a state tangent vector. More...
 
virtual MeasureVectorTan measureTangentVectorConstant (double c) const
 Gives a vector of measurement tangent vector size having duplicated "c" value. More...
 
virtual MeasureVectorTan measureTangentVectorRandom () const
 Gives a vector of measurement tangent vector size having random values. More...
 
virtual MeasureVectorTan measureTangentVectorZero () const
 Gives a vector of measurement tangent vector size having zero values. More...
 
virtual bool checkMeasureTangentVector (const MeasureVectorTan &) const
 Tells whether or not the vector has the dimensions of a measurement tangent vector. More...
 
virtual void setStateSize (Index n, Index nt)
 
virtual void setMeasureSize (Index m, Index mt)
 
virtual MeasureVector getSimulatedMeasurement (TimeIndex k)
 Get simulation of the measurement y_k using the state estimation. More...
 
virtual const StateVectorgetInnovation ()
 Get the last vector of innovation of the Kalman filter. More...
 
const StateVectorupdateStatePrediction ()
 
MeasureVector updateStateAndMeasurementPrediction ()
 
const StateVectorgetLastPrediction () const
 get the last predicted state More...
 
const MeasureVectorgetLastPredictedMeasurement () const
 get the last predicted measurement More...
 
const MeasureVectorgetLastMeasurement () const
 get the last measurement More...
 
const MatrixgetLastGain () const
 get the last Kalman gain matrix More...
 
void setStateArithmetics (StateVectorArithmetics *arith)
 
- Public Member Functions inherited from stateObservation::ZeroDelayObserver
 ZeroDelayObserver (Index n, Index m, Index p=0)
 
 ZeroDelayObserver ()
 Default constructor (default values for n,m,p are zero) More...
 
virtual ~ZeroDelayObserver ()
 Destructor. More...
 
virtual void setState (const ObserverBase::StateVector &x_k, TimeIndex k)
 Set the value of the state vector at time index k. More...
 
virtual void setCurrentState (const ObserverBase::StateVector &x_k)
 Modify the value of the state vector at the current time. More...
 
bool stateIsSet () const
 Returns if the state is set or not. The state being set is mandatory to start the estimator. More...
 
virtual void setMeasurement (const ObserverBase::MeasureVector &y_k, TimeIndex k)
 
virtual void pushMeasurement (const ObserverBase::MeasureVector &y_k)
 Sets the measurement value at the next time index. More...
 
virtual void clearMeasurements ()
 Remove all the given values of the measurements. More...
 
virtual void setInput (const ObserverBase::InputVector &u_k, TimeIndex k)
 
virtual void pushInput (const ObserverBase::InputVector &u_k)
 Set the input value at the next time indext. More...
 
virtual void clearInputs ()
 
virtual void clearInputsAndMeasurements ()
 Remove all the given values of the inputs and measurements. More...
 
virtual TimeIndex estimateState ()
 run the observer until the measurement vector is depleted. More...
 
virtual ObserverBase::StateVector getEstimatedState (TimeIndex k)
 getestimated State More...
 
virtual ObserverBase::StateVector getCurrentEstimatedState () const
 Get the Current Estimated State. More...
 
virtual TimeIndex getCurrentTime () const
 Get the value of the time index of the current state estimation. More...
 
Vector getInput (TimeIndex k) const
 Get the value of the input of the time index k. More...
 
virtual TimeSize getInputsNumber () const
 Get the number of available inputs. More...
 
virtual TimeIndex getInputTime () const
 Get the time index of the last given input. More...
 
Vector getMeasurement (TimeIndex k) const
 Get the measurement of the time index k. More...
 
virtual TimeIndex getMeasurementTime () const
 Get the time index of the last given measurement. More...
 
virtual TimeSize getMeasurementsNumber () const
 Gets the number of regitered measurements. More...
 
- Public Member Functions inherited from stateObservation::ObserverBase
 ObserverBase (Index n, Index m, Index p=0)
 
 ObserverBase ()
 default constructor (default values for n,m,p are zero) More...
 
virtual ~ObserverBase ()
 Destructor. More...
 
virtual Index getStateSize () const
 gets the size of the state vector More...
 
virtual Index getMeasureSize () const
 gets the size of the measurement vector More...
 
virtual Index getInputSize () const
 gets the size of the input vector More...
 
virtual StateVector stateVectorConstant (double c) const
 
virtual StateVector stateVectorRandom () const
 Gives a vector of state vector size having random values. More...
 
virtual StateVector stateVectorZero () const
 Gives a vector of state vector size having zero values. More...
 
virtual bool checkStateVector (const StateVector &v) const
 Tells whether or not the vector has the dimensions of a state vector. More...
 
virtual MeasureVector measureVectorConstant (double c) const
 Gives a vector of measurement vector size having duplicated "c" value. More...
 
virtual MeasureVector measureVectorRandom () const
 Gives a vector of measurement vector size having random values. More...
 
virtual MeasureVector measureVectorZero () const
 Gives a vector of measurement vector size having zero values. More...
 
virtual bool checkMeasureVector (const MeasureVector &) const
 Tells whether or not the vector has the dimensions of a measurement vector. More...
 
virtual InputVector inputVectorConstant (double c) const
 Gives a vector of input vector size having duplicated "c" value. More...
 
virtual InputVector inputVectorRandom () const
 Gives a vector of input vector size having random values. More...
 
virtual InputVector inputVectorZero () const
 Gives a vector of input vector size having zero values. More...
 
virtual bool checkInputVector (const InputVector &) const
 Tells whether or not the vector has the dimensions of a input vector. More...
 

Protected Member Functions

virtual StateVector prediction_ (TimeIndex k)
 The implementation of the (linear) prediction (state dynamics) More...
 
virtual MeasureVector simulateSensor_ (const StateVector &x, TimeIndex k)
 The implementation of the (linear) measurement (state dynamics) More...
 
- Protected Member Functions inherited from stateObservation::KalmanFilterBase
virtual StateVector oneStepEstimation_ ()
 The Kalman filter loop. More...
 
virtual MeasureVector predictSensor_ (TimeIndex k)
 Predicts the sensor measurement,. More...
 
- Protected Member Functions inherited from stateObservation::StateVectorArithmetics
virtual void stateSum (const Vector &stateVector, const Vector &tangentVector, Vector &sum)
 
virtual void stateDifference (const Vector &stateVector1, const Vector &stateVector2, Vector &difference)
 
virtual void measurementDifference (const Vector &measureVector1, const Vector &measureVector2, Vector &difference)
 

Protected Attributes

Matrix d_
 The container of the Input-State matrix. More...
 
Matrix b_
 The container of the Input-Measurement matrix. More...
 
- Protected Attributes inherited from stateObservation::KalmanFilterBase
Index nt_
 the size of tangent space of the state space More...
 
Index mt_
 the size of tangent space of the measurement space More...
 
Matrix a_
 Containers for the jacobian matrix of the process. More...
 
Matrix c_
 Containers for the jacobian matrix of the measurement. More...
 
Matrix q_
 Container for the process noise covariance matrice. More...
 
Matrix r_
 Container for the measurement noise covariance matrice. More...
 
Matrix pr_
 Container for the covariance matrix of the estimation error. More...
 
IndexedVector xbar_
 container for the prediction More...
 
IndexedVector ybar_
 container for the prediction of the sensor More...
 
Vector innovation_
 Vector containing the inovation of the Kalman filter. More...
 
struct stateObservation::KalmanFilterBase::optimizationContainer oc_
 
StateVectorArithmeticsarithm_
 
- Protected Attributes inherited from stateObservation::ZeroDelayObserver
IndexedVector x_
 while the measurements and iputs are put in lists More...
 
IndexedVectorArray y_
 Container for the measurements. More...
 
IndexedVectorArray u_
 Container for the inputs. More...
 
- Protected Attributes inherited from stateObservation::ObserverBase
Index n_
 stateSize is the size of the state vector More...
 
Index m_
 measureSize is the size of measurements vector More...
 
Index p_
 inputSize is the size of the input vector More...
 

Additional Inherited Members

- Protected Types inherited from stateObservation::KalmanFilterBase
typedef Matrix Kmatrix
 The type of Kalman gain matrix. More...
 

Detailed Description

The class of a Linear Kalman filter.

It implements the Kalman filter for linear systems (LTI-LTV). This is the class to instanciate when you want to use Kalman filtering for linear systems. To use this class, one needs to provide the matrices that describe the dynamics of the state and the measurement.

 x_{k+1}=A_k x_k+ B_k u_k + v_k

 y_k=C_k x_k + D_k u_k + w_k

Member Typedef Documentation

◆ Bmatrix

The type of the matrix linking the input to the state.

◆ Dmatrix

The type of the matrix linking the input to the measurement.

Constructor & Destructor Documentation

◆ LinearKalmanFilter() [1/2]

stateObservation::LinearKalmanFilter::LinearKalmanFilter ( Index  n,
Index  m,
Index  p = 0 
)
inline

The constructor

  • n : size of the state vector
  • m : size of the measurements vector
  • p : size of the input vector

◆ LinearKalmanFilter() [2/2]

stateObservation::LinearKalmanFilter::LinearKalmanFilter ( )
inline

Default constructor.

Member Function Documentation

◆ checkBmatrix()

bool stateObservation::LinearKalmanFilter::checkBmatrix ( const Bmatrix ) const

checks whether or not a matrix has the dimensions of the B matrix

◆ checkDmatrix()

bool stateObservation::LinearKalmanFilter::checkDmatrix ( const Dmatrix ) const

checks whether or not a matrix has the dimensions of the D matrix

◆ clearB()

virtual void stateObservation::LinearKalmanFilter::clearB ( )
virtual

Clear the value of the input-state Matrix.

◆ clearD()

virtual void stateObservation::LinearKalmanFilter::clearD ( )
virtual

Clear the value of the input-measurement matrix.

◆ getBmatrixConstant()

Bmatrix stateObservation::LinearKalmanFilter::getBmatrixConstant ( double  c) const

Get a matrix having the size of the B matrix having "c" values.

◆ getBmatrixRandom()

Bmatrix stateObservation::LinearKalmanFilter::getBmatrixRandom ( ) const

Get a matrix having the size of the B matrix having random values.

◆ getBmatrixZero()

Bmatrix stateObservation::LinearKalmanFilter::getBmatrixZero ( ) const

Get a matrix having the size of the B matrix having zero values.

◆ getDmatrixConstant()

Dmatrix stateObservation::LinearKalmanFilter::getDmatrixConstant ( double  c) const

Get a matrix having the size of the D matrix having "c" values.

◆ getDmatrixRandom()

Dmatrix stateObservation::LinearKalmanFilter::getDmatrixRandom ( ) const

Get a matrix having the size of the D matrix having random values.

◆ getDmatrixZero()

Dmatrix stateObservation::LinearKalmanFilter::getDmatrixZero ( ) const

Get a matrix having the size of the D matrix having zero values.

◆ prediction_()

virtual StateVector stateObservation::LinearKalmanFilter::prediction_ ( TimeIndex  k)
protectedvirtual

The implementation of the (linear) prediction (state dynamics)

Implements stateObservation::KalmanFilterBase.

◆ setB()

virtual void stateObservation::LinearKalmanFilter::setB ( const Bmatrix B)
virtual

Set the value of the input-state matrix.

◆ setD()

virtual void stateObservation::LinearKalmanFilter::setD ( const Dmatrix D)
virtual

Set the value of the input-measurement matrix.

◆ setInputSize()

virtual void stateObservation::LinearKalmanFilter::setInputSize ( Index  p)
virtual

changes the dimension of the input vector: resets the internal container for the input vectors and the containers for the matrices B, D

Reimplemented from stateObservation::ZeroDelayObserver.

◆ setMeasureSize()

virtual void stateObservation::LinearKalmanFilter::setMeasureSize ( Index  m)
virtual

changes the dimension of the measurement vector: resets the internal container for the measurement vectors and the containers for the matrices C, D, R

Reimplemented from stateObservation::KalmanFilterBase.

◆ setStateSize()

virtual void stateObservation::LinearKalmanFilter::setStateSize ( Index  n)
virtual

changes the dimension of the state vector: resets the internal container for the state vector and the containers for the matrices A, B, C, Q, P

Reimplemented from stateObservation::KalmanFilterBase.

◆ simulateSensor_()

virtual MeasureVector stateObservation::LinearKalmanFilter::simulateSensor_ ( const StateVector x,
TimeIndex  k 
)
protectedvirtual

The implementation of the (linear) measurement (state dynamics)

Implements stateObservation::KalmanFilterBase.

Member Data Documentation

◆ b_

Matrix stateObservation::LinearKalmanFilter::b_
protected

The container of the Input-Measurement matrix.

◆ d_

Matrix stateObservation::LinearKalmanFilter::d_
protected

The container of the Input-State matrix.


The documentation for this class was generated from the following file: