$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 <Eigen/QR> 00047 #include <Eigen/Eigenvalues> 00048 // Sample Consensus 00049 #include <sac.h> 00050 #include <ransac.h> 00051 #include <sac_model_line.h> 00052 00053 #include <tf/transform_listener.h> 00054 #include "tf/message_filter.h" 00055 #include "message_filters/subscriber.h" 00056 00057 #include <sys/time.h> 00058 00059 #include <boost/thread.hpp> 00060 00061 using namespace std; 00062 00063 class IncGroundRemoval 00064 { 00065 protected: 00066 ros::NodeHandle& node_; 00067 00068 public: 00069 00070 // ROS messages 00071 sensor_msgs::PointCloud laser_cloud_, cloud_, cloud_noground_; 00072 00073 tf::TransformListener tf_; 00074 geometry_msgs::PointStamped viewpoint_cloud_; 00075 tf::MessageFilter<sensor_msgs::PointCloud>* cloud_notifier_; 00076 message_filters::Subscriber<sensor_msgs::PointCloud>* cloud_subscriber_; 00077 00078 // Parameters 00079 double z_threshold_, ground_slope_threshold_; 00080 int sac_min_points_per_model_, sac_max_iterations_; 00081 double sac_distance_threshold_; 00082 double sac_fitting_distance_threshold_; 00083 int planar_refine_; 00084 std::string robot_footprint_frame_, laser_tilt_mount_frame_; 00085 00086 ros::Publisher cloud_publisher_; 00087 00089 IncGroundRemoval (ros::NodeHandle& anode) : node_ (anode) 00090 { 00091 node_.param ("z_threshold", z_threshold_, 0.1); // 10cm threshold for ground removal 00092 node_.param ("ground_slope_threshold", ground_slope_threshold_, 0.0); // 0% slope threshold for ground removal 00093 node_.param ("sac_distance_threshold", sac_distance_threshold_, 0.03); // 3 cm threshold 00094 node_.param ("sac_fitting_distance_threshold", sac_fitting_distance_threshold_, 0.015); // 1.5 cm threshold 00095 00096 node_.param ("planar_refine", planar_refine_, 1); // enable a final planar refinement step? 00097 node_.param ("sac_min_points_per_model", sac_min_points_per_model_, 6); // 6 points minimum per line 00098 node_.param ("sac_max_iterations", sac_max_iterations_, 200); // maximum 200 iterations 00099 node_.param ("robot_footprint_frame", robot_footprint_frame_, std::string("base_footprint")); 00100 node_.param ("laser_tilt_mount_frame", laser_tilt_mount_frame_, std::string("laser_tilt_mount_link")); 00101 00102 string cloud_topic ("tilt_laser_cloud_filtered"); 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 ros::NodeHandle public_node; 00119 00120 //subscribe (cloud_topic.c_str (), laser_cloud_, &IncGroundRemoval::cloud_cb, 1); 00121 cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::PointCloud>(public_node,cloud_topic,50); 00122 cloud_notifier_ = new tf::MessageFilter<sensor_msgs::PointCloud>(*cloud_subscriber_,tf_,"odom_combined",50); 00123 cloud_notifier_->registerCallback(boost::bind(&IncGroundRemoval::cloud_cb,this,_1)); 00124 00125 // cloud_notifier_ = new tf::MessageNotifier<sensor_msgs::PointCloud> (&tf_, node_, 00126 // boost::bind (&IncGroundRemoval::cloud_cb, this, _1), cloud_topic, "odom_combined", 50); 00127 00128 cloud_publisher_ = public_node.advertise<sensor_msgs::PointCloud> ("cloud_ground_filtered", 1); 00129 } 00130 00132 virtual ~IncGroundRemoval () { delete cloud_notifier_; } 00133 00135 void 00136 updateParametersFromServer () 00137 { 00138 node_.getParam ("z_threshold", z_threshold_); 00139 node_.getParam ("ground_slope_threshold", ground_slope_threshold_); 00140 node_.getParam ("sac_fitting_distance_threshold", sac_fitting_distance_threshold_); 00141 node_.getParam ("sac_distance_threshold", sac_distance_threshold_); 00142 } 00143 00145 00151 void 00152 splitPointsBasedOnLaserScanIndex (sensor_msgs::PointCloud *points, vector<int> *indices, vector<vector<int> > &clusters, int idx) 00153 { 00154 vector<int> seed_queue; 00155 int prev_idx = -1; 00156 // Process all points in the indices vector 00157 for (unsigned int i = 0; i < indices->size (); i++) 00158 { 00159 // Get the current laser scan measurement index 00160 int cur_idx = points->channels[idx].values.at (indices->at (i)); 00161 00162 if (cur_idx > prev_idx) // Still the same laser scan ? 00163 { 00164 seed_queue.push_back (indices->at (i)); 00165 prev_idx = cur_idx; 00166 } 00167 else // Have we found a new scan ? 00168 { 00169 prev_idx = -1; 00170 vector<int> r; 00171 r.resize (seed_queue.size ()); 00172 for (unsigned int j = 0; j < r.size (); j++) 00173 r[j] = seed_queue[j]; 00174 clusters.push_back (r); 00175 seed_queue.resize (0); 00176 } 00177 } 00178 // Copy the last laser scan as well 00179 if (seed_queue.size () > 0) 00180 { 00181 vector<int> r; 00182 r.resize (seed_queue.size ()); 00183 for (unsigned int j = 0; j < r.size (); j++) 00184 r[j] = seed_queue[j]; 00185 clusters.push_back (r); 00186 } 00187 } 00188 00190 00195 bool 00196 fitSACLine (sensor_msgs::PointCloud *points, vector<int> *indices, vector<int> &inliers) 00197 { 00198 if ((int)indices->size () < sac_min_points_per_model_) 00199 return (false); 00200 00201 // Create and initialize the SAC model 00202 sample_consensus::SACModelLine *model = new sample_consensus::SACModelLine (); 00203 sample_consensus::SAC *sac = new sample_consensus::RANSAC (model, sac_fitting_distance_threshold_); 00204 sac->setMaxIterations (sac_max_iterations_); 00205 sac->setProbability (0.99); 00206 00207 model->setDataSet (points, *indices); 00208 00209 vector<double> line_coeff; 00210 // Search for the best model 00211 if (sac->computeModel (0)) 00212 { 00213 // Obtain the inliers and the planar model coefficients 00214 if ((int)sac->getInliers ().size () < sac_min_points_per_model_) 00215 return (false); 00216 //inliers = sac->getInliers (); 00217 00218 sac->computeCoefficients (line_coeff); // Compute the model coefficients 00219 sac->refineCoefficients (line_coeff); // Refine them using least-squares 00220 model->selectWithinDistance (line_coeff, sac_distance_threshold_, inliers); 00221 00222 // Project the inliers onto the model 00223 //model->projectPointsInPlace (sac->getInliers (), coeff); 00224 } 00225 else 00226 return (false); 00227 00228 delete sac; 00229 delete model; 00230 return (true); 00231 } 00232 00234 00239 inline void 00240 flipNormalTowardsViewpoint (Eigen::Vector4d &normal, const geometry_msgs::Point32 &point, const geometry_msgs::PointStamped &viewpoint) 00241 { 00242 // See if we need to flip any plane normals 00243 float vp_m[3]; 00244 vp_m[0] = viewpoint.point.x - point.x; 00245 vp_m[1] = viewpoint.point.y - point.y; 00246 vp_m[2] = viewpoint.point.z - point.z; 00247 00248 // Dot product between the (viewpoint - point) and the plane normal 00249 double cos_theta = (vp_m[0] * normal (0) + vp_m[1] * normal (1) + vp_m[2] * normal (2)); 00250 00251 // Flip the plane normal 00252 if (cos_theta < 0) 00253 { 00254 for (int d = 0; d < 3; d++) 00255 normal (d) *= -1; 00256 // Hessian form (D = nc . p_plane (centroid here) + p) 00257 normal (3) = -1 * (normal (0) * point.x + normal (1) * point.y + normal (2) * point.z); 00258 } 00259 } 00260 00262 00267 inline void 00268 computeCentroid (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, geometry_msgs::Point32 ¢roid) 00269 { 00270 centroid.x = centroid.y = centroid.z = 0; 00271 // For each point in the cloud 00272 for (unsigned int i = 0; i < indices.size (); i++) 00273 { 00274 centroid.x += points.points.at (indices.at (i)).x; 00275 centroid.y += points.points.at (indices.at (i)).y; 00276 centroid.z += points.points.at (indices.at (i)).z; 00277 } 00278 00279 centroid.x /= indices.size (); 00280 centroid.y /= indices.size (); 00281 centroid.z /= indices.size (); 00282 } 00283 00285 00293 inline void 00294 computeCovarianceMatrix (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, Eigen::Matrix3d &covariance_matrix, geometry_msgs::Point32 ¢roid) 00295 { 00296 computeCentroid (points, indices, centroid); 00297 00298 // Initialize to 0 00299 covariance_matrix = Eigen::Matrix3d::Zero (); 00300 00301 for (unsigned int j = 0; j < indices.size (); j++) 00302 { 00303 covariance_matrix (0, 0) += (points.points[indices.at (j)].x - centroid.x) * (points.points[indices.at (j)].x - centroid.x); 00304 covariance_matrix (0, 1) += (points.points[indices.at (j)].x - centroid.x) * (points.points[indices.at (j)].y - centroid.y); 00305 covariance_matrix (0, 2) += (points.points[indices.at (j)].x - centroid.x) * (points.points[indices.at (j)].z - centroid.z); 00306 00307 covariance_matrix (1, 0) += (points.points[indices.at (j)].y - centroid.y) * (points.points[indices.at (j)].x - centroid.x); 00308 covariance_matrix (1, 1) += (points.points[indices.at (j)].y - centroid.y) * (points.points[indices.at (j)].y - centroid.y); 00309 covariance_matrix (1, 2) += (points.points[indices.at (j)].y - centroid.y) * (points.points[indices.at (j)].z - centroid.z); 00310 00311 covariance_matrix (2, 0) += (points.points[indices.at (j)].z - centroid.z) * (points.points[indices.at (j)].x - centroid.x); 00312 covariance_matrix (2, 1) += (points.points[indices.at (j)].z - centroid.z) * (points.points[indices.at (j)].y - centroid.y); 00313 covariance_matrix (2, 2) += (points.points[indices.at (j)].z - centroid.z) * (points.points[indices.at (j)].z - centroid.z); 00314 } 00315 } 00316 00318 00328 void 00329 computePointNormal (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, Eigen::Vector4d &plane_parameters, double &curvature) 00330 { 00331 geometry_msgs::Point32 centroid; 00332 // Compute the 3x3 covariance matrix 00333 Eigen::Matrix3d covariance_matrix; 00334 computeCovarianceMatrix (points, indices, covariance_matrix, centroid); 00335 00336 // Extract the eigenvalues and eigenvectors 00337 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix); 00338 Eigen::Vector3d eigen_values = ei_symm.eigenvalues (); 00339 Eigen::Matrix3d eigen_vectors = ei_symm.eigenvectors (); 00340 00341 // Normalize the surface normal (eigenvector corresponding to the smallest eigenvalue) 00342 // Note: Remember to take care of the eigen_vectors ordering 00343 double norm = sqrt ( eigen_vectors (0, 0) * eigen_vectors (0, 0) + 00344 eigen_vectors (1, 0) * eigen_vectors (1, 0) + 00345 eigen_vectors (2, 0) * eigen_vectors (2, 0)); 00346 plane_parameters (0) = eigen_vectors (0, 0) / norm; 00347 plane_parameters (1) = eigen_vectors (1, 0) / norm; 00348 plane_parameters (2) = eigen_vectors (2, 0) / norm; 00349 00350 // Hessian form (D = nc . p_plane (centroid here) + p) 00351 plane_parameters (3) = -1 * (plane_parameters (0) * centroid.x + plane_parameters (1) * centroid.y + plane_parameters (2) * centroid.z); 00352 00353 // Compute the curvature surface change 00354 curvature = fabs ( eigen_values (0) / (eigen_values (0) + eigen_values (1) + eigen_values (2)) ); 00355 } 00356 00358 00362 int 00363 getChannelIndex (const sensor_msgs::PointCloud &points, std::string channel_name) 00364 { 00365 for (unsigned int d = 0; d < points.channels.size (); d++) 00366 if (points.channels[d].name == channel_name) 00367 return (d); 00368 return (-1); 00369 } 00370 00372 00375 std::string 00376 getAvailableChannels (const sensor_msgs::PointCloud &cloud) 00377 { 00378 std::string result; 00379 if (cloud.channels.size () == 0) 00380 return (result); 00381 unsigned int i; 00382 for (i = 0; i < cloud.channels.size () - 1; i++) 00383 { 00384 std::string index = cloud.channels[i].name + " "; 00385 result += index; 00386 } 00387 std::string index = cloud.channels[i].name; 00388 result += index; 00389 return (result); 00390 } 00391 00393 // Callback 00394 void cloud_cb (const sensor_msgs::PointCloudConstPtr& msg) 00395 { 00396 laser_cloud_ = *msg; 00397 //check to see if the point cloud is empty 00398 if(laser_cloud_.points.empty()){ 00399 ROS_DEBUG("Received an empty point cloud"); 00400 cloud_publisher_.publish(msg); 00401 return; 00402 } 00403 00404 try{ 00405 tf_.transformPointCloud("odom_combined", laser_cloud_, cloud_); 00406 } 00407 catch(tf::TransformException &ex){ 00408 ROS_ERROR("Can't transform cloud for ground plane detection"); 00409 return; 00410 } 00411 00412 ROS_DEBUG ("Received %d data points with %d channels (%s).", (int)cloud_.points.size (), (int)cloud_.channels.size (), getAvailableChannels (cloud_).c_str ()); 00413 int idx_idx = getChannelIndex (cloud_, "index"); 00414 if (idx_idx == -1) 00415 { 00416 ROS_ERROR ("Channel 'index' missing in input PointCloud message!"); 00417 return; 00418 } 00419 if (cloud_.points.size () == 0) 00420 return; 00421 00422 //updateParametersFromServer (); 00423 // Copy the header 00424 cloud_noground_.header = cloud_.header; 00425 00426 timeval t1, t2; 00427 gettimeofday (&t1, NULL); 00428 00429 // Get the cloud viewpoint 00430 getCloudViewPoint (cloud_.header.frame_id, viewpoint_cloud_, &tf_); 00431 00432 // Transform z_threshold_ from the parameter parameter frame (parameter_frame_) into the point cloud frame 00433 double z_threshold_cloud = transformDoubleValueTF (z_threshold_, robot_footprint_frame_, cloud_.header.frame_id, cloud_.header.stamp, &tf_); 00434 00435 // 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) 00436 vector<int> possible_ground_indices (cloud_.points.size ()); 00437 vector<int> all_indices (cloud_.points.size ()); 00438 int nr_p = 0; 00439 for (unsigned int cp = 0; cp < cloud_.points.size (); cp++) 00440 { 00441 all_indices[cp] = cp; 00442 if (fabs (cloud_.points[cp].z) < z_threshold_cloud || // max height for ground 00443 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 00444 { 00445 possible_ground_indices[nr_p] = cp; 00446 nr_p++; 00447 } 00448 } 00449 possible_ground_indices.resize (nr_p); 00450 00451 ROS_DEBUG ("Number of possible ground indices: %d.", (int)possible_ground_indices.size ()); 00452 00453 vector<int> ground_inliers; 00454 00455 // Find the dominant plane in the space of possible ground indices 00456 fitSACLine (&cloud_, &possible_ground_indices, ground_inliers); 00457 00458 00459 if (ground_inliers.size () == 0){ 00460 ROS_DEBUG ("Couldn't fit a model to the scan."); 00461 //if we can't fit a line model to the scan, we have to assume all the possible ground inliers are on the ground 00462 ground_inliers = possible_ground_indices; 00463 } 00464 00465 ROS_DEBUG ("Total number of ground inliers before refinement: %d.", (int)ground_inliers.size ()); 00466 00467 // Do we attempt to do a planar refinement to remove points "below" the plane model found ? 00468 if (planar_refine_ > 0) 00469 { 00470 // Get the remaining point indices 00471 vector<int> remaining_possible_ground_indices; 00472 sort (all_indices.begin (), all_indices.end ()); 00473 sort (ground_inliers.begin (), ground_inliers.end ()); 00474 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (), 00475 inserter (remaining_possible_ground_indices, remaining_possible_ground_indices.begin ())); 00476 00477 // Estimate the plane from the line inliers 00478 Eigen::Vector4d plane_parameters; 00479 double curvature; 00480 computePointNormal (cloud_, ground_inliers, plane_parameters, curvature); 00481 00482 //make sure that there are inliers to refine 00483 if (!ground_inliers.empty ()) 00484 { 00485 flipNormalTowardsViewpoint (plane_parameters, cloud_.points.at (ground_inliers[0]), viewpoint_cloud_); 00486 00487 // Compute the distance from the remaining points to the model plane, and add to the inliers list if they are below 00488 for (unsigned int i = 0; i < remaining_possible_ground_indices.size (); i++) 00489 { 00490 double distance_to_ground = pointToPlaneDistanceSigned (cloud_.points.at (remaining_possible_ground_indices[i]), plane_parameters); 00491 if (distance_to_ground >= 1e-6){ 00492 continue; 00493 } 00494 ground_inliers.push_back (remaining_possible_ground_indices[i]); 00495 } 00496 } 00497 } 00498 ROS_DEBUG ("Total number of ground inliers after refinement: %d.", (int)ground_inliers.size ()); 00499 00500 #if DEBUG 00501 // Prepare new arrays 00502 cloud_noground_.points.resize (possible_ground_indices.size ()); 00503 cloud_noground_.channels.resize (1); 00504 cloud_noground_.channels[0].name = "rgb"; 00505 cloud_noground_.channels[0].values.resize (possible_ground_indices.size ()); 00506 00507 cloud_noground_.points.resize (ground_inliers.size ()); 00508 cloud_noground_.channels[0].values.resize (ground_inliers.size ()); 00509 float r = rand () / (RAND_MAX + 1.0); 00510 float g = rand () / (RAND_MAX + 1.0); 00511 float b = rand () / (RAND_MAX + 1.0); 00512 00513 for (unsigned int i = 0; i < ground_inliers.size (); i++) 00514 { 00515 cloud_noground_.points[i].x = cloud_.points.at (ground_inliers[i]).x; 00516 cloud_noground_.points[i].y = cloud_.points.at (ground_inliers[i]).y; 00517 cloud_noground_.points[i].z = cloud_.points.at (ground_inliers[i]).z; 00518 cloud_noground_.channels[0].values[i] = getRGB (r, g, b); 00519 } 00520 cloud_publisher_.publish (cloud_noground_); 00521 00522 return; 00523 #endif 00524 00525 // Get all the non-ground point indices 00526 vector<int> remaining_indices; 00527 sort (ground_inliers.begin (), ground_inliers.end ()); 00528 sort (all_indices.begin(), all_indices.end()); 00529 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (), 00530 inserter (remaining_indices, remaining_indices.begin ())); 00531 00532 // Prepare new arrays 00533 int nr_remaining_pts = remaining_indices.size (); 00534 cloud_noground_.points.resize (nr_remaining_pts); 00535 cloud_noground_.channels.resize (cloud_.channels.size ()); 00536 for (unsigned int d = 0; d < cloud_.channels.size (); d++) 00537 { 00538 cloud_noground_.channels[d].name = cloud_.channels[d].name; 00539 cloud_noground_.channels[d].values.resize (nr_remaining_pts); 00540 } 00541 00542 for (unsigned int i = 0; i < remaining_indices.size (); i++) 00543 { 00544 cloud_noground_.points[i].x = cloud_.points.at (remaining_indices[i]).x; 00545 cloud_noground_.points[i].y = cloud_.points.at (remaining_indices[i]).y; 00546 cloud_noground_.points[i].z = cloud_.points.at (remaining_indices[i]).z; 00547 for (unsigned int d = 0; d < cloud_.channels.size (); d++) 00548 cloud_noground_.channels[d].values[i] = cloud_.channels[d].values.at (remaining_indices[i]); 00549 } 00550 00551 gettimeofday (&t2, NULL); 00552 double time_spent = t2.tv_sec + (double)t2.tv_usec / 1000000.0 - (t1.tv_sec + (double)t1.tv_usec / 1000000.0); 00553 ROS_DEBUG ("Number of points found on ground plane: %d ; remaining: %d (%g seconds).", (int)ground_inliers.size (), 00554 (int)remaining_indices.size (), time_spent); 00555 cloud_publisher_.publish (cloud_noground_); 00556 } 00557 00558 00560 00564 inline double 00565 pointToPlaneDistanceSigned (const geometry_msgs::Point32 &p, const Eigen::Vector4d &plane_coefficients) 00566 { 00567 return ( plane_coefficients (0) * p.x + plane_coefficients (1) * p.y + plane_coefficients (2) * p.z + plane_coefficients (3) ); 00568 } 00569 00571 00576 void 00577 getCloudViewPoint (string cloud_frame, geometry_msgs::PointStamped &viewpoint_cloud, tf::TransformListener *tf) 00578 { 00579 // Figure out the viewpoint value in the point cloud frame 00580 geometry_msgs::PointStamped viewpoint_laser; 00581 viewpoint_laser.header.frame_id = laser_tilt_mount_frame_; 00582 // Set the viewpoint in the laser coordinate system to 0, 0, 0 00583 viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0; 00584 00585 try 00586 { 00587 tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud); 00588 ROS_DEBUG ("Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (), 00589 viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z); 00590 } 00591 catch (tf::ConnectivityException) 00592 { 00593 ROS_WARN ("Could not transform a point from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ()); 00594 // Default to 0.05, 0, 0.942768 00595 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768; 00596 } 00597 catch(tf::TransformException &ex){ 00598 ROS_ERROR("Can't transform viewpoint for ground plan detection"); 00599 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768; 00600 } 00601 } 00602 00604 00610 inline void 00611 transformPoint (tf::TransformListener *tf, const std::string &target_frame, 00612 const tf::Stamped< geometry_msgs::Point32 > &stamped_in, tf::Stamped< geometry_msgs::Point32 > &stamped_out) 00613 { 00614 tf::Stamped<tf::Point> tmp; 00615 tmp.stamp_ = stamped_in.stamp_; 00616 tmp.frame_id_ = stamped_in.frame_id_; 00617 tmp[0] = stamped_in.x; 00618 tmp[1] = stamped_in.y; 00619 tmp[2] = stamped_in.z; 00620 00621 try{ 00622 tf->transformPoint (target_frame, tmp, tmp); 00623 } 00624 catch(tf::TransformException &ex){ 00625 ROS_ERROR("Can't transform cloud for ground plane detection"); 00626 return; 00627 } 00628 00629 stamped_out.stamp_ = tmp.stamp_; 00630 stamped_out.frame_id_ = tmp.frame_id_; 00631 stamped_out.x = tmp[0]; 00632 stamped_out.y = tmp[1]; 00633 stamped_out.z = tmp[2]; 00634 } 00635 00637 00644 inline double 00645 transformDoubleValueTF (double val, std::string src_frame, std::string tgt_frame, ros::Time stamp, tf::TransformListener *tf) 00646 { 00647 geometry_msgs::Point32 temp; 00648 temp.x = temp.y = 0; 00649 temp.z = val; 00650 tf::Stamped<geometry_msgs::Point32> temp_stamped (temp, stamp, src_frame); 00651 transformPoint (tf, tgt_frame, temp_stamped, temp_stamped); 00652 return (temp_stamped.z); 00653 } 00654 00655 }; 00656 00657 /* ---[ */ 00658 int 00659 main (int argc, char** argv) 00660 { 00661 ros::init (argc, argv, "sac_ground_removal"); 00662 00663 ros::NodeHandle ros_node ("~"); 00664 00665 // For efficiency considerations please make sure the input PointCloud is in a frame with Z point upwards 00666 IncGroundRemoval p (ros_node); 00667 ros::spin (); 00668 00669 return (0); 00670 } 00671 /* ]--- */ 00672