W3cubDocs

/PointCloudLibrary

Detailed Description

Overview

The pcl_segmentation library contains algorithms for segmenting a point cloud into distinct clusters. These algorithms are best suited to processing a point cloud that is composed of a number of spatially isolated regions. In such cases, clustering is often used to break the cloud down into its constituent parts, which can then be processed independently.

Requirements

Classes

class pcl::gpu::EuclideanClusterExtraction< PointT >
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense, depending on pcl::gpu::octree More...
class pcl::gpu::EuclideanLabeledClusterExtraction< PointT >
EuclideanLabeledClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense, depending on pcl::gpu::octree More...
class pcl::ConditionalEuclideanClustering< PointT >
ConditionalEuclideanClustering performs segmentation based on Euclidean distance and a user-defined clustering condition. More...
class pcl::CPCSegmentation< PointT >
A segmentation algorithm partitioning a supervoxel graph. More...
class pcl::EuclideanClusterExtraction< PointT >
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More...
class pcl::LabeledEuclideanClusterExtraction< PointT >
LabeledEuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense, with label info. More...
class pcl::ExtractPolygonalPrismData< PointT >
ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. More...
class pcl::GrabCut< PointT >
Implementation of the GrabCut segmentation in "GrabCut — Interactive Foreground Extraction using Iterated Graph Cuts" by Carsten Rother, Vladimir Kolmogorov and Andrew Blake. More...
class pcl::segmentation::detail::RandomWalker< Graph, EdgeWeightMap, VertexColorMap >
Multilabel graph segmentation using random walks. More...
class pcl::LCCPSegmentation< PointT >
A simple segmentation algorithm partitioning a supervoxel graph into groups of locally convex connected supervoxels separated by concave borders. More...
class pcl::RegionGrowing< PointT, NormalT >
Implements the well known Region Growing algorithm used for segmentation. More...
class pcl::RegionGrowingRGB< PointT, NormalT >
Implements the well known Region Growing algorithm used for segmentation based on color of points. More...
class pcl::SACSegmentation< PointT >
SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation. More...
class pcl::SACSegmentationFromNormals< PointT, PointNT >
SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation. More...
class pcl::SeededHueSegmentation
SeededHueSegmentation. More...
class pcl::SegmentDifferences< PointT >
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold. More...
class pcl::SupervoxelClustering< PointT >
Implements a supervoxel algorithm based on voxel structure, normals, and rgb values. More...

Functions

