Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
jsk_pcl_ros::RegionAdjacencyGraph Class Reference

#include <region_adjacency_graph.h>

Classes

struct  VertexProperty
 

Public Types

enum  { RAG_EDGE_WEIGHT_DISTANCE, RAG_EDGE_WEIGHT_CONVEX_CRITERIA }
 

Public Member Functions

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)
 
virtual void getCloudClusterLabels (std::vector< int > &)
 
virtual void printGraph (const Graph &)
 
 RegionAdjacencyGraph ()
 
virtual void splitMergeRAG (const int=0.0f)
 

Private Types

typedef boost::graph_traits< Graph >::adjacency_iterator AdjacencyIterator
 
typedef boost::graph_traits< Graph >::edge_descriptor EdgeDescriptor
 
typedef boost::property< boost::edge_weight_t, floatEdgeProperty
 
typedef boost::property_map< Graph, boost::edge_weight_t >::type EdgePropertyAccess
 
typedef boost::property_traits< boost::property_map< Graph, boost::edge_weight_t >::const_type >::value_type EdgeValue
 
typedef boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, VertexProperty, EdgePropertyGraph
 
typedef boost::property_map< Graph, boost::vertex_index_t >::type IndexMap
 
typedef pcl::PointXYZRGB PointT
 
typedef boost::graph_traits< Graph >::vertex_descriptor VertexDescriptor
 
typedef boost::graph_traits< Graph >::vertex_iterator VertexIterator
 

Private Member Functions

void computeCloudClusterRPYHistogram (const pcl::PointCloud< PointT >::Ptr, const pcl::PointCloud< pcl::Normal >::Ptr, cv::Mat &)
 
template<typename T >
T convexityCriterion (const Eigen::Vector3f &, const Eigen::Vector3f &, const Eigen::Vector3f &, const Eigen::Vector3f &)
 
template<typename T >
T getCloudClusterWeightFunction (const std::vector< std::vector< Eigen::Vector3f > > &, const std::vector< std::vector< Eigen::Vector3f > > &)
 
int getCommonNeigbour (const std::vector< int > &, const std::vector< int > &)
 
float getVectorAngle (const Eigen::Vector3f &, const Eigen::Vector3f &, bool=true)
 
void sampleRandomPointsFromCloudCluster (pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, std::vector< Eigen::Vector3f > &, std::vector< Eigen::Vector3f > &, int=3)
 

Private Attributes

Graph graph_
 

Detailed Description

Definition at line 60 of file region_adjacency_graph.h.

Member Typedef Documentation

typedef boost::graph_traits< Graph>::adjacency_iterator jsk_pcl_ros::RegionAdjacencyGraph::AdjacencyIterator
private

Definition at line 80 of file region_adjacency_graph.h.

typedef boost::graph_traits< Graph>::edge_descriptor jsk_pcl_ros::RegionAdjacencyGraph::EdgeDescriptor
private

Definition at line 84 of file region_adjacency_graph.h.

typedef boost::property<boost::edge_weight_t, float> jsk_pcl_ros::RegionAdjacencyGraph::EdgeProperty
private

Definition at line 73 of file region_adjacency_graph.h.

typedef boost::property_map< Graph, boost::edge_weight_t>::type jsk_pcl_ros::RegionAdjacencyGraph::EdgePropertyAccess
private

Definition at line 86 of file region_adjacency_graph.h.

typedef boost::property_traits<boost::property_map< Graph, boost::edge_weight_t>::const_type>::value_type jsk_pcl_ros::RegionAdjacencyGraph::EdgeValue
private

Definition at line 88 of file region_adjacency_graph.h.

typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::undirectedS, VertexProperty, EdgeProperty> jsk_pcl_ros::RegionAdjacencyGraph::Graph
private

Definition at line 78 of file region_adjacency_graph.h.

typedef boost::property_map< Graph, boost::vertex_index_t>::type jsk_pcl_ros::RegionAdjacencyGraph::IndexMap
private

Definition at line 82 of file region_adjacency_graph.h.

typedef pcl::PointXYZRGB jsk_pcl_ros::RegionAdjacencyGraph::PointT
private

Definition at line 93 of file region_adjacency_graph.h.

typedef boost::graph_traits< Graph>::vertex_descriptor jsk_pcl_ros::RegionAdjacencyGraph::VertexDescriptor
private

Definition at line 92 of file region_adjacency_graph.h.

typedef boost::graph_traits< Graph>::vertex_iterator jsk_pcl_ros::RegionAdjacencyGraph::VertexIterator
private

Definition at line 90 of file region_adjacency_graph.h.

Member Enumeration Documentation

anonymous enum
Enumerator
RAG_EDGE_WEIGHT_DISTANCE 
RAG_EDGE_WEIGHT_CONVEX_CRITERIA 

Definition at line 137 of file region_adjacency_graph.h.

Constructor & Destructor Documentation

jsk_pcl_ros::RegionAdjacencyGraph::RegionAdjacencyGraph ( )

Definition at line 45 of file region_adjacency_graph.cpp.

Member Function Documentation

void jsk_pcl_ros::RegionAdjacencyGraph::computeCloudClusterRPYHistogram ( const pcl::PointCloud< PointT >::Ptr  _cloud,
const pcl::PointCloud< pcl::Normal >::Ptr  _normal,
cv::Mat &  _histogram 
)
private

Definition at line 347 of file region_adjacency_graph.cpp.

template<typename T >
T jsk_pcl_ros::RegionAdjacencyGraph::convexityCriterion ( const Eigen::Vector3f &  center_point,
const Eigen::Vector3f &  n1_point,
const Eigen::Vector3f &  center_normal,
const Eigen::Vector3f &  neigbour_normal 
)
private

Definition at line 233 of file region_adjacency_graph.cpp.

void jsk_pcl_ros::RegionAdjacencyGraph::generateRAG ( const std::vector< pcl::PointCloud< PointT >::Ptr > &  cloud_clusters,
const std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &  normal_clusters,
const pcl::PointCloud< pcl::PointXYZ >::Ptr  centroids,
std::vector< std::vector< int > > &  neigbor_indices,
const int  edge_weight_criteria = RAG_EDGE_WEIGHT_DISTANCE 
)
virtual

Definition at line 50 of file region_adjacency_graph.cpp.

void jsk_pcl_ros::RegionAdjacencyGraph::getCloudClusterLabels ( std::vector< int > &  labelMD)
virtual

Definition at line 326 of file region_adjacency_graph.cpp.

template<typename T >
T jsk_pcl_ros::RegionAdjacencyGraph::getCloudClusterWeightFunction ( const std::vector< std::vector< Eigen::Vector3f > > &  _points,
const std::vector< std::vector< Eigen::Vector3f > > &  _normal 
)
private

Definition at line 168 of file region_adjacency_graph.cpp.

int jsk_pcl_ros::RegionAdjacencyGraph::getCommonNeigbour ( const std::vector< int > &  c1_neigbour,
const std::vector< int > &  c2_neigbour 
)
private

Definition at line 308 of file region_adjacency_graph.cpp.

float jsk_pcl_ros::RegionAdjacencyGraph::getVectorAngle ( const Eigen::Vector3f &  vector1,
const Eigen::Vector3f &  vector2,
bool  indegree = true 
)
private

Definition at line 219 of file region_adjacency_graph.cpp.

void jsk_pcl_ros::RegionAdjacencyGraph::printGraph ( const Graph _graph)
virtual

Definition at line 336 of file region_adjacency_graph.cpp.

void jsk_pcl_ros::RegionAdjacencyGraph::sampleRandomPointsFromCloudCluster ( pcl::PointCloud< PointT >::Ptr  cloud,
pcl::PointCloud< pcl::Normal >::Ptr  normal,
std::vector< Eigen::Vector3f > &  point_vector,
std::vector< Eigen::Vector3f > &  normal_vector,
int  gen_sz = 3 
)
private

Definition at line 246 of file region_adjacency_graph.cpp.

void jsk_pcl_ros::RegionAdjacencyGraph::splitMergeRAG ( const int  _threshold = 0.0f)
virtual

Definition at line 265 of file region_adjacency_graph.cpp.

Member Data Documentation

Graph jsk_pcl_ros::RegionAdjacencyGraph::graph_
private

Definition at line 94 of file region_adjacency_graph.h.


The documentation for this class was generated from the following files:


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