edge_depth_refinement_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_pcl_ros/edge_depth_refinement.h"
00037 
00038 #include <pcl/segmentation/sac_segmentation.h>
00039 #include <pcl/filters/extract_indices.h>
00040 #include <pcl/io/io.h>
00041 #include "jsk_pcl_ros/pcl_util.h"
00042 #include <sstream>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046   void EdgeDepthRefinement::onInit()
00047   {
00048     ConnectionBasedNodelet::onInit();
00049 
00051     // publishers
00053     pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00054       *pnh_, "output", 1);
00055     pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00056       *pnh_, "output_coefficients", 1);
00057     pub_outlier_removed_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00058       *pnh_, "output_outlier_removed", 1);
00059     pub_outlier_removed_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00060       *pnh_, "output_outlier_removed_coefficients", 1);
00062     // dynamic reconfigure
00064     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00065     dynamic_reconfigure::Server<Config>::CallbackType f =
00066       boost::bind (&EdgeDepthRefinement::configCallback, this, _1, _2);
00067     srv_->setCallback (f);
00068   }
00069 
00070   void EdgeDepthRefinement::subscribe()
00071   {
00073     // subscribesrs
00075     sub_input_.subscribe(*pnh_, "input", 1);
00076     sub_indices_.subscribe(*pnh_, "input_indices", 1);
00077     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00078     sync_->connectInput(sub_input_, sub_indices_);
00079     sync_->registerCallback(boost::bind(&EdgeDepthRefinement::refine,
00080                                         this, _1, _2));
00081   }
00082 
00083   void EdgeDepthRefinement::unsubscribe()
00084   {
00085     sub_input_.unsubscribe();
00086     sub_indices_.unsubscribe();
00087   }
00088   
00090   // line coefficients are:
00091   // 0: point.x
00092   // 1: point.y
00093   // 2. point.z
00094   // 3. direction.x
00095   // 4: direction.y
00096   // 5. direction.z
00098   Line::Ptr EdgeDepthRefinement::lineFromCoefficients(
00099     const pcl::ModelCoefficients::Ptr coefficients)
00100   {
00101     Eigen::Vector3f p(coefficients->values[0],
00102                       coefficients->values[1],
00103                       coefficients->values[2]);
00104     Eigen::Vector3f d(coefficients->values[3],
00105                       coefficients->values[4],
00106                       coefficients->values[5]);
00107     Line::Ptr ret (new Line(d, p));
00108     return ret;
00109   }
00110 
00111   boost::tuple<int, int> EdgeDepthRefinement::findMinMaxIndex(
00112     const int width, const int height,
00113     const std::vector<int>& indices)
00114   {
00115     
00116     int min_y_index, max_y_index, min_x_index, max_x_index;
00117     int min_y = INT_MAX;
00118     int min_x = INT_MAX;
00119     int max_y = INT_MIN;
00120     int max_x = INT_MIN;
00121     for (size_t i = 0; i < indices.size(); i++) {
00122       int index = indices[i];
00123       int x = index % width;
00124       int y = index / width;
00125 
00126       if (x > max_x) {
00127         max_x = x;
00128         max_x_index = index;
00129       }
00130       if (x < min_x) {
00131         min_x = x;
00132         min_x_index = index;
00133       }
00134       if (y > max_y) {
00135         max_y = max_y;
00136         max_y_index = index;
00137       }
00138       if (y < min_y) {
00139         min_y = y;
00140         min_y_index = index;
00141       }
00142     }
00143 
00144     if (max_x_index != max_x_index) {
00145       return boost::make_tuple(
00146         max_x_index, min_x_index);
00147     }
00148     else {
00149       return boost::make_tuple(
00150         max_y_index, min_y_index);
00151     }
00152   }
00153 
00154   
00155   Segment::Ptr EdgeDepthRefinement::segmentFromIndices(
00156     const pcl::PointCloud<PointT>::Ptr& cloud,
00157     const std::vector<int>& indices,
00158     const Line::Ptr& line)
00159   {
00160     boost::tuple<int, int> min_max
00161       = findMinMaxIndex(cloud->width, cloud->height, indices);
00162     PointT min_point = cloud->points[min_max.get<0>()];
00163     PointT max_point = cloud->points[min_max.get<1>()];
00164     Eigen::Vector3f min_point_f = min_point.getVector3fMap();
00165     Eigen::Vector3f max_point_f = max_point.getVector3fMap();
00166     Eigen::Vector3f min_foot, max_foot;
00167     line->foot(min_point_f, min_foot);
00168     line->foot(max_point_f, max_foot);
00169     Segment::Ptr segment (new Segment(min_foot, max_foot));
00170     return segment;
00171   }
00172 
00173   void EdgeDepthRefinement::integrateDuplicatedIndices(
00174     const pcl::PointCloud<PointT>::Ptr& cloud,
00175     const std::set<int>& duplicated_set,
00176     const std::vector<pcl::PointIndices::Ptr> all_inliers,
00177     pcl::PointIndices::Ptr& output_indices)
00178   {
00179     std::vector<int> integrated_indices;
00180     for (std::set<int>::iterator it = duplicated_set.begin();
00181          it != duplicated_set.end();
00182          ++it) {
00183       integrated_indices = addIndices(all_inliers[*it]->indices,
00184                                       integrated_indices);
00185     }
00186     output_indices->indices = integrated_indices;
00187   }
00188   
00189   void EdgeDepthRefinement::removeDuplicatedEdges(
00190     const pcl::PointCloud<PointT>::Ptr& cloud,
00191     const std::vector<pcl::PointIndices::Ptr> all_inliers,
00192     const std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
00193     std::vector<pcl::PointIndices::Ptr>& output_inliers,
00194     std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients)
00195   {
00196     if (all_inliers.size() == 0) {
00197       JSK_NODELET_ERROR("no edges are specified");
00198       return;
00199     }
00200     std::vector<pcl::PointIndices::Ptr> nonduplicated_inliers;
00201     std::vector<pcl::ModelCoefficients::Ptr> cnonduplicated_oefficients;
00202 
00203     // buildup Lines and Segments
00204     std::vector<Line::Ptr> lines;
00205     std::vector<Segment::Ptr> segments;
00206     
00207     for (size_t i = 0; i < all_inliers.size(); i++) {
00208       pcl::PointIndices::Ptr the_inliers = all_inliers[i];
00209       pcl::ModelCoefficients::Ptr the_coefficients = all_coefficients[i];
00210       Line::Ptr the_line = lineFromCoefficients(the_coefficients);
00211       Segment::Ptr the_segment
00212         = segmentFromIndices(cloud, the_inliers->indices, the_line);
00213       lines.push_back(the_line);
00214       segments.push_back(the_segment);
00215     }
00216 
00218     // build duplication map
00219     // duplication map is a hash map from int to a list of int
00221     std::map<int, std::vector<int> > duplication_map;
00222     for (size_t i = 0; i < all_inliers.size() - 1; i++) {
00223       duplication_map[i] = std::vector<int>(); // add empty map
00224       Line::Ptr the_line = lines[i];
00225       Segment::Ptr the_segment = segments[i];
00226       for (size_t j = i + 1; j < all_inliers.size(); j++) {
00227         Line::Ptr candidate_line = lines[j];
00228         Segment::Ptr candidate_segment = segments[j];
00229         
00230         double angle_diff = the_line->angle(*candidate_line);
00231         if (duplication_angle_threshold_ > angle_diff) {
00232           double distance_diff = the_line->distance(*candidate_line);
00233           if (duplication_distance_threshold_ > distance_diff) {
00234             duplication_map[i].push_back(j);
00235           }
00236         }
00237       }
00238     }
00239 
00241     // convert duplication map into set
00243     std::vector<std::set<int> > duplication_set_list;
00244     std::set<int> duplicated_indices;
00245     for (size_t i = 0; i < all_inliers.size() - 1; i++) {
00246       std::vector<int> duplication_list = duplication_map[i];
00247       if (duplicated_indices.find(i) == duplicated_indices.end()) {
00248         if (duplication_list.size() == 0) {
00249           // nothing to do...
00250         }
00251         else {
00252           std::set<int> new_duplication_set;
00253           buildGroupFromGraphMap(duplication_map,
00254                                  i,
00255                                  duplication_list,
00256                                  new_duplication_set);
00257           duplication_set_list.push_back(new_duplication_set);
00258           // add new_duplication_set to duplicated_indices
00259           addSet<int>(duplicated_indices, new_duplication_set);
00260         }
00261       }
00262     }
00263 
00264 
00265     for (size_t i = 0; i < duplication_set_list.size(); i++) {
00266       pcl::PointIndices::Ptr integrated_indices (new pcl::PointIndices);
00267       integrateDuplicatedIndices(cloud, duplication_set_list[i],
00268                                  all_inliers,
00269                                  integrated_indices);
00270       output_inliers.push_back(integrated_indices);
00271       
00272       // use the first one,,, ok?
00273       pcl::ModelCoefficients::Ptr integrated_coefficients 
00274         = all_coefficients[(*duplication_set_list[i].begin())];
00275       output_coefficients.push_back(integrated_coefficients);
00276     }
00277 
00278     // print result for debug
00279     // JSK_NODELET_INFO("%lu duplication set", duplication_set_list.size());
00280     // for (size_t i = 0; i < duplication_set_list.size(); i++) {
00281     //   std::stringstream ss;
00282     //   ss << "[";
00283     //   for (std::set<int>::iterator it = duplication_set_list[i].begin();
00284     //        it != duplication_set_list[i].end();
00285     //        ++it)
00286     //   {
00287     //     ss << *it << ", ";
00288     //   }
00289     //   JSK_NODELET_INFO("%s", ss.str().c_str());
00290     // }
00291     
00292     // for (size_t i = 0; i < all_inliers.size() - 1; i++) {
00293     //   std::stringstream ss;
00294     //   std::vector<int> similar_indices = duplication_map[i];
00295     //   ss << i << " -> ";
00296     //   for (size_t j = 0; j < similar_indices.size(); j++) {
00297     //     ss << similar_indices[j] << ", ";
00298     //   }
00299     //   JSK_NODELET_INFO("%s", ss.str().c_str());
00300     // }
00301   }
00302   
00303   void EdgeDepthRefinement::removeOutliers(
00304     const pcl::PointCloud<PointT>::Ptr& cloud,
00305     const std::vector<PCLIndicesMsg>& indices,
00306     std::vector<pcl::PointIndices::Ptr>& output_inliers,
00307     std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients)
00308   {
00309     // output_inliers.resize(indices.size());
00310     // output_coefficients.resize(indices.size());
00311     for (size_t i = 0; i < indices.size(); i++) {
00312       std::vector<int> cluster_indices = indices[i].indices;
00313       pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00314       pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00315       removeOutliersByLine(cloud, cluster_indices, *inliers, *coefficients);
00316       if (inliers->indices.size() > min_inliers_) {
00317         output_inliers.push_back(inliers);
00318         output_coefficients.push_back(coefficients);
00319       }
00320     }
00321   }
00322   
00323   void EdgeDepthRefinement::removeOutliersByLine(
00324     const pcl::PointCloud<PointT>::Ptr& cloud,
00325     const std::vector<int>& indices,
00326     pcl::PointIndices& inliers,
00327     pcl::ModelCoefficients& coefficients)
00328   {
00329     // one line shoud have ONE line at most...?
00330     // in that case, we can estimate the true line by RANSAC
00331     pcl::SACSegmentation<PointT> seg;
00332     seg.setOptimizeCoefficients (true);
00333     seg.setModelType (pcl::SACMODEL_LINE);
00334     seg.setMethodType (pcl::SAC_RANSAC);
00335     seg.setDistanceThreshold (outlier_distance_threshold_);
00336     seg.setInputCloud(cloud);
00337     pcl::PointIndices::Ptr indices_ptr (new pcl::PointIndices);
00338     indices_ptr->indices = indices;
00339     seg.setIndices(indices_ptr);
00340     seg.segment (inliers, coefficients);
00341   }
00342 
00343   void EdgeDepthRefinement::publishIndices(
00344     ros::Publisher& pub,
00345     ros::Publisher& pub_coefficients,
00346     const std::vector<pcl::PointIndices::Ptr> inliers,
00347     const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
00348     const std_msgs::Header& header)
00349   {
00350     jsk_recognition_msgs::ClusterPointIndices output_ros_msg;
00351     jsk_recognition_msgs::ModelCoefficientsArray output_ros_coefficients_msg;
00352     output_ros_msg.header = header;
00353     output_ros_coefficients_msg.header = header;
00354     for (size_t i = 0; i < inliers.size(); i++) {
00355       PCLIndicesMsg output_indices_msg;
00356       PCLModelCoefficientMsg output_coefficients_msg;
00357       output_indices_msg.header = header;
00358       output_indices_msg.indices = inliers[i]->indices;
00359       output_ros_msg.cluster_indices.push_back(output_indices_msg);
00360 
00361       output_coefficients_msg.header = header;
00362       output_coefficients_msg.values = coefficients[i]->values;
00363       output_ros_coefficients_msg.coefficients.push_back(output_coefficients_msg);
00364     }
00365     pub.publish(output_ros_msg);
00366     pub_coefficients.publish(output_ros_coefficients_msg);
00367   }
00368 
00369   void EdgeDepthRefinement::configCallback (Config &config, uint32_t level)
00370   {
00371     boost::mutex::scoped_lock lock(mutex_);
00372     outlier_distance_threshold_ = config.outlier_distance_threshold;
00373     min_inliers_ = config.min_inliers;
00374     duplication_angle_threshold_ = config.duplication_angle_threshold;
00375     duplication_distance_threshold_ = config.duplication_distance_threshold;
00376   }
00377   
00378   void EdgeDepthRefinement::refine(
00379     const sensor_msgs::PointCloud2ConstPtr &input,
00380     const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
00381   {
00382     boost::mutex::scoped_lock lock(mutex_);
00383     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00384     pcl::fromROSMsg(*input, *cloud);
00385     
00386     std::vector<pcl::PointIndices::Ptr> inliers;
00387     std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00388 
00389     removeOutliers(cloud, indices->cluster_indices, inliers, coefficients);
00390     std::vector<pcl::PointIndices::Ptr> non_duplicated_inliers;
00391     std::vector<pcl::ModelCoefficients::Ptr> non_duplicated_coefficients;
00392     removeDuplicatedEdges(cloud, inliers, coefficients,
00393                           non_duplicated_inliers,
00394                           non_duplicated_coefficients);
00395     publishIndices(pub_outlier_removed_indices_,
00396                    pub_outlier_removed_coefficients_,
00397                    inliers, coefficients,
00398                    input->header);
00399     publishIndices(pub_indices_,
00400                    pub_coefficients_,
00401                    non_duplicated_inliers,
00402                    non_duplicated_coefficients,
00403                    input->header);
00404   }
00405   
00406 }
00407 
00408 #include <pluginlib/class_list_macros.h>
00409 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::EdgeDepthRefinement, nodelet::Nodelet);


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