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

NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures. More...

#include <normal_3d.h>

Inheritance diagram for pcl_ros::NormalEstimation:
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::NormalEstimation
< pcl::PointXYZ, pcl::Normal
impl_
 PCL implementation object.

Detailed Description

NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures.

Note:
The code is stateful as we do not expect this class to be multicore parallelized. Please look at NormalEstimationOpenMP and NormalEstimationTBB for parallel implementations.
Author:
Radu Bogdan Rusu

Definition at line 53 of file normal_3d.h.


Member Typedef Documentation

Definition at line 59 of file normal_3d.h.


Member Function Documentation

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

Child initialization routine. Internal method.

Implements pcl_ros::Feature.

Definition at line 63 of file normal_3d.h.

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

Compute the feature and publish it.

Implements pcl_ros::Feature.

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

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

Publish an empty point cloud of the feature output type.

Parameters:
cloudthe input point cloud to copy the header from.

Implements pcl_ros::Feature.

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


Member Data Documentation

PCL implementation object.

Definition at line 57 of file normal_3d.h.


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


pcl_ros
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:22:25