$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 00047 // Sample Consensus 00048 #include <point_cloud_mapping/sample_consensus/sac.h> 00049 #include <point_cloud_mapping/sample_consensus/msac.h> 00050 #include <point_cloud_mapping/sample_consensus/ransac.h> 00051 #include <point_cloud_mapping/sample_consensus/lmeds.h> 00052 #include <point_cloud_mapping/sample_consensus/sac_model_line.h> 00053 00054 // Cloud geometry 00055 #include <point_cloud_mapping/geometry/areas.h> 00056 #include <point_cloud_mapping/geometry/angles.h> 00057 #include <point_cloud_mapping/geometry/point.h> 00058 #include <point_cloud_mapping/geometry/distances.h> 00059 #include <point_cloud_mapping/geometry/nearest.h> 00060 00061 #include <tf/transform_listener.h> 00062 #include "tf/message_filter.h" 00063 #include "message_filters/subscriber.h" 00064 00065 #include <sys/time.h> 00066 00067 #include <boost/thread.hpp> 00068 00069 using namespace std; 00070 using namespace mapping_msgs; 00071 00072 class IncGroundRemoval 00073 { 00074 protected: 00075 ros::NodeHandle& node_; 00076 00077 public: 00078 00079 // ROS messages 00080 sensor_msgs::PointCloud laser_cloud_, cloud_, cloud_noground_; 00081 00082 tf::TransformListener tf_; 00083 geometry_msgs::PointStamped viewpoint_cloud_; 00084 tf::MessageFilter<sensor_msgs::PointCloud>* cloud_notifier_; 00085 message_filters::Subscriber<sensor_msgs::PointCloud>* cloud_subscriber_; 00086 00087 // Parameters 00088 double z_threshold_, ground_slope_threshold_; 00089 int sac_min_points_per_model_, sac_max_iterations_; 00090 double sac_distance_threshold_; 00091 double sac_fitting_distance_threshold_; 00092 int planar_refine_; 00093 std::string robot_footprint_frame_, laser_tilt_mount_frame_; 00094 00095 ros::Publisher cloud_publisher_; 00096 00098 IncGroundRemoval (ros::NodeHandle& anode) : node_ (anode) 00099 { 00100 node_.param ("z_threshold", z_threshold_, 0.1); // 10cm threshold for ground removal 00101 node_.param ("ground_slope_threshold", ground_slope_threshold_, 0.0); // 0% slope threshold for ground removal 00102 node_.param ("sac_distance_threshold", sac_distance_threshold_, 0.03); // 3 cm threshold 00103 node_.param ("sac_fitting_distance_threshold", sac_fitting_distance_threshold_, 0.015); // 1.5 cm threshold 00104 00105 node_.param ("planar_refine", planar_refine_, 1); // enable a final planar refinement step? 00106 node_.param ("sac_min_points_per_model", sac_min_points_per_model_, 6); // 6 points minimum per line 00107 node_.param ("sac_max_iterations", sac_max_iterations_, 200); // maximum 200 iterations 00108 node_.param ("robot_footprint_frame", robot_footprint_frame_, std::string("base_footprint")); 00109 node_.param ("laser_tilt_mount_frame", laser_tilt_mount_frame_, std::string("laser_tilt_mount_link")); 00110 00111 string cloud_topic ("tilt_laser_cloud_filtered"); 00112 00113 bool topic_found = false; 00114 std::vector<ros::master::TopicInfo> t_list; 00115 ros::master::getTopics (t_list); 00116 for (vector<ros::master::TopicInfo>::iterator it = t_list.begin (); it != t_list.end (); it++) 00117 { 00118 if (it->name == cloud_topic) 00119 { 00120 topic_found = true; 00121 break; 00122 } 00123 } 00124 if (!topic_found) 00125 ROS_WARN ("Trying to subscribe to %s, but the topic doesn't exist!", cloud_topic.c_str ()); 00126 00127 ros::NodeHandle public_node; 00128 00129 //subscribe (cloud_topic.c_str (), laser_cloud_, &IncGroundRemoval::cloud_cb, 1); 00130 cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::PointCloud>(public_node,cloud_topic,50); 00131 cloud_notifier_ = new tf::MessageFilter<sensor_msgs::PointCloud>(*cloud_subscriber_,tf_,"odom_combined",50); 00132 cloud_notifier_->registerCallback(boost::bind(&IncGroundRemoval::cloud_cb,this,_1)); 00133 00134 // cloud_notifier_ = new tf::MessageNotifier<sensor_msgs::PointCloud> (&tf_, node_, 00135 // boost::bind (&IncGroundRemoval::cloud_cb, this, _1), cloud_topic, "odom_combined", 50); 00136 00137 cloud_publisher_ = public_node.advertise<sensor_msgs::PointCloud> ("cloud_ground_filtered", 1); 00138 } 00139 00141 virtual ~IncGroundRemoval () { delete cloud_notifier_; } 00142 00144 void 00145 updateParametersFromServer () 00146 { 00147 node_.getParam ("z_threshold", z_threshold_); 00148 node_.getParam ("ground_slope_threshold", ground_slope_threshold_); 00149 node_.getParam ("sac_fitting_distance_threshold", sac_fitting_distance_threshold_); 00150 node_.getParam ("sac_distance_threshold", sac_distance_threshold_); 00151 } 00152 00154 00160 void 00161 splitPointsBasedOnLaserScanIndex (sensor_msgs::PointCloud *points, vector<int> *indices, vector<vector<int> > &clusters, int idx) 00162 { 00163 vector<int> seed_queue; 00164 int prev_idx = -1; 00165 // Process all points in the indices vector 00166 for (unsigned int i = 0; i < indices->size (); i++) 00167 { 00168 // Get the current laser scan measurement index 00169 int cur_idx = points->channels[idx].values.at (indices->at (i)); 00170 00171 if (cur_idx > prev_idx) // Still the same laser scan ? 00172 { 00173 seed_queue.push_back (indices->at (i)); 00174 prev_idx = cur_idx; 00175 } 00176 else // Have we found a new scan ? 00177 { 00178 prev_idx = -1; 00179 vector<int> r; 00180 r.resize (seed_queue.size ()); 00181 for (unsigned int j = 0; j < r.size (); j++) 00182 r[j] = seed_queue[j]; 00183 clusters.push_back (r); 00184 seed_queue.resize (0); 00185 } 00186 } 00187 // Copy the last laser scan as well 00188 if (seed_queue.size () > 0) 00189 { 00190 vector<int> r; 00191 r.resize (seed_queue.size ()); 00192 for (unsigned int j = 0; j < r.size (); j++) 00193 r[j] = seed_queue[j]; 00194 clusters.push_back (r); 00195 } 00196 } 00197 00199 00204 bool 00205 fitSACLine (sensor_msgs::PointCloud *points, vector<int> *indices, vector<int> &inliers) 00206 { 00207 if ((int)indices->size () < sac_min_points_per_model_) 00208 return (false); 00209 00210 // Create and initialize the SAC model 00211 sample_consensus::SACModelLine *model = new sample_consensus::SACModelLine (); 00212 sample_consensus::SAC *sac = new sample_consensus::RANSAC (model, sac_fitting_distance_threshold_); 00213 sac->setMaxIterations (sac_max_iterations_); 00214 sac->setProbability (0.99); 00215 00216 model->setDataSet (points, *indices); 00217 00218 vector<double> line_coeff; 00219 // Search for the best model 00220 if (sac->computeModel (0)) 00221 { 00222 // Obtain the inliers and the planar model coefficients 00223 if ((int)sac->getInliers ().size () < sac_min_points_per_model_) 00224 return (false); 00225 //inliers = sac->getInliers (); 00226 00227 sac->computeCoefficients (line_coeff); // Compute the model coefficients 00228 sac->refineCoefficients (line_coeff); // Refine them using least-squares 00229 model->selectWithinDistance (line_coeff, sac_distance_threshold_, inliers); 00230 00231 // Project the inliers onto the model 00232 //model->projectPointsInPlace (sac->getInliers (), coeff); 00233 } 00234 else 00235 return (false); 00236 00237 delete sac; 00238 delete model; 00239 return (true); 00240 } 00241 00243 // Callback 00244 void cloud_cb (const sensor_msgs::PointCloudConstPtr& msg) 00245 { 00246 laser_cloud_ = *msg; 00247 //check to see if the point cloud is empty 00248 if(laser_cloud_.points.empty()){ 00249 ROS_DEBUG("Received an empty point cloud"); 00250 cloud_publisher_.publish(msg); 00251 return; 00252 } 00253 00254 try{ 00255 tf_.transformPointCloud("odom_combined", laser_cloud_, cloud_); 00256 } 00257 catch(tf::TransformException &ex){ 00258 ROS_ERROR("Can't transform cloud for ground plane detection"); 00259 return; 00260 } 00261 00262 ROS_DEBUG ("Received %d data points with %d channels (%s).", (int)cloud_.points.size (), (int)cloud_.channels.size (), cloud_geometry::getAvailableChannels (cloud_).c_str ()); 00263 int idx_idx = cloud_geometry::getChannelIndex (cloud_, "index"); 00264 if (idx_idx == -1) 00265 { 00266 ROS_ERROR ("Channel 'index' missing in input PointCloud message!"); 00267 return; 00268 } 00269 if (cloud_.points.size () == 0) 00270 return; 00271 00272 //updateParametersFromServer (); 00273 // Copy the header 00274 cloud_noground_.header = cloud_.header; 00275 00276 timeval t1, t2; 00277 gettimeofday (&t1, NULL); 00278 00279 // Get the cloud viewpoint 00280 getCloudViewPoint (cloud_.header.frame_id, viewpoint_cloud_, &tf_); 00281 00282 // Transform z_threshold_ from the parameter parameter frame (parameter_frame_) into the point cloud frame 00283 double z_threshold_cloud = transformDoubleValueTF (z_threshold_, robot_footprint_frame_, cloud_.header.frame_id, cloud_.header.stamp, &tf_); 00284 00285 // Select points whose Z dimension is close to the ground (0,0,0 in base_footprint) or under a gentle slope (allowing for pitch/roll error) 00286 vector<int> possible_ground_indices (cloud_.points.size ()); 00287 vector<int> all_indices (cloud_.points.size ()); 00288 int nr_p = 0; 00289 for (unsigned int cp = 0; cp < cloud_.points.size (); cp++) 00290 { 00291 all_indices[cp] = cp; 00292 if (fabs (cloud_.points[cp].z) < z_threshold_cloud || // max height for ground 00293 cloud_.points[cp].z*cloud_.points[cp].z < ground_slope_threshold_ * (cloud_.points[cp].x*cloud_.points[cp].x + cloud_.points[cp].y*cloud_.points[cp].y)) // max slope for ground 00294 { 00295 possible_ground_indices[nr_p] = cp; 00296 nr_p++; 00297 } 00298 } 00299 possible_ground_indices.resize (nr_p); 00300 00301 ROS_DEBUG ("Number of possible ground indices: %d.", (int)possible_ground_indices.size ()); 00302 00303 vector<int> ground_inliers; 00304 00305 // Find the dominant plane in the space of possible ground indices 00306 fitSACLine (&cloud_, &possible_ground_indices, ground_inliers); 00307 00308 00309 if (ground_inliers.size () == 0){ 00310 ROS_DEBUG ("Couldn't fit a model to the scan."); 00311 //if we can't fit a line model to the scan, we have to assume all the possible ground inliers are on the ground 00312 ground_inliers = possible_ground_indices; 00313 } 00314 00315 ROS_DEBUG ("Total number of ground inliers before refinement: %d.", (int)ground_inliers.size ()); 00316 00317 // Do we attempt to do a planar refinement to remove points "below" the plane model found ? 00318 if (planar_refine_ > 0) 00319 { 00320 // Get the remaining point indices 00321 vector<int> remaining_possible_ground_indices; 00322 sort (all_indices.begin (), all_indices.end ()); 00323 sort (ground_inliers.begin (), ground_inliers.end ()); 00324 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (), 00325 inserter (remaining_possible_ground_indices, remaining_possible_ground_indices.begin ())); 00326 00327 // Estimate the plane from the line inliers 00328 Eigen::Vector4d plane_parameters; 00329 double curvature; 00330 cloud_geometry::nearest::computePointNormal (cloud_, ground_inliers, plane_parameters, curvature); 00331 00332 //make sure that there are inliers to refine 00333 if (!ground_inliers.empty ()) 00334 { 00335 cloud_geometry::angles::flipNormalTowardsViewpoint (plane_parameters, cloud_.points.at (ground_inliers[0]), viewpoint_cloud_); 00336 00337 // Compute the distance from the remaining points to the model plane, and add to the inliers list if they are below 00338 for (unsigned int i = 0; i < remaining_possible_ground_indices.size (); i++) 00339 { 00340 double distance_to_ground = cloud_geometry::distances::pointToPlaneDistanceSigned (cloud_.points.at (remaining_possible_ground_indices[i]), plane_parameters); 00341 if (distance_to_ground >= 1e-6){ 00342 continue; 00343 } 00344 ground_inliers.push_back (remaining_possible_ground_indices[i]); 00345 } 00346 } 00347 } 00348 ROS_DEBUG ("Total number of ground inliers after refinement: %d.", (int)ground_inliers.size ()); 00349 00350 #if DEBUG 00351 // Prepare new arrays 00352 cloud_noground_.points.resize (possible_ground_indices.size ()); 00353 cloud_noground_.channels.resize (1); 00354 cloud_noground_.channels[0].name = "rgb"; 00355 cloud_noground_.channels[0].values.resize (possible_ground_indices.size ()); 00356 00357 cloud_noground_.points.resize (ground_inliers.size ()); 00358 cloud_noground_.channels[0].values.resize (ground_inliers.size ()); 00359 float r = rand () / (RAND_MAX + 1.0); 00360 float g = rand () / (RAND_MAX + 1.0); 00361 float b = rand () / (RAND_MAX + 1.0); 00362 00363 for (unsigned int i = 0; i < ground_inliers.size (); i++) 00364 { 00365 cloud_noground_.points[i].x = cloud_.points.at (ground_inliers[i]).x; 00366 cloud_noground_.points[i].y = cloud_.points.at (ground_inliers[i]).y; 00367 cloud_noground_.points[i].z = cloud_.points.at (ground_inliers[i]).z; 00368 cloud_noground_.channels[0].values[i] = getRGB (r, g, b); 00369 } 00370 cloud_publisher_.publish (cloud_noground_); 00371 00372 return; 00373 #endif 00374 00375 // Get all the non-ground point indices 00376 vector<int> remaining_indices; 00377 sort (ground_inliers.begin (), ground_inliers.end ()); 00378 sort (all_indices.begin(), all_indices.end()); 00379 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (), 00380 inserter (remaining_indices, remaining_indices.begin ())); 00381 00382 // Prepare new arrays 00383 int nr_remaining_pts = remaining_indices.size (); 00384 cloud_noground_.points.resize (nr_remaining_pts); 00385 cloud_noground_.channels.resize (cloud_.channels.size ()); 00386 for (unsigned int d = 0; d < cloud_.channels.size (); d++) 00387 { 00388 cloud_noground_.channels[d].name = cloud_.channels[d].name; 00389 cloud_noground_.channels[d].values.resize (nr_remaining_pts); 00390 } 00391 00392 for (unsigned int i = 0; i < remaining_indices.size (); i++) 00393 { 00394 cloud_noground_.points[i].x = cloud_.points.at (remaining_indices[i]).x; 00395 cloud_noground_.points[i].y = cloud_.points.at (remaining_indices[i]).y; 00396 cloud_noground_.points[i].z = cloud_.points.at (remaining_indices[i]).z; 00397 for (unsigned int d = 0; d < cloud_.channels.size (); d++) 00398 cloud_noground_.channels[d].values[i] = cloud_.channels[d].values.at (remaining_indices[i]); 00399 } 00400 00401 gettimeofday (&t2, NULL); 00402 double time_spent = t2.tv_sec + (double)t2.tv_usec / 1000000.0 - (t1.tv_sec + (double)t1.tv_usec / 1000000.0); 00403 ROS_DEBUG ("Number of points found on ground plane: %d ; remaining: %d (%g seconds).", (int)ground_inliers.size (), 00404 (int)remaining_indices.size (), time_spent); 00405 cloud_publisher_.publish (cloud_noground_); 00406 } 00407 00408 00409 00411 00416 void 00417 getCloudViewPoint (string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, tf::TransformListener *tf) 00418 { 00419 // Figure out the viewpoint value in the point cloud frame 00420 geometry_msgs::PointStamped viewpoint_laser; 00421 viewpoint_laser.header.frame_id = laser_tilt_mount_frame_; 00422 // Set the viewpoint in the laser coordinate system to 0, 0, 0 00423 viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0; 00424 00425 try 00426 { 00427 tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud); 00428 ROS_DEBUG ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (), 00429 viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z); 00430 } 00431 catch (tf::ConnectivityException) 00432 { 00433 ROS_WARN ("Could not transform a point from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ()); 00434 // Default to 0.05, 0, 0.942768 00435 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768; 00436 } 00437 catch(tf::TransformException &ex){ 00438 ROS_ERROR("Can't transform viewpoint for ground plan detection"); 00439 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768; 00440 } 00441 } 00442 00444 00450 inline void 00451 transformPoint (tf::TransformListener *tf, const std::string &target_frame, 00452 const tf::Stamped< geometry_msgs::Point32 > &stamped_in, tf::Stamped< geometry_msgs::Point32 > &stamped_out) 00453 { 00454 tf::Stamped<tf::Point> tmp; 00455 tmp.stamp_ = stamped_in.stamp_; 00456 tmp.frame_id_ = stamped_in.frame_id_; 00457 tmp[0] = stamped_in.x; 00458 tmp[1] = stamped_in.y; 00459 tmp[2] = stamped_in.z; 00460 00461 try{ 00462 tf->transformPoint (target_frame, tmp, tmp); 00463 } 00464 catch(tf::TransformException &ex){ 00465 ROS_ERROR("Can't transform cloud for ground plane detection"); 00466 return; 00467 } 00468 00469 stamped_out.stamp_ = tmp.stamp_; 00470 stamped_out.frame_id_ = tmp.frame_id_; 00471 stamped_out.x = tmp[0]; 00472 stamped_out.y = tmp[1]; 00473 stamped_out.z = tmp[2]; 00474 } 00475 00477 00484 inline double 00485 transformDoubleValueTF (double val, std::string src_frame, std::string tgt_frame, ros::Time stamp, tf::TransformListener *tf) 00486 { 00487 geometry_msgs::Point32 temp; 00488 temp.x = temp.y = 0; 00489 temp.z = val; 00490 tf::Stamped<geometry_msgs::Point32> temp_stamped (temp, stamp, src_frame); 00491 transformPoint (tf, tgt_frame, temp_stamped, temp_stamped); 00492 return (temp_stamped.z); 00493 } 00494 00495 }; 00496 00497 /* ---[ */ 00498 int 00499 main (int argc, char** argv) 00500 { 00501 ros::init (argc, argv, "sac_ground_removal"); 00502 00503 ros::NodeHandle ros_node ("~"); 00504 00505 // For efficiency considerations please make sure the input PointCloud is in a frame with Z point upwards 00506 IncGroundRemoval p (ros_node); 00507 ros::spin (); 00508 00509 return (0); 00510 } 00511 /* ]--- */ 00512