36 #ifndef JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_ 
   37 #define JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_ 
   42 #include "jsk_recognition_msgs/ClusterPointIndices.h" 
   43 #include "jsk_recognition_msgs/PolygonArray.h" 
   44 #include "jsk_recognition_msgs/ModelCoefficientsArray.h" 
   47 #include "sensor_msgs/PointCloud2.h" 
   48 #include <dynamic_reconfigure/server.h> 
   53 #include <pcl/point_types.h> 
   54 #include <pcl/impl/point_types.hpp> 
   56 #include <std_msgs/ColorRGBA.h> 
   57 #include <jsk_recognition_msgs/BoundingBoxArray.h> 
   62 #include <jsk_topic_tools/vital_checker.h> 
   63 #include "jsk_topic_tools/diagnostic_nodelet.h" 
   64 #include "jsk_pcl_ros/ClusterPointIndicesDecomposerConfig.h" 
   68   class ClusterPointIndicesDecomposer: 
public jsk_topic_tools::DiagnosticNodelet
 
   73     typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig 
Config;
 
   75     sensor_msgs::PointCloud2,
 
   76     jsk_recognition_msgs::ClusterPointIndices > 
SyncPolicy;
 
   78     sensor_msgs::PointCloud2,
 
   81       sensor_msgs::PointCloud2,
 
   82       jsk_recognition_msgs::ClusterPointIndices,
 
   83       jsk_recognition_msgs::PolygonArray,
 
   86       sensor_msgs::PointCloud2,
 
   87       jsk_recognition_msgs::ClusterPointIndices,
 
   88       jsk_recognition_msgs::PolygonArray,
 
   91     virtual void extract(
const sensor_msgs::PointCloud2ConstPtr &
point,
 
   92                          const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices,
 
   93                          const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
   94                          const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
 
   95     virtual void extract(
const sensor_msgs::PointCloud2ConstPtr &
point,
 
   96                          const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
 
   98                                   const std::vector<pcl::IndicesPtr> indices_array,
 
   99                                   std::vector<size_t>* argsort);
 
  101                                    const std::vector<pcl::IndicesPtr> indices_array,
 
  102                                    std::vector<size_t>* argsort);
 
  104                                  const std::vector<pcl::IndicesPtr> indices_array,
 
  105                                  std::vector<size_t>* argsort);
 
  107                                      const std::vector<pcl::IndicesPtr> indices_array,
 
  108                                      std::vector<size_t>* argsort);
 
  114     (
const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
 
  116      pcl::PointCloud<pcl::PointXYZRGB>& debug_output);
 
  119     (
const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
 
  120      const std_msgs::Header 
header,
 
  121      const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  122      const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
 
  123      geometry_msgs::Pose& center_pose_msg,
 
  124      jsk_recognition_msgs::BoundingBox& bounding_box,
 
  128       const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
 
  129       pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud_transformed,
 
  130       const Eigen::Vector4f center,
 
  131       const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  132       const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
 
  134       Eigen::Quaternionf& q,
 
  135       int& nearest_plane_index);
 
  138                                  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  139                                  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
 
  146       const sensor_msgs::PointCloud2ConstPtr &
input,
 
  147       const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input);
 
  154         r = (uint8_t)(
c.r * 255);
 
  155         g = (uint8_t)(
c.g * 255);
 
  156         b = (uint8_t)(
c.b * 255);
 
  157         return ((uint32_t)
r<<16 | (uint32_t)g<<8 | (uint32_t)
b);
 
  200 #endif  // JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_