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, float > EdgeProperty
 
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 92 of file region_adjacency_graph.h.

Member Typedef Documentation

◆ AdjacencyIterator

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

Definition at line 144 of file region_adjacency_graph.h.

◆ EdgeDescriptor

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

Definition at line 148 of file region_adjacency_graph.h.

◆ EdgeProperty

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

Definition at line 137 of file region_adjacency_graph.h.

◆ EdgePropertyAccess

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

Definition at line 150 of file region_adjacency_graph.h.

◆ EdgeValue

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 152 of file region_adjacency_graph.h.

◆ Graph

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

Definition at line 142 of file region_adjacency_graph.h.

◆ IndexMap

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

Definition at line 146 of file region_adjacency_graph.h.

◆ PointT

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

Definition at line 157 of file region_adjacency_graph.h.

◆ VertexDescriptor

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

Definition at line 156 of file region_adjacency_graph.h.

◆ VertexIterator

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

Definition at line 154 of file region_adjacency_graph.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
RAG_EDGE_WEIGHT_DISTANCE 
RAG_EDGE_WEIGHT_CONVEX_CRITERIA 

Definition at line 201 of file region_adjacency_graph.h.

Constructor & Destructor Documentation

◆ RegionAdjacencyGraph()

jsk_pcl_ros::RegionAdjacencyGraph::RegionAdjacencyGraph ( )

Definition at line 77 of file region_adjacency_graph.cpp.

Member Function Documentation

◆ computeCloudClusterRPYHistogram()

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 379 of file region_adjacency_graph.cpp.

◆ convexityCriterion()

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 265 of file region_adjacency_graph.cpp.

◆ generateRAG()

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 82 of file region_adjacency_graph.cpp.

◆ getCloudClusterLabels()

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

Definition at line 358 of file region_adjacency_graph.cpp.

◆ getCloudClusterWeightFunction()

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 200 of file region_adjacency_graph.cpp.

◆ getCommonNeigbour()

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

Definition at line 340 of file region_adjacency_graph.cpp.

◆ getVectorAngle()

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

Definition at line 251 of file region_adjacency_graph.cpp.

◆ printGraph()

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

Definition at line 368 of file region_adjacency_graph.cpp.

◆ sampleRandomPointsFromCloudCluster()

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 278 of file region_adjacency_graph.cpp.

◆ splitMergeRAG()

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

Definition at line 297 of file region_adjacency_graph.cpp.

Member Data Documentation

◆ graph_

Graph jsk_pcl_ros::RegionAdjacencyGraph::graph_
private

Definition at line 158 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 Tue Jan 7 2025 04:05:46