36 #ifndef JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_ 
   37 #define JSK_PCL_ROS_ORGANIZED_PLANE_SEGMENTATION_H_ 
   42 #include "jsk_recognition_msgs/ClusterPointIndices.h" 
   43 #include "sensor_msgs/PointCloud2.h" 
   45 #include <pcl/segmentation/organized_multi_plane_segmentation.h> 
   46 #include <dynamic_reconfigure/server.h> 
   47 #include "jsk_pcl_ros/OrganizedMultiPlaneSegmentationConfig.h" 
   48 #include "jsk_recognition_msgs/PolygonArray.h" 
   49 #include "jsk_recognition_msgs/ModelCoefficientsArray.h" 
   50 #include <jsk_topic_tools/time_accumulator.h> 
   51 #include <jsk_topic_tools/vital_checker.h> 
   57 #include <jsk_topic_tools/connection_based_nodelet.h> 
   58 #include <jsk_topic_tools/diagnostic_utils.h> 
   62   class OrganizedMultiPlaneSegmentation:
 
   63     public jsk_topic_tools::ConnectionBasedNodelet
 
   66     typedef pcl::PointXYZRGBA 
PointT;
 
   67     typedef std::vector<pcl::PlanarRegion<PointT>,
 
   68                         Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > >
 
   70     typedef jsk_pcl_ros::OrganizedMultiPlaneSegmentationConfig 
Config;
 
   75     virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr& 
msg);
 
   77                                 pcl::PointCloud<pcl::Normal>::Ptr output);
 
   80                                      geometry_msgs::Polygon& 
polygon);
 
   82                                                       const std_msgs::Header& 
header,
 
   83                                                       jsk_recognition_msgs::ClusterPointIndices& output_indices);
 
   85                                   const std::vector<pcl::ModelCoefficients>& model_coefficients,
 
   86                                   const std::vector<pcl::PointIndices>& boundary_indices,
 
   89                                       const std_msgs::Header& 
header,
 
   90                                       const std::vector<pcl::PointIndices>& inlier_indices,
 
   91                                       const std::vector<pcl::PointIndices>& boundary_indices,
 
   92                                       const std::vector<pcl::ModelCoefficients>& model_coefficients,
 
   94                                       std::vector<pcl::PointIndices>& output_indices,
 
   95                                       std::vector<pcl::ModelCoefficients>& output_coefficients,
 
   96                                       std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds);
 
   98                                      std::vector<pcl::ModelCoefficients>& output_coefficients);
 
  101       const pcl::PointCloud<PointT>::Ptr cloud,
 
  102       const std::vector<pcl::PointIndices>& inliers,
 
  103       const std_msgs::Header& 
header);
 
  106       pcl::PointCloud<PointT>::Ptr 
input,
 
  107       pcl::PointCloud<pcl::Normal>::Ptr normal,
 
  109       std::vector<pcl::ModelCoefficients>& model_coefficients,
 
  110       std::vector<pcl::PointIndices>& inlier_indices,
 
  111       pcl::PointCloud<pcl::Label>::Ptr& labels,
 
  112       std::vector<pcl::PointIndices>& label_indices,
 
  113       std::vector<pcl::PointIndices>& boundary_indices);
 
  116                                     pcl::PointCloud<pcl::Normal>::Ptr normal,
 
  117                                     const std_msgs::Header& 
header);
 
  120       const std_msgs::Header& 
header,
 
  121       const pcl::PointCloud<PointT>::Ptr 
input,
 
  125       const std::vector<pcl::PointIndices>& inlier_indices,
 
  126       const std::vector<pcl::PointCloud<PointT> >& boundaries,
 
  127       const std::vector<pcl::ModelCoefficients>& model_coefficients);
 
  129       const std_msgs::Header& 
header,
 
  130       const pcl::PointCloud<PointT>::Ptr 
input,
 
  134       const std::vector<pcl::PointIndices>& inlier_indices,
 
  135       const std::vector<pcl::PointIndices>& boundary_indices,
 
  136       const std::vector<pcl::ModelCoefficients>& model_coefficients);
 
  139       const pcl::PointCloud<PointT>::Ptr 
input,
 
  140       const std::vector<pcl::PointIndices>& input_indices,
 
  141       const std::vector<pcl::ModelCoefficients>& input_coefficients,
 
  142       std::vector<pcl::PointIndices>& output_indices,
 
  143       std::vector<pcl::ModelCoefficients>& output_coefficients,
 
  144       std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_boundaries);