Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 #ifndef CGRAPHSLAMENGINE_ROS_H
00011 #define CGRAPHSLAMENGINE_ROS_H
00012
00013 #include "mrpt_graphslam_2d/interfaces/CRegistrationDeciderOrOptimizer_ROS.h"
00014
00015 #include <mrpt/graphslam/CGraphSlamEngine.h>
00016 #include <ros/ros.h>
00017
00018 namespace mrpt { namespace graphslam {
00019
00025 template<class GRAPH_t=typename mrpt::graphs::CNetworkOfPoses2DInf>
00026 class CGraphSlamEngine_ROS : public CGraphSlamEngine<GRAPH_t>
00027 {
00028 public:
00029 typedef CGraphSlamEngine<GRAPH_t> parent;
00030
00031 CGraphSlamEngine_ROS(
00032 ros::NodeHandle* nh,
00033 const std::string& config_file,
00034 const std::string& rawlog_fname="",
00035 const std::string& fname_GT="",
00036 mrpt::graphslam::CWindowManager* win_manager=NULL,
00037 mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_t>* node_reg=NULL,
00038 mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_t>* edge_reg=NULL,
00039 mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_t>* optimizer=NULL
00040 );
00041 virtual ~CGraphSlamEngine_ROS();
00048 void setupComm();
00049
00051 void initClass();
00052 ros::NodeHandle* m_nh;
00053 protected:
00058 void readParams();
00064 virtual void usePublishersBroadcasters();
00070 void readROSParameters();
00071 virtual bool _execGraphSlamStep(
00072 mrpt::obs::CActionCollectionPtr& action,
00073 mrpt::obs::CSensoryFramePtr& observations,
00074 mrpt::obs::CObservationPtr& observation,
00075 size_t& rawlog_entry);
00076
00084 virtual void setupSubs();
00085 virtual void setupPubs();
00086 virtual void setupSrvs();
00098 ros::CallbackQueue custom_service_queue;
00099
00100
00101 int m_queue_size;
00102 };
00103
00104 } }
00105
00106 #include "mrpt_graphslam_2d/CGraphSlamEngine_ROS_impl.h"
00107
00108 #endif