BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset. More...
#include <boundary.h>
Private Types | |
typedef pcl::PointCloud < pcl::Boundary > | 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::BoundaryEstimation < pcl::PointXYZ, pcl::Normal, pcl::Boundary > | impl_ |
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset.
Definition at line 54 of file boundary.h.
typedef pcl::PointCloud<pcl::Boundary> pcl_ros::BoundaryEstimation::PointCloudOut [private] |
Definition at line 59 of file boundary.h.
bool pcl_ros::BoundaryEstimation::childInit | ( | ros::NodeHandle & | nh | ) | [inline, private, virtual] |
Child initialization routine. Internal method.
Implements pcl_ros::FeatureFromNormals.
Definition at line 63 of file boundary.h.
void pcl_ros::BoundaryEstimation::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/boundary.cpp.
void pcl_ros::BoundaryEstimation::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/boundary.cpp.
pcl::BoundaryEstimation<pcl::PointXYZ, pcl::Normal, pcl::Boundary> pcl_ros::BoundaryEstimation::impl_ [private] |
Definition at line 57 of file boundary.h.