ethzasl-msf - Modular Sensor Fusion
Time delay compensated single and multi sensor fusion framework based on an EKF
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
List of all members | Public Member Functions | Public Attributes | Protected Types | Protected Attributes | Private Attributes
msf_core::MSF_SensorManager< EKFState_T > Class Template Reference

A manager for a given sensor set. Handlers for individual sensors (camera/vicon etc.) are registered with this class as handlers of particular sensors. This class also owns the EKF core instance and handles the initialization of the filter.

#include <msf_sensormanager.h>

Inheritance diagram for msf_core::MSF_SensorManager< EKFState_T >:
msf_core::StateVisitor< EKFState_T > msf_core::MSF_SensorManagerROS< EKFState_T >

Public Member Functions

 MSF_SensorManager ()
bool data_playback ()
virtual ~MSF_SensorManager ()
void addHandler (shared_ptr< SensorHandler< EKFState_T > > handler)
virtual void init (double scale) const =0
virtual void initState (EKFState_T &state) const =0
virtual void calculateQAuxiliaryStates (EKFState_T &UNUSEDPARAM(state), double UNUSEDPARAM(dt)) const =0
virtual void setP (Eigen::Matrix< double, EKFState_T::nErrorStatesAtCompileTime, EKFState_T::nErrorStatesAtCompileTime > &P) const =0
virtual void augmentCorrectionVector (Eigen::Matrix< double, EKFState_T::nErrorStatesAtCompileTime, 1 > &UNUSEDPARAM(correction)) const =0
virtual void sanityCheckCorrection (EKFState_T &UNUSEDPARAM(delaystate), const EKFState_T &UNUSEDPARAM(buffstate), Eigen::Matrix< double, EKFState_T::nErrorStatesAtCompileTime, 1 > &UNUSEDPARAM(correction)) const =0
virtual bool getParam_fixed_bias () const =0
virtual double getParam_noise_acc () const =0
virtual double getParam_noise_accbias () const =0
virtual double getParam_noise_gyr () const =0
virtual double getParam_noise_gyrbias () const =0
virtual double getParam_fuzzythres () const =0
virtual void publishStateInitial (const shared_ptr< EKFState_T > &state) const =0
virtual void publishStateAfterPropagation (const shared_ptr< EKFState_T > &state) const =0
virtual void publishStateAfterUpdate (const shared_ptr< EKFState_T > &state) const =0
- Public Member Functions inherited from msf_core::StateVisitor< EKFState_T >
virtual void resetState (EKFState_T &state) const =0
 The state is set to zero/identity, this method will be called to give the user the possibility to change the reset values of some states.
virtual ~StateVisitor ()

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
shared_ptr< MSF_Core
< EKFState_T > > 
msf_core_
 The ekf core instance.

Protected Types

typedef std::vector
< shared_ptr< SensorHandler
< EKFState_T > > > 
Handlers

Protected Attributes

Handlers handlers
 A list of sensor handlers which provide measurements.
bool data_playback_

Private Attributes

int sensorID_

Member Typedef Documentation

template<typename EKFState_T>
typedef std::vector<shared_ptr<SensorHandler<EKFState_T> > > msf_core::MSF_SensorManager< EKFState_T >::Handlers
protected

Constructor & Destructor Documentation

template<typename EKFState_T >
msf_core::MSF_SensorManager< EKFState_T >::MSF_SensorManager ( )
template<typename EKFState_T>
virtual msf_core::MSF_SensorManager< EKFState_T >::~MSF_SensorManager ( )
inlinevirtual

Member Function Documentation

template<typename EKFState_T>
void msf_core::MSF_SensorManager< EKFState_T >::addHandler ( shared_ptr< SensorHandler< EKFState_T > >  handler)
inline
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::augmentCorrectionVector ( Eigen::Matrix< double, EKFState_T::nErrorStatesAtCompileTime, 1 > &  UNUSEDPARAMcorrection) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::calculateQAuxiliaryStates ( EKFState_T &  UNUSEDPARAMstate,
double   UNUSEDPARAMdt 
) const
pure virtual
template<typename EKFState_T>
bool msf_core::MSF_SensorManager< EKFState_T >::data_playback ( )
inline
template<typename EKFState_T>
virtual bool msf_core::MSF_SensorManager< EKFState_T >::getParam_fixed_bias ( ) const
pure virtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManager< EKFState_T >::getParam_fuzzythres ( ) const
pure virtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManager< EKFState_T >::getParam_noise_acc ( ) const
pure virtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManager< EKFState_T >::getParam_noise_accbias ( ) const
pure virtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManager< EKFState_T >::getParam_noise_gyr ( ) const
pure virtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManager< EKFState_T >::getParam_noise_gyrbias ( ) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::init ( double  scale) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::initState ( EKFState_T &  state) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::publishStateAfterPropagation ( const shared_ptr< EKFState_T > &  state) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::publishStateAfterUpdate ( const shared_ptr< EKFState_T > &  state) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::publishStateInitial ( const shared_ptr< EKFState_T > &  state) const
pure virtual

This functions get called by the core to publish data to external middlewares like ROS.

Implemented in msf_core::MSF_SensorManagerROS< EKFState_T >, and msf_core::MSF_SensorManagerROS< msf_updates::EKFState >.

template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::sanityCheckCorrection ( EKFState_T &  UNUSEDPARAMdelaystate,
const EKFState_T &  UNUSEDPARAMbuffstate,
Eigen::Matrix< double, EKFState_T::nErrorStatesAtCompileTime, 1 > &  UNUSEDPARAMcorrection 
) const
pure virtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManager< EKFState_T >::setP ( Eigen::Matrix< double, EKFState_T::nErrorStatesAtCompileTime, EKFState_T::nErrorStatesAtCompileTime > &  P) const
pure virtual

Member Data Documentation

template<typename EKFState_T>
bool msf_core::MSF_SensorManager< EKFState_T >::data_playback_
protected

Used to determine if internal states get overwritten by the external state prediction (online) or internal state prediction is performed for log replay, when the external prediction is not available or should be done on the host.

template<typename EKFState_T>
Handlers msf_core::MSF_SensorManager< EKFState_T >::handlers
protected
template<typename EKFState_T>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW shared_ptr<MSF_Core<EKFState_T> > msf_core::MSF_SensorManager< EKFState_T >::msf_core_
template<typename EKFState_T>
int msf_core::MSF_SensorManager< EKFState_T >::sensorID_
private

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