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