#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, EdgeProperty > | Graph |
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_ |
Definition at line 60 of file region_adjacency_graph.h.
|
private |
Definition at line 80 of file region_adjacency_graph.h.
|
private |
Definition at line 84 of file region_adjacency_graph.h.
|
private |
Definition at line 73 of file region_adjacency_graph.h.
|
private |
Definition at line 86 of file region_adjacency_graph.h.
|
private |
Definition at line 88 of file region_adjacency_graph.h.
|
private |
Definition at line 78 of file region_adjacency_graph.h.
|
private |
Definition at line 82 of file region_adjacency_graph.h.
|
private |
Definition at line 93 of file region_adjacency_graph.h.
|
private |
Definition at line 92 of file region_adjacency_graph.h.
|
private |
Definition at line 90 of file region_adjacency_graph.h.
anonymous enum |
Enumerator | |
---|---|
RAG_EDGE_WEIGHT_DISTANCE | |
RAG_EDGE_WEIGHT_CONVEX_CRITERIA |
Definition at line 137 of file region_adjacency_graph.h.
jsk_pcl_ros::RegionAdjacencyGraph::RegionAdjacencyGraph | ( | ) |
Definition at line 45 of file region_adjacency_graph.cpp.
|
private |
Definition at line 347 of file region_adjacency_graph.cpp.
|
private |
Definition at line 233 of file region_adjacency_graph.cpp.
|
virtual |
Definition at line 50 of file region_adjacency_graph.cpp.
|
virtual |
Definition at line 326 of file region_adjacency_graph.cpp.
|
private |
Definition at line 168 of file region_adjacency_graph.cpp.
|
private |
Definition at line 308 of file region_adjacency_graph.cpp.
|
private |
Definition at line 219 of file region_adjacency_graph.cpp.
|
virtual |
Definition at line 336 of file region_adjacency_graph.cpp.
|
private |
Definition at line 246 of file region_adjacency_graph.cpp.
|
virtual |
Definition at line 265 of file region_adjacency_graph.cpp.
|
private |
Definition at line 94 of file region_adjacency_graph.h.