45 output.header = cloud->header;
62 impl_.setInputCloud (cloud);
63 impl_.setIndices (indices);
64 impl_.setSearchSurface (surface);
67 impl_.compute (output);
71 output.header = cloud->header;
void publish(const boost::shared_ptr< M > &message) const
pcl_ros::NormalEstimationOMP NormalEstimationOMP
int k_
The number of K nearest neighbors to use for each point.
boost::shared_ptr< std::vector< int > > IndicesPtr
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::PointCloud< pcl::Normal > PointCloudOut
PLUGINLIB_EXPORT_CLASS(NormalEstimationOMP, nodelet::Nodelet)
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
KdTreePtr tree_
The input point cloud dataset.
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.