Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #ifndef _REGION_ADJACENCY_GRAPH_H_
00037 #define _REGION_ADJACENCY_GRAPH_H_
00038 
00039 
00040 #include <ros/ros.h>
00041 #include <ros/console.h>
00042 
00043 
00044 #include <opencv2/imgproc/imgproc.hpp>
00045 
00046 
00047 #include <pcl/point_cloud.h>
00048 #include <pcl/features/vfh.h>
00049 
00050 
00051 #include <boost/graph/adjacency_list.hpp>
00052 #include <boost/tuple/tuple.hpp>
00053 #include <boost/config.hpp>
00054 
00055 #include <string>
00056 #include <map>
00057 
00058 namespace jsk_pcl_ros
00059 {
00060    class RegionAdjacencyGraph
00061    {
00062     private:
00063       struct VertexProperty {
00064          int v_index;
00065          pcl::PointXYZ v_center;
00066          int v_label;
00067          VertexProperty(
00068             int i = -1,
00069             pcl::PointXYZ center = pcl::PointXYZ(-1, -1, -1),
00070             int label = -1) :
00071             v_index(i), v_center(center), v_label(label) {}
00072       };
00073       typedef boost::property<boost::edge_weight_t, float> EdgeProperty;
00074       typedef typename boost::adjacency_list<boost::vecS,
00075                                              boost::vecS,
00076                                              boost::undirectedS,
00077                                              VertexProperty,
00078                                              EdgeProperty> Graph;
00079       typedef typename boost::graph_traits<
00080          Graph>::adjacency_iterator AdjacencyIterator;
00081       typedef typename boost::property_map<
00082          Graph, boost::vertex_index_t>::type IndexMap;
00083       typedef typename boost::graph_traits<
00084          Graph>::edge_descriptor EdgeDescriptor;
00085       typedef typename boost::property_map<
00086          Graph, boost::edge_weight_t>::type EdgePropertyAccess;
00087       typedef typename boost::property_traits<boost::property_map<
00088          Graph, boost::edge_weight_t>::const_type>::value_type EdgeValue;
00089       typedef typename boost::graph_traits<
00090          Graph>::vertex_iterator VertexIterator;
00091       typedef typename boost::graph_traits<
00092          Graph>::vertex_descriptor VertexDescriptor;
00093       typedef pcl::PointXYZRGB PointT;
00094       Graph graph_;
00095       
00096       void sampleRandomPointsFromCloudCluster(
00097          pcl::PointCloud<PointT>::Ptr,
00098          pcl::PointCloud<pcl::Normal>::Ptr,
00099          std::vector<Eigen::Vector3f> &,
00100          std::vector<Eigen::Vector3f> &,
00101          int = 3);
00102       template<typename T>
00103       T convexityCriterion(
00104          const Eigen::Vector3f &,
00105          const Eigen::Vector3f &,
00106          const Eigen::Vector3f &,
00107          const Eigen::Vector3f &);
00108       template<typename T>
00109       T getCloudClusterWeightFunction(
00110          const std::vector<std::vector<Eigen::Vector3f> > &,
00111          const std::vector<std::vector<Eigen::Vector3f> > &);
00112       float getVectorAngle(
00113          const Eigen::Vector3f &,
00114          const Eigen::Vector3f &,
00115          bool = true);
00116       int getCommonNeigbour(
00117          const std::vector<int> &,
00118          const std::vector<int> &);
00119       void computeCloudClusterRPYHistogram(
00120          const pcl::PointCloud<PointT>::Ptr,
00121          const pcl::PointCloud<pcl::Normal>::Ptr,
00122          cv::Mat &);
00123 
00124     public:
00125       RegionAdjacencyGraph();
00126       virtual void generateRAG(
00127          const std::vector<pcl::PointCloud<PointT>::Ptr> &,
00128          const std::vector<pcl::PointCloud<pcl::Normal>::Ptr> &,
00129          const pcl::PointCloud<pcl::PointXYZ>::Ptr,
00130          std::vector<std::vector<int> > &,
00131          const int = RAG_EDGE_WEIGHT_DISTANCE);
00132       virtual void splitMergeRAG(const int = 0.0f);
00133       virtual void getCloudClusterLabels(
00134          std::vector<int> &);
00135       virtual void printGraph(
00136          const Graph &);
00137       enum {
00138          RAG_EDGE_WEIGHT_DISTANCE,
00139          RAG_EDGE_WEIGHT_CONVEX_CRITERIA
00140       };
00141     };
00142 }  
00143 #endif  //  _REGION_ADJACENCY_GRAPH_H_