laser_scan_matcher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Ivan Dryanovski, William Morris
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the CCNY Robotics Lab nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /* This package uses Canonical Scan Matcher [1], written by
31  * Andrea Censi
32  *
33  * [1] A. Censi, "An ICP variant using a point-to-line metric"
34  * Proceedings of the IEEE International Conference
35  * on Robotics and Automation (ICRA), 2008
36  */
37 
40 #include <boost/assign.hpp>
41 #include <tf/transform_datatypes.h>
42 
43 namespace scan_tools
44 {
45 
47  nh_(nh),
48  nh_private_(nh_private),
49  initialized_(false),
50  received_imu_(false),
51  received_odom_(false),
52  received_vel_(false)
53 {
54  ROS_INFO("Starting LaserScanMatcher");
55 
56  // **** init parameters
57 
58  initParams();
59 
60  // **** state variables
61 
65  input_.laser[0] = 0.0;
66  input_.laser[1] = 0.0;
67  input_.laser[2] = 0.0;
68 
69  // Initialize output_ vectors as Null for error-checking
70  output_.cov_x_m = 0;
71  output_.dx_dy1_m = 0;
72  output_.dx_dy2_m = 0;
73 
74  // **** publishers
75 
76  if (publish_pose_)
77  {
78  pose_publisher_ = nh_.advertise<geometry_msgs::Pose2D>(
79  "pose2D", 5);
80  }
81 
83  {
84  pose_stamped_publisher_ = nh_.advertise<geometry_msgs::PoseStamped>(
85  "pose_stamped", 5);
86  }
87 
89  {
90  pose_with_covariance_publisher_ = nh_.advertise<geometry_msgs::PoseWithCovariance>(
91  "pose_with_covariance", 5);
92  }
93 
95  {
96  pose_with_covariance_stamped_publisher_ = nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>(
97  "pose_with_covariance_stamped", 5);
98  }
99 
100  // *** subscribers
101 
102  if (use_cloud_input_)
103  {
105  "cloud", 1, &LaserScanMatcher::cloudCallback, this);
106  }
107  else
108  {
110  "scan", 1, &LaserScanMatcher::scanCallback, this);
111  }
112 
113  if (use_imu_)
114  {
116  "imu/data", 1, &LaserScanMatcher::imuCallback, this);
117  }
118  if (use_odom_)
119  {
121  "odom", 1, &LaserScanMatcher::odomCallback, this);
122  }
123  if (use_vel_)
124  {
125  if (stamped_vel_)
127  "vel", 1, &LaserScanMatcher::velStmpCallback, this);
128  else
130  "vel", 1, &LaserScanMatcher::velCallback, this);
131  }
132 }
133 
135 {
136  ROS_INFO("Destroying LaserScanMatcher");
137 }
138 
140 {
141  if (!nh_private_.getParam ("base_frame", base_frame_))
142  base_frame_ = "base_link";
143  if (!nh_private_.getParam ("fixed_frame", fixed_frame_))
144  fixed_frame_ = "world";
145 
146  // **** input type - laser scan, or point clouds?
147  // if false, will subscribe to LaserScan msgs on /scan.
148  // if true, will subscribe to PointCloud2 msgs on /cloud
149 
150  if (!nh_private_.getParam ("use_cloud_input", use_cloud_input_))
151  use_cloud_input_= false;
152 
153  if (use_cloud_input_)
154  {
155  if (!nh_private_.getParam ("cloud_range_min", cloud_range_min_))
156  cloud_range_min_ = 0.1;
157  if (!nh_private_.getParam ("cloud_range_max", cloud_range_max_))
158  cloud_range_max_ = 50.0;
159  if (!nh_private_.getParam ("cloud_res", cloud_res_))
160  cloud_res_ = 0.05;
161 
164  }
165 
166  // **** keyframe params: when to generate the keyframe scan
167  // if either is set to 0, reduces to frame-to-frame matching
168 
169  if (!nh_private_.getParam ("kf_dist_linear", kf_dist_linear_))
170  kf_dist_linear_ = 0.10;
171  if (!nh_private_.getParam ("kf_dist_angular", kf_dist_angular_))
172  kf_dist_angular_ = 10.0 * (M_PI / 180.0);
173 
175 
176  // **** What predictions are available to speed up the ICP?
177  // 1) imu - [theta] from imu yaw angle - /imu topic
178  // 2) odom - [x, y, theta] from wheel odometry - /odom topic
179  // 3) vel - [x, y, theta] from velocity predictor - see alpha-beta predictors - /vel topic
180  // If more than one is enabled, priority is imu > odom > vel
181 
182  if (!nh_private_.getParam ("use_imu", use_imu_))
183  use_imu_ = true;
184  if (!nh_private_.getParam ("use_odom", use_odom_))
185  use_odom_ = true;
186  if (!nh_private_.getParam ("use_tf", use_tf_))
187  use_tf_ = true;
188  if (!nh_private_.getParam ("tf_timeout", tf_timeout_))
189  tf_timeout_ = 0.1;
190  if (!nh_private_.getParam ("use_vel", use_vel_))
191  use_vel_ = false;
192 
193  // **** Are velocity input messages stamped?
194  // if false, will subscribe to Twist msgs on /vel
195  // if true, will subscribe to TwistStamped msgs on /vel
196  if (!nh_private_.getParam ("stamped_vel", stamped_vel_))
197  stamped_vel_ = false;
198 
199  // **** How to publish the output?
200  // tf (fixed_frame->base_frame),
201  // pose message (pose of base frame in the fixed frame)
202 
203  if (!nh_private_.getParam ("publish_tf", publish_tf_))
204  publish_tf_ = true;
205  if (!nh_private_.getParam ("publish_pose", publish_pose_))
206  publish_pose_ = true;
207  if (!nh_private_.getParam ("publish_pose_stamped", publish_pose_stamped_))
208  publish_pose_stamped_ = false;
209  if (!nh_private_.getParam ("publish_pose_with_covariance", publish_pose_with_covariance_))
211  if (!nh_private_.getParam ("publish_pose_with_covariance_stamped", publish_pose_with_covariance_stamped_))
213 
214  if (!nh_private_.getParam("position_covariance", position_covariance_))
215  {
216  position_covariance_.resize(3);
217  std::fill(position_covariance_.begin(), position_covariance_.end(), 1e-9);
218  }
219 
220  if (!nh_private_.getParam("orientation_covariance", orientation_covariance_))
221  {
222  orientation_covariance_.resize(3);
223  std::fill(orientation_covariance_.begin(), orientation_covariance_.end(), 1e-9);
224  }
225  // **** CSM parameters - comments copied from algos.h (by Andrea Censi)
226 
227  // Maximum angular displacement between scans
228  if (!nh_private_.getParam ("max_angular_correction_deg", input_.max_angular_correction_deg))
230 
231  // Maximum translation between scans (m)
232  if (!nh_private_.getParam ("max_linear_correction", input_.max_linear_correction))
234 
235  // Maximum ICP cycle iterations
236  if (!nh_private_.getParam ("max_iterations", input_.max_iterations))
237  input_.max_iterations = 10;
238 
239  // A threshold for stopping (m)
240  if (!nh_private_.getParam ("epsilon_xy", input_.epsilon_xy))
241  input_.epsilon_xy = 0.000001;
242 
243  // A threshold for stopping (rad)
244  if (!nh_private_.getParam ("epsilon_theta", input_.epsilon_theta))
245  input_.epsilon_theta = 0.000001;
246 
247  // Maximum distance for a correspondence to be valid
248  if (!nh_private_.getParam ("max_correspondence_dist", input_.max_correspondence_dist))
250 
251  // Noise in the scan (m)
252  if (!nh_private_.getParam ("sigma", input_.sigma))
253  input_.sigma = 0.010;
254 
255  // Use smart tricks for finding correspondences.
256  if (!nh_private_.getParam ("use_corr_tricks", input_.use_corr_tricks))
258 
259  // Restart: Restart if error is over threshold
260  if (!nh_private_.getParam ("restart", input_.restart))
261  input_.restart = 0;
262 
263  // Restart: Threshold for restarting
264  if (!nh_private_.getParam ("restart_threshold_mean_error", input_.restart_threshold_mean_error))
266 
267  // Restart: displacement for restarting. (m)
268  if (!nh_private_.getParam ("restart_dt", input_.restart_dt))
269  input_.restart_dt = 1.0;
270 
271  // Restart: displacement for restarting. (rad)
272  if (!nh_private_.getParam ("restart_dtheta", input_.restart_dtheta))
273  input_.restart_dtheta = 0.1;
274 
275  // Max distance for staying in the same clustering
276  if (!nh_private_.getParam ("clustering_threshold", input_.clustering_threshold))
278 
279  // Number of neighbour rays used to estimate the orientation
280  if (!nh_private_.getParam ("orientation_neighbourhood", input_.orientation_neighbourhood))
282 
283  // If 0, it's vanilla ICP
284  if (!nh_private_.getParam ("use_point_to_line_distance", input_.use_point_to_line_distance))
286 
287  // Discard correspondences based on the angles
288  if (!nh_private_.getParam ("do_alpha_test", input_.do_alpha_test))
289  input_.do_alpha_test = 0;
290 
291  // Discard correspondences based on the angles - threshold angle, in degrees
292  if (!nh_private_.getParam ("do_alpha_test_thresholdDeg", input_.do_alpha_test_thresholdDeg))
294 
295  // Percentage of correspondences to consider: if 0.9,
296  // always discard the top 10% of correspondences with more error
297  if (!nh_private_.getParam ("outliers_maxPerc", input_.outliers_maxPerc))
298  input_.outliers_maxPerc = 0.90;
299 
300  // Parameters describing a simple adaptive algorithm for discarding.
301  // 1) Order the errors.
302  // 2) Choose the percentile according to outliers_adaptive_order.
303  // (if it is 0.7, get the 70% percentile)
304  // 3) Define an adaptive threshold multiplying outliers_adaptive_mult
305  // with the value of the error at the chosen percentile.
306  // 4) Discard correspondences over the threshold.
307  // This is useful to be conservative; yet remove the biggest errors.
308  if (!nh_private_.getParam ("outliers_adaptive_order", input_.outliers_adaptive_order))
310 
311  if (!nh_private_.getParam ("outliers_adaptive_mult", input_.outliers_adaptive_mult))
313 
314  // If you already have a guess of the solution, you can compute the polar angle
315  // of the points of one scan in the new position. If the polar angle is not a monotone
316  // function of the readings index, it means that the surface is not visible in the
317  // next position. If it is not visible, then we don't use it for matching.
318  if (!nh_private_.getParam ("do_visibility_test", input_.do_visibility_test))
320 
321  // no two points in laser_sens can have the same corr.
322  if (!nh_private_.getParam ("outliers_remove_doubles", input_.outliers_remove_doubles))
324 
325  // If 1, computes the covariance of ICP using the method http://purl.org/censi/2006/icpcov
326  if (!nh_private_.getParam ("do_compute_covariance", input_.do_compute_covariance))
328 
329  // Checks that find_correspondences_tricks gives the right answer
330  if (!nh_private_.getParam ("debug_verify_tricks", input_.debug_verify_tricks))
332 
333  // If 1, the field 'true_alpha' (or 'alpha') in the first scan is used to compute the
334  // incidence beta, and the factor (1/cos^2(beta)) used to weight the correspondence.");
335  if (!nh_private_.getParam ("use_ml_weights", input_.use_ml_weights))
337 
338  // If 1, the field 'readings_sigma' in the second scan is used to weight the
339  // correspondence by 1/sigma^2
340  if (!nh_private_.getParam ("use_sigma_weights", input_.use_sigma_weights))
342 }
343 
344 void LaserScanMatcher::imuCallback(const sensor_msgs::Imu::ConstPtr& imu_msg)
345 {
346  boost::mutex::scoped_lock(mutex_);
347  latest_imu_msg_ = *imu_msg;
348  if (!received_imu_)
349  {
350  tf::quaternionMsgToTF(imu_msg->orientation, last_used_imu_orientation_);
351  received_imu_ = true;
352  }
353 }
354 
355 void LaserScanMatcher::odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg)
356 {
357  boost::mutex::scoped_lock(mutex_);
358  latest_odom_msg_ = *odom_msg;
359  if (!received_odom_)
360  {
361  tf::poseMsgToTF(odom_msg->pose.pose, last_used_odom_pose_);
362  received_odom_ = true;
363  }
364 }
365 
366 void LaserScanMatcher::velCallback(const geometry_msgs::Twist::ConstPtr& twist_msg)
367 {
368  boost::mutex::scoped_lock(mutex_);
369  latest_vel_msg_ = *twist_msg;
370 
371  received_vel_ = true;
372 }
373 
374 void LaserScanMatcher::velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg)
375 {
376  boost::mutex::scoped_lock(mutex_);
377  latest_vel_msg_ = twist_msg->twist;
378 
379  received_vel_ = true;
380 }
381 
382 void LaserScanMatcher::cloudCallback (const PointCloudT::ConstPtr& cloud)
383 {
384  // **** if first scan, cache the tf from base to the scanner
385 
386  std_msgs::Header cloud_header = pcl_conversions::fromPCL(cloud->header);
387 
388  if (!initialized_)
389  {
390  // cache the static tf from base to laser
391  if (!getBaseLaserTransform(cloud_header.frame_id))
392  {
393  ROS_WARN("Skipping scan");
394  return;
395  }
396 
398  last_icp_time_ = cloud_header.stamp;
399  initialized_ = true;
400  }
401 
402  LDP curr_ldp_scan;
403  PointCloudToLDP(cloud, curr_ldp_scan);
404  processScan(curr_ldp_scan, cloud_header.stamp);
405 }
406 
407 void LaserScanMatcher::scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
408 {
409  // **** if first scan, cache the tf from base to the scanner
410 
411  if (!initialized_)
412  {
413  createCache(scan_msg); // caches the sin and cos of all angles
414 
415  // cache the static transform between the base and laser
416  if (!getBaseLaserTransform(scan_msg->header.frame_id))
417  {
418  ROS_WARN("Skipping scan");
419  return;
420  }
421 
422  laserScanToLDP(scan_msg, prev_ldp_scan_);
423  last_icp_time_ = scan_msg->header.stamp;
424  initialized_ = true;
425  }
426 
427  LDP curr_ldp_scan;
428  laserScanToLDP(scan_msg, curr_ldp_scan);
429  processScan(curr_ldp_scan, scan_msg->header.stamp);
430 }
431 
432 void LaserScanMatcher::processScan(LDP& curr_ldp_scan, const ros::Time& time)
433 {
435 
436  // CSM is used in the following way:
437  // The scans are always in the laser frame
438  // The reference scan (prevLDPcan_) has a pose of [0, 0, 0]
439  // The new scan (currLDPScan) has a pose equal to the movement
440  // of the laser in the laser frame since the last scan
441  // The computed correction is then propagated using the tf machinery
442 
443  prev_ldp_scan_->odometry[0] = 0.0;
444  prev_ldp_scan_->odometry[1] = 0.0;
445  prev_ldp_scan_->odometry[2] = 0.0;
446 
447  prev_ldp_scan_->estimate[0] = 0.0;
448  prev_ldp_scan_->estimate[1] = 0.0;
449  prev_ldp_scan_->estimate[2] = 0.0;
450 
451  prev_ldp_scan_->true_pose[0] = 0.0;
452  prev_ldp_scan_->true_pose[1] = 0.0;
453  prev_ldp_scan_->true_pose[2] = 0.0;
454 
456  input_.laser_sens = curr_ldp_scan;
457 
458  // **** estimated change since last scan
459 
460  // get the predicted offset of the scan base pose from the last scan base pose
461  tf::Transform pred_last_base_offset = getPrediction(time);
462 
463  // calculate the predicted scan base pose by applying the predicted offset to the last scan base pose
464  tf::Transform pred_base_in_fixed = last_base_in_fixed_ * pred_last_base_offset;
465 
466  // calculate the offset between the keyframe base pose and predicted scan base pose
467  tf::Transform pred_keyframe_base_offset = keyframe_base_in_fixed_.inverse() * pred_base_in_fixed;
468 
469  // convert the predicted offset from the keyframe base frame to be in the keyframe laser frame
470  tf::Transform pred_keyframe_laser_offset = laser_from_base_ * pred_keyframe_base_offset * base_from_laser_ ;
471 
472  input_.first_guess[0] = pred_keyframe_laser_offset.getOrigin().getX();
473  input_.first_guess[1] = pred_keyframe_laser_offset.getOrigin().getY();
474  input_.first_guess[2] = tf::getYaw(pred_keyframe_laser_offset.getRotation());
475 
476  // If they are non-Null, free covariance gsl matrices to avoid leaking memory
477  if (output_.cov_x_m)
478  {
479  gsl_matrix_free(output_.cov_x_m);
480  output_.cov_x_m = 0;
481  }
482  if (output_.dx_dy1_m)
483  {
484  gsl_matrix_free(output_.dx_dy1_m);
485  output_.dx_dy1_m = 0;
486  }
487  if (output_.dx_dy2_m)
488  {
489  gsl_matrix_free(output_.dx_dy2_m);
490  output_.dx_dy2_m = 0;
491  }
492 
493  // *** scan match - using point to line icp from CSM
494 
495  sm_icp(&input_, &output_);
496  tf::Transform meas_keyframe_base_offset;
497 
498  if (output_.valid)
499  {
500 
501  // the measured offset of the scan from the keyframe in the keyframe laser frame
502  tf::Transform meas_keyframe_laser_offset;
503  createTfFromXYTheta(output_.x[0], output_.x[1], output_.x[2], meas_keyframe_laser_offset);
504 
505  // convert the measured offset from the keyframe laser frame to the keyframe base frame
506  meas_keyframe_base_offset = base_from_laser_ * meas_keyframe_laser_offset * laser_from_base_;
507 
508  // calculate the measured pose of the scan in the fixed frame
509  last_base_in_fixed_ = keyframe_base_in_fixed_ * meas_keyframe_base_offset;
510 
511  // **** publish
512 
513  Eigen::Matrix2f xy_cov = Eigen::Matrix2f::Zero();
514  float yaw_cov = 0.0;
516  {
517  // get covariance from ICP
518  xy_cov(0, 0) = gsl_matrix_get(output_.cov_x_m, 0, 0);
519  xy_cov(0, 1) = gsl_matrix_get(output_.cov_x_m, 0, 1);
520  xy_cov(1, 0) = gsl_matrix_get(output_.cov_x_m, 1, 0);
521  xy_cov(1, 1) = gsl_matrix_get(output_.cov_x_m, 1, 1);
522  yaw_cov = gsl_matrix_get(output_.cov_x_m, 2, 2);
523 
524  // rotate xy covariance from the keyframe into odom frame
525  auto rotation = getLaserRotation(keyframe_base_in_fixed_);
526  xy_cov = rotation * xy_cov * rotation.transpose();
527  }
528  else {
529  xy_cov(0, 0) = position_covariance_[0];
530  xy_cov(1, 1) = position_covariance_[1];
531  yaw_cov = orientation_covariance_[2];
532  }
533 
534  if (publish_pose_)
535  {
536  // unstamped Pose2D message
537  geometry_msgs::Pose2D::Ptr pose_msg;
538  pose_msg = boost::make_shared<geometry_msgs::Pose2D>();
539  pose_msg->x = last_base_in_fixed_.getOrigin().getX();
540  pose_msg->y = last_base_in_fixed_.getOrigin().getY();
541  pose_msg->theta = tf::getYaw(last_base_in_fixed_.getRotation());
542  pose_publisher_.publish(pose_msg);
543  }
545  {
546  // stamped Pose message
547  geometry_msgs::PoseStamped::Ptr pose_stamped_msg;
548  pose_stamped_msg = boost::make_shared<geometry_msgs::PoseStamped>();
549 
550  pose_stamped_msg->header.stamp = time;
551  pose_stamped_msg->header.frame_id = fixed_frame_;
552 
553  tf::poseTFToMsg(last_base_in_fixed_, pose_stamped_msg->pose);
554 
555  pose_stamped_publisher_.publish(pose_stamped_msg);
556  }
558  {
559  // unstamped PoseWithCovariance message
560  geometry_msgs::PoseWithCovariance::Ptr pose_with_covariance_msg;
561  pose_with_covariance_msg = boost::make_shared<geometry_msgs::PoseWithCovariance>();
562  tf::poseTFToMsg(last_base_in_fixed_, pose_with_covariance_msg->pose);
563 
564  pose_with_covariance_msg->covariance = boost::assign::list_of
565  (xy_cov(0, 0)) (xy_cov(0, 1)) (0) (0) (0) (0)
566  (xy_cov(1, 0)) (xy_cov(1, 1)) (0) (0) (0) (0)
567  (0) (0) (0) (0) (0) (0)
568  (0) (0) (0) (0) (0) (0)
569  (0) (0) (0) (0) (0) (0)
570  (0) (0) (0) (0) (0) (yaw_cov);
571 
572  pose_with_covariance_publisher_.publish(pose_with_covariance_msg);
573  }
575  {
576  // stamped Pose message
577  geometry_msgs::PoseWithCovarianceStamped::Ptr pose_with_covariance_stamped_msg;
578  pose_with_covariance_stamped_msg = boost::make_shared<geometry_msgs::PoseWithCovarianceStamped>();
579 
580  pose_with_covariance_stamped_msg->header.stamp = time;
581  pose_with_covariance_stamped_msg->header.frame_id = fixed_frame_;
582 
583  tf::poseTFToMsg(last_base_in_fixed_, pose_with_covariance_stamped_msg->pose.pose);
584 
585  pose_with_covariance_stamped_msg->pose.covariance = boost::assign::list_of
586  (xy_cov(0, 0)) (xy_cov(0, 1)) (0) (0) (0) (0)
587  (xy_cov(1, 0)) (xy_cov(1, 1)) (0) (0) (0) (0)
588  (0) (0) (0) (0) (0) (0)
589  (0) (0) (0) (0) (0) (0)
590  (0) (0) (0) (0) (0) (0)
591  (0) (0) (0) (0) (0) (yaw_cov);
592 
593  pose_with_covariance_stamped_publisher_.publish(pose_with_covariance_stamped_msg);
594  }
595 
596  if (publish_tf_)
597  {
599  tf_broadcaster_.sendTransform (transform_msg);
600  }
601  }
602  else
603  {
604  meas_keyframe_base_offset.setIdentity();
605  ROS_WARN("Error in scan matching");
606  }
607 
608  // **** swap old and new
609 
610  if (newKeyframeNeeded(meas_keyframe_base_offset))
611  {
612  // generate a keyframe
614  prev_ldp_scan_ = curr_ldp_scan;
616  }
617  else
618  {
619  ld_free(curr_ldp_scan);
620  }
621 
622  last_icp_time_ = time;
623 
624  // **** statistics
625 
626  double dur = (ros::WallTime::now() - start).toSec() * 1e3;
627  ROS_DEBUG("Scan matcher total duration: %.1f ms", dur);
628 }
629 
631 {
632  if (fabs(tf::getYaw(d.getRotation())) > kf_dist_angular_) return true;
633 
634  double x = d.getOrigin().getX();
635  double y = d.getOrigin().getY();
636  if (x*x + y*y > kf_dist_linear_sq_) return true;
637 
638  return false;
639 }
640 
641 void LaserScanMatcher::PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
642  LDP& ldp)
643 {
644  double max_d2 = cloud_res_ * cloud_res_;
645 
646  PointCloudT cloud_f;
647 
648  cloud_f.points.push_back(cloud->points[0]);
649 
650  for (unsigned int i = 1; i < cloud->points.size(); ++i)
651  {
652  const PointT& pa = cloud_f.points[cloud_f.points.size() - 1];
653  const PointT& pb = cloud->points[i];
654 
655  double dx = pa.x - pb.x;
656  double dy = pa.y - pb.y;
657  double d2 = dx*dx + dy*dy;
658 
659  if (d2 > max_d2)
660  {
661  cloud_f.points.push_back(pb);
662  }
663  }
664 
665  unsigned int n = cloud_f.points.size();
666 
667  ldp = ld_alloc_new(n);
668 
669  for (unsigned int i = 0; i < n; i++)
670  {
671  // calculate position in laser frame
672  if (is_nan(cloud_f.points[i].x) || is_nan(cloud_f.points[i].y))
673  {
674  ROS_WARN("Laser Scan Matcher: Cloud input contains NaN values. \
675  Please use a filtered cloud input.");
676  }
677  else
678  {
679  double r = sqrt(cloud_f.points[i].x * cloud_f.points[i].x +
680  cloud_f.points[i].y * cloud_f.points[i].y);
681 
682  if (r > cloud_range_min_ && r < cloud_range_max_)
683  {
684  ldp->valid[i] = 1;
685  ldp->readings[i] = r;
686  }
687  else
688  {
689  ldp->valid[i] = 0;
690  ldp->readings[i] = -1; // for invalid range
691  }
692  }
693 
694  ldp->theta[i] = atan2(cloud_f.points[i].y, cloud_f.points[i].x);
695  ldp->cluster[i] = -1;
696  }
697 
698  ldp->min_theta = ldp->theta[0];
699  ldp->max_theta = ldp->theta[n-1];
700 
701  ldp->odometry[0] = 0.0;
702  ldp->odometry[1] = 0.0;
703  ldp->odometry[2] = 0.0;
704 
705  ldp->true_pose[0] = 0.0;
706  ldp->true_pose[1] = 0.0;
707  ldp->true_pose[2] = 0.0;
708 }
709 
710 void LaserScanMatcher::laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
711  LDP& ldp)
712 {
713  unsigned int n = scan_msg->ranges.size();
714  ldp = ld_alloc_new(n);
715 
716  for (unsigned int i = 0; i < n; i++)
717  {
718  // calculate position in laser frame
719 
720  double r = scan_msg->ranges[i];
721 
722  if (r > scan_msg->range_min && r < scan_msg->range_max)
723  {
724  // fill in laser scan data
725 
726  ldp->valid[i] = 1;
727  ldp->readings[i] = r;
728  }
729  else
730  {
731  ldp->valid[i] = 0;
732  ldp->readings[i] = -1; // for invalid range
733  }
734 
735  ldp->theta[i] = scan_msg->angle_min + i * scan_msg->angle_increment;
736 
737  ldp->cluster[i] = -1;
738  }
739 
740  ldp->min_theta = ldp->theta[0];
741  ldp->max_theta = ldp->theta[n-1];
742 
743  ldp->odometry[0] = 0.0;
744  ldp->odometry[1] = 0.0;
745  ldp->odometry[2] = 0.0;
746 
747  ldp->true_pose[0] = 0.0;
748  ldp->true_pose[1] = 0.0;
749  ldp->true_pose[2] = 0.0;
750 }
751 
752 void LaserScanMatcher::createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
753 {
754  a_cos_.clear();
755  a_sin_.clear();
756 
757  for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
758  {
759  double angle = scan_msg->angle_min + i * scan_msg->angle_increment;
760  a_cos_.push_back(cos(angle));
761  a_sin_.push_back(sin(angle));
762  }
763 
764  input_.min_reading = scan_msg->range_min;
765  input_.max_reading = scan_msg->range_max;
766 }
767 
768 bool LaserScanMatcher::getBaseLaserTransform(const std::string& frame_id)
769 {
770  tf::StampedTransform base_from_laser;
771  try
772  {
774  tf_listener_.lookupTransform (base_frame_, frame_id, ros::Time(0), base_from_laser);
775  }
776  catch (const tf::TransformException& ex)
777  {
778  ROS_WARN("Could not get initial transform from base to laser frame, %s", ex.what());
779  return false;
780  }
781  base_from_laser_ = base_from_laser;
783 
784  return true;
785 }
786 
787 // returns the predicted offset from the base pose of the last scan
789 {
790  boost::mutex::scoped_lock(mutex_);
791 
792  // **** base case - no input available, use zero-motion model
793  tf::Transform pred_last_base_offset = tf::Transform::getIdentity();
794 
795  // **** use velocity (for example from ab-filter)
796  if (use_vel_)
797  {
798  double dt = (stamp - last_icp_time_).toSec();
799  // NOTE: this assumes the velocity is in the base frame and that the base
800  // and laser frames share the same x,y and z axes
801  double pr_ch_x = dt * latest_vel_msg_.linear.x;
802  double pr_ch_y = dt * latest_vel_msg_.linear.y;
803  double pr_ch_a = dt * latest_vel_msg_.angular.z;
804 
805  createTfFromXYTheta(pr_ch_x, pr_ch_y, pr_ch_a, pred_last_base_offset);
806  }
807 
808  // **** use wheel odometry
809  if (use_odom_ && received_odom_)
810  {
811  // NOTE: this assumes the odometry is in the base frame
812  tf::Transform latest_odom_pose;
813  tf::poseMsgToTF(latest_odom_msg_.pose.pose, latest_odom_pose);
814 
815  pred_last_base_offset = last_used_odom_pose_.inverse() * latest_odom_pose;
816 
817  last_used_odom_pose_ = latest_odom_pose;
818  }
819 
820  // **** use imu
821  if (use_imu_ && received_imu_)
822  {
823  // NOTE: this assumes the imu is in the base frame
824  tf::Quaternion latest_imu_orientation;
825  tf::quaternionMsgToTF(latest_imu_msg_.orientation, latest_imu_orientation);
826 
827  tf::Quaternion imu_orientation_offset = last_used_imu_orientation_.inverse() * latest_imu_orientation;
828  pred_last_base_offset.setRotation(imu_orientation_offset);
829 
830  last_used_imu_orientation_ = latest_imu_orientation;
831  }
832 
833  // **** use tf
834  if (use_tf_)
835  {
836  tf::StampedTransform pred_last_base_offset_tf;
837  try
838  {
840  tf_listener_.lookupTransform (base_frame_, last_icp_time_, base_frame_, stamp, fixed_frame_, pred_last_base_offset_tf);
841  pred_last_base_offset = pred_last_base_offset_tf;
842  }
843  catch (const tf::TransformException& ex)
844  {
845  ROS_WARN("Could not get base to fixed frame transform, %s", ex.what());
846  }
847  }
848 
849  return pred_last_base_offset;
850 }
851 
853  double x, double y, double theta, tf::Transform& t)
854 {
855  t.setOrigin(tf::Vector3(x, y, 0.0));
856  tf::Quaternion q;
857  q.setRPY(0.0, 0.0, theta);
858  t.setRotation(q);
859 }
860 
861 Eigen::Matrix2f LaserScanMatcher::getLaserRotation(const tf::Transform& odom_pose) const {
862  tf::Transform laser_in_fixed = odom_pose * laser_from_base_;
863  tf::Matrix3x3 fixed_from_laser_rot(laser_in_fixed.getRotation());
864  double r,p,y;
865  fixed_from_laser_rot.getRPY(r, p, y);
866  Eigen::Rotation2Df t(y);
867  return t.toRotationMatrix();
868 }
869 
870 } // namespace scan_tools
void velCallback(const geometry_msgs::Twist::ConstPtr &twist_msg)
int do_alpha_test
int *restrict valid
void PointCloudToLDP(const PointCloudT::ConstPtr &cloud, LDP &ldp)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
double true_pose[3]
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
Quaternion inverse() const
void sm_icp(struct sm_params *input, struct sm_result *output)
pcl::PointCloud< PointT > PointCloudT
ROSCPP_DECL void start()
Transform inverse() const
std::vector< double > position_covariance_
int outliers_remove_doubles
double max_theta
tf::Transform getPrediction(const ros::Time &stamp)
double min_theta
Quaternion getRotation() const
double odometry[3]
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool getBaseLaserTransform(const std::string &frame_id)
ros::Publisher pose_with_covariance_stamped_publisher_
static double getYaw(const Quaternion &bt_q)
int *restrict cluster
int use_ml_weights
#define false
double epsilon_xy
int max_iterations
double max_angular_correction_deg
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
Eigen::Matrix2f getLaserRotation(const tf::Transform &odom_pose) const
int orientation_neighbourhood
double *restrict theta
ros::Publisher pose_with_covariance_publisher_
double clustering_threshold
double max_linear_correction
#define ROS_WARN(...)
void imuCallback(const sensor_msgs::Imu::ConstPtr &imu_msg)
double max_reading
double outliers_adaptive_mult
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
#define M_PI
void odomCallback(const nav_msgs::Odometry::ConstPtr &odom_msg)
void setIdentity()
int use_corr_tricks
double restart_dt
void cloudCallback(const PointCloudT::ConstPtr &cloud)
double sigma
gsl_matrix * dx_dy2_m
void ld_free(LDP ld)
int use_sigma_weights
double restart_threshold_mean_error
double *restrict readings
double max_correspondence_dist
void publish(const boost::shared_ptr< M > &message) const
void createCache(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
double outliers_maxPerc
std::vector< double > a_sin_
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
void sendTransform(const StampedTransform &transform)
LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private)
void processScan(LDP &curr_ldp_scan, const ros::Time &time)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int do_visibility_test
double do_alpha_test_thresholdDeg
void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr &scan_msg, LDP &ldp)
void createTfFromXYTheta(double x, double y, double theta, tf::Transform &t)
nav_msgs::Odometry latest_odom_msg_
LDP laser_sens
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
double min_reading
double restart_dtheta
double first_guess[3]
double laser[3]
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
std::vector< double > orientation_covariance_
static WallTime now()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr &twist_msg)
double estimate[3]
int is_nan(double v)
tf::TransformBroadcaster tf_broadcaster_
std::vector< double > a_cos_
double x[3]
static const Transform & getIdentity()
int do_compute_covariance
struct @4 p
geometry_msgs::Twist latest_vel_msg_
double outliers_adaptive_order
double epsilon_theta
gsl_matrix * cov_x_m
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
LDP ld_alloc_new(int nrays)
bool newKeyframeNeeded(const tf::Transform &d)
int use_point_to_line_distance
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &scan_msg)
gsl_matrix * dx_dy1_m
int debug_verify_tricks
#define ROS_DEBUG(...)
tf::TransformListener tf_listener_


laser_scan_matcher
Author(s): Ivan Dryanovski , William Morris, Andrea Censi
autogenerated on Sun Jul 2 2023 02:26:03