45 output.header = cloud->header;
60 impl_.setIndices (indices);
64 impl_.compute (output);
68 output.header = cloud->header;
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.
NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and ...
pcl::NormalEstimationOMP< pcl::PointXYZ, pcl::Normal > impl_
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl_ros::NormalEstimationOMP NormalEstimationOMP
pcl::PointCloud< pcl::Normal > PointCloudOut
ros::Publisher pub_output_
The output PointCloud publisher.
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
#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)