45 output.header = cloud->header;
59 impl_.setInputCloud (cloud);
60 impl_.setIndices (indices);
61 impl_.setSearchSurface (surface);
64 impl_.compute (output);
68 output.header = cloud->header;
void publish(const boost::shared_ptr< M > &message) const
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
int k_
The number of K nearest neighbors to use for each point.
pcl::PointCloud< pcl::Normal > PointCloudOut
double search_radius_
The nearest neighbors search radius for each point.
PLUGINLIB_EXPORT_CLASS(CropBox, nodelet::Nodelet)
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl_ros::NormalEstimation NormalEstimation
NormalEstimation estimates local surface properties at each 3D point, such as surface normals and cur...
pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > impl_
PCL implementation object.