38 #ifndef PCL_ROS_FPFH_OMP_H_ 39 #define PCL_ROS_FPFH_OMP_H_ 41 #include <pcl/features/fpfh_omp.h> 68 pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33>
impl_;
91 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
95 #endif //#ifndef PCL_ROS_FPFH_OMP_H_
pcl::FPFHEstimationOMP< pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33 > impl_
pcl::IndicesPtr IndicesPtr
FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point clou...
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.
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
pcl::PointCloud< pcl::FPFHSignature33 > PointCloudOut