euclidean_cluster_extraction_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include <pluginlib/class_list_macros.h>
00036 #include "jsk_pcl_ros/euclidean_cluster_extraction_nodelet.h" 
00037 
00038 using namespace std;
00039 using namespace pcl;
00040 
00041 namespace jsk_pcl_ros
00042 {
00043 
00044   void EuclideanClustering::extract(
00045     const sensor_msgs::PointCloud2ConstPtr &input)
00046   {
00047     boost::mutex::scoped_lock lock(mutex_);
00048     vital_checker_->poke();
00049     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
00050       (new pcl::PointCloud<pcl::PointXYZ>);
00051     pcl::fromROSMsg(*input, *cloud);
00052     
00053     std::vector<pcl::PointIndices> cluster_indices;
00054     // list up indices which are not NaN to use
00055     // organized pointcloud
00056     pcl::PointIndices::Ptr nonnan_indices (new pcl::PointIndices);
00057     for (size_t i = 0; i < cloud->points.size(); i++) {
00058       pcl::PointXYZ p = cloud->points[i];
00059       if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00060         nonnan_indices->indices.push_back(i);
00061       }
00062     }
00063     EuclideanClusterExtraction<pcl::PointXYZ> impl;
00064     {
00065       jsk_topic_tools::ScopedTimer timer = kdtree_acc_.scopedTimer();
00066 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
00067       pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00068       tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
00069 #else
00070       pcl::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ>);
00071       tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
00072 #endif
00073       tree->setInputCloud (cloud);
00074       impl.setClusterTolerance (tolerance);
00075       impl.setMinClusterSize (minsize_);
00076       impl.setMaxClusterSize (maxsize_);
00077       impl.setSearchMethod (tree);
00078       impl.setIndices(nonnan_indices);
00079       impl.setInputCloud (cloud);
00080     }
00081     
00082     {
00083       jsk_topic_tools::ScopedTimer timer = segmentation_acc_.scopedTimer();
00084       impl.extract (cluster_indices);
00085     }
00086     
00087     // Publish result indices
00088     jsk_recognition_msgs::ClusterPointIndices result;
00089     result.cluster_indices.resize(cluster_indices.size());
00090     cluster_counter_.add(cluster_indices.size());
00091     result.header = input->header;
00092     if (cogs_.size() != 0 && cogs_.size() == cluster_indices.size()) {
00093       // tracking the labels
00094       //JSK_ROS_INFO("computing distance matrix");
00095       // compute distance matrix
00096       // D[i][j] --> distance between the i-th previous cluster
00097       //             and the current j-th cluster
00098       Vector4fVector new_cogs;
00099       computeCentroidsOfClusters(new_cogs, cloud, cluster_indices);
00100       double D[cogs_.size() * new_cogs.size()];
00101       computeDistanceMatrix(D, cogs_, new_cogs);
00102       std::vector<int> pivot_table = buildLabelTrackingPivotTable(D, cogs_, new_cogs, label_tracking_tolerance);
00103       if (pivot_table.size() != 0) {
00104         cluster_indices = pivotClusterIndices(pivot_table, cluster_indices);
00105       }
00106     }
00107     Vector4fVector tmp_cogs;
00108     computeCentroidsOfClusters(tmp_cogs, cloud, cluster_indices); // NB: not efficient
00109     cogs_ = tmp_cogs;
00110       
00111     for (size_t i = 0; i < cluster_indices.size(); i++) {
00112 #if ROS_VERSION_MINIMUM(1, 10, 0)
00113       // hydro and later
00114       result.cluster_indices[i].header
00115         = pcl_conversions::fromPCL(cluster_indices[i].header);
00116 #else
00117       // groovy
00118       result.cluster_indices[i].header = cluster_indices[i].header;
00119 #endif
00120       result.cluster_indices[i].indices = cluster_indices[i].indices;
00121     }
00122 
00123     result_pub_.publish(result);
00124     
00125     jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (new jsk_recognition_msgs::Int32Stamped);
00126     cluster_num_msg->header = input->header;
00127     cluster_num_msg->data = cluster_indices.size();
00128     cluster_num_pub_.publish(cluster_num_msg);
00129 
00130     diagnostic_updater_->update();
00131   }
00132 
00133 
00134   bool EuclideanClustering::serviceCallback(
00135     jsk_pcl_ros::EuclideanSegment::Request &req,
00136     jsk_pcl_ros::EuclideanSegment::Response &res)
00137   {
00138     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00139     pcl::fromROSMsg(req.input, *cloud);
00140 
00141 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
00142     pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00143     tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
00144 #else
00145     pcl::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ>);
00146     tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
00147 #endif
00148 
00149     vector<pcl::PointIndices> cluster_indices;
00150     EuclideanClusterExtraction<pcl::PointXYZ> impl;
00151     double tor;
00152     if ( req.tolerance < 0) {
00153       tor = tolerance;
00154     } else {
00155       tor = req.tolerance;
00156     }
00157     impl.setClusterTolerance (tor);
00158     impl.setMinClusterSize (minsize_);
00159     impl.setMaxClusterSize (maxsize_);
00160     impl.setSearchMethod (tree);
00161     impl.setInputCloud (cloud);
00162     impl.extract (cluster_indices);
00163 
00164     res.output.resize( cluster_indices.size() );
00165 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
00166     pcl::PCLPointCloud2::Ptr pcl_cloud(new pcl::PCLPointCloud2);
00167     pcl_conversions::toPCL(req.input, *pcl_cloud);
00168     pcl::ExtractIndices<pcl::PCLPointCloud2> ex;
00169     ex.setInputCloud(pcl_cloud);
00170 #else
00171     pcl::ExtractIndices<sensor_msgs::PointCloud2> ex;
00172     ex.setInputCloud ( boost::make_shared< sensor_msgs::PointCloud2 > (req.input) );
00173 #endif
00174     for ( size_t i = 0; i < cluster_indices.size(); i++ ) {
00175       ex.setIndices ( boost::make_shared< pcl::PointIndices > (cluster_indices[i]) );
00176       ex.setNegative ( false );
00177 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
00178       pcl::PCLPointCloud2 output_cloud;
00179       ex.filter ( output_cloud );
00180       pcl_conversions::fromPCL(output_cloud, res.output[i]);
00181 #else
00182       ex.filter ( res.output[i] );
00183 #endif
00184     }
00185     return true;
00186   }
00187 
00188   void EuclideanClustering::onInit()
00189   {
00190     ConnectionBasedNodelet::onInit();
00191     
00193     // diagnostics
00195     diagnostic_updater_.reset(
00196       new TimeredDiagnosticUpdater(*pnh_, ros::Duration(1.0)));
00197     diagnostic_updater_->setHardwareID(getName());
00198     diagnostic_updater_->add(
00199       getName() + "::EuclideanClustering",
00200       boost::bind(
00201         &EuclideanClustering::updateDiagnostic,
00202         this,
00203         _1));
00204     double vital_rate;
00205     pnh_->param("vital_rate", vital_rate, 1.0);
00206     vital_checker_.reset(
00207       new jsk_topic_tools::VitalChecker(1 / vital_rate));
00208     diagnostic_updater_->start();
00209     
00211     // dynamic reconfigure
00213     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00214     dynamic_reconfigure::Server<Config>::CallbackType f =
00215       boost::bind (&EuclideanClustering::configCallback, this, _1, _2);
00216     srv_->setCallback (f);
00217     
00219     // Publisher
00221     result_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices> (*pnh_, "output", 1);
00222     cluster_num_pub_ = advertise<jsk_recognition_msgs::Int32Stamped> (*pnh_, "cluster_num", 1);
00223     service_ = pnh_->advertiseService(pnh_->resolveName("euclidean_clustering"),
00224                                       &EuclideanClustering::serviceCallback, this);
00225   }
00226 
00227   void EuclideanClustering::subscribe()
00228   {
00230     // Subscription
00232     sub_input_ = pnh_->subscribe("input", 1, &EuclideanClustering::extract, this);
00233   }
00234 
00235   void EuclideanClustering::unsubscribe()
00236   {
00237     sub_input_.shutdown();
00238   }
00239   
00240   void EuclideanClustering::updateDiagnostic(
00241     diagnostic_updater::DiagnosticStatusWrapper &stat)
00242   {
00243     if (vital_checker_->isAlive()) {
00244       stat.summary(
00245       diagnostic_msgs::DiagnosticStatus::OK,
00246       "EuclideanSegmentation running");
00247 
00248       addDiagnosticInformation(
00249         "Kdtree Construction", kdtree_acc_, stat);
00250       addDiagnosticInformation(
00251         "Euclidean Segmentation", segmentation_acc_, stat);
00252       stat.add("Cluster Num (Avg.)", cluster_counter_.mean());
00253       stat.add("Max Size of the cluster", maxsize_);
00254       stat.add("Min Size of the cluster", minsize_);
00255       stat.add("Cluster tolerance", tolerance);
00256       stat.add("Tracking tolerance", label_tracking_tolerance);
00257     }
00258     else {
00259       addDiagnosticErrorSummary(
00260         "EuclideanClustering", vital_checker_, stat);
00261     }
00262   }
00263   
00264   void EuclideanClustering::configCallback (Config &config, uint32_t level)
00265   {
00266     boost::mutex::scoped_lock lock(mutex_);
00267     tolerance = config.tolerance;
00268     label_tracking_tolerance = config.label_tracking_tolerance;
00269     maxsize_ = config.max_size;
00270     minsize_ = config.min_size;
00271   }
00272 
00273   std::vector<pcl::PointIndices> EuclideanClustering::pivotClusterIndices(
00274     std::vector<int>& pivot_table,
00275     std::vector<pcl::PointIndices>& cluster_indices)
00276   {
00277     std::vector<pcl::PointIndices> new_cluster_indices;
00278     new_cluster_indices.resize(pivot_table.size());
00279     for (size_t i = 0; i < pivot_table.size(); i++) {
00280       new_cluster_indices[i] = cluster_indices[pivot_table[i]];
00281     }
00282     return new_cluster_indices;
00283   }
00284   std::vector<int> EuclideanClustering::buildLabelTrackingPivotTable(
00285     double* D, Vector4fVector cogs, Vector4fVector new_cogs,
00286     double label_tracking_tolerance)
00287   {
00288     std::vector<int> pivot_table;
00289     // initialize pivot table
00290     pivot_table.resize(cogs.size());
00291     for (size_t i = 0; i < pivot_table.size(); i++)
00292       pivot_table[i] = i;
00293     for (size_t pivot_counter = 0; pivot_counter < pivot_table.size();
00294          pivot_counter++)
00295     {
00296       double minimum_distance = DBL_MAX;
00297       size_t minimum_previous_index = 0;
00298       size_t minimum_next_index = 0;
00299       for (size_t i = 0; i < cogs.size(); i++)
00300       {
00301         for (size_t j = 0; j < new_cogs.size(); j++)
00302         {
00303           double distance = D[i * cogs.size() + j];
00304           //JSK_ROS_INFO("distance %lux%lu: %f", i, j, distance);
00305           if (distance < minimum_distance)
00306           {
00307             minimum_distance = distance;
00308             minimum_previous_index = i;
00309             minimum_next_index = j;
00310           }
00311         }
00312       }
00313       if (minimum_distance > label_tracking_tolerance)
00314       {
00315         // JSK_ROS_WARN("minimum tracking distance exceeds tolerance: %f > %f",
00316         //          minimum_distance, label_tracking_tolerance);
00317         std::vector<int> dummy;
00318         return dummy;
00319       }
00320       pivot_table[minimum_previous_index] = minimum_next_index;
00321       // fill the D matrix with DBL_MAX
00322       for (size_t j = 0; j < new_cogs.size(); j++)
00323       {
00324         D[minimum_previous_index * cogs.size() + j] = DBL_MAX;
00325       }
00326     }
00327     return pivot_table;
00328   }
00329 
00330   void EuclideanClustering::computeDistanceMatrix(
00331     double* D,
00332     Vector4fVector& old_cogs,
00333     Vector4fVector& new_cogs)
00334   {
00335     for (size_t i = 0; i < old_cogs.size(); i++) {
00336       Eigen::Vector4f previous_cog = old_cogs[i];
00337       for (size_t j = 0; j < new_cogs.size(); j++) {
00338         Eigen::Vector4f next_cog = new_cogs[j];
00339         double distance = (next_cog - previous_cog).norm();
00340         D[i * old_cogs.size() + j] = distance;
00341       }
00342     }
00343   }
00344 
00345   void EuclideanClustering::computeCentroidsOfClusters(
00346     Vector4fVector& ret,
00347     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00348     std::vector<pcl::PointIndices> cluster_indices)
00349   {
00350     pcl::ExtractIndices<pcl::PointXYZ> extract;
00351     extract.setInputCloud(cloud);
00352     ret.resize(cluster_indices.size());
00353     for (size_t i = 0; i < cluster_indices.size(); i++)
00354     {
00355       // build pointcloud
00356       pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00357       pcl::PointIndices::Ptr segmented_indices (new pcl::PointIndices);
00358       for (size_t j = 0; j < cluster_indices[i].indices.size(); j++)
00359       {
00360         segmented_indices->indices.push_back(cluster_indices[i].indices[j]);
00361       }
00362       extract.setIndices(segmented_indices);
00363       extract.filter(*segmented_cloud);
00364       Eigen::Vector4f center;
00365       pcl::compute3DCentroid(*segmented_cloud, center);
00366       ret[i] = center;
00367     }
00368   }
00369   
00370 }
00371 
00372 #include <pluginlib/class_list_macros.h>
00373 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::EuclideanClustering, nodelet::Nodelet);
00374 


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47