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" 
   54 #include <jsk_topic_tools/vital_checker.h> 
   55 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   60   class MultiPlaneExtraction: 
public jsk_topic_tools::DiagnosticNodelet
 
   65     sensor_msgs::PointCloud2,
 
   66     jsk_recognition_msgs::ClusterPointIndices,
 
   67     jsk_recognition_msgs::ModelCoefficientsArray,
 
   68     jsk_recognition_msgs::PolygonArray> 
SyncPolicy;
 
   70       sensor_msgs::PointCloud2,
 
   71       jsk_recognition_msgs::ClusterPointIndices,
 
   72       jsk_recognition_msgs::ModelCoefficientsArray,
 
   74     typedef jsk_pcl_ros::MultiPlaneExtractionConfig 
Config;
 
   85       const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
 
   87       const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);
 
   89     virtual void extract(
const sensor_msgs::PointCloud2::ConstPtr& 
input,
 
   90                          const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
 
   91                          const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
 
   92                          const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons);