CGraphSlamEngine_ROS.h
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002          |                     Mobile Robot Programming Toolkit (MRPT)               |
00003          |                          http://www.mrpt.org/                             |
00004          |                                                                           |
00005          | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file        |
00006          | See: http://www.mrpt.org/Authors - All rights reserved.                   |
00007          | Released under BSD License. See details in http://www.mrpt.org/License    |
00008          +---------------------------------------------------------------------------+ */
00009 
00010 #pragma once
00011 
00012 #include "mrpt_graphslam_2d/interfaces/CRegistrationDeciderOrOptimizer_ROS.h"
00013 
00014 #include <mrpt/graphslam/CGraphSlamEngine.h>
00015 #include <ros/ros.h>
00016 
00017 namespace mrpt { namespace graphslam {
00018 
00024 template<class GRAPH_t=typename mrpt::graphs::CNetworkOfPoses2DInf>
00025 class CGraphSlamEngine_ROS : public CGraphSlamEngine<GRAPH_t>
00026 {
00027 public:
00028         typedef CGraphSlamEngine<GRAPH_t> parent;
00029 
00030         CGraphSlamEngine_ROS(
00031                         ros::NodeHandle* nh,
00032                         const std::string& config_file,
00033                         const std::string& rawlog_fname="",
00034                         const std::string& fname_GT="",
00035                         mrpt::graphslam::CWindowManager* win_manager=NULL,
00036                         mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_t>* node_reg=NULL,
00037                         mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_t>* edge_reg=NULL,
00038                         mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_t>* optimizer=NULL
00039                         );
00040         virtual ~CGraphSlamEngine_ROS();
00047         void setupComm();
00048 
00050         void initClass();
00051         ros::NodeHandle* m_nh;
00052 protected:
00057         void readParams();
00063         virtual void usePublishersBroadcasters();
00069         void readROSParameters();
00070         virtual bool _execGraphSlamStep(
00071                         mrpt::obs::CActionCollection::Ptr& action,
00072                         mrpt::obs::CSensoryFrame::Ptr& observations,
00073                         mrpt::obs::CObservation::Ptr& observation,
00074                         size_t& rawlog_entry);
00075 
00083         virtual void setupSubs();
00084         virtual void setupPubs();
00085         virtual void setupSrvs();
00097         ros::CallbackQueue custom_service_queue;
00098 
00099 
00100         int m_queue_size;
00101 };
00102 
00103 } } // end of namespaces
00104 
00105 #include "mrpt_graphslam_2d/CGraphSlamEngine_ROS_impl.h"
00106 


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