plane_concatenator_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 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros_utils/plane_concatenator.h"
00037 #include <pcl/kdtree/kdtree_flann.h>
00038 #include <pcl/sample_consensus/method_types.h>
00039 #include <pcl/sample_consensus/model_types.h>
00040 #include <pcl/segmentation/sac_segmentation.h>
00041 #include "jsk_recognition_utils/pcl_conversion_util.h"
00042 #include "jsk_recognition_utils/pcl_util.h"
00043 
00044 namespace jsk_pcl_ros_utils
00045 {
00046   void PlaneConcatenator::onInit()
00047   {
00048     DiagnosticNodelet::onInit();
00049     pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
00050     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00051     dynamic_reconfigure::Server<Config>::CallbackType f =
00052       boost::bind (
00053         &PlaneConcatenator::configCallback, this, _1, _2);
00054     srv_->setCallback (f);
00055     
00056     pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00057       *pnh_, "output/indices", 1);
00058     pub_polygon_ = advertise<jsk_recognition_msgs::PolygonArray>(
00059       *pnh_, "output/polygons", 1);
00060     pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00061       *pnh_, "output/coefficients", 1);
00062 
00063     onInitPostProcess();
00064   }
00065 
00066   void PlaneConcatenator::subscribe()
00067   {
00068     sub_cloud_.subscribe(*pnh_, "input", 1);
00069     sub_indices_.subscribe(*pnh_, "input/indices", 1);
00070     sub_polygon_.subscribe(*pnh_, "input/polygons", 1);
00071     sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
00072     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
00073     sync_->connectInput(sub_cloud_, sub_indices_,
00074                         sub_polygon_, sub_coefficients_);
00075     sync_->registerCallback(boost::bind(&PlaneConcatenator::concatenate, this,
00076                                         _1, _2, _3, _4));
00077   }
00078 
00079   void PlaneConcatenator::unsubscribe()
00080   {
00081     sub_cloud_.unsubscribe();
00082     sub_indices_.unsubscribe();
00083     sub_polygon_.unsubscribe();
00084     sub_coefficients_.unsubscribe();
00085   }
00086 
00087   void PlaneConcatenator::concatenate(
00088     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00089     const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00090     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_array_msg,
00091     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_array_msg)
00092   {
00093     boost::mutex::scoped_lock lock(mutex_);
00094     vital_checker_->poke();
00095     
00096     size_t nr_cluster = polygon_array_msg->polygons.size();
00097     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00098     pcl::fromROSMsg(*cloud_msg, *cloud);
00099     // first convert to polygon instance
00100     std::vector<pcl::ModelCoefficients::Ptr> all_coefficients
00101       = pcl_conversions::convertToPCLModelCoefficients(
00102         coefficients_array_msg->coefficients);
00103     std::vector<pcl::PointIndices::Ptr> all_indices
00104       = pcl_conversions::convertToPCLPointIndices(indices_msg->cluster_indices);
00105     std::vector<pcl::PointCloud<PointT>::Ptr> all_clouds
00106       = jsk_recognition_utils::convertToPointCloudArray<PointT>(cloud, all_indices);
00107     std::vector<jsk_recognition_utils::Plane::Ptr> planes
00108       = jsk_recognition_utils::convertToPlanes(all_coefficients);
00109     // build connection map
00110     jsk_recognition_utils::IntegerGraphMap connection_map;
00111     for (size_t i = 0; i < nr_cluster; i++) {
00112       connection_map[i] = std::vector<int>();
00113       connection_map[i].push_back(i);
00114       // build kdtree
00115       pcl::KdTreeFLANN<PointT> kdtree;
00116       pcl::PointCloud<PointT>::Ptr focused_cloud = all_clouds[i];
00117       kdtree.setInputCloud(focused_cloud);
00118       // look up near polygon
00119       jsk_recognition_utils::Plane::Ptr focused_plane = planes[i];
00120       for (size_t j = i + 1; j < nr_cluster; j++) {
00121         jsk_recognition_utils::Plane::Ptr target_plane = planes[j];
00122         if (focused_plane->angle(*target_plane) < connect_angular_threshold_) {
00123           // second, check distance
00124           bool is_near_enough = isNearPointCloud(kdtree, all_clouds[j], target_plane);
00125           if (is_near_enough) {
00126             connection_map[i].push_back(j);
00127           }
00128         }
00129       }
00130     }
00131     std::vector<std::set<int> > cloud_sets;
00132     jsk_recognition_utils::buildAllGroupsSetFromGraphMap(connection_map, cloud_sets);
00133     // build new indices
00134     std::vector<pcl::PointIndices::Ptr> new_indices;
00135     std::vector<pcl::ModelCoefficients::Ptr> new_coefficients;
00136     for (size_t i = 0; i < cloud_sets.size(); i++) {
00137       pcl::PointIndices::Ptr new_one_indices (new pcl::PointIndices);
00138       new_coefficients.push_back(all_coefficients[*cloud_sets[i].begin()]);
00139       for (std::set<int>::iterator it = cloud_sets[i].begin();
00140            it != cloud_sets[i].end();
00141            ++it) {
00142         new_one_indices = jsk_recognition_utils::addIndices(*new_one_indices, *all_indices[*it]);
00143       }
00144       if (new_one_indices->indices.size() > min_size_) {
00145         new_indices.push_back(new_one_indices);
00146       }
00147     }
00148     
00149     // refinement
00150     std::vector<pcl::ModelCoefficients::Ptr> new_refined_coefficients;
00151     for (size_t i = 0; i < new_indices.size(); i++) {
00152       pcl::ModelCoefficients::Ptr refined_coefficients
00153         = refinement(cloud, new_indices[i], new_coefficients[i]);
00154       new_refined_coefficients.push_back(refined_coefficients);
00155     }
00156 
00157     // publish
00158     jsk_recognition_msgs::ClusterPointIndices new_ros_indices;
00159     jsk_recognition_msgs::ModelCoefficientsArray new_ros_coefficients;
00160     jsk_recognition_msgs::PolygonArray new_ros_polygons;
00161     new_ros_indices.header = cloud_msg->header;
00162     new_ros_coefficients.header = cloud_msg->header;
00163     new_ros_polygons.header = cloud_msg->header;
00164     for (size_t i = 0; i < new_indices.size(); i++) {
00165       jsk_recognition_utils::ConvexPolygon::Ptr convex
00166         = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
00167           cloud, new_indices[i], new_refined_coefficients[i]);
00168       if (convex->area() > min_area_ && convex->area() < max_area_) {
00169         geometry_msgs::PolygonStamped polygon;
00170         polygon.polygon = convex->toROSMsg();
00171         polygon.header = cloud_msg->header;
00172         new_ros_polygons.polygons.push_back(polygon);
00173         pcl_msgs::PointIndices ros_indices;
00174         ros_indices.header = cloud_msg->header;
00175         ros_indices.indices = new_indices[i]->indices;
00176         new_ros_indices.cluster_indices.push_back(ros_indices);
00177         pcl_msgs::ModelCoefficients ros_coefficients;
00178         ros_coefficients.header = cloud_msg->header;
00179         ros_coefficients.values = new_refined_coefficients[i]->values;
00180         new_ros_coefficients.coefficients.push_back(ros_coefficients);
00181       }
00182     }
00183     
00184     // new_ros_indices.cluster_indices
00185     //   = pcl_conversions::convertToROSPointIndices(new_indices, cloud_msg->header);
00186     // new_ros_coefficients.coefficients
00187     //   = pcl_conversions::convertToROSModelCoefficients(
00188     //     new_refined_coefficients, cloud_msg->header);
00189 
00190     pub_indices_.publish(new_ros_indices);
00191     pub_polygon_.publish(new_ros_polygons);
00192     pub_coefficients_.publish(new_ros_coefficients);
00193   }
00194 
00195   pcl::ModelCoefficients::Ptr PlaneConcatenator::refinement(
00196     pcl::PointCloud<PointT>::Ptr cloud,
00197     pcl::PointIndices::Ptr indices,
00198     pcl::ModelCoefficients::Ptr original_coefficients)
00199   {
00200     pcl::SACSegmentation<PointT> seg;
00201     seg.setOptimizeCoefficients (true);
00202     seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
00203     seg.setMethodType (pcl::SAC_RANSAC);
00204     seg.setDistanceThreshold (ransac_refinement_outlier_threshold_);
00205     
00206     seg.setInputCloud(cloud);
00207     
00208     seg.setIndices(indices);
00209     seg.setMaxIterations (ransac_refinement_max_iteration_);
00210     Eigen::Vector3f normal (original_coefficients->values[0],
00211                             original_coefficients->values[1],
00212                             original_coefficients->values[2]);
00213     seg.setAxis(normal);
00214     // seg.setInputNormals(cloud);
00215     // seg.setDistanceFromOrigin(original_coefficients->values[3]);
00216     // seg.setEpsDist(ransac_refinement_eps_distance_);
00217     seg.setEpsAngle(ransac_refinement_eps_angle_);
00218     pcl::PointIndices::Ptr refined_inliers (new pcl::PointIndices);
00219     pcl::ModelCoefficients::Ptr refined_coefficients(new pcl::ModelCoefficients);
00220     seg.segment(*refined_inliers, *refined_coefficients);
00221     if (refined_inliers->indices.size() > 0) {
00222       return refined_coefficients;
00223     }
00224     else {
00225       return original_coefficients;
00226     }
00227   }
00228   
00229   bool PlaneConcatenator::isNearPointCloud(
00230     pcl::KdTreeFLANN<PointT>& kdtree,
00231     pcl::PointCloud<PointT>::Ptr cloud,
00232     jsk_recognition_utils::Plane::Ptr target_plane)
00233   {
00234     pcl::PointCloud<PointT>::ConstPtr input_cloud = kdtree.getInputCloud();
00235     for (size_t i = 0; i < cloud->points.size(); i++) {
00236       PointT p = cloud->points[i];
00237       std::vector<int> k_indices;
00238       std::vector<float> k_sqr_distances;
00239       if (kdtree.radiusSearch(p, connect_distance_threshold_,
00240                               k_indices, k_sqr_distances, 1) > 0) {
00241         // Decompose distance into pependicular distance and parallel distance
00242         const PointT near_p = input_cloud->points[k_indices[0]];
00243         Eigen::Affine3f plane_coordinates = target_plane->coordinates();
00244         Eigen::Vector3f plane_local_p = plane_coordinates.inverse() * p.getVector3fMap();
00245         Eigen::Vector3f plane_local_near_p = plane_coordinates.inverse() * near_p.getVector3fMap();
00246         Eigen::Vector3f plane_local_diff = plane_local_near_p - plane_local_p;
00247         double perpendicular_distance = std::abs(plane_local_diff[2]);
00248         if (perpendicular_distance < connect_perpendicular_distance_threshold_) {
00249           return true;
00250         }
00251       }
00252     }
00253     return false;
00254   }
00255     
00256   void PlaneConcatenator::configCallback(
00257     Config &config, uint32_t level)
00258   {
00259     boost::mutex::scoped_lock lock(mutex_);
00260     connect_angular_threshold_ = config.connect_angular_threshold;
00261     connect_distance_threshold_ = config.connect_distance_threshold;
00262     connect_perpendicular_distance_threshold_ = config.connect_perpendicular_distance_threshold;
00263     ransac_refinement_max_iteration_ = config.ransac_refinement_max_iteration;
00264     ransac_refinement_outlier_threshold_
00265       = config.ransac_refinement_outlier_threshold;
00266     ransac_refinement_eps_angle_ = config.ransac_refinement_eps_angle;
00267     min_size_ = config.min_size;
00268     min_area_ = config.min_area;
00269     max_area_ = config.max_area;
00270   }
00271 
00272   void PlaneConcatenator::updateDiagnostic(
00273     diagnostic_updater::DiagnosticStatusWrapper &stat)
00274   {
00275     if (vital_checker_->isAlive()) {
00276       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00277                    "PlaneConcatenator running");
00278     }
00279     else {
00280       jsk_topic_tools::addDiagnosticErrorSummary(
00281         "PlaneConcatenator", vital_checker_, stat);
00282     }
00283   }
00284 
00285 }
00286 
00287 #include <pluginlib/class_list_macros.h>
00288 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PlaneConcatenator, nodelet::Nodelet);


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:05