bool pcl::gpu::comparePointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b)
Sort clusters method (for std::sort). More...
bool pcl::gpu::compareLabeledPointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b)
Sort clusters method (for std::sort). More...
template<typename PointT >
void pcl::extractEuclideanClusters (const PointCloud< PointT > &cloud, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)())
Decompose a region of space into clusters based on the Euclidean distance between points. More...
template<typename PointT >
void pcl::extractEuclideanClusters (const PointCloud< PointT > &cloud, const Indices &indices, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)())
Decompose a region of space into clusters based on the Euclidean distance between points. More...
template<typename PointT , typename Normal >
void pcl::extractEuclideanClusters (const PointCloud< PointT > &cloud, const PointCloud< Normal > &normals, float tolerance, const typename KdTree< PointT >::Ptr &tree, std::vector< PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)())
Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation between points. More...
template<typename PointT , typename Normal >
void pcl::extractEuclideanClusters (const PointCloud< PointT > &cloud, const PointCloud< Normal > &normals, const Indices &indices, const typename KdTree< PointT >::Ptr &tree, float tolerance, std::vector< PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)())
Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation between points. More...
bool pcl::comparePointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b)
Sort clusters method (for std::sort). More...
template<typename PointT >
void pcl::extractLabeledEuclideanClusters (const PointCloud< PointT > &cloud, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< std::vector< PointIndices >> &labeled_clusters, unsigned int min_pts_per_cluster, unsigned int max_pts_per_cluster, unsigned int max_label)
Decompose a region of space into clusters based on the Euclidean distance between points. More...
template<typename PointT >
void pcl::extractLabeledEuclideanClusters (const PointCloud< PointT > &cloud, const typename search::Search< PointT >::Ptr &tree, float tolerance, std::vector< std::vector< PointIndices >> &labeled_clusters, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=std::numeric_limits< unsigned int >::max())
Decompose a region of space into clusters based on the Euclidean distance between points. More...
bool pcl::compareLabeledPointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b)
Sort clusters method (for std::sort). More...
template<typename PointT >
bool pcl::isPointIn2DPolygon (const PointT &point, const pcl::PointCloud< PointT > &polygon)
General purpose method for checking if a 3D point is inside or outside a given 2D polygon. More...
template<typename PointT >
bool pcl::isXYPointIn2DXYPolygon (const PointT &point, const pcl::PointCloud< PointT > &polygon)
Check if a 2d point (X and Y coordinates considered only!) is inside or outside a given polygon. More...
template<class Graph >
bool pcl::segmentation::randomWalker (Graph &graph)
Multilabel graph segmentation using random walks. More...
template<class Graph , class EdgeWeightMap , class VertexColorMap >
bool pcl::segmentation::randomWalker (Graph &graph, EdgeWeightMap weights, VertexColorMap colors)
Multilabel graph segmentation using random walks. More...
template<class Graph , class EdgeWeightMap , class VertexColorMap >
bool pcl::segmentation::randomWalker (Graph &graph, EdgeWeightMap weights, VertexColorMap colors, Eigen::Matrix< typename boost::property_traits< EdgeWeightMap >::value_type, Eigen::Dynamic, Eigen::Dynamic > &potentials, std::map< typename boost::property_traits< VertexColorMap >::value_type, std::size_t > &colors_to_columns_map)
Multilabel graph segmentation using random walks. More...
void pcl::seededHueSegmentation (const PointCloud< PointXYZRGB > &cloud, const search::Search< PointXYZRGB >::Ptr &tree, float tolerance, PointIndices &indices_in, PointIndices &indices_out, float delta_hue=0.0)
Decompose a region of space into clusters based on the Euclidean distance between points. More...
void pcl::seededHueSegmentation (const PointCloud< PointXYZRGB > &cloud, const search::Search< PointXYZRGBL >::Ptr &tree, float tolerance, PointIndices &indices_in, PointIndices &indices_out, float delta_hue=0.0)
Decompose a region of space into clusters based on the Euclidean distance between points. More...
template<typename PointT >
void pcl::getPointCloudDifference (const pcl::PointCloud< PointT > &src, double threshold, const typename pcl::search::Search< PointT >::Ptr &tree, pcl::PointCloud< PointT > &output)
Obtain the difference between two aligned point clouds as another point cloud, given a distance threshold. More...

Function Documentation

compareLabeledPointClusters() [1/2]

bool pcl::gpu::compareLabeledPointClusters ( const pcl::PointIndices & a,
const pcl::PointIndices & b
)
inline

#include </__w/1/s/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h>

Sort clusters method (for std::sort).

Definition at line 206 of file gpu_extract_labeled_clusters.h.

References pcl::PointIndices::indices.

Referenced by pcl::gpu::EuclideanLabeledClusterExtraction< PointT >::extract().

compareLabeledPointClusters() [2/2]

bool pcl::compareLabeledPointClusters ( const pcl::PointIndices & a,
const pcl::PointIndices & b
)
inline

#include <pcl/segmentation/extract_labeled_clusters.h>

Sort clusters method (for std::sort).

Definition at line 254 of file extract_labeled_clusters.h.

References pcl::PointIndices::indices.

comparePointClusters() [1/2]

bool pcl::gpu::comparePointClusters ( const pcl::PointIndices & a,
const pcl::PointIndices & b
)
inline

#include </__w/1/s/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h>

Sort clusters method (for std::sort).

