NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures. More...
#include <normal_3d.h>

| 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. | |
NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures.
Definition at line 53 of file normal_3d.h.
| typedef pcl::PointCloud<pcl::Normal> pcl_ros::NormalEstimation::PointCloudOut  [private] | 
Definition at line 59 of file normal_3d.h.
| 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.
| cloud | the input point cloud to copy the header from. | 
Implements pcl_ros::Feature.
Definition at line 42 of file features/normal_3d.cpp.
PCL implementation object.
Definition at line 57 of file normal_3d.h.