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);
70 output.header = cloud->header;
pcl_ros::VFHEstimation VFHEstimation
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
void publish(const boost::shared_ptr< M > &message) const
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud data...
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl::PointCloud< pcl::VFHSignature308 > PointCloudOut
int k_
The number of K nearest neighbors to use for each point.
PointCloudN::ConstPtr PointCloudNConstPtr
pcl::VFHEstimation< pcl::PointXYZ, pcl::Normal, pcl::VFHSignature308 > impl_
double search_radius_
The nearest neighbors search radius for each point.
PLUGINLIB_EXPORT_CLASS(CropBox, nodelet::Nodelet)
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr