Go to the documentation of this file.
   45   output.header = cloud->header;
 
   56   impl_.setKSearch (k_);
 
   57   impl_.setRadiusSearch (search_radius_);
 
   60   impl_.setInputCloud (
pcl_ptr(cloud));
 
   61   impl_.setIndices (indices);
 
   62   impl_.setSearchSurface (
pcl_ptr(surface));
 
   63   impl_.setInputNormals (
pcl_ptr(normals));
 
   66   impl_.compute (output);
 
   70   output.header = cloud->header;
 
   71   pub_output_.publish (
ros_ptr(output.makeShared ()));
 
  
void publish(const boost::shared_ptr< M > &message) const
pcl::IndicesPtr IndicesPtr
pcl_ros::FPFHEstimationOMP FPFHEstimationOMP
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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.
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
boost::shared_ptr< T > pcl_ptr(const boost::shared_ptr< T > &p)
pcl::PointCloud< pcl::FPFHSignature33 > PointCloudOut
FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point clou...
boost::shared_ptr< T > ros_ptr(const boost::shared_ptr< T > &p)
pcl_ros
Author(s): Open Perception, Julius Kammerl 
, William Woodall 
autogenerated on Fri Jul 12 2024 02:54:40