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 IndicesConstPtr &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 50 of file normal_3d_tbb.h.


Member Typedef Documentation

Definition at line 49 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 53 of file normal_3d_tbb.h.

void pcl_ros::NormalEstimationTBB::computePublish ( const PointCloudInConstPtr cloud,
const PointCloudInConstPtr surface,
const IndicesConstPtr 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 47 of file normal_3d_tbb.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:15:54 2013