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> 69 pcl::PointXYZ center = pcl::PointXYZ(-1, -1, -1),
71 v_index(i), v_center(center), v_label(
label) {}
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<
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_ virtual void splitMergeRAG(const int=0.0f)
void sampleRandomPointsFromCloudCluster(pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, std::vector< Eigen::Vector3f > &, std::vector< Eigen::Vector3f > &, int=3)
void computeCloudClusterRPYHistogram(const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &)
boost::property_map< Graph, boost::vertex_index_t >::type IndexMap
virtual void getCloudClusterLabels(std::vector< int > &)
boost::graph_traits< Graph >::vertex_descriptor VertexDescriptor
T convexityCriterion(const Eigen::Vector3f &, const Eigen::Vector3f &, const Eigen::Vector3f &, const Eigen::Vector3f &)
boost::graph_traits< Graph >::vertex_iterator VertexIterator
boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, VertexProperty, EdgeProperty > Graph
T getCloudClusterWeightFunction(const std::vector< std::vector< Eigen::Vector3f > > &, const std::vector< std::vector< Eigen::Vector3f > > &)
float getVectorAngle(const Eigen::Vector3f &, const Eigen::Vector3f &, bool=true)
boost::property_map< Graph, boost::edge_weight_t >::type EdgePropertyAccess
boost::property< boost::edge_weight_t, float > EdgeProperty
int getCommonNeigbour(const std::vector< int > &, const std::vector< int > &)
virtual void generateRAG(const std::vector< pcl::PointCloud< PointT >::Ptr > &, const std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &, const pcl::PointCloud< pcl::PointXYZ >::Ptr, std::vector< std::vector< int > > &, const int=RAG_EDGE_WEIGHT_DISTANCE)
boost::property_traits< boost::property_map< Graph, boost::edge_weight_t >::const_type >::value_type EdgeValue
boost::graph_traits< Graph >::adjacency_iterator AdjacencyIterator
virtual void printGraph(const Graph &)
boost::graph_traits< Graph >::edge_descriptor EdgeDescriptor
VertexProperty(int i=-1, pcl::PointXYZ center=pcl::PointXYZ(-1,-1,-1), int label=-1)