stateObservation::KalmanFilterBase Class Referenceabstract

It mostly implements the equations of Kalman filtering It is suitablle by derivation to be used incases of Linear, linearized and extended Kalman filtering. It may be derived to unscented Kalman filtering, but non-straighforwardly because the state vector is modified. This class requires to be derived to overload the update routine and the measurements simulation routine. More...

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

Inheritance diagram for stateObservation::KalmanFilterBase:
Collaboration diagram for stateObservation::KalmanFilterBase:

Classes

struct  optimizationContainer
 

Public Types

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

 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)
 
virtual void setStateSize (Index n, Index nt)
 
virtual void setMeasureSize (Index m)
 
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...
 
virtual void setInputSize (Index p)
 changes the size of the input vector: reset the stored input vectors 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 Types

typedef Matrix Kmatrix
 The type of Kalman gain matrix. More...
 

Protected Member Functions

virtual StateVector oneStepEstimation_ ()
 The Kalman filter loop. More...
 
virtual StateVector prediction_ (TimeIndex k)=0
 The abstract method to overload to implement f(x,u) More...
 
virtual MeasureVector simulateSensor_ (const StateVector &x, TimeIndex k)=0
 The abstract method to overload to implement h(x,u) 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

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...
 

Detailed Description

It mostly implements the equations of Kalman filtering It is suitablle by derivation to be used incases of Linear, linearized and extended Kalman filtering. It may be derived to unscented Kalman filtering, but non-straighforwardly because the state vector is modified. This class requires to be derived to overload the update routine and the measurements simulation routine.

 x_{k+1}=f(x_k,u_k)+v_k

 y_k=h(x_k,u_k)+w_k

Member Typedef Documentation

◆ Amatrix

The type of the jacobian df/dx.

◆ Cmatrix

The type of the jacobian dh/dx.

◆ Kmatrix

The type of Kalman gain matrix.

◆ LLTPMatrix

◆ MeasureVectorTan

MeasureVector is the type of measurement tanegnt vector.

◆ Pmatrix

The type of the covariance matrix of the state estimation error.

◆ Qmatrix

The type of the covariance matrix of the process noise v.

◆ Rmatrix

The type of the covariance matrix of the measurement noise w.

◆ StateVectorTan

StateVector is the type of state tangent vector.

Constructor & Destructor Documentation

◆ KalmanFilterBase() [1/3]

stateObservation::KalmanFilterBase::KalmanFilterBase ( )

Default constructor.

◆ KalmanFilterBase() [2/3]

stateObservation::KalmanFilterBase::KalmanFilterBase ( Index  n,
Index  m,
Index  p = 0 
)

The constructor

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

◆ KalmanFilterBase() [3/3]

stateObservation::KalmanFilterBase::KalmanFilterBase ( Index  n,
Index  nt,
Index  m,
Index  mt,
Index  p 
)

The constructor to use in case the dimension of the state space is smaller that its vector representation. For example The state could be made of rotations matrices (3x3 matrix: size = 9) Or quaternions (size =4) while they lie in a 3D space. In general the representation is in a Lie group and the representation of state derivatives are expressed in a Lie algebra. Use setSumFunction for Kalman update (mandatory)

The update can then be done using exponential maps.

  • n : size of the state vector representation
  • nt : dimension of the tangent space to the state space
  • m : size of the measurements vector
  • mt : dimension of the tangent space to the measurement space
  • p : size of the input vector

Member Function Documentation

◆ checkAmatrix()

bool stateObservation::KalmanFilterBase::checkAmatrix ( const Amatrix ) const

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

◆ checkCmatrix()

bool stateObservation::KalmanFilterBase::checkCmatrix ( const Cmatrix ) const

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

◆ checkMeasureTangentVector()

virtual bool stateObservation::KalmanFilterBase::checkMeasureTangentVector ( const MeasureVectorTan ) const
virtual

Tells whether or not the vector has the dimensions of a measurement tangent vector.

◆ checkPmatrix()

bool stateObservation::KalmanFilterBase::checkPmatrix ( const Pmatrix ) const

Checks whether or not a matrix has the dimensions of the P matrix.

◆ checkQmatrix()

bool stateObservation::KalmanFilterBase::checkQmatrix ( const Qmatrix ) const

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

◆ checkRmatrix()

bool stateObservation::KalmanFilterBase::checkRmatrix ( const Rmatrix ) const

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

◆ checkStateTangentVector()

virtual bool stateObservation::KalmanFilterBase::checkStateTangentVector ( const StateVectorTan v) const
virtual

Tells whether or not the vector has the dimensions of a state tangent vector.

◆ clearA()

virtual void stateObservation::KalmanFilterBase::clearA ( )
virtual

Clear the jacobian df/dx.

◆ clearC()

virtual void stateObservation::KalmanFilterBase::clearC ( )
virtual

Clear the jacobian dh/dx.

◆ clearQ()

virtual void stateObservation::KalmanFilterBase::clearQ ( )
virtual

Clear the process noise covariance matrix.

◆ clearR()

virtual void stateObservation::KalmanFilterBase::clearR ( )
virtual

Clear the measurement noise covariance matrix.

◆ clearStateCovariance()

virtual void stateObservation::KalmanFilterBase::clearStateCovariance ( )
virtual

Clear the covariace matrix of the current time state estimation error

◆ clearStates()

virtual void stateObservation::KalmanFilterBase::clearStates ( )
virtual

clears the state and the state covariance

they need to be set again using setState() and setStateCovariance() before starting the estimation again

Reimplemented from stateObservation::ZeroDelayObserver.

◆ getA()

virtual Matrix stateObservation::KalmanFilterBase::getA ( ) const
virtual

◆ getAmatrixConstant()

Amatrix stateObservation::KalmanFilterBase::getAmatrixConstant ( double  c) const

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

◆ getAmatrixIdentity()

Amatrix stateObservation::KalmanFilterBase::getAmatrixIdentity ( ) const

Get an identity matrix having the size of the A matrix.

◆ getAmatrixRandom()

Amatrix stateObservation::KalmanFilterBase::getAmatrixRandom ( ) const

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

◆ getAmatrixZero()

Amatrix stateObservation::KalmanFilterBase::getAmatrixZero ( ) const

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

◆ getC()

virtual Matrix stateObservation::KalmanFilterBase::getC ( ) const
virtual

◆ getCmatrixConstant()

Cmatrix stateObservation::KalmanFilterBase::getCmatrixConstant ( double  c) const

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

◆ getCmatrixRandom()

Cmatrix stateObservation::KalmanFilterBase::getCmatrixRandom ( ) const

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

◆ getCmatrixZero()

Cmatrix stateObservation::KalmanFilterBase::getCmatrixZero ( ) const

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

◆ getInnovation()

virtual const StateVector& stateObservation::KalmanFilterBase::getInnovation ( )
virtual

Get the last vector of innovation of the Kalman filter.

◆ getLastGain()

const Matrix& stateObservation::KalmanFilterBase::getLastGain ( ) const

get the last Kalman gain matrix

◆ getLastMeasurement()

const MeasureVector& stateObservation::KalmanFilterBase::getLastMeasurement ( ) const

get the last measurement

◆ getLastPredictedMeasurement()

const MeasureVector& stateObservation::KalmanFilterBase::getLastPredictedMeasurement ( ) const

get the last predicted measurement

◆ getLastPrediction()

const StateVector& stateObservation::KalmanFilterBase::getLastPrediction ( ) const

get the last predicted state

◆ getMeasurementCovariance()

Matrix stateObservation::KalmanFilterBase::getMeasurementCovariance ( ) const
inline

◆ getPmatrixConstant()

Pmatrix stateObservation::KalmanFilterBase::getPmatrixConstant ( double  c) const

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

◆ getPmatrixIdentity()

Pmatrix stateObservation::KalmanFilterBase::getPmatrixIdentity ( ) const

Get an identity matrix having the size of the P matrix.

◆ getPmatrixRandom()

Pmatrix stateObservation::KalmanFilterBase::getPmatrixRandom ( ) const

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

◆ getPmatrixZero()

Pmatrix stateObservation::KalmanFilterBase::getPmatrixZero ( ) const

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

◆ getProcessCovariance()

Matrix stateObservation::KalmanFilterBase::getProcessCovariance ( ) const
inline

◆ getQ()

virtual Matrix stateObservation::KalmanFilterBase::getQ ( ) const
virtual

Set the process noise covariance matrix.

◆ getQmatrixConstant()

Qmatrix stateObservation::KalmanFilterBase::getQmatrixConstant ( double  c) const

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

◆ getQmatrixIdentity()

