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

NormalEstimationTBB estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using Intel's Threading Building Blocks library. More...

#include <normal_3d_tbb.h>

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

List of all members.

Private Types

typedef pcl::PointCloud
< pcl::Normal > 
PointCloudOut

Private Member Functions

bool childInit (ros::NodeHandle &nh)
 Child initialization routine. Internal method.
void computePublish (const PointCloudInConstPtr &cloud, 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::NormalEstimationTBB
< pcl::PointXYZ, pcl::Normal > 
impl_

Detailed Description

NormalEstimationTBB estimates local surface properties at each 3D point, such as surface normals and curvatures, in parallel, using Intel's Threading Building Blocks library.

Author:
Radu Bogdan Rusu

Definition at line 53 of file normal_3d_tbb.h.


Member Typedef Documentation

Definition at line 58 of file normal_3d_tbb.h.


Member Function Documentation

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

Child initialization routine. Internal method.

Implements pcl_ros::Feature.

Definition at line 62 of file normal_3d_tbb.h.

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

Compute the feature and publish it.

Implements pcl_ros::Feature.

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

Publish an empty point cloud of the feature output type.

Implements pcl_ros::Feature.


Member Data Documentation

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

Definition at line 56 of file normal_3d_tbb.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43