SHOTColorEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points, normals and colors, in parallel, using the OpenMP standard. More...
#include <shot_omp.h>
Public Types | |
typedef boost::shared_ptr < const SHOTColorEstimationOMP < PointInT, PointNT, PointOutT, PointRFT > > | ConstPtr |
typedef Feature< PointInT, PointOutT >::PointCloudIn | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr < SHOTColorEstimationOMP < PointInT, PointNT, PointOutT, PointRFT > > | Ptr |
Public Member Functions | |
void | setNumberOfThreads (unsigned int nr_threads=0) |
Initialize the scheduler and set the number of threads to use. | |
SHOTColorEstimationOMP (bool describe_shape=true, bool describe_color=true, unsigned int nr_threads=0) | |
Empty constructor. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod () | |
bool | initCompute () |
This method should get called before starting the actual computation. | |
Protected Attributes | |
unsigned int | threads_ |
The number of threads the scheduler should use. |
SHOTColorEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset containing points, normals and colors, in parallel, using the OpenMP standard.
The suggested PointOutT is pcl::SHOT1344.
Definition at line 146 of file shot_omp.h.
typedef boost::shared_ptr<const SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::ConstPtr |
Reimplemented from pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >.
Definition at line 150 of file shot_omp.h.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::PointCloudIn |
Reimplemented from pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >.
Definition at line 175 of file shot_omp.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::PointCloudOut |
Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.
Definition at line 174 of file shot_omp.h.
typedef boost::shared_ptr<SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::Ptr |
Reimplemented from pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >.
Definition at line 149 of file shot_omp.h.
pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::SHOTColorEstimationOMP | ( | bool | describe_shape = true , |
bool | describe_color = true , |
||
unsigned int | nr_threads = 0 |
||
) | [inline] |
Empty constructor.
Definition at line 178 of file shot_omp.h.
void pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Estimate the Signatures of Histograms of OrienTations (SHOT) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
output | the resultant point cloud model dataset that contains the SHOT feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 194 of file shot_omp.hpp.
bool pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute | ( | ) | [protected, virtual] |
This method should get called before starting the actual computation.
Reimplemented from pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >.
Definition at line 86 of file shot_omp.hpp.
void pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::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 189 of file shot_omp.h.
unsigned int pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::threads_ [protected] |
The number of threads the scheduler should use.
Definition at line 206 of file shot_omp.h.