44 output.header = cloud->header;
59 impl_.setInputCloud (cloud);
60 impl_.setIndices (indices);
61 impl_.setSearchSurface (surface);
62 impl_.setInputNormals (normals);
65 impl_.compute (output);
69 output.header = cloud->header;
void publish(const boost::shared_ptr< M > &message) const
pcl::PointCloud< pcl::SHOT352 > PointCloudOut
int k_
The number of K nearest neighbors to use for each point.
PointCloudN::ConstPtr PointCloudNConstPtr
double search_radius_
The nearest neighbors search radius for each point.
pcl_ros::SHOTEstimation SHOTEstimation
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.
pcl::SHOTEstimation< pcl::PointXYZ, pcl::Normal, pcl::SHOT352 > impl_
PLUGINLIB_EXPORT_CLASS(CropBox, nodelet::Nodelet)
SHOTEstimation estimates SHOT descriptor.
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr