36 #ifndef JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_
37 #define JSK_PCL_ROS_EUCLIDEAN_CLUSTER_EXTRACTION_NODELET_H_
42 #include <std_msgs/ColorRGBA.h>
44 #include <dynamic_reconfigure/server.h>
48 #include <pcl/point_types.h>
49 #include <pcl/impl/point_types.hpp>
50 #include <pcl/kdtree/kdtree_flann.h>
51 #include <pcl/segmentation/sac_segmentation.h>
52 #include <pcl/segmentation/extract_clusters.h>
53 #include <pcl/filters/extract_indices.h>
54 #include <pcl/filters/voxel_grid.h>
55 #include <pcl/common/centroid.h>
57 #include "jsk_recognition_msgs/ClusterPointIndices.h"
58 #include "jsk_recognition_msgs/EuclideanSegment.h"
59 #include "jsk_recognition_msgs/Int32Stamped.h"
61 #include "jsk_pcl_ros/EuclideanClusteringConfig.h"
62 #include <Eigen/StdVector>
65 #include <jsk_topic_tools/time_accumulator.h>
67 #include <jsk_topic_tools/diagnostic_nodelet.h>
71 class EuclideanClustering :
public jsk_topic_tools::DiagnosticNodelet
75 jsk_recognition_msgs::ClusterPointIndices,
79 jsk_recognition_msgs::ClusterPointIndices,
82 typedef jsk_pcl_ros::EuclideanClusteringConfig
Config;
83 typedef std::vector<Eigen::Vector4f,
84 Eigen::aligned_allocator<Eigen::Vector4f> >
127 virtual void extract(
const sensor_msgs::PointCloud2ConstPtr &
input);
128 virtual void multi_extract(
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_indices,
129 const sensor_msgs::PointCloud2::ConstPtr&
input);
131 std::vector<pcl::PointIndices::Ptr> &cluster_indices,
132 std::vector<pcl::PointIndices> &clustered_indices);
134 jsk_recognition_msgs::EuclideanSegment::Response &
res);
137 std::vector<int>& pivot_table,
138 std::vector<pcl::PointIndices>& cluster_indices);
153 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
154 std::vector<pcl::PointIndices> cluster_indices);
158 const pcl::PointCloud<pcl::PointXYZ>::Ptr& original_cloud,
159 pcl::PointCloud<pcl::PointXYZ>::Ptr& sampled_cloud,
160 std::vector<std::vector<int> >& sampled_to_original_indices,
161 std::vector<int>& original_to_sampled_indices,