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 |
Public Member Functions | |
| EuclideanClusterExtraction () | |
| Empty constructor. | |
| void | setSearchMethod (const KdTreePtr &tree) |
| Provide a pointer to the search object. | |
| KdTreePtr | getSearchMethod () const |
| Get a pointer to the search method used. | |
| void | setClusterTolerance (double tolerance) |
| Set the spatial cluster tolerance as a measure in the L2 Euclidean space. | |
| double | getClusterTolerance () const |
| Get the spatial cluster tolerance as a measure in the L2 Euclidean space. | |
| void | setMinClusterSize (int min_cluster_size) |
| Set the minimum number of points that a cluster needs to contain in order to be considered valid. | |
| int | getMinClusterSize () const |
| Get the minimum number of points that a cluster needs to contain in order to be considered valid. | |
| void | setMaxClusterSize (int max_cluster_size) |
| Set the maximum number of points that a cluster needs to contain in order to be considered valid. | |
| int | getMaxClusterSize () const |
| Get the maximum number of points that a cluster needs to contain in order to be considered valid. | |
| void | extract (std::vector< PointIndices > &clusters) |
| Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>. | |
Protected Member Functions | |
| virtual std::string | getClassName () const |
| Class getName method. | |
Protected Attributes | |
| KdTreePtr | tree_ |
| A pointer to the spatial search object. | |
| double | cluster_tolerance_ |
| The spatial cluster tolerance as a measure in the L2 Euclidean space. | |
| int | min_pts_per_cluster_ |
| The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). | |
| int | max_pts_per_cluster_ |
| The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). | |
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 |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 300 of file extract_clusters.h.
| typedef PointCloud::ConstPtr pcl::EuclideanClusterExtraction< PointT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 302 of file extract_clusters.h.
| typedef PointCloud::Ptr pcl::EuclideanClusterExtraction< PointT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 301 of file extract_clusters.h.
| typedef PointIndices::ConstPtr pcl::EuclideanClusterExtraction< PointT >::PointIndicesConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 308 of file extract_clusters.h.
| typedef PointIndices::Ptr pcl::EuclideanClusterExtraction< PointT >::PointIndicesPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 307 of file extract_clusters.h.
| pcl::EuclideanClusterExtraction< PointT >::EuclideanClusterExtraction | ( | ) | [inline] |
Empty constructor.
Definition at line 312 of file extract_clusters.h.
| void pcl::EuclideanClusterExtraction< PointT >::extract | ( | std::vector< PointIndices > & | clusters | ) | [inline] |
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::EuclideanClusterExtraction< PointT >::cluster_tolerance_, pcl::comparePointClusters(), pcl::PCLBase< PointT >::deinitCompute(), pcl::extractEuclideanClusters(), pcl::PCLBase< PointT >::indices_, pcl::PCLBase< PointT >::initCompute(), pcl::PCLBase< PointT >::input_, pcl::EuclideanClusterExtraction< PointT >::max_pts_per_cluster_, pcl::EuclideanClusterExtraction< PointT >::min_pts_per_cluster_, and pcl::EuclideanClusterExtraction< PointT >::tree_.
Referenced by pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute().
| virtual std::string pcl::EuclideanClusterExtraction< PointT >::getClassName | ( | ) | const [inline, protected, virtual] |
Class getName method.
Definition at line 410 of file extract_clusters.h.
| double pcl::EuclideanClusterExtraction< PointT >::getClusterTolerance | ( | ) | const [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_.
| int pcl::EuclideanClusterExtraction< PointT >::getMaxClusterSize | ( | ) | const [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::EuclideanClusterExtraction< PointT >::max_pts_per_cluster_.
| int pcl::EuclideanClusterExtraction< PointT >::getMinClusterSize | ( | ) | const [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_.
| KdTreePtr pcl::EuclideanClusterExtraction< PointT >::getSearchMethod | ( | ) | const [inline] |
Get a pointer to the search method used.
Definition at line 331 of file extract_clusters.h.
References pcl::EuclideanClusterExtraction< PointT >::tree_.
| void pcl::EuclideanClusterExtraction< PointT >::setClusterTolerance | ( | double | tolerance | ) | [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().
| void pcl::EuclideanClusterExtraction< PointT >::setMaxClusterSize | ( | int | max_cluster_size | ) | [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().
| void pcl::EuclideanClusterExtraction< PointT >::setMinClusterSize | ( | int | min_cluster_size | ) | [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().
| void pcl::EuclideanClusterExtraction< PointT >::setSearchMethod | ( | const KdTreePtr & | tree | ) | [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().
double pcl::EuclideanClusterExtraction< PointT >::cluster_tolerance_ [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 >::extract(), pcl::EuclideanClusterExtraction< PointT >::getClusterTolerance(), and pcl::EuclideanClusterExtraction< PointT >::setClusterTolerance().
int pcl::EuclideanClusterExtraction< PointT >::max_pts_per_cluster_ [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 >::extract(), pcl::EuclideanClusterExtraction< PointT >::getMaxClusterSize(), and pcl::EuclideanClusterExtraction< PointT >::setMaxClusterSize().
int pcl::EuclideanClusterExtraction< PointT >::min_pts_per_cluster_ [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 >::extract(), pcl::EuclideanClusterExtraction< PointT >::getMinClusterSize(), and pcl::EuclideanClusterExtraction< PointT >::setMinClusterSize().
KdTreePtr pcl::EuclideanClusterExtraction< PointT >::tree_ [protected] |
A pointer to the spatial search object.
Definition at line 398 of file extract_clusters.h.
Referenced by pcl::EuclideanClusterExtraction< PointT >::extract(), pcl::EuclideanClusterExtraction< PointT >::getSearchMethod(), and pcl::EuclideanClusterExtraction< PointT >::setSearchMethod().