region_adjacency_graph.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef _REGION_ADJACENCY_GRAPH_H_
37 #define _REGION_ADJACENCY_GRAPH_H_
38 
39 // ROS header directives
40 #include <ros/ros.h>
41 #include <ros/console.h>
42 
43 // OpenCV header directives
44 #include <opencv2/imgproc/imgproc.hpp>
45 
46 // PCL header directives
47 #include <pcl/point_cloud.h>
48 #include <pcl/features/vfh.h>
49 
50 // boost header directives
51 #include <boost/graph/adjacency_list.hpp>
52 #include <boost/tuple/tuple.hpp>
53 #include <boost/config.hpp>
54 
55 #include <string>
56 #include <map>
57 
58 namespace jsk_pcl_ros
59 {
61  {
62  private:
63  struct VertexProperty {
64  int v_index;
65  pcl::PointXYZ v_center;
66  int v_label;
68  int i = -1,
69  pcl::PointXYZ center = pcl::PointXYZ(-1, -1, -1),
70  int label = -1) :
71  v_index(i), v_center(center), v_label(label) {}
72  };
73  typedef boost::property<boost::edge_weight_t, float> EdgeProperty;
74  typedef typename boost::adjacency_list<boost::vecS,
75  boost::vecS,
76  boost::undirectedS,
78  EdgeProperty> Graph;
79  typedef typename boost::graph_traits<
80  Graph>::adjacency_iterator AdjacencyIterator;
81  typedef typename boost::property_map<
82  Graph, boost::vertex_index_t>::type IndexMap;
83  typedef typename boost::graph_traits<
84  Graph>::edge_descriptor EdgeDescriptor;
85  typedef typename boost::property_map<
86  Graph, boost::edge_weight_t>::type EdgePropertyAccess;
87  typedef typename boost::property_traits<boost::property_map<
88  Graph, boost::edge_weight_t>::const_type>::value_type EdgeValue;
89  typedef typename boost::graph_traits<
90  Graph>::vertex_iterator VertexIterator;
91  typedef typename boost::graph_traits<
92  Graph>::vertex_descriptor VertexDescriptor;
93  typedef pcl::PointXYZRGB PointT;
94  Graph graph_;
95 
97  pcl::PointCloud<PointT>::Ptr,
98  pcl::PointCloud<pcl::Normal>::Ptr,
99  std::vector<Eigen::Vector3f> &,
100  std::vector<Eigen::Vector3f> &,
101  int = 3);
102  template<typename T>
104  const Eigen::Vector3f &,
105  const Eigen::Vector3f &,
106  const Eigen::Vector3f &,
107  const Eigen::Vector3f &);
108  template<typename T>
110  const std::vector<std::vector<Eigen::Vector3f> > &,
111  const std::vector<std::vector<Eigen::Vector3f> > &);
112  float getVectorAngle(
113  const Eigen::Vector3f &,
114  const Eigen::Vector3f &,
115  bool = true);
116  int getCommonNeigbour(
117  const std::vector<int> &,
118  const std::vector<int> &);
120  const pcl::PointCloud<PointT>::Ptr,
121  const pcl::PointCloud<pcl::Normal>::Ptr,
122  cv::Mat &);
123 
124  public:
126  virtual void generateRAG(
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> > &,
131  const int = RAG_EDGE_WEIGHT_DISTANCE);
132  virtual void splitMergeRAG(const int = 0.0f);
133  virtual void getCloudClusterLabels(
134  std::vector<int> &);
135  virtual void printGraph(
136  const Graph &);
137  enum {
140  };
141  };
142 } // namespace jsk_pcl_ros
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)
label
void computeCloudClusterRPYHistogram(const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &)
pointer T
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)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47