Definition at line 212 of file gpu_extract_clusters.h.

References pcl::PointIndices::indices.

Referenced by pcl::LabeledEuclideanClusterExtraction< PointT >::extract(), and pcl::EuclideanClusterExtraction< PointT >::extract().

comparePointClusters() [2/2]

bool pcl::comparePointClusters ( const pcl::PointIndices & a,
const pcl::PointIndices & b
)
inline

#include <pcl/segmentation/extract_clusters.h>

Sort clusters method (for std::sort).

Definition at line 448 of file extract_clusters.h.

References pcl::PointIndices::indices.

extractEuclideanClusters() [1/4]

template<typename PointT >
void pcl::extractEuclideanClusters ( const PointCloud< PointT > & cloud,
const Indices & indices,
const typename search::Search< PointT >::Ptr & tree,
float tolerance,
std::vector< PointIndices > & clusters,
unsigned int min_pts_per_cluster = 1,
unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ()
)

#include <pcl/segmentation/extract_clusters.h>

Decompose a region of space into clusters based on the Euclidean distance between points.

Parameters
cloud the point cloud message
indices a list of point indices to use from cloud
tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud and indices
Parameters
tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
clusters the resultant clusters containing point indices (as a vector of PointIndices)
min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)
Todo:
: fix the return value, make sure the exit is not needed anymore

Definition at line 127 of file extract_clusters.hpp.

References pcl::search::Search< PointT >::getIndices(), pcl::search::Search< PointT >::getInputCloud(), pcl::search::Search< PointT >::getSortedResults(), pcl::PointIndices::header, pcl::PointCloud< PointT >::header, pcl::PointIndices::indices, pcl::search::Search< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

extractEuclideanClusters() [2/4]

template<typename PointT , typename Normal >
void pcl::extractEuclideanClusters ( const PointCloud< PointT > & cloud,
const PointCloud< Normal > & normals,
const Indices & indices,
const typename KdTree< PointT >::Ptr & tree,
float tolerance,
std::vector< PointIndices > & clusters,
double eps_angle,
unsigned int min_pts_per_cluster = 1,
unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ()
)

#include <pcl/segmentation/extract_clusters.h>

Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation between points.

Each point added to the cluster is origin to another radius search. Each point within radius range will be compared to the origin in respect to normal angle and euclidean distance. If both are under their respective threshold the point will be added to the cluster. Generally speaking the cluster algorithm will not stop on smooth surfaces but on surfaces with sharp edges.

Parameters
cloud the point cloud message
normals the point cloud message containing normal information
indices a list of point indices to use from cloud
tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space
clusters the resultant clusters containing point indices (as PointIndices)
eps_angle the maximum allowed difference between normals in radians for cluster/region growing
min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)

Definition at line 217 of file extract_clusters.h.

References pcl::KdTree< PointT >::getIndices(), pcl::KdTree< PointT >::getInputCloud(), pcl::PointIndices::header, pcl::PointCloud< PointT >::header, pcl::PointIndices::indices, pcl::PointCloud< PointT >::push_back(), pcl::KdTree< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

extractEuclideanClusters() [3/4]

template<typename PointT , typename Normal >
void pcl::extractEuclideanClusters ( const PointCloud< PointT > & cloud,
const PointCloud< Normal > & normals,
float tolerance,
const typename KdTree< PointT >::Ptr & tree,
std::vector< PointIndices > & clusters,
double eps_angle,
unsigned int min_pts_per_cluster = 1,
unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ()
)

#include <pcl/segmentation/extract_clusters.h>

Decompose a region of space into clusters based on the euclidean distance between points, and the normal angular deviation between points.

Each point added to the cluster is origin to another radius search. Each point within radius range will be compared to the origin in respect to normal angle and euclidean distance. If both are under their respective threshold the point will be added to the cluster. Generally speaking the cluster algorithm will not stop on smooth surfaces but on surfaces with sharp edges.

