36 #ifndef _REGION_ADJACENCY_GRAPH_H_ 
   37 #define _REGION_ADJACENCY_GRAPH_H_ 
   44 #include <opencv2/imgproc/imgproc.hpp> 
   47 #include <pcl/point_cloud.h> 
   48 #include <pcl/features/vfh.h> 
   51 #include <boost/graph/adjacency_list.hpp> 
   52 #include <boost/tuple/tuple.hpp> 
   53 #include <boost/config.hpp> 
   60    class RegionAdjacencyGraph
 
   63       struct VertexProperty {
 
   69             pcl::PointXYZ center = pcl::PointXYZ(-1, -1, -1),
 
   73       typedef boost::property<boost::edge_weight_t, float> 
EdgeProperty;
 
   74       typedef typename boost::adjacency_list<boost::vecS,
 
   79       typedef typename boost::graph_traits<
 
   81       typedef typename boost::property_map<
 
   83       typedef typename boost::graph_traits<
 
   85       typedef typename boost::property_map<
 
   87       typedef typename boost::property_traits<boost::property_map<
 
   89       typedef typename boost::graph_traits<
 
   91       typedef typename boost::graph_traits<
 
   93       typedef pcl::PointXYZRGB 
PointT;
 
   97          pcl::PointCloud<PointT>::Ptr,
 
   98          pcl::PointCloud<pcl::Normal>::Ptr,
 
   99          std::vector<Eigen::Vector3f> &,
 
  100          std::vector<Eigen::Vector3f> &,
 
  104          const Eigen::Vector3f &,
 
  105          const Eigen::Vector3f &,
 
  106          const Eigen::Vector3f &,
 
  107          const Eigen::Vector3f &);
 
  110          const std::vector<std::vector<Eigen::Vector3f> > &,
 
  111          const std::vector<std::vector<Eigen::Vector3f> > &);
 
  113          const Eigen::Vector3f &,
 
  114          const Eigen::Vector3f &,
 
  117          const std::vector<int> &,
 
  118          const std::vector<int> &);
 
  120          const pcl::PointCloud<PointT>::Ptr,
 
  121          const pcl::PointCloud<pcl::Normal>::Ptr,
 
  127          const std::vector<pcl::PointCloud<PointT>::Ptr> &,
 
  128          const std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &,
 
  129          const pcl::PointCloud<pcl::PointXYZ>::Ptr,
 
  130          std::vector<std::vector<int> > &,
 
  143 #endif  //  _REGION_ADJACENCY_GRAPH_H_