Go to the documentation of this file.
45 output.header = cloud->header;
55 impl_.setKSearch (k_);
56 impl_.setRadiusSearch (search_radius_);
59 impl_.setInputCloud (
pcl_ptr(cloud));
60 impl_.setIndices (indices);
61 impl_.setSearchSurface (
pcl_ptr(surface));
64 impl_.compute (output);
68 output.header = cloud->header;
69 pub_output_.publish (
ros_ptr(output.makeShared ()));
pcl::PointCloud< pcl::Normal > PointCloudOut
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
void publish(const boost::shared_ptr< M > &message) const
pcl::IndicesPtr IndicesPtr
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Publisher pub_output_
The output PointCloud publisher.
boost::shared_ptr< T > pcl_ptr(const boost::shared_ptr< T > &p)
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and ...
pcl_ros::NormalEstimationOMP NormalEstimationOMP
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