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>
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 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::PrincipalCurvaturesEstimation < pcl::PointXYZ, pcl::Normal, pcl::PrincipalCurvatures > | impl_ |
PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface curvatures for a given point cloud dataset containing points and normals.
Definition at line 54 of file principal_curvatures.h.
typedef pcl::PointCloud<pcl::PrincipalCurvatures> pcl_ros::PrincipalCurvaturesEstimation::PointCloudOut [private] |
Definition at line 59 of file principal_curvatures.h.
bool pcl_ros::PrincipalCurvaturesEstimation::childInit | ( | ros::NodeHandle & | nh | ) | [inline, private, virtual] |
Child initialization routine. Internal method.
Implements pcl_ros::FeatureFromNormals.
Definition at line 63 of file principal_curvatures.h.
void pcl_ros::PrincipalCurvaturesEstimation::computePublish | ( | const PointCloudInConstPtr & | cloud, |
const PointCloudNConstPtr & | normals, | ||
const PointCloudInConstPtr & | surface, | ||
const IndicesPtr & | indices | ||
) | [private, virtual] |
Compute the feature and publish it.
Implements pcl_ros::FeatureFromNormals.
Definition at line 50 of file features/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 features/principal_curvatures.cpp.
pcl::PrincipalCurvaturesEstimation<pcl::PointXYZ, pcl::Normal, pcl::PrincipalCurvatures> pcl_ros::PrincipalCurvaturesEstimation::impl_ [private] |
Definition at line 57 of file principal_curvatures.h.