45   void EuclideanClustering::downsample_cloud(
 
   46     const pcl::PointCloud<pcl::PointXYZ>::Ptr& original_cloud,
 
   47     pcl::PointCloud<pcl::PointXYZ>::Ptr& sampled_cloud,
 
   48     std::vector<std::vector<int> >& sampled_to_original_indices,
 
   49     std::vector<int>& original_to_sampled_indices,
 
   52     pcl::VoxelGrid<pcl::PointXYZ> voxel;
 
   53     voxel.setLeafSize(leaf_size, leaf_size, leaf_size);
 
   54     voxel.setSaveLeafLayout(
true);
 
   55     voxel.setInputCloud(original_cloud);
 
   56     voxel.filter(*sampled_cloud);
 
   57     sampled_to_original_indices.resize(original_cloud->points.size());
 
   58     original_to_sampled_indices.resize(original_cloud->points.size());
 
   59     std::fill(original_to_sampled_indices.begin(),
 
   60               original_to_sampled_indices.end(),
 
   62     std::fill(sampled_to_original_indices.begin(),
 
   63               sampled_to_original_indices.end(),
 
   65     for (
size_t i = 0; 
i < original_cloud->points.size(); ++
i) {
 
   66       pcl::PointXYZ 
p = original_cloud->points[
i];
 
   67       if (std::isnan(
p.x) || std::isnan(
p.y) || std::isnan(
p.z)) {
 
   71       const int index = voxel.getCentroidIndexAt(
 
   72         voxel.getGridCoordinates(
p.x, 
p.y, 
p.z));
 
   76       original_to_sampled_indices[
i] = 
index;
 
   77       sampled_to_original_indices[
index].push_back(
i);
 
   81   void EuclideanClustering::clusteringClusterIndices(
 
   82     pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud,
 
   83     std::vector<pcl::PointIndices::Ptr> &cluster_indices,
 
   84     std::vector<pcl::PointIndices> &clustered_indices) {
 
   88     clustered_indices.clear();
 
   91     pcl::PointCloud<pcl::PointXYZ>::Ptr preprocessed_cloud(
 
   92       new pcl::PointCloud<pcl::PointXYZ>);
 
   94       downsample_cloud(
cloud,
 
   96                        downsample_to_original_indices_,
 
   97                        original_to_downsample_indices_,
 
  101       preprocessed_cloud = 
cloud;
 
  104     if (preprocessed_cloud->points.size() == 0) {
 
  108     for(pcl::PointIndices::Ptr point_indices : cluster_indices){
 
  109       pcl::PointIndices::Ptr nonnan_indices (
new pcl::PointIndices);
 
  110       for(
int original_index : point_indices->indices) {
 
  113           index = original_to_downsample_indices_[original_index];
 
  115           index = original_index;
 
  121         pcl::PointXYZ 
p = preprocessed_cloud->points[
index];
 
  122         if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
 
  123           nonnan_indices->indices.push_back(
index);
 
  126       removeDuplicatedIndices(nonnan_indices);
 
  128       pcl::PointIndices result_point_indices;
 
  129       if (nonnan_indices->indices.size() > 0) {
 
  131         pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud(
new pcl::PointCloud<pcl::PointXYZ>);
 
  133           pcl::ExtractIndices<pcl::PointXYZ> extract;
 
  134           extract.setInputCloud(preprocessed_cloud);
 
  135           extract.setIndices (nonnan_indices);
 
  136           extract.setNegative(
false);
 
  137           extract.filter (*filtered_cloud);
 
  141         if (filtered_cloud->points.size() > 0) {
 
  142           jsk_topic_tools::ScopedTimer timer = kdtree_acc_.scopedTimer();
 
  143 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) 
  144           pcl::search::KdTree<pcl::PointXYZ>::Ptr 
tree (
new pcl::search::KdTree<pcl::PointXYZ>());
 
  145 #elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) 
  146           pcl::search::KdTree<pcl::PointXYZ>::Ptr 
tree (
new pcl::search::KdTree<pcl::PointXYZ>);
 
  147           tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
 
  149           pcl::KdTree<pcl::PointXYZ>::Ptr 
tree (
new pcl::KdTreeFLANN<pcl::PointXYZ>);
 
  150           tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
 
  152           tree->setInputCloud(filtered_cloud);
 
  154           impl.setMinClusterSize(minsize_);
 
  155           impl.setMaxClusterSize(maxsize_);
 
  156           impl.setSearchMethod(
tree);
 
  157           impl.setInputCloud(filtered_cloud);
 
  160         std::vector<pcl::PointIndices> output_indices;
 
  162           jsk_topic_tools::ScopedTimer timer = segmentation_acc_.scopedTimer();
 
  163           impl.extract(output_indices);
 
  165             for (
size_t i = 0; 
i < output_indices.size(); ++
i) {
 
  166               pcl::PointIndices::Ptr tmp_indices(
new pcl::PointIndices);
 
  167               for (
size_t j = 0; j < output_indices.at(
i).indices.size(); ++j) {
 
  168                 tmp_indices->indices.insert(
 
  169                   tmp_indices->indices.end(),
 
  170                   downsample_to_original_indices_[nonnan_indices->indices[output_indices.at(
i).indices[j]]].begin(),
 
  171                   downsample_to_original_indices_[nonnan_indices->indices[output_indices.at(
i).indices[j]]].end());
 
  173               removeDuplicatedIndices(tmp_indices);
 
  174               output_indices[
i] = *tmp_indices;
 
  177             for (
size_t i = 0; 
i < output_indices.size(); ++
i) {
 
  178               pcl::PointIndices tmp_indices;
 
  179               tmp_indices.indices.resize( output_indices.at(
i).indices.size());
 
  180               for (
size_t j = 0; j < output_indices.at(
i).indices.size(); ++j) {
 
  181                 tmp_indices.indices[j] = nonnan_indices->indices[output_indices.at(
i).indices[j]];
 
  183               output_indices[
i] = tmp_indices;
 
  187         std::vector<int> result_indices;
 
  188         std::vector<int> examine_indices;
 
  189         switch (cluster_filter_type_) {
 
  190           case jsk_pcl_ros::EuclideanClustering_All:  {
 
  191             for (
size_t i_e = 0; i_e < output_indices.size(); ++i_e) {
 
  192               examine_indices.push_back(i_e);
 
  196           case jsk_pcl_ros::EuclideanClustering_MaxSize: {
 
  200             for(
size_t i=0; 
i < output_indices.size(); 
i++){
 
  201               if(output_indices[
i].indices.size() > 
size){
 
  202                 size = output_indices[
i].indices.size();
 
  207               examine_indices.push_back(
index);
 
  212         for (
int index : examine_indices) {
 
  213           result_point_indices.indices = output_indices.at(
index).indices;
 
  214           clustered_indices.push_back(result_point_indices);
 
  217         clustered_indices.push_back(result_point_indices);
 
  222   void EuclideanClustering::extract(
 
  223     const sensor_msgs::PointCloud2ConstPtr &
input)
 
  225     vital_checker_->poke();
 
  226     pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud 
  227       (
new pcl::PointCloud<pcl::PointXYZ>);
 
  230     pcl::PointIndices::Ptr whole_indices(
new pcl::PointIndices);
 
  231     whole_indices->indices.resize(
input->height * 
input->width);
 
  233       whole_indices->indices[
i] = 
i;
 
  235     std::vector<pcl::PointIndices::Ptr> cluster_indices{whole_indices};
 
  236     std::vector<pcl::PointIndices> clustered_indices;
 
  237     clusteringClusterIndices(
cloud,
 
  242     jsk_recognition_msgs::ClusterPointIndices 
result;
 
  243     result.cluster_indices.resize(clustered_indices.size());
 
  244     cluster_counter_.add(clustered_indices.size());
 
  246     if (cogs_.size() != 0 && cogs_.size() == clustered_indices.size()) {
 
  253       computeCentroidsOfClusters(new_cogs, 
cloud, clustered_indices);
 
  254       double D[cogs_.size() * new_cogs.size()];
 
  255       computeDistanceMatrix(
D, cogs_, new_cogs);
 
  256       std::vector<int> pivot_table = buildLabelTrackingPivotTable(
D, cogs_, new_cogs, label_tracking_tolerance);
 
  257       if (pivot_table.size() != 0) {
 
  258         clustered_indices = pivotClusterIndices(pivot_table, clustered_indices);
 
  262     computeCentroidsOfClusters(tmp_cogs, 
cloud, clustered_indices); 
 
  265     for (
size_t i = 0; 
i < clustered_indices.size(); 
i++) {
 
  266 #if ROS_VERSION_MINIMUM(1, 10, 0) 
  268       result.cluster_indices[
i].header
 
  272       result.cluster_indices[
i].header = clustered_indices[
i].header;
 
  274       result.cluster_indices[
i].indices = clustered_indices[
i].indices;
 
  277     result_pub_.publish(
result);
 
  279     jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (
new jsk_recognition_msgs::Int32Stamped);
 
  280     cluster_num_msg->header = 
input->header;
 
  281     cluster_num_msg->data = clustered_indices.size();
 
  282     cluster_num_pub_.publish(cluster_num_msg);
 
  284     diagnostic_updater_->update();
 
  287   void EuclideanClustering::multi_extract(
 
  288     const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& input_cluster_indices,
 
  289     const sensor_msgs::PointCloud2::ConstPtr& 
input) {
 
  290     vital_checker_->poke();
 
  291     pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud 
  292       (
new pcl::PointCloud<pcl::PointXYZ>);
 
  295     std::vector<pcl::PointIndices::Ptr> cluster_indices =
 
  297     std::vector<pcl::PointIndices> clustered_indices;
 
  298     clusteringClusterIndices(
cloud,
 
  303     jsk_recognition_msgs::ClusterPointIndices 
result;
 
  304     result.cluster_indices.resize(clustered_indices.size());
 
  305     cluster_counter_.add(clustered_indices.size());
 
  308     for (
size_t i = 0; 
i < clustered_indices.size(); 
i++) {
 
  309 #if ROS_VERSION_MINIMUM(1, 10, 0) 
  311       result.cluster_indices[
i].header
 
  315       result.cluster_indices[
i].header = clustered_indices[
i].header;
 
  317       result.cluster_indices[
i].indices = clustered_indices[
i].indices;
 
  320     result_pub_.publish(
result);
 
  322     jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (
new jsk_recognition_msgs::Int32Stamped);
 
  323     cluster_num_msg->header = 
input->header;
 
  324     cluster_num_msg->data = clustered_indices.size();
 
  325     cluster_num_pub_.publish(cluster_num_msg);
 
  327     diagnostic_updater_->update();
 
  330   bool EuclideanClustering::serviceCallback(
 
  331     jsk_recognition_msgs::EuclideanSegment::Request &
req,
 
  332     jsk_recognition_msgs::EuclideanSegment::Response &
res)
 
  334     pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointXYZ>);
 
  337 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) 
  338     pcl::search::KdTree<pcl::PointXYZ>::Ptr 
tree (
new pcl::search::KdTree<pcl::PointXYZ> ());
 
  339 #elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 ) 
  340     pcl::search::KdTree<pcl::PointXYZ>::Ptr 
tree (
new pcl::search::KdTree<pcl::PointXYZ>);
 
  341     tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
 
  343     pcl::KdTree<pcl::PointXYZ>::Ptr 
tree (
new pcl::KdTreeFLANN<pcl::PointXYZ>);
 
  344     tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
 
  347     vector<pcl::PointIndices> cluster_indices;
 
  350     if ( 
req.tolerance < 0) {
 
  355     impl.setClusterTolerance (tor);
 
  356     impl.setMinClusterSize (minsize_);
 
  357     impl.setMaxClusterSize (maxsize_);
 
  358     impl.setSearchMethod (
tree);
 
  359     impl.setInputCloud (
cloud);
 
  360     impl.extract (cluster_indices);
 
  362     res.output.resize( cluster_indices.size() );
 
  363 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 ) 
  364     pcl::PCLPointCloud2::Ptr pcl_cloud(
new pcl::PCLPointCloud2);
 
  366     pcl::ExtractIndices<pcl::PCLPointCloud2> 
ex;
 
  367     ex.setInputCloud(pcl_cloud);
 
  368 #elif  ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) 
  369     pcl::ExtractIndices<sensor_msgs::PointCloud2> 
ex;
 
  370     ex.setInputCloud ( 
req.input.makeShared() );
 
  372     pcl::ExtractIndices<sensor_msgs::PointCloud2> 
ex;
 
  373     ex.setInputCloud ( boost::make_shared< sensor_msgs::PointCloud2 > (
req.input) );
 
  375     for ( 
size_t i = 0; 
i < cluster_indices.size(); 
i++ ) {
 
  376 #if  ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) 
  377       ex.setIndices ( std::make_shared< pcl::PointIndices > (cluster_indices[
i]) );
 
  379       ex.setIndices ( boost::make_shared< pcl::PointIndices > (cluster_indices[
i]) );
 
  381       ex.setNegative ( 
false );
 
  382 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 ) 
  383       pcl::PCLPointCloud2 output_cloud;
 
  384       ex.filter ( output_cloud );
 
  387       ex.filter ( 
res.output[
i] );
 
  393   void EuclideanClustering::onInit()
 
  395     DiagnosticNodelet::onInit();
 
  397     pnh_->param(
"multi", multi_, 
false);
 
  398     pnh_->param(
"approximate_sync", approximate_sync_, 
false);
 
  399     pnh_->param(
"queue_size", queue_size_, 20);
 
  404     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
  405     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  406       boost::bind (&EuclideanClustering::configCallback, 
this, 
_1, 
_2);
 
  407     srv_->setCallback (
f);
 
  412     result_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices> (*pnh_, 
"output", 1);
 
  413     cluster_num_pub_ = advertise<jsk_recognition_msgs::Int32Stamped> (*pnh_, 
"cluster_num", 1);
 
  414     service_ = pnh_->advertiseService(pnh_->resolveName(
"euclidean_clustering"),
 
  415                                       &EuclideanClustering::serviceCallback, 
this);
 
  420   EuclideanClustering::~EuclideanClustering() {
 
  432   void EuclideanClustering::subscribe()
 
  438       sub_cluster_indices_.subscribe(*pnh_, 
"input/cluster_indices", 1);
 
  439       sub_point_cloud_.subscribe(*pnh_, 
"input", 1);
 
  440       if (approximate_sync_) {
 
  441         async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
 
  442         async_->connectInput(sub_cluster_indices_, sub_point_cloud_);
 
  443         async_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, 
this, 
_1, 
_2));
 
  445         sync_  = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
 
  446         sync_->connectInput(sub_cluster_indices_, sub_point_cloud_);
 
  447         sync_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, 
this, 
_1, 
_2));
 
  450       sub_input_ = pnh_->subscribe(
"input", 1, &EuclideanClustering::extract, 
this);
 
  454   void EuclideanClustering::unsubscribe()
 
  457       sub_cluster_indices_.unsubscribe();
 
  458       sub_point_cloud_.unsubscribe();
 
  460       sub_input_.shutdown();
 
  464   void EuclideanClustering::updateDiagnostic(
 
  467     if (vital_checker_->isAlive()) {
 
  469       diagnostic_msgs::DiagnosticStatus::OK,
 
  470       "EuclideanSegmentation running");
 
  472       jsk_topic_tools::addDiagnosticInformation(
 
  473         "Kdtree Construction", kdtree_acc_, stat);
 
  474       jsk_topic_tools::addDiagnosticInformation(
 
  475         "Euclidean Segmentation", segmentation_acc_, stat);
 
  476       stat.
add(
"Cluster Num (Avg.)", cluster_counter_.mean());
 
  477       stat.
add(
"Max Size of the cluster", maxsize_);
 
  478       stat.
add(
"Min Size of the cluster", minsize_);
 
  480       stat.
add(
"Tracking tolerance", label_tracking_tolerance);
 
  481       stat.
add(
"MultiEuclideanClustering", multi_);
 
  482       stat.
add(
"Downsample enable", downsample_);
 
  484         stat.
add(
"Leaf size", leaf_size_);
 
  487     DiagnosticNodelet::updateDiagnostic(stat);
 
  490   void EuclideanClustering::configCallback (
Config &config, uint32_t level)
 
  494     label_tracking_tolerance = 
config.label_tracking_tolerance;
 
  495     maxsize_ = 
config.max_size;
 
  496     minsize_ = 
config.min_size;
 
  497     cluster_filter_type_ = 
config.cluster_filter;
 
  499     downsample_ = 
config.downsample_enable;
 
  500     leaf_size_ = 
config.leaf_size;
 
  503   std::vector<pcl::PointIndices> EuclideanClustering::pivotClusterIndices(
 
  504     std::vector<int>& pivot_table,
 
  505     std::vector<pcl::PointIndices>& cluster_indices)
 
  507     std::vector<pcl::PointIndices> new_cluster_indices;
 
  508     new_cluster_indices.resize(pivot_table.size());
 
  509     for (
size_t i = 0; 
i < pivot_table.size(); 
i++) {
 
  510       new_cluster_indices[
i] = cluster_indices[pivot_table[
i]];
 
  512     return new_cluster_indices;
 
  514   std::vector<int> EuclideanClustering::buildLabelTrackingPivotTable(
 
  516     double label_tracking_tolerance)
 
  518     std::vector<int> pivot_table;
 
  520     pivot_table.resize(cogs.size());
 
  521     for (
size_t i = 0; 
i < pivot_table.size(); 
i++)
 
  523     for (
size_t pivot_counter = 0; pivot_counter < pivot_table.size();
 
  526       double minimum_distance = DBL_MAX;
 
  527       size_t minimum_previous_index = 0;
 
  528       size_t minimum_next_index = 0;
 
  529       for (
size_t i = 0; 
i < cogs.size(); 
i++)
 
  531         for (
size_t j = 0; j < new_cogs.size(); j++)
 
  538             minimum_previous_index = 
i;
 
  539             minimum_next_index = j;
 
  543       if (minimum_distance > label_tracking_tolerance)
 
  547         std::vector<int> dummy;
 
  550       pivot_table[minimum_previous_index] = minimum_next_index;
 
  552       for (
size_t j = 0; j < new_cogs.size(); j++)
 
  554         D[minimum_previous_index * cogs.size() + j] = DBL_MAX;
 
  560   void EuclideanClustering::computeDistanceMatrix(
 
  565     for (
size_t i = 0; 
i < old_cogs.size(); 
i++) {
 
  566       Eigen::Vector4f previous_cog = old_cogs[
i];
 
  567       for (
size_t j = 0; j < new_cogs.size(); j++) {
 
  568         Eigen::Vector4f next_cog = new_cogs[j];
 
  569         double distance = (next_cog - previous_cog).norm();
 
  575   void EuclideanClustering::removeDuplicatedIndices(
 
  576     pcl::PointIndices::Ptr indices)
 
  578     std::sort(indices->indices.begin(), indices->indices.end());
 
  579     indices->indices.erase(
 
  580       std::unique(indices->indices.begin(), indices->indices.end()),
 
  581       indices->indices.end());
 
  584   void EuclideanClustering::computeCentroidsOfClusters(
 
  586     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
 
  587     std::vector<pcl::PointIndices> cluster_indices)
 
  589     pcl::ExtractIndices<pcl::PointXYZ> extract;
 
  590     extract.setInputCloud(
cloud);
 
  591     ret.resize(cluster_indices.size());
 
  592     for (
size_t i = 0; 
i < cluster_indices.size(); 
i++)
 
  595       pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud (
new pcl::PointCloud<pcl::PointXYZ>);
 
  596       pcl::PointIndices::Ptr segmented_indices (
new pcl::PointIndices);
 
  597       for (
size_t j = 0; j < cluster_indices[
i].indices.size(); j++)
 
  599         segmented_indices->indices.push_back(cluster_indices[
i].indices[j]);
 
  601       extract.setIndices(segmented_indices);
 
  602       extract.filter(*segmented_cloud);
 
  603       Eigen::Vector4f center;
 
  604       pcl::compute3DCentroid(*segmented_cloud, center);