38 #ifndef PCL_ROS_BOUNDARY_H_ 39 #define PCL_ROS_BOUNDARY_H_ 41 #define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET true 43 #include <pcl/features/boundary.h> 59 pcl::BoundaryEstimation<pcl::PointXYZ, pcl::Normal, pcl::Boundary>
impl_;
82 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
86 #endif //#ifndef PCL_ROS_BOUNDARY_H_
pcl::BoundaryEstimation< pcl::PointXYZ, pcl::Normal, pcl::Boundary > impl_
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
PointCloudN::ConstPtr PointCloudNConstPtr
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle cr...
pcl::PointCloud< pcl::Boundary > PointCloudOut
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr