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 | Protected Attributes | Private Types | Private Attributes
msf_core::MSF_SensorManagerROS< EKFState_T > Class Template Reference

Abstract class defining user configurable calculations for the msf_core with ROS interfaces.

#include <msf_sensormanagerROS.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW MSF_SensorManagerROS (ros::NodeHandle pnh=ros::NodeHandle("~core"))
virtual ~MSF_SensorManagerROS ()
virtual void coreConfig (msf_core::MSF_CoreConfig &config, uint32_t level)
 Gets called by the internal callback caller.
void Config (msf_core::MSF_CoreConfig &config, uint32_t level)
 Gets called by dynamic reconfigure and calls all registered callbacks in callbacks_.
void setHLStateBuffer (const sensor_fusion_comm::ExtEkf &msg)
virtual bool getParam_fixed_bias () const
virtual double getParam_noise_acc () const
virtual double getParam_noise_accbias () const
virtual double getParam_noise_gyr () const
virtual double getParam_noise_gyrbias () const
virtual double getParam_fuzzythres () const
virtual void publishStateInitial (const shared_ptr< EKFState_T > &state) const
virtual void publishStateAfterPropagation (const shared_ptr< EKFState_T > &state) const
virtual void publishStateAfterUpdate (const shared_ptr< EKFState_T > &state) const
- Public Member Functions inherited from msf_core::MSF_SensorManager< EKFState_T >
 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
- 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 ()

Protected Attributes

msf_core::MSF_CoreConfig config_
 Dynamic reconfigure config.
- Protected Attributes inherited from msf_core::MSF_SensorManager< EKFState_T >
Handlers handlers
 A list of sensor handlers which provide measurements.
bool data_playback_

Private Types

typedef
EKFState_T::StateDefinition_T 
StateDefinition_T
typedef EKFState_T::StateSequence_T StateSequence_T

Private Attributes

ReconfigureServerreconfServer_
 Dynamic reconfigure server.
ros::Publisher pubState_
 Publishes all states of the filter.
ros::Publisher pubPose_
 Publishes 6DoF pose output.
ros::Publisher pubPoseAfterUpdate_
 Publishes 6DoF pose output after the update has been applied.
ros::Publisher pubPoseCrtl_
 Publishes 6DoF pose including velocity output.
ros::Publisher pubCorrect_
 Publishes corrections for external state propagation.
tf::TransformBroadcaster tf_broadcaster_
sensor_fusion_comm::ExtEkf hl_state_buf_
 Buffer to store external propagation data.

Additional Inherited Members

- Public Attributes inherited from msf_core::MSF_SensorManager< EKFState_T >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
shared_ptr< MSF_Core
< EKFState_T > > 
msf_core_
 The ekf core instance.
- Protected Types inherited from msf_core::MSF_SensorManager< EKFState_T >
typedef std::vector
< shared_ptr< SensorHandler
< EKFState_T > > > 
Handlers

Member Typedef Documentation

template<typename EKFState_T>
typedef EKFState_T::StateDefinition_T msf_core::MSF_SensorManagerROS< EKFState_T >::StateDefinition_T
private
template<typename EKFState_T>
typedef EKFState_T::StateSequence_T msf_core::MSF_SensorManagerROS< EKFState_T >::StateSequence_T
private

Constructor & Destructor Documentation

template<typename EKFState_T>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW msf_core::MSF_SensorManagerROS< EKFState_T >::MSF_SensorManagerROS ( ros::NodeHandle  pnh = ros::NodeHandle("~core"))
inline
template<typename EKFState_T>
virtual msf_core::MSF_SensorManagerROS< EKFState_T >::~MSF_SensorManagerROS ( )
inlinevirtual

Member Function Documentation

template<typename EKFState_T>
void msf_core::MSF_SensorManagerROS< EKFState_T >::Config ( msf_core::MSF_CoreConfig &  config,
uint32_t  level 
)
inline
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManagerROS< EKFState_T >::coreConfig ( msf_core::MSF_CoreConfig &  config,
uint32_t  level 
)
inlinevirtual
template<typename EKFState_T>
virtual bool msf_core::MSF_SensorManagerROS< EKFState_T >::getParam_fixed_bias ( ) const
inlinevirtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManagerROS< EKFState_T >::getParam_fuzzythres ( ) const
inlinevirtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManagerROS< EKFState_T >::getParam_noise_acc ( ) const
inlinevirtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManagerROS< EKFState_T >::getParam_noise_accbias ( ) const
inlinevirtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManagerROS< EKFState_T >::getParam_noise_gyr ( ) const
inlinevirtual
template<typename EKFState_T>
virtual double msf_core::MSF_SensorManagerROS< EKFState_T >::getParam_noise_gyrbias ( ) const
inlinevirtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManagerROS< EKFState_T >::publishStateAfterPropagation ( const shared_ptr< EKFState_T > &  state) const
inlinevirtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManagerROS< EKFState_T >::publishStateAfterUpdate ( const shared_ptr< EKFState_T > &  state) const
inlinevirtual
template<typename EKFState_T>
virtual void msf_core::MSF_SensorManagerROS< EKFState_T >::publishStateInitial ( const shared_ptr< EKFState_T > &  state) const
inlinevirtual

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

Initialize the HLP based propagation.

Parameters
Statethe state to send to the HLP.

Implements msf_core::MSF_SensorManager< EKFState_T >.

template<typename EKFState_T>
void msf_core::MSF_SensorManagerROS< EKFState_T >::setHLStateBuffer ( const sensor_fusion_comm::ExtEkf &  msg)
inline

Member Data Documentation

template<typename EKFState_T>
msf_core::MSF_CoreConfig msf_core::MSF_SensorManagerROS< EKFState_T >::config_
protected
template<typename EKFState_T>
sensor_fusion_comm::ExtEkf msf_core::MSF_SensorManagerROS< EKFState_T >::hl_state_buf_
private
template<typename EKFState_T>
ros::Publisher msf_core::MSF_SensorManagerROS< EKFState_T >::pubCorrect_
private
template<typename EKFState_T>
ros::Publisher msf_core::MSF_SensorManagerROS< EKFState_T >::pubPose_
private
template<typename EKFState_T>
ros::Publisher msf_core::MSF_SensorManagerROS< EKFState_T >::pubPoseAfterUpdate_
private
template<typename EKFState_T>
ros::Publisher msf_core::MSF_SensorManagerROS< EKFState_T >::pubPoseCrtl_
private
template<typename EKFState_T>
ros::Publisher msf_core::MSF_SensorManagerROS< EKFState_T >::pubState_
private
template<typename EKFState_T>
ReconfigureServer* msf_core::MSF_SensorManagerROS< EKFState_T >::reconfServer_
private
template<typename EKFState_T>
tf::TransformBroadcaster msf_core::MSF_SensorManagerROS< EKFState_T >::tf_broadcaster_
mutableprivate

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