multi_plane_extraction_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Ryohei Ueda and 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/multi_plane_extraction.h"
00037 #include <pluginlib/class_list_macros.h>
00038 #include <pcl/filters/extract_indices.h>
00039 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00040 
00041 #include <pcl/filters/project_inliers.h>
00042 #include <set>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046 
00047   void MultiPlaneExtraction::onInit()
00048   {
00049     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00050     DiagnosticNodelet::onInit();
00051     pnh_->param("use_indices", use_indices_, true);
00052     pnh_->param("use_async", use_async_, false);
00054     // Publishers
00056     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00057     nonplane_pub_ = advertise<pcl::PointCloud<pcl::PointXYZRGB> >(*pnh_, "output_nonplane_cloud", 1);
00058     pub_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/indices", 1);
00059     if (!pnh_->getParam("max_queue_size", maximum_queue_size_)) {
00060       maximum_queue_size_ = 100;
00061     }
00062     pnh_->param("use_sensor_frame", use_sensor_frame_, false);
00063     if (use_sensor_frame_) {
00064       pnh_->param("sensor_frame", sensor_frame_, std::string("head_root"));
00065       tf_listener_ = TfListenerSingleton::getInstance();
00066     }
00068     // Dynamic Reconfigure
00070     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00071     dynamic_reconfigure::Server<Config>::CallbackType f =
00072       boost::bind (&MultiPlaneExtraction::configCallback, this, _1, _2);
00073     srv_->setCallback (f);
00074   }
00075 
00076   void MultiPlaneExtraction::subscribe()
00077   {
00079     // Subscribe
00081 
00082     
00083     sub_input_.subscribe(*pnh_, "input", 1);
00084     
00085     sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
00086     sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00087     if (use_async_) {
00088       if (use_indices_) {
00089         sub_indices_.subscribe(*pnh_, "indices", 1);
00090         async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(maximum_queue_size_);
00091         async_->connectInput(sub_input_, sub_indices_, sub_coefficients_, sub_polygons_);
00092         async_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4));
00093       }
00094       else {
00095         async_wo_indices_ = boost::make_shared<message_filters::Synchronizer<ASyncWithoutIndicesPolicy> >(maximum_queue_size_);
00096         async_wo_indices_->connectInput(sub_input_, sub_coefficients_, sub_polygons_);
00097         async_wo_indices_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3));
00098       }    }
00099     else {
00100       if (use_indices_) {
00101         sub_indices_.subscribe(*pnh_, "indices", 1);
00102         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(maximum_queue_size_);
00103         sync_->connectInput(sub_input_, sub_indices_, sub_coefficients_, sub_polygons_);
00104         sync_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4));
00105       }
00106       else {
00107         sync_wo_indices_ = boost::make_shared<message_filters::Synchronizer<SyncWithoutIndicesPolicy> >(maximum_queue_size_);
00108         sync_wo_indices_->connectInput(sub_input_, sub_coefficients_, sub_polygons_);
00109         sync_wo_indices_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3));
00110       }
00111     }
00112   }
00113 
00114   void MultiPlaneExtraction::unsubscribe()
00115   {
00116     sub_input_.unsubscribe();
00117     if (use_indices_) {
00118       sub_indices_.unsubscribe();
00119     }
00120     sub_polygons_.unsubscribe();
00121     sub_coefficients_.unsubscribe();
00122   }
00123 
00124   void MultiPlaneExtraction::configCallback(Config& config, uint32_t level)
00125   {
00126     boost::mutex::scoped_lock lock(mutex_);
00127     min_height_ = config.min_height;
00128     max_height_ = config.max_height;
00129     maginify_ = config.maginify;
00130   }
00131 
00132   void MultiPlaneExtraction::updateDiagnostic(
00133     diagnostic_updater::DiagnosticStatusWrapper &stat)
00134   {
00135     if (vital_checker_->isAlive()) {
00136       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00137                    "MultiPlaneExtraction running");
00138       stat.add("Minimum Height", min_height_);
00139       stat.add("Maximum Height", max_height_);
00140       stat.add("Number of Planes", plane_counter_.mean());
00141     }
00142     else {
00143       jsk_topic_tools::addDiagnosticErrorSummary(
00144         "MultiPlaneExtraction", vital_checker_, stat);
00145     }
00146   }
00147 
00148   void MultiPlaneExtraction::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00149                                      const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00150                                      const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
00151   {
00152     extract(input, jsk_recognition_msgs::ClusterPointIndices::ConstPtr(),
00153             coefficients, polygons);
00154   }
00155   
00156   void MultiPlaneExtraction::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
00157                                      const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
00158                                      const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
00159                                      const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
00160   {
00161     boost::mutex::scoped_lock lock(mutex_);
00162     vital_checker_->poke();
00163     Eigen::Vector3f viewpoint;
00164     try {
00165       if (use_sensor_frame_) {
00166         tf::StampedTransform transform
00167           = lookupTransformWithDuration(tf_listener_,
00168                                         input->header.frame_id,
00169                                         sensor_frame_,
00170                                         input->header.stamp,
00171                                         ros::Duration(5.0));
00172         Eigen::Affine3f sensor_pose;
00173         tf::transformTFToEigen(transform, sensor_pose);
00174         viewpoint = Eigen::Vector3f(sensor_pose.translation());
00175       }
00176     }
00177     catch (tf2::ConnectivityException &e)
00178     {
00179       JSK_NODELET_ERROR("Transform error: %s", e.what());
00180     }
00181     catch (tf2::InvalidArgumentException &e)
00182     {
00183       JSK_NODELET_ERROR("Transform error: %s", e.what());
00184     }
00185     catch (...)
00186     {
00187       JSK_NODELET_ERROR("Unknown transform error");
00188     }
00189     // convert all to the pcl types
00190     pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00191     pcl::PointCloud<pcl::PointXYZRGB>::Ptr nonplane_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00192     pcl::fromROSMsg(*input, *input_cloud);
00193     if (indices) {
00194       // concat indices into one PointIndices
00195       pcl::PointIndices::Ptr all_indices (new pcl::PointIndices);
00196       for (size_t i = 0; i < indices->cluster_indices.size(); i++) {
00197         std::vector<int> one_indices = indices->cluster_indices[i].indices;
00198         for (size_t j = 0; j < one_indices.size(); j++) {
00199           all_indices->indices.push_back(one_indices[j]);
00200         }
00201       }
00202 
00203     
00204       pcl::ExtractIndices<pcl::PointXYZRGB> extract_nonplane;
00205       extract_nonplane.setNegative(true);
00206       extract_nonplane.setInputCloud(input_cloud);
00207       extract_nonplane.setIndices(all_indices);
00208       extract_nonplane.filter(*nonplane_cloud);
00209       nonplane_pub_.publish(nonplane_cloud);
00210     }
00211     else {
00212       nonplane_cloud = input_cloud;
00213     }
00214     // for each plane, project nonplane_cloud to the plane and find the points
00215     // inside of the polygon
00216     
00217     std::set<int> result_set;
00218     plane_counter_.add(coefficients->coefficients.size());
00219     for (size_t plane_i = 0; plane_i < coefficients->coefficients.size(); plane_i++) {
00220 
00221       pcl::ExtractPolygonalPrismData<pcl::PointXYZRGB> prism_extract;
00222       prism_extract.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
00223       pcl::PointCloud<pcl::PointXYZRGB>::Ptr hull_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
00224       geometry_msgs::Polygon the_polygon = polygons->polygons[plane_i].polygon;
00225       if (the_polygon.points.size() <= 2) {
00226         JSK_NODELET_WARN("too small polygon");
00227         continue;
00228       }
00229       // compute centroid first
00230       Eigen::Vector3f centroid(0, 0, 0);
00231       for (size_t i = 0; i < the_polygon.points.size(); i++) {
00232         pcl::PointXYZRGB p;
00233         pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00234           the_polygon.points[i], p);
00235         centroid = centroid + p.getVector3fMap();
00236       }
00237       centroid = centroid / the_polygon.points.size();
00238       
00239       for (size_t i = 0; i < the_polygon.points.size(); i++) {
00240         pcl::PointXYZRGB p;
00241         pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00242           the_polygon.points[i], p);
00243         Eigen::Vector3f dir = (p.getVector3fMap() - centroid).normalized();
00244         p.getVector3fMap() = dir * maginify_ + p.getVector3fMap();
00245         hull_cloud->points.push_back(p);
00246       }
00247       
00248       pcl::PointXYZRGB p_last;
00249         pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
00250           the_polygon.points[0], p_last);
00251       hull_cloud->points.push_back(p_last);
00252       
00253       prism_extract.setInputCloud(nonplane_cloud);
00254       prism_extract.setHeightLimits(min_height_, max_height_);
00255       prism_extract.setInputPlanarHull(hull_cloud);
00256       pcl::PointIndices output_indices;
00257       prism_extract.segment(output_indices);
00258       // append output to result_cloud
00259       for (size_t i = 0; i < output_indices.indices.size(); i++) {
00260         result_set.insert(output_indices.indices[i]);
00261       }
00262     }
00263 
00264     // convert std::set to PCLIndicesMsg
00265     //PCLIndicesMsg output_indices;
00266     pcl::PointCloud<pcl::PointXYZRGB> result_cloud;
00267     pcl::PointIndices::Ptr all_result_indices (new pcl::PointIndices());
00268     for (std::set<int>::iterator it = result_set.begin();
00269          it != result_set.end();
00270          it++) {
00271       all_result_indices->indices.push_back(*it);
00272     }
00273 
00274     pcl::ExtractIndices<pcl::PointXYZRGB> extract_all_indices;
00275     extract_all_indices.setInputCloud(nonplane_cloud);
00276     extract_all_indices.setIndices(all_result_indices);
00277     extract_all_indices.filter(result_cloud);
00278     
00279     sensor_msgs::PointCloud2 ros_result;
00280     pcl::toROSMsg(result_cloud, ros_result);
00281     ros_result.header = input->header;
00282     pub_.publish(ros_result);
00283     PCLIndicesMsg ros_indices;
00284     pcl_conversions::fromPCL(*all_result_indices, ros_indices);
00285     ros_indices.header = input->header;
00286     pub_indices_.publish(ros_indices);
00287     diagnostic_updater_->update();
00288   }
00289 }
00290 
00291 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::MultiPlaneExtraction, nodelet::Nodelet);


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