organized_multi_plane_segmentation_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/organized_multi_plane_segmentation.h"
00037 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00038 #include <pcl/segmentation/impl/organized_multi_plane_segmentation.hpp>
00039 #include <pcl/filters/extract_indices.h>
00040 #include <pcl/kdtree/kdtree_flann.h>
00041 #include <set>
00042 #include <Eigen/StdVector>
00043 #include <pcl/surface/convex_hull.h>
00044 #include <pcl/filters/project_inliers.h>
00045 #include <pcl/features/integral_image_normal.h>
00046 
00047 #include "jsk_recognition_utils/pcl_conversion_util.h"
00048 #include <pluginlib/class_list_macros.h>
00049 
00050 #include <boost/format.hpp>
00051 #include <pcl/common/centroid.h>
00052 #include <visualization_msgs/Marker.h>
00053 #include "jsk_recognition_utils/geo_util.h"
00054 
00055 #include <pcl/sample_consensus/method_types.h>
00056 #include <pcl/sample_consensus/model_types.h>
00057 #include <pcl/segmentation/sac_segmentation.h>
00058 #include <pcl/surface/convex_hull.h>
00059 
00060 #include <jsk_topic_tools/color_utils.h>
00061 
00062 namespace jsk_pcl_ros
00063 {
00064 
00065   void OrganizedMultiPlaneSegmentation::onInit()
00066   {
00067     ConnectionBasedNodelet::onInit();
00068     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00070     // prepare diagnostics
00072     diagnostic_updater_.reset(new diagnostic_updater::Updater);
00073     diagnostic_updater_->setHardwareID(getName());
00074     diagnostic_updater_->add(
00075       getName() + "::NormalEstimation",
00076       boost::bind(
00077         &OrganizedMultiPlaneSegmentation::updateDiagnosticNormalEstimation,
00078         this,
00079         _1));
00080     diagnostic_updater_->add(
00081       getName() + "::PlaneSegmentation",
00082       boost::bind(
00083         &OrganizedMultiPlaneSegmentation::updateDiagnosticPlaneSegmentation,
00084         this,
00085         _1));
00086     double vital_rate;
00087     pnh_->param("vital_rate", vital_rate, 1.0);
00088     normal_estimation_vital_checker_.reset(
00089       new jsk_topic_tools::VitalChecker(1 / vital_rate));
00090     plane_segmentation_vital_checker_.reset(
00091       new jsk_topic_tools::VitalChecker(1 / vital_rate));
00092     estimate_normal_ = true;
00093     pnh_->getParam("estimate_normal", estimate_normal_);
00095     // prepare publishers
00097     pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
00098     polygon_pub_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output_polygon", 1);
00099     coefficients_pub_
00100       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output_coefficients", 1);
00101     org_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output_nonconnected", 1);
00102     org_polygon_pub_
00103       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output_nonconnected_polygon", 1);
00104     org_coefficients_pub_
00105       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, 
00106         "output_nonconnected_coefficients", 1);
00107     
00108     refined_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, 
00109       "output_refined", 1);
00110     refined_polygon_pub_
00111       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output_refined_polygon", 1);
00112     refined_coefficients_pub_
00113       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, 
00114         "output_refined_coefficients", 1);
00115     
00116     pub_connection_marker_
00117       = advertise<visualization_msgs::Marker>(*pnh_, 
00118         "debug_connection_map", 1);
00119 
00120     if (estimate_normal_) {
00121       normal_pub_
00122         = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_normal", 1);
00123     }
00124     
00125     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00126     dynamic_reconfigure::Server<Config>::CallbackType f =
00127       boost::bind (
00128         &OrganizedMultiPlaneSegmentation::configCallback, this, _1, _2);
00129     srv_->setCallback (f);
00130 
00131     diagnostics_timer_ = pnh_->createTimer(
00132       ros::Duration(1.0),
00133       boost::bind(&OrganizedMultiPlaneSegmentation::updateDiagnostics,
00134                   this,
00135                   _1));
00136     onInitPostProcess();
00137   }
00138 
00139   void OrganizedMultiPlaneSegmentation::forceToDirectOrigin(
00140     const std::vector<pcl::ModelCoefficients>& coefficients,
00141     std::vector<pcl::ModelCoefficients>& output_coefficients)
00142   {
00143     output_coefficients.resize(coefficients.size());
00144     for (size_t i = 0; i < coefficients.size(); i++) {
00145       pcl::ModelCoefficients plane_coefficient = coefficients[i];
00146       jsk_recognition_utils::Plane plane(coefficients[i].values);
00147       
00148       Eigen::Vector3f p = plane.getPointOnPlane();
00149       Eigen::Vector3f n = plane.getNormal();
00150       if (p.dot(n) < 0) {
00151         output_coefficients[i] = plane_coefficient;
00152       }
00153       else {
00154         jsk_recognition_utils::Plane flip = plane.flip();
00155         pcl::ModelCoefficients new_coefficient;
00156         flip.toCoefficients(new_coefficient.values);
00157         output_coefficients[i] = new_coefficient;
00158       }
00159     }
00160   }
00161 
00162   void OrganizedMultiPlaneSegmentation::subscribe()
00163   {
00164     sub_ = pnh_->subscribe("input", 1,
00165                            &OrganizedMultiPlaneSegmentation::segment, this);
00166   }
00167 
00168   void OrganizedMultiPlaneSegmentation::unsubscribe()
00169   {
00170     sub_.shutdown();
00171   }
00172 
00173   void OrganizedMultiPlaneSegmentation::configCallback(Config &config, uint32_t level)
00174   {
00175     boost::mutex::scoped_lock lock(mutex_);
00176     min_size_ = config.min_size;
00177     angular_threshold_ = config.angular_threshold;
00178     distance_threshold_ = config.distance_threshold;
00179     max_curvature_ = config.max_curvature;
00180     connect_plane_angle_threshold_ = config.connect_plane_angle_threshold;
00181     connect_distance_threshold_ = config.connect_distance_threshold;
00182     max_depth_change_factor_ = config.max_depth_change_factor;
00183     normal_smoothing_size_ = config.normal_smoothing_size;
00184     depth_dependent_smoothing_ = config.depth_dependent_smoothing;
00185     estimation_method_ = config.estimation_method;
00186     border_policy_ignore_ = config.border_policy_ignore;
00187     publish_normal_ = config.publish_normal;
00188     ransac_refine_coefficients_ = config.ransac_refine_coefficients;
00189     ransac_refine_outlier_distance_threshold_
00190       = config.ransac_refine_outlier_distance_threshold;
00191     min_refined_area_threshold_ = config.min_refined_area_threshold;
00192     max_refined_area_threshold_ = config.max_refined_area_threshold;
00193     //concave_alpha_ = config.concave_alpha;
00194   }
00195   
00196   void OrganizedMultiPlaneSegmentation::connectPlanesMap(
00197     const pcl::PointCloud<PointT>::Ptr& input,
00198     const std::vector<pcl::ModelCoefficients>& model_coefficients,
00199     const std::vector<pcl::PointIndices>& boundary_indices,
00200     jsk_recognition_utils::IntegerGraphMap& connection_map)
00201   {
00202     NODELET_DEBUG("size of model_coefficients: %lu", model_coefficients.size());
00203     if (model_coefficients.size() == 0) {
00204       return;                   // do nothing
00205     }
00206 
00207     if (model_coefficients.size() == 1) {
00208       connection_map[0]= std::vector<int>();
00209       return;
00210     }
00211     
00212     pcl::ExtractIndices<PointT> extract;
00213     extract.setInputCloud(input);
00214     for (size_t i = 0; i < model_coefficients.size(); i++) {
00215       // initialize connection_map[i]
00216       connection_map[i] = std::vector<int>();
00217       connection_map[i].push_back(i);
00218       for (size_t j = i + 1; j < model_coefficients.size(); j++) {
00219         // check if i and j can be connected
00220         pcl::ModelCoefficients a_coefficient = model_coefficients[i];
00221         pcl::ModelCoefficients b_coefficient = model_coefficients[j];
00222         Eigen::Vector3f a_normal(a_coefficient.values[0], a_coefficient.values[1], a_coefficient.values[2]);
00223         Eigen::Vector3f b_normal(b_coefficient.values[0], b_coefficient.values[1], b_coefficient.values[2]);
00224         double a_distance = a_coefficient.values[3];
00225         double b_distance = b_coefficient.values[3];
00226         // force to check the coefficients is normalized
00227         if (a_normal.norm() != 1.0) {
00228           a_distance = a_distance / a_normal.norm();
00229           a_normal = a_normal / a_normal.norm();
00230         }
00231         if (b_normal.norm() != 1.0) {
00232           b_distance = b_distance / b_normal.norm();
00233           b_normal = b_normal / b_normal.norm();
00234         }
00235         double theta = fabs(acos(a_normal.dot(b_normal)));
00236         NODELET_DEBUG("%lu - %lu angle: %f", i, j, theta);
00237         if (theta > M_PI / 2.0) {
00238           theta = M_PI  - theta;
00239         }
00240         if (theta > connect_plane_angle_threshold_) {
00241           continue;
00242         }
00243         // the planes are near enough as a plane formula.
00244 
00245         // compute the distance between two boundaries.
00246         // if they are near enough, we can regard these two map should connect
00247         pcl::PointIndices::Ptr a_indices
00248           = boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
00249         pcl::PointIndices::Ptr b_indices
00250           = boost::make_shared<pcl::PointIndices>(boundary_indices[j]);
00251         pcl::PointCloud<PointT> a_cloud, b_cloud;
00252         extract.setIndices(a_indices);
00253         extract.filter(a_cloud);
00254         extract.setIndices(b_indices);
00255         extract.filter(b_cloud);
00256         if (a_cloud.points.size() > 0) {
00257           pcl::KdTreeFLANN<PointT> kdtree;
00258           kdtree.setInputCloud(a_cloud.makeShared());
00259           bool foundp = false;
00260           for (size_t pi = 0; pi < b_cloud.points.size(); pi++) {
00261             PointT p = b_cloud.points[pi];
00262             std::vector<int> k_indices;
00263             std::vector<float> k_sqr_distances;
00264             if (kdtree.radiusSearch(
00265                   p, connect_distance_threshold_, k_indices, k_sqr_distances, 1) > 0) {
00266               NODELET_DEBUG("%lu - %lu connected", i, j);
00267               foundp = true;
00268               break;
00269             }
00270           }
00271           if (foundp) {
00272             connection_map[i].push_back(j);
00273           }
00274         }
00275       }
00276     }
00277   }
00278 
00279   void OrganizedMultiPlaneSegmentation::pclIndicesArrayToClusterPointIndices(
00280     const std::vector<pcl::PointIndices>& inlier_indices,
00281     const std_msgs::Header& header,
00282     jsk_recognition_msgs::ClusterPointIndices& output_indices)
00283   {
00284     for (size_t i = 0; i < inlier_indices.size(); i++) {
00285       pcl::PointIndices inlier = inlier_indices[i];
00286       PCLIndicesMsg one_indices;
00287       one_indices.header = header;
00288       one_indices.indices = inlier.indices;
00289       output_indices.cluster_indices.push_back(one_indices);
00290     }
00291   }
00292   
00293   void OrganizedMultiPlaneSegmentation::pointCloudToPolygon(
00294     const pcl::PointCloud<PointT>& input,
00295     geometry_msgs::Polygon& polygon)
00296   {
00297     for (size_t i = 0; i < input.points.size(); i++) {
00298       geometry_msgs::Point32 point;
00299       point.x = input.points[i].x;
00300       point.y = input.points[i].y;
00301       point.z = input.points[i].z;
00302       polygon.points.push_back(point);
00303     }
00304   }
00305   
00306   void OrganizedMultiPlaneSegmentation::buildConnectedPlanes(
00307     const pcl::PointCloud<PointT>::Ptr& input,
00308     const std_msgs::Header& header,
00309     const std::vector<pcl::PointIndices>& inlier_indices,
00310     const std::vector<pcl::PointIndices>& boundary_indices,
00311     const std::vector<pcl::ModelCoefficients>& model_coefficients,
00312     const jsk_recognition_utils::IntegerGraphMap& connection_map,
00313     std::vector<pcl::PointIndices>& output_indices,
00314     std::vector<pcl::ModelCoefficients>& output_coefficients,
00315     std::vector<pcl::PointCloud<PointT> >& output_boundary_clouds)
00316   { 
00317     std::vector<std::set<int> > cloud_sets;
00318     NODELET_DEBUG("connection_map:");
00319     for (jsk_recognition_utils::IntegerGraphMap::const_iterator it = connection_map.begin();
00320          it != connection_map.end();
00321          ++it) {
00322       int from_index = it->first;
00323       std::stringstream ss;
00324       ss << "connection map: " << from_index << " [";
00325       for (size_t i = 0; i < it->second.size(); i++) {
00326         ss << i << ", ";
00327       }
00328       NODELET_DEBUG("%s", ss.str().c_str());
00329     }
00330 
00331     jsk_recognition_utils::buildAllGroupsSetFromGraphMap(connection_map, cloud_sets);
00332     connected_plane_num_counter_.add(cloud_sets.size());
00333     for (size_t i = 0; i < cloud_sets.size(); i++) {
00334       pcl::PointIndices one_indices;
00335       pcl::PointIndices one_boundaries;
00336       std::vector<float> new_coefficients;
00337       new_coefficients.resize(4, 0);
00338       for (std::set<int>::iterator it = cloud_sets[i].begin();
00339            it != cloud_sets[i].end();
00340            ++it) {
00341         NODELET_DEBUG("%lu includes %d", i, *it);
00342         new_coefficients = model_coefficients[*it].values;
00343         pcl::PointIndices inlier = inlier_indices[*it];
00344         pcl::PointIndices boundary_inlier = boundary_indices[*it];
00345         // append indices...
00346         one_indices = *jsk_recognition_utils::addIndices(one_indices, inlier);
00347         one_boundaries = *jsk_recognition_utils::addIndices(one_boundaries, boundary_inlier);
00348       }
00349       if (one_indices.indices.size() == 0) {
00350         continue;
00351       }
00352       // normalize coefficients
00353       double norm = sqrt(new_coefficients[0] * new_coefficients[0] 
00354                          + new_coefficients[1] * new_coefficients[1]
00355                          + new_coefficients[2] * new_coefficients[2]);
00356       new_coefficients[0] /= norm;
00357       new_coefficients[1] /= norm;
00358       new_coefficients[2] /= norm;
00359       new_coefficients[3] /= norm;
00360       
00361       // take the average of the coefficients
00362       pcl::ModelCoefficients pcl_new_coefficients;
00363       pcl_new_coefficients.values = new_coefficients;
00364       // estimate concave hull
00365       pcl::PointIndices::Ptr indices_ptr
00366         = boost::make_shared<pcl::PointIndices>(one_boundaries);
00367       pcl::ModelCoefficients::Ptr coefficients_ptr
00368         = boost::make_shared<pcl::ModelCoefficients>(pcl_new_coefficients);
00369       jsk_recognition_utils::ConvexPolygon::Ptr convex
00370         = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
00371           input, indices_ptr, coefficients_ptr);
00372       if (convex) {
00373         pcl::PointCloud<PointT> chull_output;
00374         convex->boundariesToPointCloud<PointT>(chull_output);
00375         output_indices.push_back(one_indices);
00376         output_coefficients.push_back(pcl_new_coefficients);
00377         output_boundary_clouds.push_back(chull_output);
00378       }
00379       else {
00380         NODELET_ERROR("failed to build convex");
00381       }
00382     }
00383 
00384   }
00385 
00387   // simple PCL wrapper
00389   void OrganizedMultiPlaneSegmentation::segmentOrganizedMultiPlanes(
00390     pcl::PointCloud<PointT>::Ptr input,
00391     pcl::PointCloud<pcl::Normal>::Ptr normal,
00392     PlanarRegionVector& regions,
00393     std::vector<pcl::ModelCoefficients>& model_coefficients,
00394     std::vector<pcl::PointIndices>& inlier_indices,
00395     pcl::PointCloud<pcl::Label>::Ptr& labels,
00396     std::vector<pcl::PointIndices>& label_indices,
00397     std::vector<pcl::PointIndices>& boundary_indices)
00398   {
00399     plane_segmentation_vital_checker_->poke();
00400     pcl::OrganizedMultiPlaneSegmentation<PointT, pcl::Normal, pcl::Label> mps;
00401     mps.setMinInliers(min_size_);
00402     mps.setAngularThreshold(angular_threshold_);
00403     mps.setDistanceThreshold(distance_threshold_);
00404     mps.setMaximumCurvature(max_curvature_);
00405     mps.setInputCloud(input);
00406     mps.setInputNormals(normal);
00407     {
00408       jsk_topic_tools::ScopedTimer timer = plane_segmentation_time_acc_.scopedTimer();
00409       mps.segmentAndRefine(
00410         regions, model_coefficients, inlier_indices,
00411         labels, label_indices, boundary_indices);
00412     }
00413   }
00414   
00415   void OrganizedMultiPlaneSegmentation::publishSegmentationInformation(
00416     const std_msgs::Header& header,
00417     const pcl::PointCloud<PointT>::Ptr input,
00418     ros::Publisher& indices_pub,
00419     ros::Publisher& polygon_pub,
00420     ros::Publisher& coefficients_pub,
00421     const std::vector<pcl::PointIndices>& inlier_indices,
00422     const std::vector<pcl::PointCloud<PointT> >& boundaries,
00423     const std::vector<pcl::ModelCoefficients>& model_coefficients)
00424   {
00425     jsk_recognition_msgs::ClusterPointIndices indices;
00426     jsk_recognition_msgs::ModelCoefficientsArray coefficients_array;
00427     jsk_recognition_msgs::PolygonArray polygon_array;
00428     indices.header = header;
00429     polygon_array.header = header;
00430     coefficients_array.header = header;
00431     
00433     // publish inliers
00435     pclIndicesArrayToClusterPointIndices(inlier_indices, header, indices);
00436     indices_pub.publish(indices);
00437     
00439     // boundaries as polygon
00441     for (size_t i = 0; i < boundaries.size(); i++) {
00442       geometry_msgs::PolygonStamped polygon;
00443       pcl::PointCloud<PointT> boundary_cloud = boundaries[i];
00444       pointCloudToPolygon(boundary_cloud, polygon.polygon);
00445       polygon.header = header;
00446       polygon_array.polygons.push_back(polygon);
00447     }
00448     polygon_pub.publish(polygon_array);
00449 
00451     // publish coefficients
00453     for (size_t i = 0; i < model_coefficients.size(); i++) {
00454       PCLModelCoefficientMsg coefficient;
00455       coefficient.values = model_coefficients[i].values;
00456       coefficient.header = header;
00457       coefficients_array.coefficients.push_back(coefficient);
00458     }
00459     coefficients_pub.publish(coefficients_array);    
00460   }
00461   
00462   void OrganizedMultiPlaneSegmentation::publishSegmentationInformation(
00463     const std_msgs::Header& header,
00464     const pcl::PointCloud<PointT>::Ptr input,
00465     ros::Publisher& indices_pub,
00466     ros::Publisher& polygon_pub,
00467     ros::Publisher& coefficients_pub,
00468     const std::vector<pcl::PointIndices>& inlier_indices,
00469     const std::vector<pcl::PointIndices>& boundary_indices,
00470     const std::vector<pcl::ModelCoefficients>& model_coefficients)
00471   {
00472     // convert boundary_indices into boundary pointcloud
00473     std::vector<pcl::PointCloud<PointT> > boundaries;
00474     pcl::ExtractIndices<PointT> extract;
00475     extract.setInputCloud(input);
00476     for (size_t i = 0; i < boundary_indices.size(); i++) {
00477       pcl::PointCloud<PointT> boundary_cloud;
00478       pcl::PointIndices boundary_one_indices = boundary_indices[i];
00479       pcl::PointIndices::Ptr indices_ptr = boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
00480       extract.setIndices(indices_ptr);
00481       extract.filter(boundary_cloud);
00482       boundaries.push_back(boundary_cloud);
00483     }
00484     
00485     publishSegmentationInformation(
00486       header, input, indices_pub, polygon_pub, coefficients_pub,
00487       inlier_indices, boundaries, model_coefficients);
00488   }
00489 
00490   void OrganizedMultiPlaneSegmentation::publishMarkerOfConnection(
00491     jsk_recognition_utils::IntegerGraphMap connection_map,
00492     const pcl::PointCloud<PointT>::Ptr cloud,
00493     const std::vector<pcl::PointIndices>& inliers,
00494     const std_msgs::Header& header)
00495   {
00497     // visualize connection as lines
00499     visualization_msgs::Marker connection_marker;
00500     connection_marker.type = visualization_msgs::Marker::LINE_LIST;
00501     connection_marker.scale.x = 0.01;
00502     connection_marker.header = header;
00503     connection_marker.pose.orientation.w = 1.0;
00504     connection_marker.color = jsk_topic_tools::colorCategory20(0);
00505     
00507     // first, compute centroids for each clusters
00509     jsk_recognition_utils::Vertices centroids;
00510     for (size_t i = 0; i < inliers.size(); i++) {
00511       pcl::PointIndices::Ptr target_inliers
00512         = boost::make_shared<pcl::PointIndices>(inliers[i]);
00513       pcl::PointCloud<PointT>::Ptr target_cloud (new pcl::PointCloud<PointT>);
00514       Eigen::Vector4f centroid;
00515       pcl::ExtractIndices<PointT> ex;
00516       ex.setInputCloud(cloud);
00517       ex.setIndices(target_inliers);
00518       ex.filter(*target_cloud);
00519       pcl::compute3DCentroid(*target_cloud, centroid);
00520       Eigen::Vector3f centroid_3f(centroid[0], centroid[1], centroid[2]);
00521       centroids.push_back(centroid_3f);
00522     }
00523 
00524     for (jsk_recognition_utils::IntegerGraphMap::iterator it = connection_map.begin();
00525          it != connection_map.end();
00526          ++it) {
00527       // from = i
00528       int from_index = it->first;
00529       std::vector<int> the_connection_map = connection_map[from_index];
00530       for (size_t j = 0; j < the_connection_map.size(); j++) {
00531         int to_index = the_connection_map[j];
00532         //std::cout << "connection: " << from_index << " --> " << to_index << std::endl;
00533         Eigen::Vector3f from_point = centroids[from_index];
00534         Eigen::Vector3f to_point = centroids[to_index];
00535         geometry_msgs::Point from_point_ros, to_point_ros;
00536         jsk_recognition_utils::pointFromVectorToXYZ<Eigen::Vector3f, geometry_msgs::Point>(
00537           from_point, from_point_ros);
00538         jsk_recognition_utils::pointFromVectorToXYZ<Eigen::Vector3f, geometry_msgs::Point>(
00539           to_point, to_point_ros);
00540         connection_marker.points.push_back(from_point_ros);
00541         connection_marker.points.push_back(to_point_ros);
00542         connection_marker.colors.push_back(jsk_topic_tools::colorCategory20(from_index));
00543         connection_marker.colors.push_back(jsk_topic_tools::colorCategory20(from_index));
00544       }
00545     }
00546     pub_connection_marker_.publish(connection_marker);
00547   }
00548   
00549   void OrganizedMultiPlaneSegmentation::segmentFromNormals(
00550     pcl::PointCloud<PointT>::Ptr input,
00551     pcl::PointCloud<pcl::Normal>::Ptr normal,
00552     const std_msgs::Header& header)
00553   {
00554     PlanarRegionVector regions;
00555     std::vector<pcl::ModelCoefficients> model_coefficients;
00556     std::vector<pcl::PointIndices> inlier_indices;
00557     pcl::PointCloud<pcl::Label>::Ptr labels (new pcl::PointCloud<pcl::Label>());
00558     std::vector<pcl::PointIndices> label_indices;
00559     std::vector<pcl::PointIndices> boundary_indices;
00561     // segment planes based on pcl's organized multi plane
00562     // segmentation.
00564     segmentOrganizedMultiPlanes(input, normal, regions, model_coefficients,
00565                                 inlier_indices, labels, label_indices,
00566                                 boundary_indices);
00567     std::vector<pcl::ModelCoefficients> fixed_model_coefficients;
00568     forceToDirectOrigin(model_coefficients, fixed_model_coefficients);
00569     model_coefficients = fixed_model_coefficients;
00570     
00571     original_plane_num_counter_.add(regions.size());
00572     publishSegmentationInformation(
00573       header, input,
00574       org_pub_, org_polygon_pub_, org_coefficients_pub_,
00575       inlier_indices, boundary_indices, model_coefficients);
00576     
00578     // segmentation by PCL organized multiplane segmentation
00579     // is not enough. we "connect" planes like graph problem.
00581     jsk_recognition_utils::IntegerGraphMap connection_map;
00582     connectPlanesMap(input, model_coefficients, boundary_indices, connection_map);
00583     publishMarkerOfConnection(connection_map, input, inlier_indices, header);
00584     std::vector<pcl::PointIndices> output_nonrefined_indices;
00585     std::vector<pcl::ModelCoefficients> output_nonrefined_coefficients;
00586     std::vector<pcl::PointCloud<PointT> > output_nonrefined_boundary_clouds;
00587     buildConnectedPlanes(input, header,
00588                          inlier_indices,
00589                          boundary_indices,
00590                          model_coefficients,
00591                          connection_map,
00592                          output_nonrefined_indices,
00593                          output_nonrefined_coefficients,
00594                          output_nonrefined_boundary_clouds);
00595     std::vector<pcl::ModelCoefficients> fixed_output_nonrefined_coefficients;
00596     forceToDirectOrigin(output_nonrefined_coefficients, fixed_output_nonrefined_coefficients);
00597     output_nonrefined_coefficients = fixed_output_nonrefined_coefficients;
00598     publishSegmentationInformation(
00599       header, input,
00600       pub_, polygon_pub_, coefficients_pub_,
00601       output_nonrefined_indices,
00602       output_nonrefined_boundary_clouds,
00603       output_nonrefined_coefficients);
00605     // refine coefficients based on RANSAC
00607     if (ransac_refine_coefficients_) {
00608       std::vector<pcl::PointIndices> refined_inliers;
00609       std::vector<pcl::ModelCoefficients> refined_coefficients;
00610       std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> refined_convexes;
00611       refineBasedOnRANSAC(
00612         input, output_nonrefined_indices, output_nonrefined_coefficients,
00613         refined_inliers, refined_coefficients, refined_convexes);
00614       std::vector<pcl::PointCloud<PointT> > refined_boundary_clouds;
00615       for (size_t i = 0; i < refined_convexes.size(); i++) {
00616         pcl::PointCloud<PointT> refined_boundary;
00617         refined_convexes[i]->boundariesToPointCloud(refined_boundary);
00618         refined_boundary_clouds.push_back(refined_boundary);
00619       }
00620       std::vector<pcl::ModelCoefficients> fixed_refined_coefficients;
00621       forceToDirectOrigin(refined_coefficients, fixed_refined_coefficients);
00622       refined_coefficients = fixed_refined_coefficients;
00623       publishSegmentationInformation(
00624         header, input,
00625         refined_pub_, refined_polygon_pub_, refined_coefficients_pub_,
00626         refined_inliers, refined_boundary_clouds, refined_coefficients);
00627     }
00628   }
00629 
00630   void OrganizedMultiPlaneSegmentation::refineBasedOnRANSAC(
00631     const pcl::PointCloud<PointT>::Ptr input,
00632     const std::vector<pcl::PointIndices>& input_indices,
00633     const std::vector<pcl::ModelCoefficients>& input_coefficients,
00634     std::vector<pcl::PointIndices>& output_indices,
00635     std::vector<pcl::ModelCoefficients>& output_coefficients,
00636     std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_convexes)
00637   {
00638     jsk_topic_tools::ScopedTimer timer
00639       = ransac_refinement_time_acc_.scopedTimer();
00640     for (size_t i = 0; i < input_indices.size(); i++) {
00641       pcl::PointIndices::Ptr input_indices_ptr
00642         = boost::make_shared<pcl::PointIndices>(input_indices[i]);
00643       Eigen::Vector3f normal(input_coefficients[i].values[0],
00644                              input_coefficients[i].values[1],
00645                              input_coefficients[i].values[2]);
00646       normal.normalize();
00648       // run RANSAC
00650       pcl::SACSegmentation<PointT> seg;
00651       seg.setOptimizeCoefficients (true);
00652       seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
00653       seg.setMethodType (pcl::SAC_RANSAC);
00654       seg.setDistanceThreshold (ransac_refine_outlier_distance_threshold_);
00655       seg.setInputCloud(input);
00656       seg.setIndices(input_indices_ptr);
00657       seg.setMaxIterations (10000);
00658       seg.setAxis(normal);
00659       seg.setEpsAngle(pcl::deg2rad(20.0));
00660       pcl::PointIndices::Ptr refined_inliers (new pcl::PointIndices);
00661       pcl::ModelCoefficients::Ptr refined_coefficients(new pcl::ModelCoefficients);
00662       seg.segment(*refined_inliers, *refined_coefficients);
00663       if (refined_inliers->indices.size() > 0) {
00665         // compute boundaries from convex hull of
00667         jsk_recognition_utils::ConvexPolygon::Ptr convex = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
00668           input, refined_inliers, refined_coefficients);
00669         if (convex) {
00670           // check area threshold
00671           double area = convex->area();
00672           if (area > min_refined_area_threshold_ &&
00673               area < max_refined_area_threshold_) {
00674             output_convexes.push_back(convex);
00675             output_indices.push_back(*refined_inliers);
00676             output_coefficients.push_back(*refined_coefficients);
00677           }
00678         }
00679       }
00680     }
00681   }
00682 
00683   void OrganizedMultiPlaneSegmentation::estimateNormal(pcl::PointCloud<PointT>::Ptr input,
00684                                                        pcl::PointCloud<pcl::Normal>::Ptr output)
00685   {
00686     jsk_topic_tools::ScopedTimer timer = normal_estimation_time_acc_.scopedTimer();
00687     pcl::IntegralImageNormalEstimation<PointT, pcl::Normal> ne;
00688     if (estimation_method_ == 0) {
00689       ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
00690     }
00691     else if (estimation_method_ == 1) {
00692      ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
00693     }
00694     else if (estimation_method_ == 2) {
00695       ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
00696     }
00697     else {
00698       NODELET_FATAL("unknown estimation method, force to use COVARIANCE_MATRIX: %d",
00699                     estimation_method_);
00700       ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
00701     }
00702 
00703     if (border_policy_ignore_) {
00704       ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<PointT, pcl::Normal>::BORDER_POLICY_IGNORE);
00705     }
00706     else {
00707       ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<PointT, pcl::Normal>::BORDER_POLICY_MIRROR);
00708     }
00709     
00710     ne.setMaxDepthChangeFactor(max_depth_change_factor_);
00711     ne.setNormalSmoothingSize(normal_smoothing_size_);
00712     ne.setDepthDependentSmoothing(depth_dependent_smoothing_);
00713     ne.setInputCloud(input);
00714     ne.compute(*output);
00715   }
00716   
00717   void OrganizedMultiPlaneSegmentation::segment
00718   (const sensor_msgs::PointCloud2::ConstPtr& msg)
00719   {
00720     boost::mutex::scoped_lock lock(mutex_);
00721     
00722     // if estimate_normal_ is true, we run integral image normal estimation
00723     // before segmenting planes
00724     pcl::PointCloud<PointT>::Ptr input(new pcl::PointCloud<PointT>());
00725     pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>());
00726     pcl::fromROSMsg(*msg, *input);
00727     
00728     if (estimate_normal_) {
00729       normal_estimation_vital_checker_->poke();
00730       estimateNormal(input, normal);
00731       // publish normal to ros
00732       if (publish_normal_) {
00733         sensor_msgs::PointCloud2 normal_ros_cloud;
00734         pcl::toROSMsg(*normal, normal_ros_cloud);
00735         normal_ros_cloud.header = msg->header;
00736         normal_pub_.publish(normal_ros_cloud);
00737       }
00738     }
00739     else {
00740       pcl::fromROSMsg(*msg, *normal);
00741     }
00742     
00743     segmentFromNormals(input, normal, msg->header);
00744     diagnostic_updater_->update();
00745   }
00746 
00747   void OrganizedMultiPlaneSegmentation::updateDiagnosticNormalEstimation(
00748     diagnostic_updater::DiagnosticStatusWrapper &stat)
00749   {
00750     if (estimate_normal_) {
00751       bool alivep = normal_estimation_vital_checker_->isAlive();
00752       if (alivep) {
00753         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "NormalEstimation running");
00754         jsk_topic_tools::addDiagnosticInformation(
00755           "Time to estimate normal", normal_estimation_time_acc_, stat);
00756         // normal estimation parameters
00757         if (estimation_method_ == 0) {
00758           stat.add("Estimation Method", "AVERAGE_3D_GRADIENT");
00759         }
00760         else if (estimation_method_ == 1) {
00761           stat.add("Estimation Method", "COVARIANCE_MATRIX");
00762         }
00763         else if (estimation_method_ == 2) {
00764           stat.add("Estimation Method", "AVERAGE_DEPTH_CHANGE");
00765         }
00766         if (border_policy_ignore_) {
00767           stat.add("Border Policy", "ignore");
00768         }
00769         else {
00770           stat.add("Border Policy", "mirror");
00771         }
00772         stat.add("Max Depth Change Factor", max_depth_change_factor_);
00773         stat.add("Normal Smoothing Size", normal_smoothing_size_);
00774         if (depth_dependent_smoothing_) {
00775           stat.add("Depth Dependent Smooting", "Enabled");
00776         }
00777         else {
00778           stat.add("Depth Dependent Smooting", "Disabled");
00779         }
00780         if (publish_normal_) {
00781           stat.add("Publish Normal", "Enabled");
00782         }
00783         else {
00784           stat.add("Publish Normal", "Disabled");
00785         }
00786       }
00787       else {
00788         stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00789                      (boost::format("NormalEstimation not running for %f sec")
00790                       % normal_estimation_vital_checker_->deadSec()).str());
00791       }
00792       
00793     }
00794     else {
00795       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00796                    "NormalEstimation is not activated");
00797     }
00798   }
00799 
00800   void OrganizedMultiPlaneSegmentation::updateDiagnosticPlaneSegmentation(
00801     diagnostic_updater::DiagnosticStatusWrapper &stat)
00802   {
00803     bool alivep = plane_segmentation_vital_checker_->isAlive();
00804     if (alivep) {
00805       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00806                    "PlaneSegmentation running");
00807       jsk_topic_tools::addDiagnosticInformation(
00808         "Time to segment planes", plane_segmentation_time_acc_, stat);
00809       if (ransac_refine_coefficients_) {
00810         jsk_topic_tools::addDiagnosticInformation(
00811           "Time to refine by RANSAC", ransac_refinement_time_acc_, stat);
00812       }
00813       stat.add("Minimum Inliers", min_size_);
00814       stat.add("Angular Threshold (rad)", angular_threshold_);
00815       stat.add("Angular Threshold (deg)", angular_threshold_ / M_PI * 180.0);
00816       stat.add("Distance Threshold", distance_threshold_);
00817       stat.add("Max Curvature", max_curvature_);
00818       if (ransac_refine_coefficients_) {
00819         stat.add("Use RANSAC refinement", "True");
00820         stat.add("RANSAC refinement distance threshold",
00821                  ransac_refine_outlier_distance_threshold_);
00822       }
00823       else {
00824         stat.add("Use RANSAC refinement", "False");
00825       }
00826       
00827       stat.add("Number of original segmented planes (Avg.)", 
00828                original_plane_num_counter_.mean());
00829       stat.add("Number of connected segmented planes (Avg.)", 
00830                connected_plane_num_counter_.mean());
00831     }
00832     else {
00833       stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR,
00834                    (boost::format("PlaneSegmentation not running for %f sec")
00835                     % plane_segmentation_vital_checker_->deadSec()).str());
00836     }
00837     
00838   }
00839 
00840   void OrganizedMultiPlaneSegmentation::updateDiagnostics(
00841     const ros::TimerEvent& event)
00842   {
00843     boost::mutex::scoped_lock lock(mutex_);
00844     diagnostic_updater_->update();
00845   }
00846   
00847 }
00848 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OrganizedMultiPlaneSegmentation,
00849                         nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:44