Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT > Class Template Reference

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>

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

List of all members.

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.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
class pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >

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.

Note:
If you use this code in any academic work, please cite:
Author:
Samuele Salti

Definition at line 146 of file shot_omp.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
typedef boost::shared_ptr<const SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::ConstPtr
template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::PointCloudIn
template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
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.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
typedef boost::shared_ptr<SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::Ptr

Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
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.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT , typename PointRFT >
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 ()

Parameters:
outputthe 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.

template<typename PointInT , typename PointNT , typename PointOutT , typename PointRFT >
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.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
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.

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

Definition at line 189 of file shot_omp.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
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.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:35