The base class for observers. The observer is destinated to any dynamical system with a vector state representation. This class mostly defined an abstract interface, static constants and types. It is templated by: More...
#include <state-observation/observer/observer-base.hpp>
Public Types | |
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 | |
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 void | setStateSize (Index n) |
Changes the size of the state vector. More... | |
virtual Index | getStateSize () const |
gets the size of the state vector More... | |
virtual void | setMeasureSize (Index m) |
Changes the size of the measurement vector. More... | |
virtual Index | getMeasureSize () const |
gets the size of the measurement vector More... | |
virtual void | setInputSize (Index p) |
Changes the size of the input vector. More... | |
virtual Index | getInputSize () const |
gets the size of the input vector More... | |
virtual void | setState (const StateVector &x_k, TimeIndex k)=0 |
Set the value of the state vector at time index k. More... | |
virtual void | clearStates ()=0 |
Remove all the given values of the state. More... | |
virtual void | setMeasurement (const MeasureVector &y_k, TimeIndex k)=0 |
Set the value of the measurements vector at time index k. More... | |
virtual void | clearMeasurements ()=0 |
Remove all the given values of the measurements. More... | |
virtual void | setInput (const InputVector &x_k, TimeIndex k)=0 |
Set the value of the input vector at time index k. More... | |
virtual void | clearInputs ()=0 |
Remove all the given values of the inputs. More... | |
virtual void | clearInputsAndMeasurements () |
Remove all the given values of the inputs and measurements. More... | |
virtual StateVector | getEstimatedState (TimeIndex k)=0 |
virtual void | reset () |
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 Attributes | |
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... | |
The base class for observers. The observer is destinated to any dynamical system with a vector state representation. This class mostly defined an abstract interface, static constants and types. It is templated by:
InputVector is the type of the input vector.
MeasureVector is the type of measurements vector.
StateVector is the type of state vector.
constructor
stateObservation::ObserverBase::ObserverBase | ( | ) |
default constructor (default values for n,m,p are zero)
|
inlinevirtual |
Destructor.
|
virtual |
Tells whether or not the vector has the dimensions of a input vector.
|
virtual |
Tells whether or not the vector has the dimensions of a measurement vector.
|
virtual |
Tells whether or not the vector has the dimensions of a state vector.
|
pure virtual |
Remove all the given values of the inputs.
Implemented in stateObservation::ZeroDelayObserver.
|
virtual |
Remove all the given values of the inputs and measurements.
Reimplemented in stateObservation::ZeroDelayObserver.
|
pure virtual |
Remove all the given values of the measurements.
Implemented in stateObservation::ZeroDelayObserver.
|
pure virtual |
Remove all the given values of the state.
Implemented in stateObservation::KalmanFilterBase, and stateObservation::ZeroDelayObserver.
|
pure virtual |
Run the observer loop and gets the state estimation of the state at instant k
Implemented in stateObservation::ZeroDelayObserver.
|
virtual |
gets the size of the input vector
|
virtual |
gets the size of the measurement vector
|
virtual |
gets the size of the state vector
|
virtual |
Gives a vector of input vector size having duplicated "c" value.
|
virtual |
Gives a vector of input vector size having random values.
|
virtual |
Gives a vector of input vector size having zero values.
|
virtual |
Gives a vector of measurement vector size having duplicated "c" value.
|
virtual |
Gives a vector of measurement vector size having random values.
|
virtual |
Gives a vector of measurement vector size having zero values.
|
virtual |
Reinitializes the whole observer default behavior is to call the three "ObserverBase::clear*" methods
Reimplemented in stateObservation::KalmanFilterBase, and stateObservation::ExtendedKalmanFilter.
|
pure virtual |
Set the value of the input vector at time index k.
Implemented in stateObservation::ZeroDelayObserver.
|
virtual |
Changes the size of the input vector.
Reimplemented in stateObservation::ZeroDelayObserver, and stateObservation::LinearKalmanFilter.
|
pure virtual |
Set the value of the measurements vector at time index k.
Implemented in stateObservation::ZeroDelayObserver.
|
virtual |
Changes the size of the measurement vector.
Reimplemented in stateObservation::KalmanFilterBase, stateObservation::ZeroDelayObserver, and stateObservation::LinearKalmanFilter.
|
pure virtual |
Set the value of the state vector at time index k.
Implemented in stateObservation::ZeroDelayObserver.
|
virtual |
Changes the size of the state vector.
Reimplemented in stateObservation::KalmanFilterBase, stateObservation::ZeroDelayObserver, and stateObservation::LinearKalmanFilter.
|
virtual |
These are initializer for vectors We do not use the get prefix to be consistent with eigen initializers Gives a vector of state vector size having duplicated "c" value
|
virtual |
Gives a vector of state vector size having random values.
|
virtual |
Gives a vector of state vector size having zero values.
|
protected |
measureSize is the size of measurements vector
|
protected |
stateSize is the size of the state vector
|
protected |
inputSize is the size of the input vector