Public Types | Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
pcl::CVFHEstimation< PointInT, PointNT, PointOutT > Class Template Reference

CVFHEstimation estimates the Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given point cloud dataset containing XYZ data and normals, as presented in: More...

#include <cvfh.h>

Inheritance diagram for pcl::CVFHEstimation< PointInT, PointNT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::search::Search
< PointNormal >::Ptr 
KdTreePtr
typedef pcl::NormalEstimation
< PointNormal, PointNormal
NormalEstimator
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef pcl::VFHEstimation
< PointInT, PointNT,
pcl::VFHSignature308
VFHEstimator

Public Member Functions

void compute (PointCloudOut &output)
 Overloaded computed method from pcl::Feature.
 CVFHEstimation ()
 Empty constructor.
void filterNormalsWithHighCurvature (const pcl::PointCloud< PointNT > &cloud, std::vector< int > &indices_to_use, std::vector< int > &indices_out, std::vector< int > &indices_in, float threshold)
 Removes normals with high curvature caused by real edges or noisy data.
void getCentroidClusters (std::vector< Eigen::Vector3f > &centroids)
 Get the centroids used to compute different CVFH descriptors.
void getCentroidNormalClusters (std::vector< Eigen::Vector3f > &centroids)
 Get the normal centroids used to compute different CVFH descriptors.
void getViewPoint (float &vpx, float &vpy, float &vpz)
 Get the viewpoint.
void setClusterTolerance (float d)
 Sets max. Euclidean distance between points to be added to the cluster.
void setCurvatureThreshold (float d)
 Sets curvature threshold for removing normals.
void setEPSAngleThreshold (float d)
 Sets max. deviation of the normals between two points so they can be clustered together.
void setMinPoints (size_t min)
 Set minimum amount of points for a cluster to be considered.
void setNormalizeBins (bool normalize)
 Sets wether if the CVFH signatures should be normalized or not.
void setRadiusNormals (float radius_normals)
 Set the radius used to compute normals.
void setViewPoint (float vpx, float vpy, float vpz)
 Set the viewpoint.

Protected Attributes

std::vector< Eigen::Vector3f > centroids_dominant_orientations_
 Centroids that were used to compute different CVFH descriptors.
std::vector< Eigen::Vector3f > dominant_normals_
 Normal centroids that were used to compute different CVFH descriptors.

Private Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the Clustered Viewpoint Feature Histograms (CVFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface ()
void computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &)
 Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
void extractEuclideanClustersSmooth (const pcl::PointCloud< pcl::PointNormal > &cloud, const pcl::PointCloud< pcl::PointNormal > &normals, float tolerance, const pcl::search::Search< pcl::PointNormal >::Ptr &tree, std::vector< pcl::PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)())
 Region growing method using Euclidean distances and neighbors normals to add points to a region.

Private Attributes

float cluster_tolerance_
 allowed Euclidean distance between points to be added to the cluster.
float curv_threshold_
 Curvature threshold for removing normals.
float eps_angle_threshold_
 deviation of the normals between two points so they can be clustered together.
float leaf_size_
 Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel size of the training data or the normalize_bins_ flag must be set to true.
size_t min_points_
 Minimum amount of points in a clustered region to be considered stable for CVFH computation.
bool normalize_bins_
 Wether to normalize the signatures or not. Default: false.
float radius_normals_
 Radius for the normals computation.
float vpx_
 Values describing the viewpoint ("pinhole" camera model assumed). By default, the viewpoint is set to 0,0,0.
float vpy_
float vpz_

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
class pcl::CVFHEstimation< PointInT, PointNT, PointOutT >

CVFHEstimation estimates the Clustered Viewpoint Feature Histogram (CVFH) descriptor for a given point cloud dataset containing XYZ data and normals, as presented in:

The suggested PointOutT is pcl::VFHSignature308.

Author:
Aitor Aldoma

Definition at line 65 of file cvfh.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef pcl::search::Search<PointNormal>::Ptr pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::KdTreePtr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 77 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef pcl::NormalEstimation<PointNormal, PointNormal> pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::NormalEstimator

Definition at line 78 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::PointCloudOut

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 76 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef pcl::VFHEstimation<PointInT, PointNT, pcl::VFHSignature308> pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::VFHEstimator

Definition at line 79 of file cvfh.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::CVFHEstimation ( ) [inline]

Empty constructor.

Definition at line 82 of file cvfh.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::compute ( PointCloudOut output)

Overloaded computed method from pcl::Feature.

Parameters:
[out]outputthe resultant point cloud model dataset containing the estimated features

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 49 of file cvfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::computeFeature ( PointCloudOut output) [private, virtual]

