Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements methods for interacting with ROS. More...
#include <CGraphSlamEngine_ROS.h>
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::NodeHandle * | m_nh |
Protected Member Functions | |
virtual bool | _execGraphSlamStep (mrpt::obs::CActionCollectionPtr &action, mrpt::obs::CSensoryFramePtr &observations, mrpt::obs::CObservationPtr &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
| |
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 |
Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements methods for interacting with ROS.
Definition at line 26 of file CGraphSlamEngine_ROS.h.
typedef CGraphSlamEngine<GRAPH_t> mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::parent |
Definition at line 29 of file CGraphSlamEngine_ROS.h.
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 15 of file CGraphSlamEngine_ROS_impl.h.
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::~CGraphSlamEngine_ROS | ( | ) | [virtual] |
Definition at line 38 of file CGraphSlamEngine_ROS_impl.h.
bool mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::_execGraphSlamStep | ( | mrpt::obs::CActionCollectionPtr & | action, |
mrpt::obs::CSensoryFramePtr & | observations, | ||
mrpt::obs::CObservationPtr & | observation, | ||
size_t & | rawlog_entry | ||
) | [protected, virtual] |
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 95 of file CGraphSlamEngine_ROS_impl.h.
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::initClass | ( | ) |
Initialize object instance.
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 44 of file CGraphSlamEngine_ROS_impl.h.
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::readParams | ( | ) | [protected] |
Read the problem configuration parameters.
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 86 of file CGraphSlamEngine_ROS_impl.h.
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::readROSParameters | ( | ) | [protected] |
Read configuration parameters from the ROS parameter server.
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 92 of file CGraphSlamEngine_ROS_impl.h.
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 112 of file CGraphSlamEngine_ROS_impl.h.
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupPubs | ( | ) | [protected, virtual] |
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 130 of file CGraphSlamEngine_ROS_impl.h.
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupSrvs | ( | ) | [protected, virtual] |
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 136 of file CGraphSlamEngine_ROS_impl.h.
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupSubs | ( | ) | [protected, virtual] |
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 124 of file CGraphSlamEngine_ROS_impl.h.
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 109 of file CGraphSlamEngine_ROS_impl.h.
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.
Definition at line 98 of file CGraphSlamEngine_ROS.h.
ros::NodeHandle* mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::m_nh |
Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.
Definition at line 52 of file CGraphSlamEngine_ROS.h.
int mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::m_queue_size [protected] |
Definition at line 101 of file CGraphSlamEngine_ROS.h.