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

Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods. More...

#include <feature.h>

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

List of all members.

Public Types

typedef PCLBase< PointInT > BaseClass
typedef boost::shared_ptr
< const Feature< PointInT,
PointOutT > > 
ConstPtr
typedef pcl::search::Search
< PointInT > 
KdTree
typedef pcl::search::Search
< PointInT >::Ptr 
KdTreePtr
typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud
< PointOutT
PointCloudOut
typedef boost::shared_ptr
< Feature< PointInT, PointOutT > > 
Ptr
typedef boost::function< int(size_t,
double, std::vector< int >
&, std::vector< float > &)> 
SearchMethod
typedef boost::function< int(const
PointCloudIn &cloud, size_t
index, double, std::vector
< int > &, std::vector< float > &)> 
SearchMethodSurface

Public Member Functions

void compute (PointCloudOut &output)
 Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
 Feature ()
 Empty constructor.
int getKSearch () const
 get the number of k nearest neighbors used for the feature estimation.
double getRadiusSearch () const
 Get the sphere radius used for determining the neighbors.
KdTreePtr getSearchMethod () const
 Get a pointer to the search method used.
double getSearchParameter () const
 Get the internal search parameter.
PointCloudInConstPtr getSearchSurface () const
 Get a pointer to the surface point cloud dataset.
void setKSearch (int k)
 Set the number of k nearest neighbors to use for the feature estimation.
void setRadiusSearch (double radius)
 Set the sphere radius that is to be used for determining the nearest neighbors used for the feature estimation.
void setSearchMethod (const KdTreePtr &tree)
 Provide a pointer to the search object.
void setSearchSurface (const PointCloudInConstPtr &cloud)
 Provide a pointer to a dataset to add additional information to estimate the features for every point in the input dataset. This is optional, if this is not set, it will only use the data in the input cloud to estimate the features. This is useful when you only need to compute the features for a downsampled cloud.
virtual ~Feature ()
 Empty destructor.

Protected Member Functions

virtual bool deinitCompute ()
 This method should get called after ending the actual computation.
const std::stringgetClassName () const
 Get a string representation of the name of this class.
virtual bool initCompute ()
 This method should get called before starting the actual computation.
