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>
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. |
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.
Definition at line 75 of file fpfh_omp.h.
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.
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.
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.
pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::FPFHEstimationOMP | ( | unsigned int | nr_threads = 0 | ) | [inline] |
Initialize the scheduler and set the number of threads to use.
[in] | nr_threads | the number of hardware threads to use (0 sets the value back to automatic) |
Definition at line 98 of file fpfh_omp.h.
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 ()
[out] | output | the 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.
void pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >::setNumberOfThreads | ( | unsigned int | nr_threads = 0 | ) | [inline] |
Initialize the scheduler and set the number of threads to use.
[in] | nr_threads | the number of hardware threads to use (0 sets the value back to automatic) |
Definition at line 107 of file fpfh_omp.h.
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.
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.
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.
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.