38 #ifndef PCL_ROS_FEATURES_VFH_H_ 39 #define PCL_ROS_FEATURES_VFH_H_ 41 #include <pcl/features/vfh.h> 56 pcl::VFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::VFHSignature308>
impl_;
79 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
83 #endif //#ifndef PCL_ROS_FEATURES_VFH_H_
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud data...
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl::PointCloud< pcl::VFHSignature308 > PointCloudOut
PointCloudN::ConstPtr PointCloudNConstPtr
pcl::VFHEstimation< pcl::PointXYZ, pcl::Normal, pcl::VFHSignature308 > impl_
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.