$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 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/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. 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 * $Id: table_object_detector.cpp 36637 2011-04-20 01:33:25Z michael.s.dixon $ 00035 * 00036 */ 00037 00046 #include <boost/make_shared.hpp> 00047 #include <ros/ros.h> 00048 #include "pcl/io/io.h" 00049 #include "pcl_ros/publisher.h" 00050 #include "pcl/point_types.h" 00051 00052 #include "pcl/io/io.h" 00053 #include "pcl/io/pcd_io.h" 00054 #include "pcl/filters/voxel_grid.h" 00055 #include "pcl/filters/passthrough.h" 00056 #include "pcl/filters/extract_indices.h" 00057 #include "pcl/features/normal_3d.h" 00058 #include "pcl/kdtree/kdtree.h" 00059 #include "pcl/kdtree/kdtree_flann.h" 00060 #include "pcl/kdtree/organized_data.h" 00061 #include "pcl/sample_consensus/method_types.h" 00062 #include "pcl/sample_consensus/model_types.h" 00063 #include "pcl/segmentation/sac_segmentation.h" 00064 #include "pcl/filters/project_inliers.h" 00065 #include "pcl/surface/convex_hull.h" 00066 #include "pcl/segmentation/extract_polygonal_prism_data.h" 00067 #include "pcl/segmentation/extract_clusters.h" 00068 00069 // ROS messages 00070 #include <sensor_msgs/PointCloud2.h> 00071 #include "pcl/PointIndices.h" 00072 #include "pcl/ModelCoefficients.h" 00073 00074 //#include <robot_msgs/Polygon3D.h> 00075 //#include <robot_msgs/PolygonalMap.h> 00076 00077 //#include <robot_srvs/FindTable.h> 00078 //#include <robot_msgs/Table.h> 00079 //#include <robot_msgs/ObjectOnTable.h> 00080 00081 class TableObjectDetector 00082 { 00083 typedef pcl::PointXYZRGB Point; 00084 typedef pcl::KdTree<Point>::Ptr KdTreePtr; 00085 00086 public: 00087 ros::NodeHandle nh_; 00088 00089 ros::Subscriber cloud_sub_; 00090 ros::Publisher cloud_pub_; 00091 00092 // PCL objects 00093 KdTreePtr normals_tree_, clusters_tree_; 00094 pcl::PassThrough<Point> pass_; 00095 pcl::VoxelGrid<Point> grid_, grid_objects_; 00096 pcl::NormalEstimation<Point, pcl::Normal> n3d_; 00097 pcl::SACSegmentationFromNormals<Point, pcl::Normal> seg_; 00098 pcl::ProjectInliers<Point> proj_; 00099 pcl::ConvexHull<Point> hull_; 00100 pcl::ExtractPolygonalPrismData<Point> prism_; 00101 pcl::EuclideanClusterExtraction<Point> cluster_; 00102 00103 //pcl::OrganizedDataIndex<Point> tree_; 00104 00105 double downsample_leaf_, downsample_leaf_objects_; 00106 int k_; 00107 double min_z_bounds_, max_z_bounds_; 00108 double sac_distance_threshold_; 00109 double normal_distance_weight_; 00110 00111 // Min/Max height from the table plane object points will be considered from/to 00112 double object_min_height_, object_max_height_; 00113 00114 // Object cluster tolerance and minimum cluster size 00115 double object_cluster_tolerance_, object_cluster_min_size_; 00116 00117 // The raw, input point cloud data 00118 pcl::PointCloud<Point>::ConstPtr cloud_; 00119 // The filtered and downsampled point cloud data 00120 pcl::PointCloud<Point>::ConstPtr cloud_filtered_, cloud_downsampled_; 00121 // The resultant estimated point cloud normals for \a cloud_filtered_ 00122 pcl::PointCloud<pcl::Normal>::ConstPtr cloud_normals_; 00123 // The vector of indices from cloud_filtered_ that represent the planar table component 00124 pcl::PointIndices::ConstPtr table_inliers_; 00125 // The model coefficients of the planar table component 00126 pcl::ModelCoefficients::ConstPtr table_coefficients_; 00127 // The set of point inliers projected on the planar table component from \a cloud_filtered_ 00128 pcl::PointCloud<Point>::ConstPtr table_projected_; 00129 // The convex hull of \a table_projected_ 00130 pcl::PointCloud<Point>::ConstPtr table_hull_; 00131 // The remaining of the \a cloud_filtered_ which lies inside the \a table_hull_ polygon 00132 pcl::PointCloud<Point>::ConstPtr cloud_objects_, cloud_objects_downsampled_; 00133 00135 TableObjectDetector () : nh_ ("~") 00136 { 00137 cloud_sub_ = nh_.subscribe ("input", 1, &TableObjectDetector::input_callback, this); 00138 cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud2> ("cloud_out", 1); 00139 00140 // ---[ Create all PCL objects and set their parameters 00141 00142 // Filtering parameters 00143 downsample_leaf_ = 0.01; // 1cm voxel size by default 00144 downsample_leaf_objects_ = 0.003; // 3mm voxel size by default 00145 nh_.getParam ("downsample_leaf", downsample_leaf_); 00146 grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_); 00147 grid_objects_.setLeafSize (downsample_leaf_objects_, downsample_leaf_objects_, downsample_leaf_objects_); 00148 grid_.setFilterFieldName ("z"); 00149 pass_.setFilterFieldName ("z"); 00150 00151 min_z_bounds_ = 0.4; // restrict the Z dimension between 0.4m 00152 max_z_bounds_ = 1.6; // and 1.6m 00153 nh_.getParam ("min_z_bounds", min_z_bounds_); 00154 nh_.getParam ("max_z_bounds", max_z_bounds_); 00155 grid_.setFilterLimits (min_z_bounds_, max_z_bounds_); 00156 pass_.setFilterLimits (min_z_bounds_, max_z_bounds_); 00157 grid_.setDownsampleAllData (false); 00158 grid_objects_.setDownsampleAllData (false); 00159 00160 normals_tree_ = boost::make_shared<pcl::KdTreeFLANN<Point> > (); 00161 clusters_tree_ = boost::make_shared<pcl::KdTreeFLANN<Point> > (); 00162 clusters_tree_->setEpsilon (1); 00163 //tree_.setSearchWindowAsK (10); 00164 //tree_.setMaxDistance (0.5); 00165 00166 // Normal estimation parameters 00167 k_ = 10; // 50 k-neighbors by default 00168 nh_.getParam ("search_k_closest", k_); 00169 n3d_.setKSearch (k_); 00170 //n3d_.setRadiusSearch (0.015); 00171 n3d_.setSearchMethod (normals_tree_); 00172 00173 // Table model fitting parameters 00174 sac_distance_threshold_ = 0.1; // 5cm 00175 nh_.getParam ("sac_distance_threshold", sac_distance_threshold_); 00176 seg_.setDistanceThreshold (sac_distance_threshold_); 00177 seg_.setMaxIterations (10000); 00178 00179 normal_distance_weight_ = 0.1; 00180 nh_.getParam ("normal_distance_weight", normal_distance_weight_); 00181 seg_.setNormalDistanceWeight (normal_distance_weight_); 00182 seg_.setOptimizeCoefficients (true); 00183 seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE); 00184 seg_.setMethodType (pcl::SAC_RANSAC); 00185 seg_.setProbability (0.99); 00186 00187 proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE); 00188 00189 // Consider objects starting at 1cm from the table and ending at 0.5m 00190 object_min_height_ = 0.01; 00191 object_max_height_ = 0.5; 00192 nh_.getParam ("object_min_height", object_min_height_); 00193 nh_.getParam ("object_max_height", object_max_height_); 00194 prism_.setHeightLimits (object_min_height_, object_max_height_); 00195 00196 // Clustering parameters 00197 object_cluster_tolerance_ = 0.05; // 5cm between two objects 00198 object_cluster_min_size_ = 100; // 100 points per object cluster 00199 nh_.getParam ("object_cluster_tolerance", object_cluster_tolerance_); 00200 nh_.getParam ("object_cluster_min_size", object_cluster_min_size_); 00201 cluster_.setClusterTolerance (object_cluster_tolerance_); 00202 cluster_.setMinClusterSize (object_cluster_min_size_); 00203 cluster_.setSearchMethod (clusters_tree_); 00204 00205 // param ("~normal_eps_angle_", eps_angle_, 15.0); // 15 degrees 00206 // eps_angle_ = cloud_geometry::deg2rad (eps_angle_); // convert to radians 00207 // 00208 // param ("~region_angle_threshold", region_angle_threshold_, 30.0); // Difference between normals in degrees for cluster/region growing 00209 // region_angle_threshold_ = cloud_geometry::deg2rad (region_angle_threshold_); // convert to radians 00210 // if (publish_debug_) 00211 // { 00212 // advertise<PolygonalMap> ("semantic_polygonal_map", 1); 00213 // advertise<PointCloud> ("cloud_annotated", 1); 00214 // } 00215 } 00216 00218 // Callback 00219 void 00220 input_callback (const sensor_msgs::PointCloud2ConstPtr &cloud2_in) 00221 { 00222 ros::Time t1 = ros::Time::now (); 00223 ROS_INFO ("[TableObjectDetector::input_callback] PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.", cloud2_in->width * cloud2_in->height, pcl::getFieldsList (*cloud2_in).c_str (), cloud2_in->header.stamp.toSec (), cloud2_in->header.frame_id.c_str (), nh_.resolveName ("input").c_str ()); 00224 00225 // ---[ Convert the dataset 00226 pcl::PointCloud<Point> cloud; 00227 pcl::fromROSMsg (*cloud2_in, cloud); 00228 cloud_ = boost::make_shared<const pcl::PointCloud<Point> > (cloud); 00229 00230 // ---[ Create the voxel grid 00231 pcl::PointCloud<Point> cloud_filtered; 00232 pass_.setInputCloud (cloud_); 00233 pass_.filter (cloud_filtered); 00234 cloud_filtered_.reset (new pcl::PointCloud<Point> (cloud_filtered)); 00235 ROS_INFO ("[TableObjectDetector::input_callback] Number of points left after filtering (%f -> %f): %d out of %d.", min_z_bounds_, max_z_bounds_, (int)cloud_filtered.points.size (), (int)cloud.points.size ()); 00236 00237 pcl::PointCloud<Point> cloud_downsampled; 00238 grid_.setInputCloud (cloud_filtered_); 00239 // grid_.setInputCloud (cloud_); 00240 grid_.filter (cloud_downsampled); 00241 cloud_downsampled_.reset (new pcl::PointCloud<Point> (cloud_downsampled)); 00242 00243 if ((int)cloud_filtered_->points.size () < k_) 00244 { 00245 ROS_WARN ("[TableObjectDetector::input_callback] Filtering returned %d points! Continuing.", (int)cloud_filtered_->points.size ()); 00246 //pcl::PointCloud<pcl::PointXYZRGBNormal> cloud_temp; 00247 //pcl::concatenateFields <Point, pcl::Normal, pcl::PointXYZRGBNormal> (cloud_filtered, cloud_normals, cloud_temp); 00248 //pcl::io::savePCDFile ("test.pcd", cloud, false); 00249 return; 00250 } 00251 00252 // ---[ Estimate the point normals 00253 pcl::PointCloud<pcl::Normal> cloud_normals; 00254 // n3d_.setSearchSurface (cloud_); 00255 n3d_.setInputCloud (cloud_downsampled_); 00256 n3d_.compute (cloud_normals); 00257 cloud_normals_.reset (new pcl::PointCloud<pcl::Normal> (cloud_normals)); 00258 ROS_INFO ("[TableObjectDetector::input_callback] %d normals estimated.", (int)cloud_normals.points.size ()); 00259 00260 //ROS_ASSERT (cloud_normals_->points.size () == cloud_filtered_->points.size ()); 00261 00262 // ---[ Perform segmentation 00263 pcl::PointIndices table_inliers; pcl::ModelCoefficients table_coefficients; 00264 seg_.setInputCloud (cloud_downsampled_); 00265 seg_.setInputNormals (cloud_normals_); 00266 seg_.segment (table_inliers, table_coefficients); 00267 table_inliers_.reset (new pcl::PointIndices (table_inliers)); 00268 table_coefficients_.reset (new pcl::ModelCoefficients (table_coefficients)); 00269 if (table_coefficients.values.size () > 3) 00270 ROS_INFO ("[TableObjectDetector::input_callback] Model found with %d inliers: [%f %f %f %f].", (int)table_inliers.indices.size (), 00271 table_coefficients.values[0], table_coefficients.values[1], table_coefficients.values[2], table_coefficients.values[3]); 00272 00273 if (table_inliers_->indices.size () == 0) 00274 return; 00275 00276 // ---[ Extract the table 00277 pcl::PointCloud<Point> table_projected; 00278 //proj_.setInputCloud (cloud_filtered_); 00279 proj_.setInputCloud (cloud_downsampled_); 00280 proj_.setIndices (table_inliers_); 00281 proj_.setModelCoefficients (table_coefficients_); 00282 proj_.filter (table_projected); 00283 table_projected_.reset (new pcl::PointCloud<Point> (table_projected)); 00284 ROS_INFO ("[TableObjectDetector::input_callback] Number of projected inliers: %d.", (int)table_projected.points.size ()); 00285 00286 // ---[ Estimate the convex hull 00287 pcl::PointCloud<Point> table_hull; 00288 hull_.setInputCloud (table_projected_); 00289 hull_.reconstruct (table_hull); 00290 table_hull_.reset (new pcl::PointCloud<Point> (table_hull)); 00291 00292 // ---[ Extract the remaining of all-table 00293 //SampleConsensusModelNormalPlane<Point, pcl::Normal> model_refine; 00294 //model_refine.selectWithinDistance (model_coefficients, sac_distance_threshold_, std::vector<int> &inliers); 00295 00296 // pcl::PointCloud<Point> cloud_all_minus_table; 00297 // pcl::ExtractIndices<Point> extract_all_minus_table; 00298 // extract_all_minus_table.setInputCloud (cloud_filtered_); 00299 // extract_all_minus_table.setIndices (table_inliers_); 00300 // extract_all_minus_table.setNegative (true); 00301 // extract_all_minus_table.filter (cloud_all_minus_table); 00302 // boost::shared_ptr<const pcl::PointCloud<Point> > cloud_all_minus_table_ptr = boost::make_shared<const pcl::PointCloud<Point> > (cloud_all_minus_table); 00303 00304 // ---[ Get the objects on top of the table 00305 pcl::PointIndices cloud_object_indices; 00306 //prism_.setInputCloud (cloud_all_minus_table_ptr); 00307 prism_.setInputCloud (cloud_filtered_); 00308 // prism_.setInputCloud (cloud_downsampled_); 00309 prism_.setInputPlanarHull (table_hull_); 00310 prism_.segment (cloud_object_indices); 00311 ROS_INFO ("[TableObjectDetector::input_callback] Number of object point indices: %d.", (int)cloud_object_indices.indices.size ()); 00312 00313 pcl::PointCloud<Point> cloud_objects; 00314 pcl::ExtractIndices<Point> extract_object_indices; 00315 //extract_object_indices.setInputCloud (cloud_all_minus_table_ptr); 00316 extract_object_indices.setInputCloud (cloud_filtered_); 00317 // extract_object_indices.setInputCloud (cloud_downsampled_); 00318 extract_object_indices.setIndices (boost::make_shared<const pcl::PointIndices> (cloud_object_indices)); 00319 extract_object_indices.filter (cloud_objects); 00320 cloud_objects_.reset (new pcl::PointCloud<Point> (cloud_objects)); 00321 ROS_INFO ("[TableObjectDetector::input_callback] Number of object point candidates: %d.", (int)cloud_objects.points.size ()); 00322 00323 if (cloud_objects.points.size () == 0) 00324 return; 00325 00326 // ---[ Downsample the points 00327 pcl::PointCloud<Point> cloud_objects_downsampled; 00328 grid_objects_.setInputCloud (cloud_objects_); 00329 grid_objects_.filter (cloud_objects_downsampled); 00330 cloud_objects_downsampled_.reset (new pcl::PointCloud<Point> (cloud_objects_downsampled)); 00331 ROS_INFO ("[TableObjectDetector::input_callback] Number of object point candidates left after downsampling: %d.", (int)cloud_objects_downsampled.points.size ()); 00332 00333 // ---[ Split the objects into Euclidean clusters 00334 std::vector<pcl::PointIndices> clusters; 00335 cluster_.setInputCloud (cloud_objects_downsampled_); 00336 cluster_.extract (clusters); 00337 ROS_INFO ("[TableObjectDetector::input_callback] Number of clusters found matching the given constraints: %d.", (int)clusters.size ()); 00338 00339 for (size_t i = 0; i < clusters.size (); ++i) 00340 { 00341 std::stringstream ss; 00342 ss << "cluster_" << i << ".pcd"; 00343 00344 pcl::PointCloud<Point> cloud_object_cluster; 00345 pcl::copyPointCloud (cloud_objects_downsampled, clusters[i], cloud_object_cluster); 00346 00347 pcl::io::savePCDFile (ss.str (), cloud_object_cluster); 00348 } 00349 00350 // -temp- 00351 pcl::PointCloud<Point> cloud_objects_clusters; 00352 pcl::copyPointCloud (cloud_objects_downsampled, clusters, cloud_objects_clusters); 00353 00354 // Publish the table convex hull (optional) 00355 sensor_msgs::PointCloud2 cloud_out; 00356 pcl::toROSMsg (cloud_objects_clusters, cloud_out); 00357 cloud_pub_.publish (cloud_out); 00358 ROS_WARN ("Spent %f seconds.", (ros::Time::now () - t1).toSec ()); 00359 } 00360 }; 00361 00362 /* ---[ */ 00363 int 00364 main (int argc, char** argv) 00365 { 00366 ros::init (argc, argv, "table_object_detector"); 00367 00368 TableObjectDetector p; 00369 ros::spin (); 00370 00371 return (0); 00372 } 00373 /* ]--- */ 00374