Go to the documentation of this file.
38 #ifndef PCL_ROS_FPFH_H_
39 #define PCL_ROS_FPFH_H_
41 #include <pcl/features/fpfh.h>
71 pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33>
impl_;
94 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
98 #endif //#ifndef PCL_FPFH_H_
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
boost::shared_ptr< const PointCloudN > PointCloudNConstPtr
pcl::IndicesPtr IndicesPtr
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud d...
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
pcl::FPFHEstimation< pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33 > impl_
pcl::PointCloud< pcl::FPFHSignature33 > PointCloudOut
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40