Parameters
cloud the point cloud message
normals the point cloud message containing normal information
tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
tolerance the spatial cluster tolerance as a measure in the L2 Euclidean space
clusters the resultant clusters containing point indices (as a vector of PointIndices)
eps_angle the maximum allowed difference between normals in radians for cluster/region growing
min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)

Definition at line 103 of file extract_clusters.h.

References pcl::KdTree< PointT >::getInputCloud(), pcl::PointIndices::header, pcl::PointCloud< PointT >::header, pcl::PointIndices::indices, pcl::PointCloud< PointT >::push_back(), pcl::KdTree< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

extractEuclideanClusters() [4/4]

template<typename PointT >
void pcl::extractEuclideanClusters ( const PointCloud< PointT > & cloud,
const typename search::Search< PointT >::Ptr & tree,
float tolerance,
std::vector< PointIndices > & clusters,
unsigned int min_pts_per_cluster = 1,
unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ()
)

#include <pcl/segmentation/extract_clusters.h>

Decompose a region of space into clusters based on the Euclidean distance between points.

Parameters
cloud the point cloud message
tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
clusters the resultant clusters containing point indices (as a vector of PointIndices)
min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)

Definition at line 46 of file extract_clusters.hpp.

References pcl::search::Search< PointT >::getInputCloud(), pcl::search::Search< PointT >::getSortedResults(), pcl::PointIndices::header, pcl::PointCloud< PointT >::header, pcl::PointIndices::indices, pcl::search::Search< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

Referenced by pcl::EuclideanClusterExtraction< PointT >::extract().

extractLabeledEuclideanClusters() [1/2]

template<typename PointT >
void pcl::extractLabeledEuclideanClusters ( const PointCloud< PointT > & cloud,
const typename search::Search< PointT >::Ptr & tree,
float tolerance,
std::vector< std::vector< PointIndices >> & labeled_clusters,
unsigned int min_pts_per_cluster,
unsigned int max_pts_per_cluster,
unsigned int max_label
)

#include <pcl/segmentation/extract_labeled_clusters.h>

Decompose a region of space into clusters based on the Euclidean distance between points.

Parameters
[in] cloud the point cloud message
[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
[out] labeled_clusters the resultant clusters containing point indices (as a vector of PointIndices)
[in] min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
[in] max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)
[in] max_label
Deprecated:
Scheduled for removal in version 1 . 14 : "Use of max_label is deprecated"

Definition at line 45 of file extract_labeled_clusters.hpp.

Referenced by pcl::LabeledEuclideanClusterExtraction< PointT >::extract().

extractLabeledEuclideanClusters() [2/2]

template<typename PointT >
void pcl::extractLabeledEuclideanClusters ( const PointCloud< PointT > & cloud,
const typename search::Search< PointT >::Ptr & tree,
float tolerance,
std::vector< std::vector< PointIndices >> & labeled_clusters,
unsigned int min_pts_per_cluster = 1,
unsigned int max_pts_per_cluster = std::numeric_limits<unsigned int>::max()
)

#include <pcl/segmentation/extract_labeled_clusters.h>

Decompose a region of space into clusters based on the Euclidean distance between points.

Parameters
[in] cloud the point cloud message
[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
[out] labeled_clusters the resultant clusters containing point indices (as a vector of PointIndices)
[in] min_pts_per_cluster minimum number of points that a cluster may contain (default: 1)
[in] max_pts_per_cluster maximum number of points that a cluster may contain (default: max int)

Definition at line 64 of file extract_labeled_clusters.hpp.

References pcl::search::Search< PointT >::getInputCloud(), pcl::PointIndices::header, pcl::PointCloud< PointT >::header, pcl::PointIndices::indices, pcl::search::Search< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

getPointCloudDifference()

template<typename PointT >
void pcl::getPointCloudDifference ( const pcl::PointCloud< PointT > & src,
double threshold,
const typename pcl::search::Search< PointT >::Ptr & tree,
pcl::PointCloud< PointT > & output
)

#include <pcl/segmentation/segment_differences.h>

Obtain the difference between two aligned point clouds as another point cloud, given a distance threshold.

Parameters
src the input point cloud source
threshold the distance threshold (tolerance) for point correspondences. (e.g., check if f a point p1 from src has a correspondence > threshold than a point p2 from tgt)
tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching built over the target cloud
output the resultant output point cloud difference

Definition at line 50 of file segment_differences.hpp.

References pcl::copyPointCloud(), pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), pcl::search::Search< PointT >::nearestKSearch(), and pcl::PointCloud< PointT >::size().

