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

#include <pfhrgb.h>

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

List of all members.

Public Types

typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

Public Member Functions

void computePointPFHRGBSignature (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, const std::vector< int > &indices, int nr_split, Eigen::VectorXf &pfhrgb_histogram)
bool computeRGBPairFeatures (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7)
 PFHRGBEstimation ()

Protected Member Functions

void computeFeature (PointCloudOut &output)
 Abstract feature estimation method.

Private Member Functions

void computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &)
 Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Private Attributes

float d_pi_
 Float constant = 1.0 / (2.0 * M_PI)
int f_index_ [7]
 Placeholder for a histogram index.
int nr_subdiv_
 The number of subdivisions for each angular feature interval.
Eigen::VectorXf pfhrgb_histogram_
 Placeholder for a point's PFHRGB signature.
Eigen::VectorXf pfhrgb_tuple_
 Placeholder for a PFHRGB 7-tuple.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHRGBSignature250>
class pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >

Definition at line 52 of file pfhrgb.h.


Member Typedef Documentation

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::PointCloudOut

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 61 of file pfhrgb.h.


Constructor & Destructor Documentation

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::PFHRGBEstimation ( ) [inline]

Definition at line 64 of file pfhrgb.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computeFeature ( PointCloudOut output) [protected, virtual]

Abstract feature estimation method.

Parameters:
[out]outputthe resultant features

nr_subdiv^3 for RGB and nr_subdiv^3 for the angular features

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 141 of file pfhrgb.hpp.

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
void pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computeFeatureEigen ( pcl::PointCloud< Eigen::MatrixXf > &  ) [inline, private, virtual]

Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Parameters:
[out]outputthe output point cloud

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 103 of file pfhrgb.h.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computePointPFHRGBSignature ( const pcl::PointCloud< PointInT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
const std::vector< int > &  indices,
int  nr_split,
Eigen::VectorXf &  pfhrgb_histogram 
)

Definition at line 62 of file pfhrgb.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::computeRGBPairFeatures ( const pcl::PointCloud< PointInT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
int  p_idx,
int  q_idx,
float &  f1,
float &  f2,
float &  f3,
float &  f4,
float &  f5,
float &  f6,
float &  f7 
)

Definition at line 45 of file pfhrgb.hpp.


Member Data Documentation

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
float pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::d_pi_ [private]

Float constant = 1.0 / (2.0 * M_PI)

Definition at line 97 of file pfhrgb.h.

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
int pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::f_index_[7] [private]

Placeholder for a histogram index.

Definition at line 94 of file pfhrgb.h.

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
int pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::nr_subdiv_ [private]

The number of subdivisions for each angular feature interval.

Definition at line 85 of file pfhrgb.h.

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
Eigen::VectorXf pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::pfhrgb_histogram_ [private]

Placeholder for a point's PFHRGB signature.

Definition at line 88 of file pfhrgb.h.

template<typename PointInT , typename PointNT , typename PointOutT = pcl::PFHRGBSignature250>
Eigen::VectorXf pcl::PFHRGBEstimation< PointInT, PointNT, PointOutT >::pfhrgb_tuple_ [private]

Placeholder for a PFHRGB 7-tuple.

Definition at line 91 of file pfhrgb.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:51