35 #ifndef JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_ 36 #define JSK_PCL_ROS_MULTI_PLANE_EXTRACTION_H_ 46 #include "jsk_recognition_msgs/ClusterPointIndices.h" 47 #include "sensor_msgs/PointCloud2.h" 48 #include "jsk_recognition_msgs/ModelCoefficientsArray.h" 49 #include "jsk_recognition_msgs/PolygonArray.h" 50 #include <dynamic_reconfigure/server.h> 51 #include "jsk_pcl_ros/MultiPlaneExtractionConfig.h" 65 sensor_msgs::PointCloud2,
66 jsk_recognition_msgs::ClusterPointIndices,
67 jsk_recognition_msgs::ModelCoefficientsArray,
70 sensor_msgs::PointCloud2,
71 jsk_recognition_msgs::ClusterPointIndices,
72 jsk_recognition_msgs::ModelCoefficientsArray,
74 typedef jsk_pcl_ros::MultiPlaneExtractionConfig
Config;
84 const jsk_recognition_msgs::PolygonArray::ConstPtr&
polygons);
86 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
88 virtual void extract(
const sensor_msgs::PointCloud2::ConstPtr& input,
89 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
90 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr&
coefficients,
91 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
boost::mutex mutex
global mutex.