NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using the OpenMP standard. More...
#include <normal_3d_omp.h>
Public Types | |
typedef boost::shared_ptr < const NormalEstimationOMP < PointInT, PointOutT > > | ConstPtr |
typedef NormalEstimation < PointInT, PointOutT > ::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < NormalEstimationOMP < PointInT, PointOutT > > | Ptr |
Public Member Functions | |
NormalEstimationOMP (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. | |
Protected Attributes | |
unsigned int | threads_ |
The number of threads the scheduler should use. | |
Private Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate normals for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod () |
NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using the OpenMP standard.
Definition at line 54 of file normal_3d_omp.h.
typedef boost::shared_ptr<const NormalEstimationOMP<PointInT, PointOutT> > pcl::NormalEstimationOMP< PointInT, PointOutT >::ConstPtr |
Reimplemented from pcl::NormalEstimation< PointInT, PointOutT >.
Definition at line 58 of file normal_3d_omp.h.
typedef NormalEstimation<PointInT, PointOutT>::PointCloudOut pcl::NormalEstimationOMP< PointInT, PointOutT >::PointCloudOut |
Reimplemented from pcl::NormalEstimation< PointInT, PointOutT >.
Definition at line 71 of file normal_3d_omp.h.
typedef boost::shared_ptr<NormalEstimationOMP<PointInT, PointOutT> > pcl::NormalEstimationOMP< PointInT, PointOutT >::Ptr |
Reimplemented from pcl::NormalEstimation< PointInT, PointOutT >.
Definition at line 57 of file normal_3d_omp.h.
pcl::NormalEstimationOMP< PointInT, PointOutT >::NormalEstimationOMP | ( | unsigned int | nr_threads = 0 | ) | [inline] |
Initialize the scheduler and set the number of threads to use.
nr_threads | the number of hardware threads to use (0 sets the value back to automatic) |
Definition at line 77 of file normal_3d_omp.h.
void pcl::NormalEstimationOMP< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [private, virtual] |
Estimate normals for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
output | the resultant point cloud model dataset that contains surface normals and curvatures |
Reimplemented from pcl::NormalEstimation< PointInT, PointOutT >.
Definition at line 48 of file normal_3d_omp.hpp.
void pcl::NormalEstimationOMP< PointInT, PointOutT >::setNumberOfThreads | ( | unsigned int | nr_threads = 0 | ) | [inline] |
Initialize the scheduler and set the number of threads to use.
nr_threads | the number of hardware threads to use (0 sets the value back to automatic) |
Definition at line 86 of file normal_3d_omp.h.
unsigned int pcl::NormalEstimationOMP< PointInT, PointOutT >::threads_ [protected] |
The number of threads the scheduler should use.
Definition at line 90 of file normal_3d_omp.h.