46 #include <Eigen/Eigenvalues>
58 #include <boost/thread.hpp>
92 node_.
param (
"z_threshold", z_threshold_, 0.1);
93 node_.
param (
"ground_slope_threshold", ground_slope_threshold_, 0.0);
94 node_.
param (
"sac_distance_threshold", sac_distance_threshold_, 0.03);
95 node_.
param (
"sac_fitting_distance_threshold", sac_fitting_distance_threshold_, 0.015);
97 node_.
param (
"planar_refine", planar_refine_, 1);
98 node_.
param (
"sac_min_points_per_model", sac_min_points_per_model_, 6);
99 node_.
param (
"sac_max_iterations", sac_max_iterations_, 200);
100 node_.
param (
"robot_footprint_frame", robot_footprint_frame_, std::string(
"base_footprint"));
101 node_.
param (
"laser_tilt_mount_frame", laser_tilt_mount_frame_, std::string(
"laser_tilt_mount_link"));
103 string cloud_topic (
"tilt_laser_cloud_filtered");
105 bool topic_found =
false;
106 std::vector<ros::master::TopicInfo> t_list;
108 for (vector<ros::master::TopicInfo>::iterator it = t_list.begin (); it != t_list.end (); it++)
110 if (it->name == cloud_topic)
117 ROS_WARN (
"Trying to subscribe to %s, but the topic doesn't exist!", cloud_topic.c_str ());
129 cloud_publisher_ = public_node.
advertise<sensor_msgs::PointCloud2> (
"cloud_ground_filtered", 1);
139 node_.
getParam (
"z_threshold", z_threshold_);
140 node_.
getParam (
"ground_slope_threshold", ground_slope_threshold_);
141 node_.
getParam (
"sac_fitting_distance_threshold", sac_fitting_distance_threshold_);
142 node_.
getParam (
"sac_distance_threshold", sac_distance_threshold_);
154 if ((
int)indices->size () < sac_min_points_per_model_)
165 vector<double> line_coeff;
170 if ((
int)sac->
getInliers ().size () < sac_min_points_per_model_)
200 vp_m[0] = viewpoint.point.x - point.x;
201 vp_m[1] = viewpoint.point.y - point.y;
202 vp_m[2] = viewpoint.point.z - point.z;
205 double cos_theta = (vp_m[0] * normal (0) + vp_m[1] * normal (1) + vp_m[2] * normal (2));
210 for (
int d = 0;
d < 3;
d++)
213 normal (3) = -1 * (normal (0) * point.x + normal (1) * point.y + normal (2) * point.z);
226 centroid.x = centroid.y = centroid.z = 0;
228 for (
unsigned int i = 0; i < indices.size (); i++)
230 centroid.x += points.points.at (indices.at (i)).x;
231 centroid.y += points.points.at (indices.at (i)).y;
232 centroid.z += points.points.at (indices.at (i)).z;
235 centroid.x /= indices.size ();
236 centroid.y /= indices.size ();
237 centroid.z /= indices.size ();
252 computeCentroid (points, indices, centroid);
255 covariance_matrix = Eigen::Matrix3d::Zero ();
257 for (
unsigned int j = 0; j < indices.size (); j++)
259 covariance_matrix (0, 0) += (points.points[indices.at (j)].x - centroid.x) * (points.points[indices.at (j)].x - centroid.x);
260 covariance_matrix (0, 1) += (points.points[indices.at (j)].x - centroid.x) * (points.points[indices.at (j)].y - centroid.y);
261 covariance_matrix (0, 2) += (points.points[indices.at (j)].x - centroid.x) * (points.points[indices.at (j)].z - centroid.z);
263 covariance_matrix (1, 0) += (points.points[indices.at (j)].y - centroid.y) * (points.points[indices.at (j)].x - centroid.x);
264 covariance_matrix (1, 1) += (points.points[indices.at (j)].y - centroid.y) * (points.points[indices.at (j)].y - centroid.y);
265 covariance_matrix (1, 2) += (points.points[indices.at (j)].y - centroid.y) * (points.points[indices.at (j)].z - centroid.z);
267 covariance_matrix (2, 0) += (points.points[indices.at (j)].z - centroid.z) * (points.points[indices.at (j)].x - centroid.x);
268 covariance_matrix (2, 1) += (points.points[indices.at (j)].z - centroid.z) * (points.points[indices.at (j)].y - centroid.y);
269 covariance_matrix (2, 2) += (points.points[indices.at (j)].z - centroid.z) * (points.points[indices.at (j)].z - centroid.z);
287 pcl::PointXYZ centroid;
289 Eigen::Matrix3d covariance_matrix;
290 computeCovarianceMatrix (points, indices, covariance_matrix, centroid);
293 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> ei_symm (covariance_matrix);
294 Eigen::Vector3d eigen_values = ei_symm.eigenvalues ();
295 Eigen::Matrix3d eigen_vectors = ei_symm.eigenvectors ();
299 double norm = sqrt ( eigen_vectors (0, 0) * eigen_vectors (0, 0) +
300 eigen_vectors (1, 0) * eigen_vectors (1, 0) +
301 eigen_vectors (2, 0) * eigen_vectors (2, 0));
302 plane_parameters (0) = eigen_vectors (0, 0) / norm;
303 plane_parameters (1) = eigen_vectors (1, 0) / norm;
304 plane_parameters (2) = eigen_vectors (2, 0) / norm;
307 plane_parameters (3) = -1 * (plane_parameters (0) * centroid.x + plane_parameters (1) * centroid.y + plane_parameters (2) * centroid.z);
310 curvature = fabs ( eigen_values (0) / (eigen_values (0) + eigen_values (1) + eigen_values (2)) );
315 void cloud_cb (
const sensor_msgs::PointCloud2::ConstPtr& msg)
319 if(laser_cloud_.points.empty()){
320 ROS_DEBUG(
"Received an empty point cloud");
329 ROS_ERROR(
"Can't transform cloud for ground plane detection");
333 ROS_DEBUG (
"Received %d data points.", (
int)cloud_.points.size ());
334 if (cloud_.points.size () == 0)
339 cloud_noground_.header = cloud_.header;
342 gettimeofday (&t1, NULL);
345 getCloudViewPoint (cloud_.header.frame_id, viewpoint_cloud_, &tf_);
349 double z_threshold_cloud = transformDoubleValueTF (z_threshold_, robot_footprint_frame_, cloud_.header.frame_id,
header.stamp, &tf_);
352 vector<int> possible_ground_indices (cloud_.points.size ());
353 vector<int> all_indices (cloud_.points.size ());
355 for (
unsigned int cp = 0; cp < cloud_.points.size (); cp++)
357 all_indices[cp] = cp;
358 if (fabs (cloud_.points[cp].z) < z_threshold_cloud ||
359 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))
361 possible_ground_indices[nr_p] = cp;
365 possible_ground_indices.resize (nr_p);
367 ROS_DEBUG (
"Number of possible ground indices: %d.", (
int)possible_ground_indices.size ());
369 vector<int> ground_inliers;
372 fitSACLine (&cloud_, &possible_ground_indices, ground_inliers);
375 if (ground_inliers.size () == 0){
376 ROS_DEBUG (
"Couldn't fit a model to the scan.");
378 ground_inliers = possible_ground_indices;
381 ROS_DEBUG (
"Total number of ground inliers before refinement: %d.", (
int)ground_inliers.size ());
384 if (planar_refine_ > 0)
387 vector<int> remaining_possible_ground_indices;
388 sort (all_indices.begin (), all_indices.end ());
389 sort (ground_inliers.begin (), ground_inliers.end ());
390 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (),
391 inserter (remaining_possible_ground_indices, remaining_possible_ground_indices.begin ()));
394 Eigen::Vector4d plane_parameters;
396 computePointNormal (cloud_, ground_inliers, plane_parameters, curvature);
399 if (!ground_inliers.empty ())
401 flipNormalTowardsViewpoint (plane_parameters, cloud_.points.at (ground_inliers[0]), viewpoint_cloud_);
404 for (
unsigned int i = 0; i < remaining_possible_ground_indices.size (); i++)
406 double distance_to_ground = pointToPlaneDistanceSigned (cloud_.points.at (remaining_possible_ground_indices[i]), plane_parameters);
407 if (distance_to_ground >= 1e-6){
410 ground_inliers.push_back (remaining_possible_ground_indices[i]);
414 ROS_DEBUG (
"Total number of ground inliers after refinement: %d.", (
int)ground_inliers.size ());
417 vector<int> remaining_indices;
418 sort (ground_inliers.begin (), ground_inliers.end ());
419 sort (all_indices.begin(), all_indices.end());
420 set_difference (all_indices.begin (), all_indices.end (), ground_inliers.begin (), ground_inliers.end (),
421 inserter (remaining_indices, remaining_indices.begin ()));
424 int nr_remaining_pts = remaining_indices.size ();
425 cloud_noground_.points.resize (nr_remaining_pts);
427 for (
unsigned int i = 0; i < remaining_indices.size (); i++)
429 cloud_noground_.points[i].x = cloud_.points.at (remaining_indices[i]).x;
430 cloud_noground_.points[i].y = cloud_.points.at (remaining_indices[i]).y;
431 cloud_noground_.points[i].z = cloud_.points.at (remaining_indices[i]).z;
434 gettimeofday (&t2, NULL);
435 double time_spent = t2.tv_sec + (double)t2.tv_usec / 1000000.0 - (t1.tv_sec + (
double)t1.tv_usec / 1000000.0);
436 ROS_DEBUG (
"Number of points found on ground plane: %d ; remaining: %d (%g seconds).", (
int)ground_inliers.size (),
437 (
int)remaining_indices.size (), time_spent);
438 sensor_msgs::PointCloud2 out;
440 cloud_publisher_.
publish (out);
452 return ( plane_coefficients (0) * p.x + plane_coefficients (1) * p.y + plane_coefficients (2) * p.z + plane_coefficients (3) );
465 geometry_msgs::PointStamped viewpoint_laser;
466 viewpoint_laser.header.frame_id = laser_tilt_mount_frame_;
468 viewpoint_laser.point.x = viewpoint_laser.point.y = viewpoint_laser.point.z = 0.0;
472 tf->transformPoint (cloud_frame, viewpoint_laser, viewpoint_cloud);
473 ROS_DEBUG (
"Cloud view point in frame %s is: %g, %g, %g.", cloud_frame.c_str (),
474 viewpoint_cloud.point.x, viewpoint_cloud.point.y, viewpoint_cloud.point.z);
478 ROS_WARN (
"Could not transform a point from frame %s to frame %s!", viewpoint_laser.header.frame_id.c_str (), cloud_frame.c_str ());
480 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
483 ROS_ERROR(
"Can't transform viewpoint for ground plan detection");
484 viewpoint_cloud.point.x = 0.05; viewpoint_cloud.point.y = 0.0; viewpoint_cloud.point.z = 0.942768;
502 tmp[0] = stamped_in.x;
503 tmp[1] = stamped_in.y;
504 tmp[2] = stamped_in.z;
507 tf->transformPoint (target_frame, tmp, tmp);
510 ROS_ERROR(
"Can't transform cloud for ground plane detection");
516 stamped_out.x = tmp[0];
517 stamped_out.y = tmp[1];
518 stamped_out.z = tmp[2];
536 transformPoint (
tf, tgt_frame, temp_stamped, temp_stamped);
537 return (temp_stamped.z);
546 ros::init (argc, argv,
"sac_ground_removal");