45 output.header = cloud->header;
60 impl_.setInputCloud (cloud);
61 impl_.setIndices (indices);
62 impl_.setSearchSurface (surface);
63 impl_.setInputNormals (normals);
66 impl_.compute (output);
69 output.header = cloud->header;
void publish(const boost::shared_ptr< M > &message) const
pcl::BoundaryEstimation< pcl::PointXYZ, pcl::Normal, pcl::Boundary > impl_
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
int k_
The number of K nearest neighbors to use for each point.
PointCloudN::ConstPtr PointCloudNConstPtr
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
double search_radius_
The nearest neighbors search radius for each point.
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle cr...
pcl::PointCloud< pcl::Boundary > PointCloudOut
PLUGINLIB_EXPORT_CLASS(CropBox, nodelet::Nodelet)
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
pcl_ros::BoundaryEstimation BoundaryEstimation