Public Member Functions | Protected Attributes
omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType > Class Template Reference

This class defines an INTERFACE that all recursive estimator filters need to implement It is ROS free It is templated on the type of the state that it estimates and the type of measurements it accepts as input TODO: For multimodality I will need different measurement types. More...

#include <RecursiveEstimatorFilterInterface.h>

List of all members.

Public Member Functions

virtual void addPredictedState (const StateType &predicted_state, const double &predicted_state_timestamp_ns)=0
 Add a new prediction about the state generated in the higher level (as prediction about the next measurement)
virtual void correctState ()=0
 Third and final step when updating the filter. The predicted next state is corrected based on the difference between predicted and acquired measurement.
virtual MeasurementType getPredictedMeasurement () const
 Get the predicted next measurement.
virtual StateType getState () const
 Get the currently belief state.
virtual void predictMeasurement ()=0
 Second step when updating the filter. The next measurement is predicted from the predicted next state.
virtual void predictState (double time_interval_ns)=0
 First step when updating the filter. The next state is predicted from current state and system model.
 RecursiveEstimatorFilterInterface (double loop_period_ns)
 Constructor.
virtual void setMeasurement (const MeasurementType &acquired_measurement, const double &measurement_timestamp)
 Set the latest acquired measurement.
virtual ~RecursiveEstimatorFilterInterface ()
 Destructor.

Protected Attributes

std::string _filter_name
double _loop_period_ns
MeasurementType _measurement
double _measurement_timestamp_ns
StateType _most_likely_predicted_state
MeasurementType _predicted_measurement
std::vector< StateType > _predicted_states
double _previous_measurement_timestamp_ns
StateType _state

Detailed Description

template<class StateType, class MeasurementType>
class omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >

This class defines an INTERFACE that all recursive estimator filters need to implement It is ROS free It is templated on the type of the state that it estimates and the type of measurements it accepts as input TODO: For multimodality I will need different measurement types.

Definition at line 50 of file RecursiveEstimatorFilterInterface.h.


Constructor & Destructor Documentation

template<class StateType , class MeasurementType >
omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::RecursiveEstimatorFilterInterface ( double  loop_period_ns) [inline]

Constructor.

Definition at line 58 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
virtual omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::~RecursiveEstimatorFilterInterface ( ) [inline, virtual]

Destructor.

Definition at line 74 of file RecursiveEstimatorFilterInterface.h.


Member Function Documentation

template<class StateType , class MeasurementType >
virtual void omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::addPredictedState ( const StateType &  predicted_state,
const double &  predicted_state_timestamp_ns 
) [pure virtual]

Add a new prediction about the state generated in the higher level (as prediction about the next measurement)

Parameters:
predicted_statePredicted next state
template<class StateType , class MeasurementType >
virtual void omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::correctState ( ) [pure virtual]

Third and final step when updating the filter. The predicted next state is corrected based on the difference between predicted and acquired measurement.

template<class StateType , class MeasurementType >
virtual MeasurementType omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::getPredictedMeasurement ( ) const [inline, virtual]

Get the predicted next measurement.

Returns:
MeasurementType MeasurementType Predicted next measurement based on the predicted next state

Definition at line 123 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
virtual StateType omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::getState ( ) const [inline, virtual]

Get the currently belief state.

Returns:
StateType Currently belief state

Definition at line 133 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
virtual void omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::predictMeasurement ( ) [pure virtual]

Second step when updating the filter. The next measurement is predicted from the predicted next state.

template<class StateType , class MeasurementType >
virtual void omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::predictState ( double  time_interval_ns) [pure virtual]

First step when updating the filter. The next state is predicted from current state and system model.

template<class StateType , class MeasurementType >
virtual void omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::setMeasurement ( const MeasurementType &  acquired_measurement,
const double &  measurement_timestamp 
) [inline, virtual]

Set the latest acquired measurement.

Parameters:
acquired_measurementLatest acquired measurement

Definition at line 103 of file RecursiveEstimatorFilterInterface.h.


Member Data Documentation

template<class StateType , class MeasurementType >
std::string omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_filter_name [protected]

Definition at line 158 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
double omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_loop_period_ns [protected]

Definition at line 148 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
MeasurementType omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_measurement [protected]

Definition at line 141 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
double omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_measurement_timestamp_ns [protected]

Definition at line 151 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
StateType omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_most_likely_predicted_state [protected]

Definition at line 166 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
MeasurementType omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_predicted_measurement [protected]

Definition at line 168 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
std::vector<StateType> omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_predicted_states [protected]

Definition at line 163 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
double omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_previous_measurement_timestamp_ns [protected]

Definition at line 156 of file RecursiveEstimatorFilterInterface.h.

template<class StateType , class MeasurementType >
StateType omip::RecursiveEstimatorFilterInterface< StateType, MeasurementType >::_state [protected]

Definition at line 140 of file RecursiveEstimatorFilterInterface.h.


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


omip_common
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:26:37