Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t > Class Template Reference

Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements methods for interacting with ROS. More...

#include <CGraphSlamEngine_ROS.h>

Inheritance diagram for mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef CGraphSlamEngine< GRAPH_t > parent

Public Member Functions

 CGraphSlamEngine_ROS (ros::NodeHandle *nh, const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_t > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_t > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_t > *optimizer=NULL)
void initClass ()
 Initialize object instance.
void setupComm ()
 Wrapper method around the protected setup* class methods.
virtual ~CGraphSlamEngine_ROS ()

Public Attributes

ros::NodeHandlem_nh

Protected Member Functions

virtual bool _execGraphSlamStep (mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
void readParams ()
 Read the problem configuration parameters.
void readROSParameters ()
 Read configuration parameters from the ROS parameter server.
virtual void usePublishersBroadcasters ()
 Provide feedback about the SLAM operation.
setup* ROS-related methods

Methods for setting up topic subscribers, publishers, and corresponding services

See also:
setupComm
virtual void setupSubs ()
virtual void setupPubs ()
virtual void setupSrvs ()

Protected Attributes

ros::CallbackQueue custom_service_queue
 Custom Callback queue for processing requests for the services outside the standard CallbackQueue.
int m_queue_size

Detailed Description

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
class mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >

Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements methods for interacting with ROS.

Definition at line 25 of file CGraphSlamEngine_ROS.h.


Member Typedef Documentation

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef CGraphSlamEngine<GRAPH_t> mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::parent

Definition at line 28 of file CGraphSlamEngine_ROS.h.


Constructor & Destructor Documentation

template<class GRAPH_t>
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::CGraphSlamEngine_ROS ( ros::NodeHandle nh,
const std::string &  config_file,
const std::string &  rawlog_fname = "",
const std::string &  fname_GT = "",
mrpt::graphslam::CWindowManager *  win_manager = NULL,
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_t > *  node_reg = NULL,
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_t > *  edge_reg = NULL,
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_t > *  optimizer = NULL 
)

Definition at line 14 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::~CGraphSlamEngine_ROS ( ) [virtual]

Definition at line 37 of file CGraphSlamEngine_ROS_impl.h.


Member Function Documentation

template<class GRAPH_t >
bool mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::_execGraphSlamStep ( mrpt::obs::CActionCollection::Ptr &  action,
mrpt::obs::CSensoryFrame::Ptr &  observations,
mrpt::obs::CObservation::Ptr &  observation,
size_t &  rawlog_entry 
) [protected, virtual]
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::initClass ( )

Initialize object instance.

Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.

Definition at line 43 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::readParams ( ) [protected]

Read the problem configuration parameters.

See also:
readROSParameters, CGraphSlamEngine::loadParams

Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.

Definition at line 82 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::readROSParameters ( ) [protected]

Read configuration parameters from the ROS parameter server.

Note:
Method is automatically called on object construction.
See also:
readParams, initClass

Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.

Definition at line 88 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupComm ( )

Wrapper method around the protected setup* class methods.

Handy for setting up publishers, subscribers, services all at once.

Definition at line 108 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupPubs ( ) [protected, virtual]
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupSrvs ( ) [protected, virtual]
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupSubs ( ) [protected, virtual]
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::usePublishersBroadcasters ( ) [protected, virtual]

Provide feedback about the SLAM operation.

Method makes the necessary calls to all the publishers of the class and broadcaster instances

Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.

Definition at line 105 of file CGraphSlamEngine_ROS_impl.h.


Member Data Documentation

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
ros::CallbackQueue mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::custom_service_queue [protected]

Custom Callback queue for processing requests for the services outside the standard CallbackQueue.

Note:
Logical thing would be to define it in CGraphSlamEngine_MR, but that results in an segfault with the following error message: ``` pure virtual method called terminate called without an active exception ```

Definition at line 97 of file CGraphSlamEngine_ROS.h.

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
ros::NodeHandle* mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::m_nh

Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.

Definition at line 51 of file CGraphSlamEngine_ROS.h.

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::m_queue_size [protected]

Definition at line 100 of file CGraphSlamEngine_ROS.h.


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


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Thu Jun 6 2019 21:40:26