$search
00001 /* 00002 * Copyright (c) 2008 Radu Bogdan Rusu <rusu -=- cs.tum.edu> 00003 * 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 * $Id$ 00028 * 00029 */ 00030 00042 // ROS core 00043 #include <ros/ros.h> 00044 // ROS messages 00045 #include <sensor_msgs/PointCloud.h> 00046 #include <geometry_msgs/Polygon.h> 00047 #include <mapping_msgs/PolygonalMap.h> 00048 00049 // Sample Consensus 00050 #include <point_cloud_mapping/sample_consensus/sac.h> 00051 #include <point_cloud_mapping/sample_consensus/msac.h> 00052 #include <point_cloud_mapping/sample_consensus/ransac.h> 00053 #include <point_cloud_mapping/sample_consensus/lmeds.h> 00054 #include <point_cloud_mapping/sample_consensus/sac_model_line.h> 00055 00056 // Cloud geometry 00057 #include <point_cloud_mapping/geometry/angles.h> 00058 #include <point_cloud_mapping/geometry/areas.h> 00059 #include <point_cloud_mapping/geometry/point.h> 00060 #include <point_cloud_mapping/geometry/distances.h> 00061 #include <point_cloud_mapping/geometry/nearest.h> 00062 00063 #include <tf/transform_listener.h> 00064 00065 #include <sys/time.h> 00066 00067 using namespace std; 00068 using namespace mapping_msgs; 00069 00070 class GroundRemoval 00071 { 00072 protected: 00073 ros::NodeHandle& node_; 00074 00075 public: 00076 00077 // ROS messages 00078 sensor_msgs::PointCloud cloud_, cloud_noground_; 00079 00080 tf::TransformListener tf_; 00081 geometry_msgs::PointStamped viewpoint_cloud_; 00082 00083 // Parameters 00084 double z_threshold_; 00085 int sac_min_points_per_model_, sac_max_iterations_; 00086 double sac_distance_threshold_; 00087 int planar_refine_; 00088 00089 ros::Publisher cloud_publisher_; 00090 ros::Subscriber cloud_subscriber_; 00091 00093 GroundRemoval (ros::NodeHandle& anode) : node_ (anode) 00094 { 00095 node_.param ("z_threshold", z_threshold_, 0.1); // 10cm threshold for ground removal 00096 node_.param ("sac_distance_threshold", sac_distance_threshold_, 0.03); // 3 cm threshold 00097 00098 node_.param ("planar_refine", planar_refine_, 1); // enable a final planar refinement step? 00099 node_.param ("sac_min_points_per_model", sac_min_points_per_model_, 6); // 6 points minimum per line 00100 node_.param ("sac_max_iterations", sac_max_iterations_, 200); // maximum 200 iterations 00101 00102 string cloud_topic ("full_cloud"); 00103 00104 bool topic_found = false; 00105 std::vector<ros::master::TopicInfo> t_list; 00106 ros::master::getTopics (t_list); 00107 for (vector<ros::master::TopicInfo>::iterator it = t_list.begin (); it != t_list.end (); it++) 00108 { 00109 if (it->name == cloud_topic) 00110 { 00111 topic_found = true; 00112 break; 00113 } 00114 } 00115 if (!topic_found) 00116 ROS_WARN ("Trying to subscribe to %s, but the topic doesn't exist!", cloud_topic.c_str ()); 00117 00118 cloud_subscriber_ = node_.subscribe (cloud_topic, 1, &GroundRemoval::cloud_cb, this); 00119 cloud_publisher_ = node_.advertise<sensor_msgs::PointCloud> ("cloud_ground_filtered", 1); 00120 } 00121 00123 void 00124 updateParametersFromServer () 00125 { 00126 if (node_.hasParam ("z_threshold")) node_.getParam ("z_threshold", z_threshold_); 00127 if (node_.hasParam ("sac_distance_threshold")) node_.getParam ("sac_distance_threshold", sac_distance_threshold_); 00128 } 00129 00131 00137 void 00138 splitPointsBasedOnLaserScanIndex (sensor_msgs::PointCloud *points, vector<int> *indices, vector<vector<int> > &clusters, int idx) 00139 { 00140 vector<int> seed_queue; 00141 int prev_idx = -1; 00142 // Process all points in the indices vector 00143 for (unsigned int i = 0; i < indices->size (); i++) 00144 { 00145 // Get the current laser scan measurement index 00146 int cur_idx = points->channels[idx].values.at (indices->at (i)); 00147 00148 if (cur_idx > prev_idx) // Still the same laser scan ? 00149 { 00150 seed_queue.push_back (indices->at (i)); 00151 prev_idx = cur_idx; 00152 } 00153 else // Have we found a new scan ? 00154 { 00155 prev_idx = -1; 00156 vector<int> r; 00157 r.resize (seed_queue.size ()); 00158 for (unsigned int j = 0; j < r.size (); j++) 00159 r[j] = seed_queue[j]; 00160 clusters.push_back (r); 00161 seed_queue.resize (0); 00162 seed_queue.push_back (indices->at (i)); 00163 } 00164 } 00165 // Copy the last laser scan as well 00166 if (seed_queue.size () > 0) 00167 { 00168 vector<int> r; 00169 r.resize (seed_queue.size ()); 00170 for (unsigned int j = 0; j < r.size (); j++) 00171 r[j] = seed_queue[j]; 00172 clusters.push_back (r); 00173 } 00174 } 00175 00177 00182 bool 00183 fitSACLine (sensor_msgs::PointCloud *points, vector<int> *indices, vector<int> &inliers) 00184 { 00185 if ((int)indices->size () < sac_min_points_per_model_) 00186 return (false); 00187 00188 // Create and initialize the SAC model 00189 sample_consensus::SACModelLine *model = new sample_consensus::SACModelLine (); 00190 sample_consensus::SAC *sac = new sample_consensus::RANSAC (model, sac_distance_threshold_); 00191 sac->setMaxIterations (sac_max_iterations_); 00192 sac->setProbability (0.99); 00193 00194 model->setDataSet (points, *indices); 00195 00196 vector<double> line_coeff; 00197 // Search for the best model 00198 if (sac->computeModel (0)) 00199 { 00200 // Obtain the inliers and the planar model coefficients 00201 if ((int)sac->getInliers ().size () < sac_min_points_per_model_) 00202 return (false); 00203 //inliers = sac->getInliers (); 00204 00205 sac->computeCoefficients (line_coeff); // Compute the model coefficients 00206 sac->refineCoefficients (line_coeff); // Refine them using least-squares 00207 model->selectWithinDistance (line_coeff, sac_distance_threshold_, inliers); 00208 00209 // Project the inliers onto the model 00210 //model->projectPointsInPlace (sac->getInliers (), coeff); 00211 } 00212 else 00213 return (false); 00214 00215 delete sac; 00216 delete model; 00217 return (true); 00218 } 00219 00221 // Callback 00222 void cloud_cb (const sensor_msgs::PointCloudConstPtr& msg) 00223 { 00224 cloud_ = *msg; 00225 //check to see if the point cloud is empty 00226 if (cloud_.points.empty ()) 00227 { 00228 ROS_DEBUG("Received an empty point cloud"); 00229 cloud_publisher_.publsih(msg); 00230 return; 00231 } 00232 00233 ROS_INFO ("Received %d data points with %d channels (%s).", (int)cloud_.points.size (), (int)cloud_.channels.size (), cloud_geometry::getAvailableChannels (cloud_).c_str ()); 00234 int idx_idx = cloud_geometry::getChannelIndex (cloud_, "index"); 00235 if (idx_idx == -1) 00236 { 00237 ROS_ERROR ("Channel 'index' missing in input PointCloud message!"); 00238 return; 00239 } 00240 if (cloud_.points.size () == 0) 00241 return; 00242 00243 //updateParametersFromServer (); 00244 // Copy the header 00245 cloud_noground_.header = cloud_.header; 00246 00247 timeval t1, t2; 00248 gettimeofday (&t1, NULL); 00249 00250 // Get the cloud viewpoint 00251 getCloudViewPoint (cloud_.header.frame_id, viewpoint_cloud_, &tf_); 00252 00253 // Transform z_threshold_ from the parameter parameter frame (parameter_frame_) into the point cloud frame 00254 z_threshold_ = transformDoubleValueTF (z_threshold_, "base_footprint", cloud_.header.frame_id, cloud_.header.stamp, &tf_); 00255 00256 // Select points whose Z dimension is close to the ground (0,0,0 in base_footprint) 00257 vector<int> possible_ground_indices (cloud_.points.size ()); 00258 vector<int> all_indices (cloud_.points.size ()); 00259 int nr_p = 0; 00260 for (unsigned int cp = 0; cp < cloud_.points.size (); cp++) 00261 { 00262 all_indices[cp] = cp; 00263 if (fabs (cloud_.points[cp].z) < z_threshold_) 00264 { 00265 possible_ground_indices[nr_p] = cp; 00266 nr_p++; 00267 } 00268 } 00269 possible_ground_indices.resize (nr_p); 00270 00271 ROS_INFO ("Number of possible ground indices: %d.", (int)possible_ground_indices.size ()); 00272 00273 vector<vector<int> > clusters; 00274 // Split the points into clusters based on their laser scan information 00275 splitPointsBasedOnLaserScanIndex (&cloud_, &possible_ground_indices, clusters, idx_idx); 00276 00277 ROS_INFO ("Number of clusters: %d", (int)clusters.size ()); 00278 00279 vector<int> ground_inliers; 00280 nr_p = 0; 00281 00282 // Prepare enough space 00283 vector<vector<int> > cluster_ground_inliers (clusters.size ()); 00284 // Parallelize the search 00285 #pragma omp parallel for schedule(dynamic) 00286 for (int cc = 0; cc < (int)clusters.size (); cc++) 00287 { 00288 // Find the dominant plane in the space of possible ground indices 00289 fitSACLine (&cloud_, &clusters[cc], cluster_ground_inliers[cc]); 00290 } 00291 00292 // Copy the line inliers (ground results) 00293 for (unsigned int cc = 0; cc < cluster_ground_inliers.size (); cc++) 00294 { 00295 if (cluster_ground_inliers[cc].size () == 0) 00296 ROS_WARN ("Couldn't fit a model for cluster %d (%d points).", cc, (int)clusters[cc].size ()); 00297 00298 int cur_size = ground_inliers.size (); 00299 ground_inliers.resize (cur_size + cluster_ground_inliers[cc].size ()); 00300 for (unsigned int i = 0; i < cluster_ground_inliers[cc].size (); i++) 00301 ground_inliers[cur_size + i] = cluster_ground_inliers[cc][i]; 00302 } 00303 ROS_INFO ("Total number of ground inliers before refinement: %d.", (int)ground_inliers.size ()); 00304 00305 // Do we attempt to do a planar refinement to remove points "below" the plane model found ? 00306 if (planar_refine_ > 0) 00307 { 00308 // Get the remaining point indices 00309 vector<int> remaining_possible_ground_indices; 00310 sort (possible_ground_indices.begin (), possible_ground_indices.end ()); 00311 sort (ground_inliers.begin (), ground_inliers.end ()); 00312 set_difference (possible_ground_indices.begin (), possible_ground_indices.end (), ground_inliers.begin (), ground_inliers.end (), 00313 inserter (remaining_possible_ground_indices, remaining_possible_ground_indices.begin ())); 00314 00315 // Estimate the plane from the line inliers 00316 Eigen::Vector4d plane_parameters; 00317 double curvature; 00318 cloud_geometry::nearest::computePointNormal (cloud_, ground_inliers, plane_parameters, curvature); 00319 00320 //make sure that there are inliers to refine 00321 if (!ground_inliers.empty ()) 00322 { 00323 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, cloud_.points.at (ground_inliers[0]), viewpoint_cloud_); 00324 00325 // Compute the distance from the remaining points to the model plane, and add to the inliers list if they are below 00326 for (unsigned int i = 0; i < remaining_possible_ground_indices.size (); i++) 00327 { 00328 double distance_to_ground = cloud_geometry::distances::pointToPlaneDistanceSigned (cloud_.points.at (remaining_possible_ground_indices[i]), plane_parameters); 00329 if (distance_to_ground > 0) 00330 continue; 00331 ground_inliers.push_back (remaining_possible_ground_indices[i]); 00332 } 00333 } 00334 } 00335 ROS_INFO ("Total number of ground inliers after refinement: %d.", (int)ground_inliers.size ()); 00336 00337 #if DEBUG 00338 // Prepare new arrays 00339 cloud_noground_.points.resize (possible_ground_indices.size ()); 00340 cloud_noground_.channels.resize (1); 00341 cloud_noground_.channels[0].name = "rgb"; 00342 cloud_noground_.channels[0].values.resize (possible_ground_indices.size ()); 00343 00344 cloud_noground_.points.resize (ground_inliers.size ()); 00345 cloud_noground_.channels[0].values.resize (ground_inliers.size ()); 00346 float r = rand () / (RAND_MAX + 1.0); 00347 float g = rand () / (RAND_MAX + 1.0); 00348 float b = rand () / (RAND_MAX + 1.0); 00349 00350 for (unsigned int i = 0; i < ground_inliers.size (); i++) 00351 { 00352 cloud_noground_.points[i].x = cloud_.points.at (ground_inliers[i]).x; 00353 cloud_noground_.points[i].y = cloud_.points.at (ground_inliers[i]).y; 00354 cloud_noground_.points[i].z = cloud_.points.at (ground_inliers[i]).z; 00355 cloud_noground_.channels[0].values[i] = getRGB (r, g, b); 00356 } 00357 cloud_publisher_.publish(cloud_noground_); 00358 00359 return; 00360 #endif 00361 00362 // Get all the non-ground point indices 00363 vector<int> remaining_indices; 00364 sort (ground_inliers.begin (), ground_inliers.end ()); 00365 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (), 00366 inserter (remaining_indices, remaining_indices.begin ())); 00367 00368 // Prepare new arrays 00369 int nr_remaining_pts = remaining_indices.size (); 00370 cloud_noground_.points.resize (nr_remaining_pts); 00371 cloud_noground_.channels.resize (cloud_.channels.size ()); 00372 for (unsigned int d = 0; d < cloud_.channels.size (); d++) 00373 { 00374 cloud_noground_.channels[d].name = cloud_.channels[d].name; 00375 cloud_noground_.channels[d].values.resize (nr_remaining_pts); 00376 } 00377 00378 for (unsigned int i = 0; i < remaining_indices.size (); i++) 00379 { 00380 cloud_noground_.points[i].x = cloud_.points.at (remaining_indices[i]).x; 00381 cloud_noground_.points[i].y = cloud_.points.at (remaining_indices[i]).y; 00382 cloud_noground_.points[i].z = cloud_.points.at (remaining_indices[i]).z; 00383 for (unsigned int d = 0; d < cloud_.channels.size (); d++) 00384 cloud_noground_.channels[d].values[i] = cloud_.channels[d].values.at (remaining_indices[i]); 00385 } 00386 00387 gettimeofday (&t2, NULL); 00388 double time_spent = t2.tv_sec + (double)t2.tv_usec / 1000000.0 - (t1.tv_sec + (double)t1.tv_usec / 1000000.0); 00389 ROS_INFO ("Number of points found on ground plane: %d ; remaining: %d (%g seconds).", (int)ground_inliers.size (), 00390 (int)remaining_indices.size (), time_spent); 00391 cloud_publisher_.publish (cloud_noground_); 00392 } 00393 00394 00395 00397 00402 void 00403 getCloudViewPoint (string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, tf::TransformListener *tf) 00404 { 00405 // Figure out the viewpoint value in the point cloud frame 00406 geometry_msgs::PointStamped viewpoint_laser; 00407 viewpoint_laser.header.frame_id = "laser_tilt_mount_link"; 00408 // Set the viewpoint in the laser coordinate system to 0, 0, 0 00409 viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0; 00410 00411 try 00412 { 00413 tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud); 00414 ROS_INFO ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (), 00415 viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z); 00416 } 00417 catch (tf::TransformException& ex) 00418 { 00419 ROS_WARN ("Could not transform a point from frame %s to frame %s! %s", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str (), ex.what()); 00420 // Default to 0.05, 0, 0.942768 00421 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768; 00422 } 00423 } 00424 00426 00432 inline void 00433 transformPoint (tf::TransformListener *tf, const std::string &target_frame, 00434 const tf::Stamped< geometry_msgs::Point32 > &stamped_in, tf::Stamped< geometry_msgs::Point32 > &stamped_out) 00435 { 00436 tf::Stamped<tf::Point> tmp; 00437 tmp.stamp_ = stamped_in.stamp_; 00438 tmp.frame_id_ = stamped_in.frame_id_; 00439 tmp[0] = stamped_in.x; 00440 tmp[1] = stamped_in.y; 00441 tmp[2] = stamped_in.z; 00442 00443 try{ 00444 tf->transformPoint (target_frame, tmp, tmp); 00445 } 00446 catch (tf::TransformException& ex) 00447 { 00448 ROS_ERROR("%s", ex.what()); 00449 } 00450 00451 stamped_out.stamp_ = tmp.stamp_; 00452 stamped_out.frame_id_ = tmp.frame_id_; 00453 stamped_out.x = tmp[0]; 00454 stamped_out.y = tmp[1]; 00455 stamped_out.z = tmp[2]; 00456 } 00457 00459 00466 inline double 00467 transformDoubleValueTF (double val, std::string src_frame, std::string tgt_frame, ros::Time stamp, tf::TransformListener *tf) 00468 { 00469 geometry_msgs::Point32 temp; 00470 temp.x = temp.y = 0; 00471 temp.z = val; 00472 tf::Stamped<geometry_msgs::Point32> temp_stamped (temp, stamp, src_frame); 00473 transformPoint (tf, tgt_frame, temp_stamped, temp_stamped); 00474 return (temp_stamped.z); 00475 } 00476 00477 }; 00478 00479 /* ---[ */ 00480 int 00481 main (int argc, char** argv) 00482 { 00483 ros::init (argc, argv, "sac_ground_removal"); 00484 ros::NodeHandle ros_node("~"); 00485 00486 // For efficiency considerations please make sure the input PointCloud is in a frame with Z point upwards 00487 GroundRemoval p (ros_node); 00488 ros::spin (); 00489 00490 return (0); 00491 } 00492 /* ]--- */ 00493