45 output.header = cloud->header;
61 impl_.setIndices (indices);
66 impl_.compute (output);
70 output.header = cloud->header;
FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud d...
pcl::IndicesPtr IndicesPtr
int k_
The number of K nearest neighbors to use for each point.
void publish(const boost::shared_ptr< M > &message) const
double search_radius_
The nearest neighbors search radius for each point.
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl::PointCloud< pcl::FPFHSignature33 > PointCloudOut
ros::Publisher pub_output_
The output PointCloud publisher.
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
pcl_ros::FPFHEstimation FPFHEstimation
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
boost::shared_ptr< T > pcl_ptr(const boost::shared_ptr< T > &p)
boost::shared_ptr< T > ros_ptr(const boost::shared_ptr< T > &p)
pcl::FPFHEstimation< pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33 > impl_