|
| | ExtendedKalmanFilter (Index n, Index m) |
| |
| | ExtendedKalmanFilter (Index n, Index m, Index p, bool directInputOutputFeedthrough=true, bool directInputStateProcessFeedthrough=true) |
| |
| | ExtendedKalmanFilter (Index n, Index nt, Index m, Index mt, Index p, bool directInputOutputFeedthrough, bool directInputStateProcessFeedthrough) |
| |
| void | setFunctor (DynamicalSystemFunctorBase *f) |
| |
| DynamicalSystemFunctorBase * | getFunctor (void) const |
| |
| DynamicalSystemFunctorBase * | functor () const |
| | Gets a pointer to the functor. More...
|
| |
| void | clearFunctor () |
| |
| void | setDirectInputOutputFeedthrough (bool b=true) |
| |
| void | setDirectInputStateFeedthrough (bool b=true) |
| |
| virtual Amatrix | getAMatrixFD (const Vector &dx) |
| |
| virtual Cmatrix | getCMatrixFD (const Vector &dx) |
| |
| virtual void | reset () |
| | Reset the extended kalman filter (call also the reset function of the dynamics functor) More...
|
| |
| | 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...
|
| |
| 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 StateVector & | getInnovation () |
| | Get the last vector of innovation of the Kalman filter. More...
|
| |
| const StateVector & | updateStatePrediction () |
| |
| MeasureVector | updateStateAndMeasurementPrediction () |
| |
| const StateVector & | getLastPrediction () const |
| | get the last predicted state More...
|
| |
| const MeasureVector & | getLastPredictedMeasurement () const |
| | get the last predicted measurement More...
|
| |
| const MeasureVector & | getLastMeasurement () const |
| | get the last measurement More...
|
| |
| const Matrix & | getLastGain () const |
| | get the last Kalman gain matrix More...
|
| |
| void | setStateArithmetics (StateVectorArithmetics *arith) |
| |
| | 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...
|
| |
| | 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...
|
| |
The class to intanciate to use an extended Kalman filter.
To use this class, one needs to provide a pointer on a functor
that describes the state dynamics and the measurement dynamics.
The functor type needs to be a derived class from the class
DynamicsFunctorBase.
x_{k+1}=f(x_k,u_k)+v_k
y_k=h(x_k,u_k)+w_k