38 #ifndef PCL_ROS_PFH_H_ 39 #define PCL_ROS_PFH_H_ 41 #include <pcl/features/pfh.h> 71 pcl::PFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::PFHSignature125>
impl_;
94 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
98 #endif //#ifndef PCL_ROS_PFH_H_
pcl::PointCloud< pcl::PFHSignature125 > PointCloudOut
PointCloudN::ConstPtr PointCloudNConstPtr
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
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).
pcl::PFHEstimation< pcl::PointXYZ, pcl::Normal, pcl::PFHSignature125 > impl_
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset ...