Point Cloud Library (PCL)
1.9.1
|
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More...
#include <pcl/segmentation/extract_clusters.h>
Public Types | |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::Ptr | PointCloudPtr |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef pcl::search::Search< PointT > | KdTree |
typedef pcl::search::Search< PointT >::Ptr | KdTreePtr |
typedef PointIndices::Ptr | PointIndicesPtr |
typedef PointIndices::ConstPtr | PointIndicesConstPtr |
![]() | |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::Ptr | PointCloudPtr |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef boost::shared_ptr< PointIndices > | PointIndicesPtr |
typedef boost::shared_ptr< PointIndices const > | PointIndicesConstPtr |
Public Member Functions | |
EuclideanClusterExtraction () | |
Empty constructor. More... | |
void | setSearchMethod (const KdTreePtr &tree) |
Provide a pointer to the search object. More... | |
KdTreePtr | getSearchMethod () const |
Get a pointer to the search method used. More... | |
void | setClusterTolerance (double tolerance) |
Set the spatial cluster tolerance as a measure in the L2 Euclidean space. More... | |
double | getClusterTolerance () const |
Get the spatial cluster tolerance as a measure in the L2 Euclidean space. More... | |
void | setMinClusterSize (int min_cluster_size) |
Set the minimum number of points that a cluster needs to contain in order to be considered valid. More... | |
int | getMinClusterSize () const |
Get the minimum number of points that a cluster needs to contain in order to be considered valid. More... | |
void | setMaxClusterSize (int max_cluster_size) |
Set the maximum number of points that a cluster needs to contain in order to be considered valid. More... | |
int | getMaxClusterSize () const |
Get the maximum number of points that a cluster needs to contain in order to be considered valid. More... | |
void | extract (std::vector< PointIndices > &clusters) |
Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()> More... | |
![]() | |
PCLBase () | |
Empty constructor. More... | |
PCLBase (const PCLBase &base) | |
Copy constructor. More... | |
virtual | ~PCLBase () |
Destructor. More... | |
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. More... | |
PointCloudConstPtr const | getInputCloud () const |
Get a pointer to the input point cloud dataset. More... | |
virtual void | setIndices (const IndicesPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
virtual void | setIndices (const IndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
virtual void | setIndices (const PointIndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
virtual void | setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) |
Set the indices for the points laying within an interest region of the point cloud. More... | |
IndicesPtr const | getIndices () |
Get a pointer to the vector of indices used. More... | |
IndicesConstPtr const | getIndices () const |
Get a pointer to the vector of indices used. More... | |
const PointT & | operator[] (size_t pos) const |
Override PointCloud operator[] to shorten code. More... | |
Protected Member Functions | |
virtual std::string | getClassName () const |
Class getName method. More... | |
![]() | |
bool | initCompute () |
This method should get called before starting the actual computation. More... | |
bool | deinitCompute () |
This method should get called after finishing the actual computation. More... | |
Protected Attributes | |
KdTreePtr | tree_ |
A pointer to the spatial search object. More... | |
double | cluster_tolerance_ |
The spatial cluster tolerance as a measure in the L2 Euclidean space. More... | |
int | min_pts_per_cluster_ |
The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). More... | |
int | max_pts_per_cluster_ |
The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). More... | |
![]() | |
PointCloudConstPtr | input_ |
The input point cloud dataset. More... | |
IndicesPtr | indices_ |
A pointer to the vector of point indices to use. More... | |
bool | use_indices_ |
Set to true if point indices are used. More... | |
bool | fake_indices_ |
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More... | |
EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.
Definition at line 295 of file extract_clusters.h.
typedef pcl::search::Search<PointT> pcl::EuclideanClusterExtraction< PointT >::KdTree |
Definition at line 304 of file extract_clusters.h.
typedef pcl::search::Search<PointT>::Ptr pcl::EuclideanClusterExtraction< PointT >::KdTreePtr |
Definition at line 305 of file extract_clusters.h.
typedef pcl::PointCloud<PointT> pcl::EuclideanClusterExtraction< PointT >::PointCloud |
Definition at line 300 of file extract_clusters.h.
typedef PointCloud::ConstPtr pcl::EuclideanClusterExtraction< PointT >::PointCloudConstPtr |
Definition at line 302 of file extract_clusters.h.
typedef PointCloud::Ptr pcl::EuclideanClusterExtraction< PointT >::PointCloudPtr |
Definition at line 301 of file extract_clusters.h.
typedef PointIndices::ConstPtr pcl::EuclideanClusterExtraction< PointT >::PointIndicesConstPtr |
Definition at line 308 of file extract_clusters.h.
typedef PointIndices::Ptr pcl::EuclideanClusterExtraction< PointT >::PointIndicesPtr |
Definition at line 307 of file extract_clusters.h.
|
inline |
Empty constructor.
Definition at line 312 of file extract_clusters.h.
void pcl::EuclideanClusterExtraction< PointT >::extract | ( | std::vector< PointIndices > & | clusters | ) |
Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>
[out] | clusters | the resultant point clusters |
Definition at line 210 of file extract_clusters.hpp.
References pcl::gpu::comparePointClusters(), and pcl::extractEuclideanClusters().
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), pcl::EuclideanClusterExtraction< PointT >::getMaxClusterSize(), and pcl::CPCSegmentation< PointT >::segment().
|
inlineprotectedvirtual |
Class getName method.
Definition at line 410 of file extract_clusters.h.
|
inline |
Get the spatial cluster tolerance as a measure in the L2 Euclidean space.
Definition at line 347 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::cluster_tolerance_.
|
inline |
Get the maximum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 379 of file extract_clusters.h.
References pcl::PCLBase< PointT >::deinitCompute(), pcl::EuclideanClusterExtraction< PointT >::extract(), pcl::PCLBase< PointT >::indices_, pcl::PCLBase< PointT >::initCompute(), pcl::PCLBase< PointT >::input_, and pcl::EuclideanClusterExtraction< PointT >::max_pts_per_cluster_.
|
inline |
Get the minimum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 363 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::min_pts_per_cluster_.
|
inline |
Get a pointer to the search method used.
Definition at line 331 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::tree_.
|
inline |
Set the spatial cluster tolerance as a measure in the L2 Euclidean space.
[in] | tolerance | the spatial cluster tolerance as a measure in the L2 Euclidean space |
Definition at line 340 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::cluster_tolerance_.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), and pcl::CPCSegmentation< PointT >::segment().
|
inline |
Set the maximum number of points that a cluster needs to contain in order to be considered valid.
[in] | max_cluster_size | the maximum cluster size |
Definition at line 372 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::max_pts_per_cluster_.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), and pcl::CPCSegmentation< PointT >::segment().
|
inline |
Set the minimum number of points that a cluster needs to contain in order to be considered valid.
[in] | min_cluster_size | the minimum cluster size |
Definition at line 356 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::min_pts_per_cluster_.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), and pcl::CPCSegmentation< PointT >::segment().
|
inline |
Provide a pointer to the search object.
[in] | tree | a pointer to the spatial search object. |
Definition at line 322 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::tree_.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), and pcl::CPCSegmentation< PointT >::segment().
|
protected |
The spatial cluster tolerance as a measure in the L2 Euclidean space.
Definition at line 401 of file extract_clusters.h.
Referenced by pcl::EuclideanClusterExtraction< PointT >::getClusterTolerance(), and pcl::EuclideanClusterExtraction< PointT >::setClusterTolerance().
|
protected |
The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT).
Definition at line 407 of file extract_clusters.h.
Referenced by pcl::EuclideanClusterExtraction< PointT >::getMaxClusterSize(), and pcl::EuclideanClusterExtraction< PointT >::setMaxClusterSize().
|
protected |
The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1).
Definition at line 404 of file extract_clusters.h.
Referenced by pcl::EuclideanClusterExtraction< PointT >::getMinClusterSize(), and pcl::EuclideanClusterExtraction< PointT >::setMinClusterSize().
|
protected |
A pointer to the spatial search object.
Definition at line 398 of file extract_clusters.h.
Referenced by pcl::EuclideanClusterExtraction< PointT >::getSearchMethod(), and pcl::EuclideanClusterExtraction< PointT >::setSearchMethod().