Qmatrix stateObservation::KalmanFilterBase::getQmatrixIdentity ( ) const

Get an identity matrix having the size of the Q matrix.

◆ getQmatrixRandom()

Qmatrix stateObservation::KalmanFilterBase::getQmatrixRandom ( ) const

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

◆ getQmatrixZero()

Qmatrix stateObservation::KalmanFilterBase::getQmatrixZero ( ) const

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

◆ getR()

virtual Matrix stateObservation::KalmanFilterBase::getR ( ) const
virtual

Set the measurement noise covariance matrix.

◆ getRmatrixConstant()

Rmatrix stateObservation::KalmanFilterBase::getRmatrixConstant ( double  c) const

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

◆ getRmatrixIdentity()

Rmatrix stateObservation::KalmanFilterBase::getRmatrixIdentity ( ) const

Get an identity matrix having the size of the R matrix.

◆ getRmatrixRandom()

Rmatrix stateObservation::KalmanFilterBase::getRmatrixRandom ( ) const

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

◆ getRmatrixZero()

Rmatrix stateObservation::KalmanFilterBase::getRmatrixZero ( ) const

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

◆ getSimulatedMeasurement()

virtual MeasureVector stateObservation::KalmanFilterBase::getSimulatedMeasurement ( TimeIndex  k)
virtual

Get simulation of the measurement y_k using the state estimation.

◆ getStateCovariance()

virtual Pmatrix stateObservation::KalmanFilterBase::getStateCovariance ( ) const
virtual

Get the covariance matrix of the current time state estimation.

◆ measureTangentVectorConstant()

virtual MeasureVectorTan stateObservation::KalmanFilterBase::measureTangentVectorConstant ( double  c) const
virtual

Gives a vector of measurement tangent vector size having duplicated "c" value.

◆ measureTangentVectorRandom()

virtual MeasureVectorTan stateObservation::KalmanFilterBase::measureTangentVectorRandom ( ) const
virtual

Gives a vector of measurement tangent vector size having random values.

◆ measureTangentVectorZero()

virtual MeasureVectorTan stateObservation::KalmanFilterBase::measureTangentVectorZero ( ) const
virtual

Gives a vector of measurement tangent vector size having zero values.

◆ oneStepEstimation_()

virtual StateVector stateObservation::KalmanFilterBase::oneStepEstimation_ ( )
protectedvirtual

The Kalman filter loop.

Implements stateObservation::ZeroDelayObserver.

◆ prediction_()

virtual StateVector stateObservation::KalmanFilterBase::prediction_ ( TimeIndex  k)
protectedpure virtual

The abstract method to overload to implement f(x,u)

Implemented in stateObservation::ExtendedKalmanFilter, and stateObservation::LinearKalmanFilter.

◆ predictSensor_()

virtual MeasureVector stateObservation::KalmanFilterBase::predictSensor_ ( TimeIndex  k)
protectedvirtual

Predicts the sensor measurement,.

Reimplemented in stateObservation::ExtendedKalmanFilter.

◆ reset()

virtual void stateObservation::KalmanFilterBase::reset ( )
virtual

Resets all the observer.

Reimplemented from stateObservation::ObserverBase.

Reimplemented in stateObservation::ExtendedKalmanFilter.

◆ setA()

virtual void stateObservation::KalmanFilterBase::setA ( const Amatrix A)
virtual

Set the value of the jacobian df/dx.

◆ setC()

virtual void stateObservation::KalmanFilterBase::setC ( const Cmatrix C)
virtual

Set the value of the Jacobian dh/dx.

◆ setMeasurementCovariance()

void stateObservation::KalmanFilterBase::setMeasurementCovariance ( const Rmatrix R)
inline

◆ setMeasureSize() [1/2]

virtual void stateObservation::KalmanFilterBase::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, R

Reimplemented from stateObservation::ZeroDelayObserver.

Reimplemented in stateObservation::LinearKalmanFilter.

◆ setMeasureSize() [2/2]

virtual void stateObservation::KalmanFilterBase::setMeasureSize ( Index  m,
Index  mt 
)
virtual

Changes the dimension of the measurement vector: m is the size of the measurementVector mt is the dimension of the measurement tangent space resets the internal container for the measurement vectors and the containers for the matrices C, R

◆ setProcessCovariance()

void stateObservation::KalmanFilterBase::setProcessCovariance ( const Qmatrix Q)
inline

