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

FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard. More...

#include <fpfh_omp.h>

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

List of all members.

Private Types

typedef pcl::PointCloud
< pcl::FPFHSignature33 > 
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::FPFHEstimationOMP
< pcl::PointXYZ, pcl::Normal,
pcl::FPFHSignature33 > 
impl_

Detailed Description

FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals, in parallel, using the OpenMP standard.

Note:
If you use this code in any academic work, please cite:
Author:
Radu Bogdan Rusu

Definition at line 65 of file fpfh_omp.h.


Member Typedef Documentation

typedef pcl::PointCloud<pcl::FPFHSignature33> pcl_ros::FPFHEstimationOMP::PointCloudOut [private]

Definition at line 70 of file fpfh_omp.h.


Member Function Documentation

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

Child initialization routine. Internal method.

Implements pcl_ros::FeatureFromNormals.

Definition at line 74 of file fpfh_omp.h.

void pcl_ros::FPFHEstimationOMP::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/fpfh_omp.cpp.

void pcl_ros::FPFHEstimationOMP::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/fpfh_omp.cpp.


Member Data Documentation

pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> pcl_ros::FPFHEstimationOMP::impl_ [private]

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