Referenced by pcl::SegmentDifferences< PointT >::segment().

isPointIn2DPolygon()

template<typename PointT >
bool pcl::isPointIn2DPolygon ( const PointT & point,
const pcl::PointCloud< PointT > & polygon
)

#include <pcl/segmentation/extract_polygonal_prism_data.h>

General purpose method for checking if a 3D point is inside or outside a given 2D polygon.

Note
this method accepts any general 3D point that is projected onto the 2D polygon, but performs an internal XY projection of both the polygon and the point.
Parameters
point a 3D point projected onto the same plane as the polygon
polygon a polygon

Definition at line 48 of file extract_polygonal_prism_data.hpp.

References pcl::computeMeanAndCovarianceMatrix(), pcl::eigen33(), pcl::isXYPointIn2DXYPolygon(), pcl::PointCloud< PointT >::resize(), and pcl::PointCloud< PointT >::size().

isXYPointIn2DXYPolygon()

template<typename PointT >
bool pcl::isXYPointIn2DXYPolygon ( const PointT & point,
const pcl::PointCloud< PointT > & polygon
)

#include <pcl/segmentation/extract_polygonal_prism_data.h>

Check if a 2d point (X and Y coordinates considered only!) is inside or outside a given polygon.

This method assumes that both the point and the polygon are projected onto the XY plane.