◆ setQ()

virtual void stateObservation::KalmanFilterBase::setQ ( const Qmatrix Q)
virtual

Set the process noise covariance matrix.

◆ setR()

virtual void stateObservation::KalmanFilterBase::setR ( const Rmatrix R)
virtual

Set the measurement noise covariance matrix.

◆ setStateArithmetics()

void stateObservation::KalmanFilterBase::setStateArithmetics ( StateVectorArithmetics arith)

set update functions for sum and difference for the state vector (used for the case of multiplicative Kalman filter)

◆ setStateCovariance()

virtual void stateObservation::KalmanFilterBase::setStateCovariance ( const Pmatrix P)
virtual

Set the covariance matrix of the current time state estimation error.

◆ setStateSize() [1/2]

virtual void stateObservation::KalmanFilterBase::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, C, Q, P

Reimplemented from stateObservation::ZeroDelayObserver.

Reimplemented in stateObservation::LinearKalmanFilter.

◆ setStateSize() [2/2]

virtual void stateObservation::KalmanFilterBase::setStateSize ( Index  n,
Index  nt 
)
virtual

Changes the dimension of the state vector: n is the dimension of the state representation and nt is the dimension of the tangent vector representation resets the internal container for the state vector and the containers for the matrices A, C, Q, P

◆ simulateSensor_()

virtual MeasureVector stateObservation::KalmanFilterBase::simulateSensor_ ( const StateVector x,
TimeIndex  k 
)
protectedpure virtual

The abstract method to overload to implement h(x,u)

Implemented in stateObservation::ExtendedKalmanFilter, and stateObservation::LinearKalmanFilter.

◆ stateTangentVectorConstant()

virtual StateVectorTan stateObservation::KalmanFilterBase::stateTangentVectorConstant ( double  c) const
virtual

Gives a vector of state tangent vector size having duplicated "c" value.

◆ stateTangentVectorRandom()

virtual StateVectorTan stateObservation::KalmanFilterBase::stateTangentVectorRandom ( ) const
virtual

Gives a vector of state tangent vector size having random values.

◆ stateTangentVectorZero()

virtual StateVectorTan stateObservation::KalmanFilterBase::stateTangentVectorZero ( ) const
virtual

Gives a vector of state tangent vector size having zero values.

◆ updateStateAndMeasurementPrediction()

Vector stateObservation::KalmanFilterBase::updateStateAndMeasurementPrediction ( )
inline

update the predicted state, enables to precompute the predicted measurementÅ” triggers also Vector updateStatePrediction() returns the measurement prediction definition in the bottom of this file

◆ updateStatePrediction()

const Vector & stateObservation::KalmanFilterBase::updateStatePrediction ( )
inline

A function that gives the prediction (this is NOT the estimation of the state), for the estimation call getEstimateState method it is only an execution of the state synamics with the current state estimation and the current input value

Member Data Documentation

◆ a_

Matrix stateObservation::KalmanFilterBase::a_
protected

Containers for the jacobian matrix of the process.

◆ arithm_

StateVectorArithmetics* stateObservation::KalmanFilterBase::arithm_
protected

◆ c_

Matrix stateObservation::KalmanFilterBase::c_
protected

Containers for the jacobian matrix of the measurement.

◆ innovation_

Vector stateObservation::KalmanFilterBase::innovation_
protected

Vector containing the inovation of the Kalman filter.

◆ mt_

Index stateObservation::KalmanFilterBase::mt_
protected

the size of tangent space of the measurement space

◆ nt_

Index stateObservation::KalmanFilterBase::nt_
protected

the size of tangent space of the state space

◆ oc_

struct stateObservation::KalmanFilterBase::optimizationContainer stateObservation::KalmanFilterBase::oc_
protected

◆ pr_

Matrix stateObservation::KalmanFilterBase::pr_
protected

Container for the covariance matrix of the estimation error.

◆ q_

Matrix stateObservation::KalmanFilterBase::q_
protected

Container for the process noise covariance matrice.

◆ r_

Matrix stateObservation::KalmanFilterBase::r_
protected

Container for the measurement noise covariance matrice.

◆ xbar_

IndexedVector stateObservation::KalmanFilterBase::xbar_
protected

container for the prediction

◆ ybar_

IndexedVector stateObservation::KalmanFilterBase::ybar_
protected

container for the prediction of the sensor


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