CRegistrationDeciderOrOptimizer_ROS.h
Go to the documentation of this file.
00001 #ifndef CREGISTRATIONDECIDEROROPTIMIZER_ROS_H
00002 #define CREGISTRATIONDECIDEROROPTIMIZER_ROS_H
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <mrpt/utils/COutputLogger.h>
00007 #include <mrpt/graphslam/interfaces/CRegistrationDeciderOrOptimizer.h>
00008 
00009 namespace mrpt { namespace graphslam {
00010 
00016 template<class GRAPH_t=typename mrpt::graphs::CNetworkOfPoses2DInf>
00017 class CRegistrationDeciderOrOptimizer_ROS :
00018         public virtual mrpt::graphslam::CRegistrationDeciderOrOptimizer<GRAPH_t>
00019 {
00020 public:
00021         CRegistrationDeciderOrOptimizer_ROS();
00022         virtual ~CRegistrationDeciderOrOptimizer_ROS();
00023 
00024         virtual void setNodeHandle(ros::NodeHandle* nh);
00025 
00026 protected:
00029         ros::NodeHandle* m_nh;
00030 
00031 
00032 };
00033 
00034 
00035 } } // end of namespaces
00036 
00037 #include "mrpt_graphslam_2d/interfaces/CRegistrationDeciderOrOptimizer_ROS_impl.h"
00038 
00039 #endif /* end of include guard: CREGISTRATIONDECIDEROROPTIMIZER_ROS_H */


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sun Sep 17 2017 03:02:04