Note
(This is highly optimized code taken from http://www.visibone.com/inpoly/) Copyright (c) 1995-1996 Galacticomm, Inc. Freeware source code.
Parameters
point a 2D point projected onto the same plane as the polygon
polygon a polygon

Definition at line 108 of file extract_polygonal_prism_data.hpp.

References pcl::PointCloud< PointT >::size().

Referenced by pcl::isPointIn2DPolygon(), and pcl::ExtractPolygonalPrismData< PointT >::segment().

randomWalker() [1/3]

template<class Graph >
bool pcl::segmentation::randomWalker ( Graph & graph )

#include <pcl/segmentation/impl/random_walker.hpp>

Multilabel graph segmentation using random walks.

This is an implementation of the algorithm described in "Random Walks for Image Segmentation" by Leo Grady.

Given a weighted undirected graph and a small number of user-defined labels this algorithm analytically determines the probability that a random walker starting at each unlabeled vertex will first reach one of the prelabeled vertices. The unlabeled vertices are then assigned to the label for which the greatest probability is calculated.

The input is a BGL graph, a property map that associates a weight to each edge of the graph, and a property map that contains initial vertex colors (the term "color" is used interchangeably with "label").

Note
The colors of unlabeled vertices should be set to 0, the colors of labeled vetices could be any positive numbers.
This is the responsibility of the user to make sure that every connected component of the graph has at least one colored vertex. If the user failed to do so, then the behavior of the algorithm is undefined, i.e. it may or may not succeed, and also may or may not report failure.

The output of the algorithm (i.e. label assignment) is written back to the color map.

Parameters
[in] graph an undirected graph with internal edge weight and vertex color property maps

Several overloads of randomWalker() function are provided for convenience.

See also
randomWalker(Graph&, EdgeWeightMap, VertexColorMap)
randomWalker(Graph&, EdgeWeightMap, VertexColorMap, Eigen::Matrix <typename boost::property_traits<EdgeWeightMap>::value_type, Eigen::Dynamic, Eigen::Dynamic>&, std::map<typename boost::property_traits <VertexColorMap>::value_type, std::size_t>&)
Author
Sergey Alexandrov

Definition at line 280 of file random_walker.hpp.

randomWalker() [2/3]

template<class Graph , class EdgeWeightMap , class VertexColorMap >
bool pcl::segmentation::randomWalker ( Graph & graph,
EdgeWeightMap weights,
VertexColorMap colors
)

#include <pcl/segmentation/impl/random_walker.hpp>

Multilabel graph segmentation using random walks.

This is an overloaded function provided for convenience. See the documentation for randomWalker().

Parameters
[in] graph an undirected graph
[in] weights an external edge weight property map
[in,out] colors an external vertex color property map
Author
Sergey Alexandrov

Definition at line 288 of file random_walker.hpp.

randomWalker() [3/3]

template<class Graph , class EdgeWeightMap , class VertexColorMap >
bool pcl::segmentation::randomWalker ( Graph & graph,
EdgeWeightMap weights,
VertexColorMap colors,
Eigen::Matrix< typename boost::property_traits< EdgeWeightMap >::value_type, Eigen::Dynamic, Eigen::Dynamic > & potentials,
std::map< typename boost::property_traits< VertexColorMap >::value_type, std::size_t > & colors_to_columns_map
)

#include <pcl/segmentation/impl/random_walker.hpp>

Multilabel graph segmentation using random walks.

This is an overloaded function provided for convenience. See the documentation for randomWalker().

Parameters
[in] graph an undirected graph
[in] weights an external edge weight property map
[in,out] colors an external vertex color property map
[out] potentials a matrix with calculated probabilities, where rows correspond to vertices, and columns correspond to colors
[out] colors_to_columns_map a mapping between colors and columns in potentials matrix
Author
Sergey Alexandrov

Definition at line 314 of file random_walker.hpp.

seededHueSegmentation() [1/2]

void pcl::seededHueSegmentation ( const PointCloud< PointXYZRGB > & cloud,
const search::Search< PointXYZRGB >::Ptr & tree,
float tolerance,
PointIndices & indices_in,
PointIndices & indices_out,
float delta_hue = 0.0
)

#include <pcl/segmentation/seeded_hue_segmentation.h>

Decompose a region of space into clusters based on the Euclidean distance between points.

Parameters
[in] cloud the point cloud message
[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
[in] indices_in the cluster containing the seed point indices (as a vector of PointIndices)
[out] indices_out
[in] delta_hue
Todo:
look how to make this templated!

Definition at line 49 of file seeded_hue_segmentation.hpp.

References pcl::search::Search< PointT >::getInputCloud(), pcl::_PointXYZHSV::h, pcl::PointIndices::indices, pcl::PointXYZRGBtoXYZHSV(), pcl::search::Search< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

Referenced by pcl::SeededHueSegmentation::segment().

seededHueSegmentation() [2/2]

void pcl::seededHueSegmentation ( const PointCloud< PointXYZRGB > & cloud,
const search::Search< PointXYZRGBL >::Ptr & tree,
float tolerance,
PointIndices & indices_in,
PointIndices & indices_out,
float delta_hue = 0.0
)

#include <pcl/segmentation/seeded_hue_segmentation.h>

Decompose a region of space into clusters based on the Euclidean distance between points.

Parameters
[in] cloud the point cloud message
[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors searching
Note
the tree has to be created as a spatial locator on cloud
Parameters
[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space
[in] indices_in the cluster containing the seed point indices (as a vector of PointIndices)
[out] indices_out
[in] delta_hue
Todo:
look how to make this templated!

Definition at line 127 of file seeded_hue_segmentation.hpp.

References pcl::search::Search< PointT >::getInputCloud(), pcl::_PointXYZHSV::h, pcl::PointIndices::indices, pcl::PointXYZRGBtoXYZHSV(), pcl::search::Search< PointT >::radiusSearch(), and pcl::PointCloud< PointT >::size().

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/group__segmentation.html