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

#include <feature.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const FeatureFromNormals
< PointInT, PointNT, PointOutT > > 
ConstPtr
typedef pcl::PointCloud< PointNTPointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef boost::shared_ptr
< FeatureFromNormals< PointInT,
PointNT, PointOutT > > 
Ptr

Public Member Functions

 FeatureFromNormals ()
 Empty constructor.
PointCloudNConstPtr getInputNormals () const
 Get a pointer to the normals of the input XYZ point cloud dataset.
void setInputNormals (const PointCloudNConstPtr &normals)
 Provide a pointer to the input dataset that contains the point normals of the XYZ dataset. In case of search surface is set to be different from the input cloud, normals should correspond to the search surface, not the input cloud!
virtual ~FeatureFromNormals ()
 Empty destructor.

Protected Member Functions

virtual bool initCompute ()
 This method should get called before starting the actual computation.

Protected Attributes

PointCloudNConstPtr normals_
 A pointer to the input dataset that contains the point normals of the XYZ dataset.

Private Types

typedef Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

Detailed Description

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

Definition at line 310 of file feature.h.


Member Typedef Documentation

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

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Reimplemented in pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::FPFHEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimation< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PPFEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PPFRGBRegionEstimation< PointInT, PointNT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >, pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::CRHEstimation< PointInT, PointNT, PointOutT >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >, and pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >.

Definition at line 323 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudIn [private]
template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudIn::ConstPtr pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudInConstPtr [private]

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 314 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudIn::Ptr pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudInPtr [private]

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 313 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef pcl::PointCloud<PointNT> pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudN

Definition at line 318 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudN::ConstPtr pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudNConstPtr

Definition at line 320 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudN::Ptr pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudNPtr

Definition at line 319 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::PointCloudOut [private]
template<typename PointInT, typename PointNT, typename PointOutT>
typedef boost::shared_ptr< FeatureFromNormals<PointInT, PointNT, PointOutT> > pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::Ptr

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Reimplemented in pcl::SHOTColorEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimation< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::RSDEstimation< PointInT, PointNT, PointOutT >, pcl::PFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::BoundaryEstimation< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::FPFHEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimation< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PPFEstimation< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::PPFRGBRegionEstimation< PointInT, PointNT, PointOutT >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >, pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >, pcl::CVFHEstimation< PointInT, PointNT, PointOutT >, pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT >, pcl::CRHEstimation< PointInT, PointNT, PointOutT >, pcl::PrincipalCurvaturesEstimation< PointInT, PointNT, PointOutT >, pcl::BOARDLocalReferenceFrameEstimation< PointInT, PointNT, PointOutT >, pcl::IntensityGradientEstimation< PointInT, PointNT, PointOutT, IntensitySelectorT >, and pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >.

Definition at line 322 of file feature.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::FeatureFromNormals ( ) [inline]

Empty constructor.

Definition at line 331 of file feature.h.

template<typename PointInT, typename PointNT, typename PointOutT>
virtual pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::~FeatureFromNormals ( ) [inline, virtual]

Empty destructor.

Definition at line 334 of file feature.h.


Member Function Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
PointCloudNConstPtr pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::getInputNormals ( ) const [inline]

Get a pointer to the normals of the input XYZ point cloud dataset.

Definition at line 348 of file feature.h.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::initCompute ( ) [protected, virtual]
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::setInputNormals ( const PointCloudNConstPtr normals) [inline]

Provide a pointer to the input dataset that contains the point normals of the XYZ dataset. In case of search surface is set to be different from the input cloud, normals should correspond to the search surface, not the input cloud!

Parameters:
[in]normalsthe const boost shared pointer to a PointCloud of normals. By convention, L2 norm of each normal should be 1.

Definition at line 344 of file feature.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
PointCloudNConstPtr pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >::normals_ [protected]

A pointer to the input dataset that contains the point normals of the XYZ dataset.

Definition at line 354 of file feature.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:44