00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include "laser_scan_matcher/laser_scan_matcher.h"
00039
00040 namespace scan_tools
00041 {
00042
00043 LaserScanMatcher::LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private):
00044 nh_(nh),
00045 nh_private_(nh_private),
00046 initialized_(false),
00047 received_imu_(false),
00048 received_odom_(false),
00049 received_vel_(false)
00050 {
00051 ROS_INFO("Starting LaserScanMatcher");
00052
00053
00054
00055 initParams();
00056
00057
00058
00059 f2b_.setIdentity();
00060 f2b_kf_.setIdentity();
00061 input_.laser[0] = 0.0;
00062 input_.laser[1] = 0.0;
00063 input_.laser[2] = 0.0;
00064
00065
00066
00067 if (publish_pose_)
00068 {
00069 pose_publisher_ = nh_.advertise<geometry_msgs::Pose2D>(
00070 "pose2D", 5);
00071 }
00072
00073 if (publish_pose_stamped_)
00074 {
00075 pose_stamped_publisher_ = nh_.advertise<geometry_msgs::PoseStamped>(
00076 "pose_stamped", 5);
00077 }
00078
00079
00080
00081 if (use_cloud_input_)
00082 {
00083 cloud_subscriber_ = nh_.subscribe(
00084 "cloud", 1, &LaserScanMatcher::cloudCallback, this);
00085 }
00086 else
00087 {
00088 scan_subscriber_ = nh_.subscribe(
00089 "scan", 1, &LaserScanMatcher::scanCallback, this);
00090 }
00091
00092 if (use_imu_)
00093 {
00094 imu_subscriber_ = nh_.subscribe(
00095 "imu/data", 1, &LaserScanMatcher::imuCallback, this);
00096 }
00097 if (use_odom_)
00098 {
00099 odom_subscriber_ = nh_.subscribe(
00100 "odom", 1, &LaserScanMatcher::odomCallback, this);
00101 }
00102 if (use_vel_)
00103 {
00104 vel_subscriber_ = nh_.subscribe(
00105 "vel", 1, &LaserScanMatcher::velCallback, this);
00106 }
00107 }
00108
00109 LaserScanMatcher::~LaserScanMatcher()
00110 {
00111 ROS_INFO("Destroying LaserScanMatcher");
00112 }
00113
00114 void LaserScanMatcher::initParams()
00115 {
00116 if (!nh_private_.getParam ("base_frame", base_frame_))
00117 base_frame_ = "base_link";
00118 if (!nh_private_.getParam ("fixed_frame", fixed_frame_))
00119 fixed_frame_ = "world";
00120
00121
00122
00123
00124
00125 if (!nh_private_.getParam ("use_cloud_input", use_cloud_input_))
00126 use_cloud_input_= false;
00127
00128 if (use_cloud_input_)
00129 {
00130 if (!nh_private_.getParam ("cloud_range_min", cloud_range_min_))
00131 cloud_range_min_ = 0.1;
00132 if (!nh_private_.getParam ("cloud_range_max", cloud_range_max_))
00133 cloud_range_max_ = 50.0;
00134 if (!nh_private_.getParam ("cloud_res", cloud_res_))
00135 cloud_res_ = 0.05;
00136
00137 input_.min_reading = cloud_range_min_;
00138 input_.max_reading = cloud_range_max_;
00139 }
00140
00141
00142
00143
00144 if (!nh_private_.getParam ("kf_dist_linear", kf_dist_linear_))
00145 kf_dist_linear_ = 0.10;
00146 if (!nh_private_.getParam ("kf_dist_angular", kf_dist_angular_))
00147 kf_dist_angular_ = 10.0 * (M_PI / 180.0);
00148
00149 kf_dist_linear_sq_ = kf_dist_linear_ * kf_dist_linear_;
00150
00151
00152
00153
00154
00155
00156
00157 if (!nh_private_.getParam ("use_imu", use_imu_))
00158 use_imu_ = true;
00159 if (!nh_private_.getParam ("use_odom", use_odom_))
00160 use_odom_ = true;
00161 if (!nh_private_.getParam ("use_vel", use_vel_))
00162 use_vel_ = false;
00163
00164
00165
00166
00167
00168 if (!nh_private_.getParam ("publish_tf", publish_tf_))
00169 publish_tf_ = true;
00170 if (!nh_private_.getParam ("publish_pose", publish_pose_))
00171 publish_pose_ = true;
00172 if (!nh_private_.getParam ("publish_pose_stamped", publish_pose_stamped_))
00173 publish_pose_stamped_ = false;
00174
00175
00176
00177
00178 if (!nh_private_.getParam ("max_angular_correction_deg", input_.max_angular_correction_deg))
00179 input_.max_angular_correction_deg = 45.0;
00180
00181
00182 if (!nh_private_.getParam ("max_linear_correction", input_.max_linear_correction))
00183 input_.max_linear_correction = 0.50;
00184
00185
00186 if (!nh_private_.getParam ("max_iterations", input_.max_iterations))
00187 input_.max_iterations = 10;
00188
00189
00190 if (!nh_private_.getParam ("epsilon_xy", input_.epsilon_xy))
00191 input_.epsilon_xy = 0.000001;
00192
00193
00194 if (!nh_private_.getParam ("epsilon_theta", input_.epsilon_theta))
00195 input_.epsilon_theta = 0.000001;
00196
00197
00198 if (!nh_private_.getParam ("max_correspondence_dist", input_.max_correspondence_dist))
00199 input_.max_correspondence_dist = 0.3;
00200
00201
00202 if (!nh_private_.getParam ("sigma", input_.sigma))
00203 input_.sigma = 0.010;
00204
00205
00206 if (!nh_private_.getParam ("use_corr_tricks", input_.use_corr_tricks))
00207 input_.use_corr_tricks = 1;
00208
00209
00210 if (!nh_private_.getParam ("restart", input_.restart))
00211 input_.restart = 0;
00212
00213
00214 if (!nh_private_.getParam ("restart_threshold_mean_error", input_.restart_threshold_mean_error))
00215 input_.restart_threshold_mean_error = 0.01;
00216
00217
00218 if (!nh_private_.getParam ("restart_dt", input_.restart_dt))
00219 input_.restart_dt = 1.0;
00220
00221
00222 if (!nh_private_.getParam ("restart_dtheta", input_.restart_dtheta))
00223 input_.restart_dtheta = 0.1;
00224
00225
00226 if (!nh_private_.getParam ("clustering_threshold", input_.clustering_threshold))
00227 input_.clustering_threshold = 0.25;
00228
00229
00230 if (!nh_private_.getParam ("orientation_neighbourhood", input_.orientation_neighbourhood))
00231 input_.orientation_neighbourhood = 20;
00232
00233
00234 if (!nh_private_.getParam ("use_point_to_line_distance", input_.use_point_to_line_distance))
00235 input_.use_point_to_line_distance = 1;
00236
00237
00238 if (!nh_private_.getParam ("do_alpha_test", input_.do_alpha_test))
00239 input_.do_alpha_test = 0;
00240
00241
00242 if (!nh_private_.getParam ("do_alpha_test_thresholdDeg", input_.do_alpha_test_thresholdDeg))
00243 input_.do_alpha_test_thresholdDeg = 20.0;
00244
00245
00246
00247 if (!nh_private_.getParam ("outliers_maxPerc", input_.outliers_maxPerc))
00248 input_.outliers_maxPerc = 0.90;
00249
00250
00251
00252
00253
00254
00255
00256
00257
00258 if (!nh_private_.getParam ("outliers_adaptive_order", input_.outliers_adaptive_order))
00259 input_.outliers_adaptive_order = 0.7;
00260
00261 if (!nh_private_.getParam ("outliers_adaptive_mult", input_.outliers_adaptive_mult))
00262 input_.outliers_adaptive_mult = 2.0;
00263
00264
00265
00266
00267
00268 if (!nh_private_.getParam ("do_visibility_test", input_.do_visibility_test))
00269 input_.do_visibility_test = 0;
00270
00271
00272 if (!nh_private_.getParam ("outliers_remove_doubles", input_.outliers_remove_doubles))
00273 input_.outliers_remove_doubles = 1;
00274
00275
00276 if (!nh_private_.getParam ("do_compute_covariance", input_.do_compute_covariance))
00277 input_.do_compute_covariance = 0;
00278
00279
00280 if (!nh_private_.getParam ("debug_verify_tricks", input_.debug_verify_tricks))
00281 input_.debug_verify_tricks = 0;
00282
00283
00284
00285 if (!nh_private_.getParam ("use_ml_weights", input_.use_ml_weights))
00286 input_.use_ml_weights = 0;
00287
00288
00289
00290 if (!nh_private_.getParam ("use_sigma_weights", input_.use_sigma_weights))
00291 input_.use_sigma_weights = 0;
00292 }
00293
00294 void LaserScanMatcher::imuCallback(const sensor_msgs::Imu::ConstPtr& imu_msg)
00295 {
00296 boost::mutex::scoped_lock(mutex_);
00297 latest_imu_msg_ = *imu_msg;
00298 if (!received_imu_)
00299 {
00300 last_used_imu_msg_ = *imu_msg;
00301 received_imu_ = true;
00302 }
00303 }
00304
00305 void LaserScanMatcher::odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg)
00306 {
00307 boost::mutex::scoped_lock(mutex_);
00308 latest_odom_msg_ = *odom_msg;
00309 if (!received_odom_)
00310 {
00311 last_used_odom_msg_ = *odom_msg;
00312 received_odom_ = true;
00313 }
00314 }
00315
00316 void LaserScanMatcher::velCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg)
00317 {
00318 boost::mutex::scoped_lock(mutex_);
00319 latest_vel_msg_ = *twist_msg;
00320
00321 received_vel_ = true;
00322 }
00323
00324 void LaserScanMatcher::cloudCallback (const PointCloudT::ConstPtr& cloud)
00325 {
00326
00327
00328 if (!initialized_)
00329 {
00330
00331 if (!getBaseToLaserTf(cloud->header.frame_id))
00332 {
00333 ROS_WARN("Skipping scan");
00334 return;
00335 }
00336
00337 PointCloudToLDP(cloud, prev_ldp_scan_);
00338 last_icp_time_ = cloud->header.stamp;
00339 initialized_ = true;
00340 }
00341
00342 LDP curr_ldp_scan;
00343 PointCloudToLDP(cloud, curr_ldp_scan);
00344 processScan(curr_ldp_scan, cloud->header.stamp);
00345 }
00346
00347 void LaserScanMatcher::scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
00348 {
00349
00350
00351 if (!initialized_)
00352 {
00353 createCache(scan_msg);
00354
00355
00356 if (!getBaseToLaserTf(scan_msg->header.frame_id))
00357 {
00358 ROS_WARN("Skipping scan");
00359 return;
00360 }
00361
00362 laserScanToLDP(scan_msg, prev_ldp_scan_);
00363 last_icp_time_ = scan_msg->header.stamp;
00364 initialized_ = true;
00365 }
00366
00367 LDP curr_ldp_scan;
00368 laserScanToLDP(scan_msg, curr_ldp_scan);
00369 processScan(curr_ldp_scan, scan_msg->header.stamp);
00370 }
00371
00372 void LaserScanMatcher::processScan(LDP& curr_ldp_scan, const ros::Time& time)
00373 {
00374 ros::WallTime start = ros::WallTime::now();
00375
00376
00377
00378
00379
00380
00381
00382
00383 prev_ldp_scan_->odometry[0] = 0.0;
00384 prev_ldp_scan_->odometry[1] = 0.0;
00385 prev_ldp_scan_->odometry[2] = 0.0;
00386
00387 prev_ldp_scan_->estimate[0] = 0.0;
00388 prev_ldp_scan_->estimate[1] = 0.0;
00389 prev_ldp_scan_->estimate[2] = 0.0;
00390
00391 prev_ldp_scan_->true_pose[0] = 0.0;
00392 prev_ldp_scan_->true_pose[1] = 0.0;
00393 prev_ldp_scan_->true_pose[2] = 0.0;
00394
00395 input_.laser_ref = prev_ldp_scan_;
00396 input_.laser_sens = curr_ldp_scan;
00397
00398
00399
00400 double dt = (time - last_icp_time_).toSec();
00401 double pr_ch_x, pr_ch_y, pr_ch_a;
00402 getPrediction(pr_ch_x, pr_ch_y, pr_ch_a, dt);
00403
00404
00405
00406 tf::Transform pr_ch;
00407 createTfFromXYTheta(pr_ch_x, pr_ch_y, pr_ch_a, pr_ch);
00408
00409
00410
00411 pr_ch = pr_ch * (f2b_ * f2b_kf_.inverse());
00412
00413
00414
00415 tf::Transform pr_ch_l;
00416 pr_ch_l = laser_to_base_ * f2b_.inverse() * pr_ch * f2b_ * base_to_laser_ ;
00417
00418 input_.first_guess[0] = pr_ch_l.getOrigin().getX();
00419 input_.first_guess[1] = pr_ch_l.getOrigin().getY();
00420 input_.first_guess[2] = tf::getYaw(pr_ch_l.getRotation());
00421
00422
00423
00424 sm_icp(&input_, &output_);
00425 tf::Transform corr_ch;
00426
00427 if (output_.valid)
00428 {
00429
00430 tf::Transform corr_ch_l;
00431 createTfFromXYTheta(output_.x[0], output_.x[1], output_.x[2], corr_ch_l);
00432
00433
00434 corr_ch = base_to_laser_ * corr_ch_l * laser_to_base_;
00435
00436
00437 f2b_ = f2b_kf_ * corr_ch;
00438
00439
00440
00441 if (publish_pose_)
00442 {
00443
00444 geometry_msgs::Pose2D::Ptr pose_msg;
00445 pose_msg = boost::make_shared<geometry_msgs::Pose2D>();
00446 pose_msg->x = f2b_.getOrigin().getX();
00447 pose_msg->y = f2b_.getOrigin().getY();
00448 pose_msg->theta = tf::getYaw(f2b_.getRotation());
00449 pose_publisher_.publish(pose_msg);
00450 }
00451 if (publish_pose_stamped_)
00452 {
00453
00454 geometry_msgs::PoseStamped::Ptr pose_stamped_msg;
00455 pose_stamped_msg = boost::make_shared<geometry_msgs::PoseStamped>();
00456
00457 pose_stamped_msg->header.stamp = time;
00458 pose_stamped_msg->header.frame_id = fixed_frame_;
00459
00460 tf::poseTFToMsg(f2b_, pose_stamped_msg->pose);
00461
00462 pose_stamped_publisher_.publish(pose_stamped_msg);
00463 }
00464 if (publish_tf_)
00465 {
00466 tf::StampedTransform transform_msg (f2b_, time, fixed_frame_, base_frame_);
00467 tf_broadcaster_.sendTransform (transform_msg);
00468 }
00469 }
00470 else
00471 {
00472 corr_ch.setIdentity();
00473 ROS_WARN("Error in scan matching");
00474 }
00475
00476
00477
00478 if (newKeyframeNeeded(corr_ch))
00479 {
00480
00481 ld_free(prev_ldp_scan_);
00482 prev_ldp_scan_ = curr_ldp_scan;
00483 f2b_kf_ = f2b_;
00484 }
00485 else
00486 {
00487 ld_free(curr_ldp_scan);
00488 }
00489
00490 last_icp_time_ = time;
00491
00492
00493
00494 double dur = (ros::WallTime::now() - start).toSec() * 1e3;
00495 ROS_DEBUG("Scan matcher total duration: %.1f ms", dur);
00496 }
00497
00498 bool LaserScanMatcher::newKeyframeNeeded(const tf::Transform& d)
00499 {
00500 if (fabs(tf::getYaw(d.getRotation())) > kf_dist_angular_) return true;
00501
00502 double x = d.getOrigin().getX();
00503 double y = d.getOrigin().getY();
00504 if (x*x + y*y > kf_dist_linear_sq_) return true;
00505
00506 return false;
00507 }
00508
00509 void LaserScanMatcher::PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
00510 LDP& ldp)
00511 {
00512 double max_d2 = cloud_res_ * cloud_res_;
00513
00514 PointCloudT cloud_f;
00515
00516 cloud_f.points.push_back(cloud->points[0]);
00517
00518 for (unsigned int i = 1; i < cloud->points.size(); ++i)
00519 {
00520 const PointT& pa = cloud_f.points[cloud_f.points.size() - 1];
00521 const PointT& pb = cloud->points[i];
00522
00523 double dx = pa.x - pb.x;
00524 double dy = pa.y - pb.y;
00525 double d2 = dx*dx + dy*dy;
00526
00527 if (d2 > max_d2)
00528 {
00529 cloud_f.points.push_back(pb);
00530 }
00531 }
00532
00533 unsigned int n = cloud_f.points.size();
00534
00535 ldp = ld_alloc_new(n);
00536
00537 for (unsigned int i = 0; i < n; i++)
00538 {
00539
00540 if (is_nan(cloud_f.points[i].x) || is_nan(cloud_f.points[i].y))
00541 {
00542 ROS_WARN("Laser Scan Matcher: Cloud input contains NaN values. \
00543 Please use a filtered cloud input.");
00544 }
00545 else
00546 {
00547 double r = sqrt(cloud_f.points[i].x * cloud_f.points[i].x +
00548 cloud_f.points[i].y * cloud_f.points[i].y);
00549
00550 if (r > cloud_range_min_ && r < cloud_range_max_)
00551 {
00552 ldp->valid[i] = 1;
00553 ldp->readings[i] = r;
00554 }
00555 else
00556 {
00557 ldp->valid[i] = 0;
00558 ldp->readings[i] = -1;
00559 }
00560 }
00561
00562 ldp->theta[i] = atan2(cloud_f.points[i].y, cloud_f.points[i].x);
00563 ldp->cluster[i] = -1;
00564 }
00565
00566 ldp->min_theta = ldp->theta[0];
00567 ldp->max_theta = ldp->theta[n-1];
00568
00569 ldp->odometry[0] = 0.0;
00570 ldp->odometry[1] = 0.0;
00571 ldp->odometry[2] = 0.0;
00572
00573 ldp->true_pose[0] = 0.0;
00574 ldp->true_pose[1] = 0.0;
00575 ldp->true_pose[2] = 0.0;
00576 }
00577
00578 void LaserScanMatcher::laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
00579 LDP& ldp)
00580 {
00581 unsigned int n = scan_msg->ranges.size();
00582 ldp = ld_alloc_new(n);
00583
00584 for (unsigned int i = 0; i < n; i++)
00585 {
00586
00587
00588 double r = scan_msg->ranges[i];
00589
00590 if (r > scan_msg->range_min && r < scan_msg->range_max)
00591 {
00592
00593
00594 ldp->valid[i] = 1;
00595 ldp->readings[i] = r;
00596 }
00597 else
00598 {
00599 ldp->valid[i] = 0;
00600 ldp->readings[i] = -1;
00601 }
00602
00603 ldp->theta[i] = scan_msg->angle_min + i * scan_msg->angle_increment;
00604
00605 ldp->cluster[i] = -1;
00606 }
00607
00608 ldp->min_theta = ldp->theta[0];
00609 ldp->max_theta = ldp->theta[n-1];
00610
00611 ldp->odometry[0] = 0.0;
00612 ldp->odometry[1] = 0.0;
00613 ldp->odometry[2] = 0.0;
00614
00615 ldp->true_pose[0] = 0.0;
00616 ldp->true_pose[1] = 0.0;
00617 ldp->true_pose[2] = 0.0;
00618 }
00619
00620 void LaserScanMatcher::createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
00621 {
00622 a_cos_.clear();
00623 a_sin_.clear();
00624
00625 for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
00626 {
00627 double angle = scan_msg->angle_min + i * scan_msg->angle_increment;
00628 a_cos_.push_back(cos(angle));
00629 a_sin_.push_back(sin(angle));
00630 }
00631
00632 input_.min_reading = scan_msg->range_min;
00633 input_.max_reading = scan_msg->range_max;
00634 }
00635
00636 bool LaserScanMatcher::getBaseToLaserTf (const std::string& frame_id)
00637 {
00638 ros::Time t = ros::Time::now();
00639
00640 tf::StampedTransform base_to_laser_tf;
00641 try
00642 {
00643 tf_listener_.waitForTransform(
00644 base_frame_, frame_id, t, ros::Duration(1.0));
00645 tf_listener_.lookupTransform (
00646 base_frame_, frame_id, t, base_to_laser_tf);
00647 }
00648 catch (tf::TransformException ex)
00649 {
00650 ROS_WARN("Could not get initial transform from base to laser frame, %s", ex.what());
00651 return false;
00652 }
00653 base_to_laser_ = base_to_laser_tf;
00654 laser_to_base_ = base_to_laser_.inverse();
00655
00656 return true;
00657 }
00658
00659
00660
00661 void LaserScanMatcher::getPrediction(double& pr_ch_x, double& pr_ch_y,
00662 double& pr_ch_a, double dt)
00663 {
00664 boost::mutex::scoped_lock(mutex_);
00665
00666
00667 pr_ch_x = 0.0;
00668 pr_ch_y = 0.0;
00669 pr_ch_a = 0.0;
00670
00671
00672 if (use_vel_)
00673 {
00674 pr_ch_x = dt * latest_vel_msg_.twist.linear.x;
00675 pr_ch_y = dt * latest_vel_msg_.twist.linear.y;
00676 pr_ch_a = dt * latest_vel_msg_.twist.angular.z;
00677
00678 if (pr_ch_a >= M_PI) pr_ch_a -= 2.0 * M_PI;
00679 else if (pr_ch_a < -M_PI) pr_ch_a += 2.0 * M_PI;
00680 }
00681
00682
00683 if (use_odom_ && received_odom_)
00684 {
00685 pr_ch_x = latest_odom_msg_.pose.pose.position.x -
00686 last_used_odom_msg_.pose.pose.position.x;
00687
00688 pr_ch_y = latest_odom_msg_.pose.pose.position.y -
00689 last_used_odom_msg_.pose.pose.position.y;
00690
00691 pr_ch_a = tf::getYaw(latest_odom_msg_.pose.pose.orientation) -
00692 tf::getYaw(last_used_odom_msg_.pose.pose.orientation);
00693
00694 if (pr_ch_a >= M_PI) pr_ch_a -= 2.0 * M_PI;
00695 else if (pr_ch_a < -M_PI) pr_ch_a += 2.0 * M_PI;
00696
00697 last_used_odom_msg_ = latest_odom_msg_;
00698 }
00699
00700
00701 if (use_imu_ && received_imu_)
00702 {
00703 pr_ch_a = tf::getYaw(latest_imu_msg_.orientation) -
00704 tf::getYaw(last_used_imu_msg_.orientation);
00705
00706 if (pr_ch_a >= M_PI) pr_ch_a -= 2.0 * M_PI;
00707 else if (pr_ch_a < -M_PI) pr_ch_a += 2.0 * M_PI;
00708
00709 last_used_imu_msg_ = latest_imu_msg_;
00710 }
00711 }
00712
00713 void LaserScanMatcher::createTfFromXYTheta(
00714 double x, double y, double theta, tf::Transform& t)
00715 {
00716 t.setOrigin(tf::Vector3(x, y, 0.0));
00717 tf::Quaternion q;
00718 q.setRPY(0.0, 0.0, theta);
00719 t.setRotation(q);
00720 }
00721
00722 }
00723