Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
pcl::EuclideanClusterExtraction< PointT > Class Template Reference

EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense. More...

#include <extract_clusters.h>

Inheritance diagram for pcl::EuclideanClusterExtraction< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::search::Search
< PointT
KdTree
typedef pcl::search::Search
< PointT >::Ptr 
KdTreePtr
typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr

Public Member Functions

 EuclideanClusterExtraction ()
 Empty constructor.
void extract (std::vector< PointIndices > &clusters)
 Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>
double getClusterTolerance () const
 Get the spatial cluster tolerance as a measure in the L2 Euclidean space.
int getMaxClusterSize () const
 Get the maximum 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.
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.
void setMaxClusterSize (int max_cluster_size)
 Set the maximum number of points that a cluster needs to contain in order to be considered valid.
void setMinClusterSize (int min_cluster_size)
 Set the minimum number of points that a cluster needs to contain in order to be considered valid.
void setSearchMethod (const KdTreePtr &tree)
 Provide a pointer to the search object.

Protected Member Functions

virtual std::string getClassName () const
 Class getName method.

Protected Attributes

double cluster_tolerance_
 The spatial cluster tolerance as a measure in the L2 Euclidean space.
int max_pts_per_cluster_
 The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT).
int min_pts_per_cluster_
 The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1).
KdTreePtr tree_
 A pointer to the spatial search object.

Private Types

typedef PCLBase< PointTBasePCLBase

Detailed Description

template<typename PointT>
class pcl::EuclideanClusterExtraction< PointT >

EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.

Author:
Radu Bogdan Rusu

Definition at line 295 of file extract_clusters.h.


Member Typedef Documentation

template<typename PointT>
typedef PCLBase<PointT> pcl::EuclideanClusterExtraction< PointT >::BasePCLBase [private]

Definition at line 297 of file extract_clusters.h.

Definition at line 304 of file extract_clusters.h.

template<typename PointT>
typedef pcl::search::Search<PointT>::Ptr pcl::EuclideanClusterExtraction< PointT >::KdTreePtr

Definition at line 305 of file extract_clusters.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 300 of file extract_clusters.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 302 of file extract_clusters.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 301 of file extract_clusters.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 308 of file extract_clusters.h.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 307 of file extract_clusters.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::EuclideanClusterExtraction< PointT >::EuclideanClusterExtraction ( ) [inline]

Empty constructor.

Definition at line 312 of file extract_clusters.h.


Member Function Documentation

template<typename PointT >
void pcl::EuclideanClusterExtraction< PointT >::extract ( std::vector< PointIndices > &  clusters)

Cluster extraction in a PointCloud given by <setInputCloud (), setIndices ()>

Parameters:
[out]clustersthe resultant point clusters

Definition at line 210 of file extract_clusters.hpp.

template<typename PointT>
virtual std::string pcl::EuclideanClusterExtraction< PointT >::getClassName ( ) const [inline, protected, virtual]

Class getName method.

Definition at line 410 of file extract_clusters.h.

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
KdTreePtr pcl::EuclideanClusterExtraction< PointT >::getSearchMethod ( ) const [inline]

Get a pointer to the search method used.

Todo:
fix this for a generic search tree

Definition at line 331 of file extract_clusters.h.

template<typename PointT>
void pcl::EuclideanClusterExtraction< PointT >::setClusterTolerance ( double  tolerance) [inline]

Set the spatial cluster tolerance as a measure in the L2 Euclidean space.

Parameters:
[in]tolerancethe spatial cluster tolerance as a measure in the L2 Euclidean space

Definition at line 340 of file extract_clusters.h.

template<typename PointT>
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.

Parameters:
[in]max_cluster_sizethe maximum cluster size

Definition at line 372 of file extract_clusters.h.

template<typename PointT>
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.

Parameters:
[in]min_cluster_sizethe minimum cluster size

Definition at line 356 of file extract_clusters.h.

template<typename PointT>
void pcl::EuclideanClusterExtraction< PointT >::setSearchMethod ( const KdTreePtr tree) [inline]

Provide a pointer to the search object.

Parameters:
[in]treea pointer to the spatial search object.

Definition at line 322 of file extract_clusters.h.


Member Data Documentation

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
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.

template<typename PointT>
KdTreePtr pcl::EuclideanClusterExtraction< PointT >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 398 of file extract_clusters.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:40:09