int searchForNeighbors (size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const
 Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface.
int searchForNeighbors (const PointCloudIn &cloud, size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const
 Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface.

Protected Attributes

bool fake_surface_
 If no surface is given, we use the input PointCloud as the surface.
std::string feature_name_
 The feature name.
int k_
 The number of K nearest neighbors to use for each point.
SearchMethodSurface search_method_surface_
 The search method template for points.
double search_parameter_
 The actual search parameter (from either search_radius_ or k_).
double search_radius_
 The nearest neighbors search radius for each point.
PointCloudInConstPtr surface_
 An input point cloud describing the surface that is to be used for nearest neighbors estimation.
KdTreePtr tree_
 A pointer to the spatial search object.

Private Member Functions

virtual void computeFeature (PointCloudOut &output)=0
 Abstract feature estimation method.

Detailed Description

template<typename PointInT, typename PointOutT>
class pcl::Feature< PointInT, PointOutT >

Feature represents the base feature class. Some generic 3D operations that are applicable to all features are defined here as static methods.

Attention:
The convention for a feature descriptor is:
  • if the nearest neighbors for the query point at which the descriptor is to be computed cannot be determined, the descriptor values will be set to NaN (not a number)
  • it is impossible to estimate a feature descriptor for a point that doesn't have finite 3D coordinates. Therefore, any point that has NaN data on x, y, or z, will most likely have its descriptor set to NaN.
Author:
Radu B. Rusu

Definition at line 105 of file feature.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT>
typedef PCLBase<PointInT> pcl::Feature< PointInT, PointOutT >::BaseClass

Reimplemented in pcl::NarfDescriptor, and pcl::RangeImageBorderExtractor.

Definition at line 111 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef boost::shared_ptr< const Feature<PointInT, PointOutT> > pcl::Feature< PointInT, PointOutT >::ConstPtr

Reimplemented in pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >, pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >, pcl::FeatureFromNormals< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::FeatureFromNormals< PointT, PointNT, PointFeature >, pcl::FeatureFromNormals< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::NormalEstimation< PointInT, PointOutT >, pcl::NormalEstimation< PointType, pcl::Normal >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::FPFHEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimation< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >, pcl::PPFEstimation< PointInT, PointNT, PointOutT >, pcl::RIFTEstimation< PointInT, GradientT, PointOutT >, pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PPFRGBRegionEstimation< PointInT, PointNT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >, pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >, pcl::SHOTLocalReferenceFrameEstimationOMP< PointInT, PointOutT >, pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >, pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::CRHEstimation< PointInT, PointNT, PointOutT >, pcl::IntegralImageNormalEstimation< PointInT, PointOutT >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::IntegralImageNormalEstimation< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >, pcl::IntegralImageNormalEstimation< PointT, Normal >, pcl::IntegralImageNormalEstimation< PointT, pcl::Normal >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::ESFEstimation< PointInT, PointOutT >, pcl::NarfDescriptor, pcl::RangeImageBorderExtractor, pcl::IntensitySpinEstimation< PointInT, PointOutT >, pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >, pcl::MomentInvariantsEstimation< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointType, pcl::Normal >, pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >, and pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >.

Definition at line 114 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef pcl::search::Search<PointInT> pcl::Feature< PointInT, PointOutT >::KdTree

Definition at line 116 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef pcl::search::Search<PointInT>::Ptr pcl::Feature< PointInT, PointOutT >::KdTreePtr
template<typename PointInT, typename PointOutT>
typedef pcl::PointCloud<PointInT> pcl::Feature< PointInT, PointOutT >::PointCloudIn

Reimplemented in pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >, pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >, pcl::FeatureFromNormals< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::FeatureFromNormals< PointT, PointNT, PointFeature >, pcl::FeatureFromNormals< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTLocalReferenceFrameEstimationOMP< PointInT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::IntegralImageNormalEstimation< PointInT, PointOutT >, pcl::IntegralImageNormalEstimation< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >, pcl::IntegralImageNormalEstimation< PointT, Normal >, pcl::IntegralImageNormalEstimation< PointT, pcl::Normal >, pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >, pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >, pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::ESFEstimation< PointInT, PointOutT >, pcl::IntensitySpinEstimation< PointInT, PointOutT >, pcl::RIFTEstimation< PointInT, GradientT, PointOutT >, and pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >.

Definition at line 119 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef PointCloudIn::ConstPtr pcl::Feature< PointInT, PointOutT >::PointCloudInConstPtr
template<typename PointInT, typename PointOutT>
typedef PointCloudIn::Ptr pcl::Feature< PointInT, PointOutT >::PointCloudInPtr
template<typename PointInT, typename PointOutT>
typedef pcl::PointCloud<PointOutT> pcl::Feature< PointInT, PointOutT >::PointCloudOut

Reimplemented in pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >, pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >, pcl::FeatureFromNormals< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::FeatureFromNormals< PointT, PointNT, PointFeature >, pcl::FeatureFromNormals< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::NormalEstimation< PointInT, PointOutT >, pcl::NormalEstimation< PointType, pcl::Normal >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTLocalReferenceFrameEstimationOMP< PointInT, PointOutT >, pcl::BoundaryEstimation< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::FPFHEstimation< PointInT, PointNT, PointOutT >, pcl::IntegralImageNormalEstimation< PointInT, PointOutT >, pcl::FPFHEstimation< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::IntegralImageNormalEstimation< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >, pcl::IntegralImageNormalEstimation< PointT, Normal >, pcl::IntegralImageNormalEstimation< PointT, pcl::Normal >, pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::PPFEstimation< PointInT, PointNT, PointOutT >, pcl::PPFRGBRegionEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >, pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >, pcl::CRHEstimation< PointInT, PointNT, PointOutT >, pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::ESFEstimation< PointInT, PointOutT >, pcl::IntensitySpinEstimation< PointInT, PointOutT >, pcl::RIFTEstimation< PointInT, GradientT, PointOutT >, pcl::NormalEstimationOMP< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointType, pcl::Normal >, pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >, pcl::MomentInvariantsEstimation< PointInT, PointOutT >, pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >, pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >, and pcl::PPFRGBEstimation< PointInT, PointNT, PointOutT >.

Definition at line 123 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef boost::shared_ptr< Feature<PointInT, PointOutT> > pcl::Feature< PointInT, PointOutT >::Ptr

Reimplemented in pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >, pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >, pcl::FeatureFromNormals< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::FeatureFromNormals< PointT, PointNT, PointFeature >, pcl::FeatureFromNormals< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::NormalEstimation< PointInT, PointOutT >, pcl::NormalEstimation< PointType, pcl::Normal >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::FPFHEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimation< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >, pcl::PPFEstimation< PointInT, PointNT, PointOutT >, pcl::RIFTEstimation< PointInT, GradientT, PointOutT >, pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PPFRGBRegionEstimation< PointInT, PointNT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >, pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >, pcl::SHOTLocalReferenceFrameEstimationOMP< PointInT, PointOutT >, pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >, pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::CRHEstimation< PointInT, PointNT, PointOutT >, pcl::IntegralImageNormalEstimation< PointInT, PointOutT >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::IntegralImageNormalEstimation< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >, pcl::IntegralImageNormalEstimation< PointT, Normal >, pcl::IntegralImageNormalEstimation< PointT, pcl::Normal >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::ESFEstimation< PointInT, PointOutT >, pcl::NarfDescriptor, pcl::RangeImageBorderExtractor, pcl::IntensitySpinEstimation< PointInT, PointOutT >, pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >, pcl::MomentInvariantsEstimation< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointType, pcl::Normal >, pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >, and pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >.

Definition at line 113 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef boost::function<int (size_t, double, std::vector<int> &, std::vector<float> &)> pcl::Feature< PointInT, PointOutT >::SearchMethod

Definition at line 125 of file feature.h.

template<typename PointInT, typename PointOutT>
typedef boost::function<int (const PointCloudIn &cloud, size_t index, double, std::vector<int> &, std::vector<float> &)> pcl::Feature< PointInT, PointOutT >::SearchMethodSurface

Definition at line 126 of file feature.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT>
pcl::Feature< PointInT, PointOutT >::Feature ( ) [inline]

Empty constructor.

Definition at line 130 of file feature.h.

template<typename PointInT, typename PointOutT>
virtual pcl::Feature< PointInT, PointOutT >::~Feature ( ) [inline, virtual]

Empty destructor.

Definition at line 138 of file feature.h.


Member Function Documentation

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

Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

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

Reimplemented in pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::RangeImageBorderExtractor, pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >, pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >, pcl::ESFEstimation< PointInT, PointOutT >, and pcl::NarfDescriptor.

Definition at line 189 of file feature.hpp.

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

Abstract feature estimation method.

Parameters:
[out]outputthe resultant features

Implemented in pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::NormalEstimation< PointInT, PointOutT >, pcl::NormalEstimation< PointType, pcl::Normal >, pcl::RangeImageBorderExtractor, pcl::IntegralImageNormalEstimation< PointInT, PointOutT >, pcl::IntegralImageNormalEstimation< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >, pcl::IntegralImageNormalEstimation< PointT, Normal >, pcl::IntegralImageNormalEstimation< PointT, pcl::Normal >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimation< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >, pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >, pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >, pcl::RIFTEstimation< PointInT, GradientT, PointOutT >, pcl::CRHEstimation< PointInT, PointNT, PointOutT >, pcl::IntensitySpinEstimation< PointInT, PointOutT >, pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >, pcl::LinearLeastSquaresNormalEstimation< PointInT, PointOutT >, pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTLocalReferenceFrameEstimation< PointInT, PointOutT >, pcl::MomentInvariantsEstimation< PointInT, PointOutT >, pcl::ESFEstimation< PointInT, PointOutT >, pcl::SHOTLocalReferenceFrameEstimationOMP< PointInT, PointOutT >, pcl::NarfDescriptor, pcl::PPFEstimation< PointInT, PointNT, PointOutT >, pcl::NormalEstimationOMP< PointInT, PointOutT >, pcl::NormalEstimationOMP< PointType, pcl::Normal >, pcl::PPFRGBRegionEstimation< PointInT, PointNT, PointOutT >, pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >, pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >, and pcl::PPFRGBEstimation< PointInT, PointNT, PointOutT >.

template<typename PointInT , typename PointOutT >
bool pcl::Feature< PointInT, PointOutT >::deinitCompute ( ) [protected, virtual]

This method should get called after ending the actual computation.

Reimplemented from pcl::PCLBase< PointInT >.

Definition at line 176 of file feature.hpp.

template<typename PointInT, typename PointOutT>
const std::string& pcl::Feature< PointInT, PointOutT >::getClassName ( ) const [inline, protected]

Get a string representation of the name of this class.

Definition at line 246 of file feature.h.

template<typename PointInT, typename PointOutT>
int pcl::Feature< PointInT, PointOutT >::getKSearch ( ) const [inline]

get the number of k nearest neighbors used for the feature estimation.

Definition at line 190 of file feature.h.

template<typename PointInT, typename PointOutT>
double pcl::Feature< PointInT, PointOutT >::getRadiusSearch ( ) const [inline]

Get the sphere radius used for determining the neighbors.

Definition at line 207 of file feature.h.

template<typename PointInT, typename PointOutT>
KdTreePtr pcl::Feature< PointInT, PointOutT >::getSearchMethod ( ) const [inline]

Get a pointer to the search method used.

Definition at line 170 of file feature.h.

template<typename PointInT, typename PointOutT>
double pcl::Feature< PointInT, PointOutT >::getSearchParameter ( ) const [inline]

Get the internal search parameter.

Definition at line 177 of file feature.h.

template<typename PointInT, typename PointOutT>
PointCloudInConstPtr pcl::Feature< PointInT, PointOutT >::getSearchSurface ( ) const [inline]

Get a pointer to the surface point cloud dataset.

Definition at line 157 of file feature.h.

template<typename PointInT , typename PointOutT >
bool pcl::Feature< PointInT, PointOutT >::initCompute ( ) [protected, virtual]
template<typename PointInT, typename PointOutT>
int pcl::Feature< PointInT, PointOutT >::searchForNeighbors ( size_t  index,
double  parameter,
std::vector< int > &  indices,
std::vector< float > &  distances 
) const [inline, protected]

Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface.

Parameters:
[in]indexthe index of the query point
[in]parameterthe search parameter (either k or radius)
[out]indicesthe resultant vector of indices representing the k-nearest neighbors
[out]distancesthe resultant vector of distances representing the distances from the query point to the k-nearest neighbors
Returns:
the number of neighbors found. If no neighbors are found or an error occurred, return 0.

Definition at line 270 of file feature.h.

template<typename PointInT, typename PointOutT>
int pcl::Feature< PointInT, PointOutT >::searchForNeighbors ( const PointCloudIn cloud,
size_t  index,
double  parameter,
std::vector< int > &  indices,
std::vector< float > &  distances 
) const [inline, protected]

Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface.

Parameters:
[in]cloudthe query point cloud
[in]indexthe index of the query point in cloud
[in]parameterthe search parameter (either k or radius)
[out]indicesthe resultant vector of indices representing the k-nearest neighbors
[out]distancesthe resultant vector of distances representing the distances from the query point to the k-nearest neighbors
Returns:
the number of neighbors found. If no neighbors are found or an error occurred, return 0.

Definition at line 288 of file feature.h.

template<typename PointInT, typename PointOutT>
void pcl::Feature< PointInT, PointOutT >::setKSearch ( int  k) [inline]

Set the number of k nearest neighbors to use for the feature estimation.

Parameters:
[in]kthe number of k-nearest neighbors

Reimplemented in pcl::RSDEstimation< PointInT, PointNT, PointOutT >.

Definition at line 186 of file feature.h.

template<typename PointInT, typename PointOutT>
void pcl::Feature< PointInT, PointOutT >::setRadiusSearch ( double  radius) [inline]

Set the sphere radius that is to be used for determining the nearest neighbors used for the feature estimation.

Parameters:
[in]radiusthe sphere radius used as the maximum distance to consider a point a neighbor

Definition at line 200 of file feature.h.

template<typename PointInT, typename PointOutT>
void pcl::Feature< PointInT, PointOutT >::setSearchMethod ( const KdTreePtr tree) [inline]

Provide a pointer to the search object.

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

Definition at line 166 of file feature.h.

template<typename PointInT, typename PointOutT>
void pcl::Feature< PointInT, PointOutT >::setSearchSurface ( const PointCloudInConstPtr cloud) [inline]

Provide a pointer to a dataset to add additional information to estimate the features for every point in the input dataset. This is optional, if this is not set, it will only use the data in the input cloud to estimate the features. This is useful when you only need to compute the features for a downsampled cloud.

Parameters:
[in]clouda pointer to a PointCloud message

Definition at line 148 of file feature.h.


Member Data Documentation

template<typename PointInT, typename PointOutT>
bool pcl::Feature< PointInT, PointOutT >::fake_surface_ [protected]

If no surface is given, we use the input PointCloud as the surface.

Definition at line 257 of file feature.h.

template<typename PointInT, typename PointOutT>
std::string pcl::Feature< PointInT, PointOutT >::feature_name_ [protected]

The feature name.

Definition at line 222 of file feature.h.

template<typename PointInT, typename PointOutT>
int pcl::Feature< PointInT, PointOutT >::k_ [protected]

The number of K nearest neighbors to use for each point.

Definition at line 242 of file feature.h.

template<typename PointInT, typename PointOutT>
SearchMethodSurface pcl::Feature< PointInT, PointOutT >::search_method_surface_ [protected]

The search method template for points.

Definition at line 225 of file feature.h.

template<typename PointInT, typename PointOutT>
double pcl::Feature< PointInT, PointOutT >::search_parameter_ [protected]

The actual search parameter (from either search_radius_ or k_).

Definition at line 236 of file feature.h.

template<typename PointInT, typename PointOutT>
double pcl::Feature< PointInT, PointOutT >::search_radius_ [protected]

The nearest neighbors search radius for each point.

Definition at line 239 of file feature.h.

template<typename PointInT, typename PointOutT>
PointCloudInConstPtr pcl::Feature< PointInT, PointOutT >::surface_ [protected]

An input point cloud describing the surface that is to be used for nearest neighbors estimation.

Definition at line 230 of file feature.h.

template<typename PointInT, typename PointOutT>
KdTreePtr pcl::Feature< PointInT, PointOutT >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 233 of file feature.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:37