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

FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard. More...

#include <fpfh_omp.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const FPFHEstimationOMP
< PointInT, PointNT, PointOutT > > 
ConstPtr
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< FPFHEstimationOMP< PointInT,
PointNT, PointOutT > > 
Ptr

Public Member Functions

 FPFHEstimationOMP (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.

Public Attributes

int nr_bins_f1_
 The number of subdivisions for each angular feature interval.
int nr_bins_f2_
int nr_bins_f3_

Private Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

Private Attributes

unsigned int threads_
 The number of threads the scheduler should use.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT>
class pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >

FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard.

Note:
If you use this code in any academic work, please cite:
Attention:
The convention for FPFH features is:
  • if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN (not a number)
  • it is impossible to estimate a FPFH descriptor for a point that doesn't have finite 3D coordinates. Therefore, any point that contains NaN data on x, y, or z, will have its FPFH feature property set to NaN.
Author:
Radu B. Rusu

Definition at line 75 of file fpfh_omp.h.


Member Typedef Documentation

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

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

Definition at line 79 of file fpfh_omp.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::PointCloudOut

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

Definition at line 93 of file fpfh_omp.h.

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

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

Definition at line 78 of file fpfh_omp.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::FPFHEstimationOMP ( unsigned int  nr_threads = 0) [inline]

Initialize the scheduler and set the number of threads to use.

Parameters:
[in]nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 98 of file fpfh_omp.h.


Member Function Documentation

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

Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

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

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

Definition at line 48 of file fpfh_omp.hpp.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::setNumberOfThreads ( unsigned int  nr_threads = 0) [inline]

Initialize the scheduler and set the number of threads to use.

Parameters:
[in]nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 107 of file fpfh_omp.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
int pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::nr_bins_f1_

The number of subdivisions for each angular feature interval.

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

Definition at line 120 of file fpfh_omp.h.

template<typename PointInT, typename PointNT, typename PointOutT>
int pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::nr_bins_f2_

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

Definition at line 120 of file fpfh_omp.h.

template<typename PointInT, typename PointNT, typename PointOutT>
int pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::nr_bins_f3_

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

Definition at line 120 of file fpfh_omp.h.

template<typename PointInT, typename PointNT, typename PointOutT>
unsigned int pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::threads_ [private]

The number of threads the scheduler should use.

Definition at line 123 of file fpfh_omp.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:56