pcl_ros::PrincipalCurvaturesEstimation Class Reference

PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals. More...

#include <principal_curvatures.h>

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

List of all members.

Private Types

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

Detailed Description

PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals.

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

Definition at line 50 of file principal_curvatures.h.


Member Typedef Documentation

typedef pcl::PointCloud<pcl::PrincipalCurvatures> pcl_ros::PrincipalCurvaturesEstimation::PointCloudOut [private]

Definition at line 46 of file principal_curvatures.h.


Member Function Documentation

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

Child initialization routine. Internal method.

Implements pcl_ros::FeatureFromNormals.

Definition at line 50 of file principal_curvatures.h.

void pcl_ros::PrincipalCurvaturesEstimation::computePublish ( const PointCloudInConstPtr cloud,
const PointCloudNConstPtr normals,
const PointCloudInConstPtr surface,
const IndicesConstPtr indices 
) [private, virtual]

Compute the feature and publish it.

Implements pcl_ros::FeatureFromNormals.

Definition at line 50 of file principal_curvatures.cpp.

void pcl_ros::PrincipalCurvaturesEstimation::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 principal_curvatures.cpp.


Member Data Documentation

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

Definition at line 44 of file principal_curvatures.h.


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


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