Private Types | Private Member Functions | Private Attributes
pcl_ros::PFHEstimation Class Reference

PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing points and normals. More...

#include <pfh.h>

Inheritance diagram for pcl_ros::PFHEstimation:
Inheritance graph
[legend]

List of all members.

Private Types

typedef pcl::PointCloud
< pcl::PFHSignature125 > 
PointCloudOut

Private Member Functions

bool childInit (ros::NodeHandle &nh)
 Child initialization routine. Internal method.
void computePublish (const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
 Compute the feature and publish it.
void emptyPublish (const PointCloudInConstPtr &cloud)
 Publish an empty point cloud of the feature output type.

Private Attributes

pcl::PFHEstimation
< pcl::PointXYZ, pcl::Normal,
pcl::PFHSignature125 > 
impl_

Detailed Description

PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing points and normals.

Note:
If you use this code in any academic work, please cite:
Note:
The code is stateful as we do not expect this class to be multicore parallelized. Please look at FPFHEstimationOpenMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
Author:
Radu Bogdan Rusu

Definition at line 68 of file pfh.h.


Member Typedef Documentation

typedef pcl::PointCloud<pcl::PFHSignature125> pcl_ros::PFHEstimation::PointCloudOut [private]

Definition at line 73 of file pfh.h.


Member Function Documentation

bool pcl_ros::PFHEstimation::childInit ( ros::NodeHandle nh) [inline, private, virtual]

Child initialization routine. Internal method.

Implements pcl_ros::FeatureFromNormals.

Definition at line 77 of file pfh.h.

void pcl_ros::PFHEstimation::computePublish ( const PointCloudInConstPtr cloud,
const PointCloudNConstPtr normals,
const PointCloudInConstPtr surface,
const IndicesPtr indices 
) [private, virtual]

Compute the feature and publish it.

Implements pcl_ros::FeatureFromNormals.

Definition at line 50 of file features/pfh.cpp.

void pcl_ros::PFHEstimation::emptyPublish ( const PointCloudInConstPtr cloud) [private, virtual]

Publish an empty point cloud of the feature output type.

Implements pcl_ros::FeatureFromNormals.

Definition at line 42 of file features/pfh.cpp.


Member Data Documentation

pcl::PFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::PFHSignature125> pcl_ros::PFHEstimation::impl_ [private]

Definition at line 71 of file pfh.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Jun 6 2019 21:01:45