Estimate the Clustered Viewpoint Feature Histograms (CVFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface ()

Parameters:
[out]outputthe resultant point cloud model dataset that contains the CVFH feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 193 of file cvfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::computeFeatureEigen ( pcl::PointCloud< Eigen::MatrixXf > &  ) [inline, private, virtual]

Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Parameters:
[out]outputthe output point cloud

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 290 of file cvfh.h.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::extractEuclideanClustersSmooth ( const pcl::PointCloud< pcl::PointNormal > &  cloud,
const pcl::PointCloud< pcl::PointNormal > &  normals,
float  tolerance,
const pcl::search::Search< pcl::PointNormal >::Ptr tree,
std::vector< pcl::PointIndices > &  clusters,
double  eps_angle,
unsigned int  min_pts_per_cluster = 1,
unsigned int  max_pts_per_cluster = (std::numeric_limits<int>::max) () 
) [private]

Region growing method using Euclidean distances and neighbors normals to add points to a region.

Parameters:
[in]cloudpoint cloud to split into regions
[in]normalsare the normals of cloud
[in]toleranceis the allowed Euclidean distance between points to be added to the cluster
[in]treeis the spatial search structure for nearest neighbour search
[out]clustersvector of indices representing the clustered regions
[in]eps_angledeviation of the normals between two points so they can be clustered together
[in]min_pts_per_clusterminimum cluster size. (default: 1 point)
[in]max_pts_per_clustermaximum cluster size. (default: all the points)

Definition at line 72 of file cvfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::filterNormalsWithHighCurvature ( const pcl::PointCloud< PointNT > &  cloud,
std::vector< int > &  indices_to_use,
std::vector< int > &  indices_out,
std::vector< int > &  indices_in,
float  threshold 
)

Removes normals with high curvature caused by real edges or noisy data.

Parameters:
[in]cloudpointcloud to be filtered
[out]indices_outthe indices of the points with higher curvature than threshold
[out]indices_inthe indices of the remaining points after filtering
[in]thresholdthreshold value for curvature

Definition at line 160 of file cvfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::getCentroidClusters ( std::vector< Eigen::Vector3f > &  centroids) [inline]

Get the centroids used to compute different CVFH descriptors.

Parameters:
[out]centroidsvector to hold the centroids

Definition at line 149 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::getCentroidNormalClusters ( std::vector< Eigen::Vector3f > &  centroids) [inline]

Get the normal centroids used to compute different CVFH descriptors.

Parameters:
[out]centroidsvector to hold the normal centroids

Definition at line 159 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::getViewPoint ( float &  vpx,
float &  vpy,
float &  vpz 
) [inline]

Get the viewpoint.

Parameters:
[out]vpxthe X coordinate of the viewpoint
[out]vpythe Y coordinate of the viewpoint
[out]vpzthe Z coordinate of the viewpoint

Definition at line 138 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setClusterTolerance ( float  d) [inline]

Sets max. Euclidean distance between points to be added to the cluster.

Parameters:
[in]dthe maximum Euclidean distance

Definition at line 170 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setCurvatureThreshold ( float  d) [inline]

Sets curvature threshold for removing normals.

Parameters:
[in]dthe curvature threshold

Definition at line 188 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setEPSAngleThreshold ( float  d) [inline]

Sets max. deviation of the normals between two points so they can be clustered together.

Parameters:
[in]dthe maximum deviation

Definition at line 179 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setMinPoints ( size_t  min) [inline]

Set minimum amount of points for a cluster to be considered.

Parameters:
[in]minthe minimum amount of points to be set

Definition at line 197 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setNormalizeBins ( bool  normalize) [inline]

Sets wether if the CVFH signatures should be normalized or not.

Parameters:
[in]normalizetrue if normalization is required, false otherwise

Definition at line 206 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setRadiusNormals ( float  radius_normals) [inline]

Set the radius used to compute normals.

Parameters:
[in]radius_normalsthe radius

Definition at line 127 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::setViewPoint ( float  vpx,
float  vpy,
float  vpz 
) [inline]

Set the viewpoint.

Parameters:
[in]vpxthe X coordinate of the viewpoint
[in]vpythe Y coordinate of the viewpoint
[in]vpzthe Z coordinate of the viewpoint

Definition at line 116 of file cvfh.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
std::vector<Eigen::Vector3f> pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::centroids_dominant_orientations_ [protected]

Centroids that were used to compute different CVFH descriptors.

Definition at line 281 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::cluster_tolerance_ [private]

allowed Euclidean distance between points to be added to the cluster.

Definition at line 235 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::curv_threshold_ [private]

Curvature threshold for removing normals.

Definition at line 232 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
std::vector<Eigen::Vector3f> pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::dominant_normals_ [protected]

Normal centroids that were used to compute different CVFH descriptors.

Definition at line 283 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::eps_angle_threshold_ [private]

deviation of the normals between two points so they can be clustered together.

Definition at line 238 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::leaf_size_ [private]

Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel size of the training data or the normalize_bins_ flag must be set to true.

Definition at line 226 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
size_t pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::min_points_ [private]

Minimum amount of points in a clustered region to be considered stable for CVFH computation.

Definition at line 243 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
bool pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::normalize_bins_ [private]

Wether to normalize the signatures or not. Default: false.

Definition at line 229 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::radius_normals_ [private]

Radius for the normals computation.

Definition at line 246 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::vpx_ [private]

Values describing the viewpoint ("pinhole" camera model assumed). By default, the viewpoint is set to 0,0,0.

Definition at line 221 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::vpy_ [private]

Definition at line 221 of file cvfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::CVFHEstimation< PointInT, PointNT, PointOutT >::vpz_ [private]

Definition at line 221 of file cvfh.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:17