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 #include <stdio.h>
00032
00033 #include <algorithm>
00034 #include <iterator>
00035
00036 #include <boost/bind.hpp>
00037
00038 #include <visualization_msgs/Marker.h>
00039 #include <visualization_msgs/MarkerArray.h>
00040 #include <std_msgs/Float64MultiArray.h>
00041
00042 #include "nav_pcontroller/BaseDistance.h"
00043
00057 #define MODE_FREE 0
00058 #define MODE_PROJECTING 1
00059 #define MODE_HARD_PROJECTING 2
00060 #define MODE_BRAKING 3
00061 #define MODE_REPELLING 4
00062 #define MODE_PROJECTION_MASK 3
00063
00064 #if !ROS_VERSION_MINIMUM(1, 8, 0)
00065 namespace tf {
00066 typedef btMatrix3x3 Matrix3x3;
00067 }
00068 #endif
00069
00070 BaseDistance::BaseDistance()
00071 : n_("~")
00072 {
00073 d_ = 1 / 10.0;
00074 rob_x_ = rob_y_ = rob_th_ = 0.0;
00075 vx_last_ = vy_last_ = vth_last_ = 0.0;
00076
00077
00078 n_.param<std::string>("odom_frame", odom_frame_, "odom");
00079 n_.param<std::string>("base_link_frame", base_link_frame_, "base_link");
00080 n_.param("n_lasers", n_lasers_, 2);
00081 if(n_lasers_ < 1 || n_lasers_ > 2)
00082 ROS_FATAL("Only one or two lasers are supported. %d lasers specified.", n_lasers_);
00083 n_.param("slowdown_far", slowdown_far_, 0.30);
00084 n_.param("slowdown_near", slowdown_near_, 0.15);
00085 n_.param("safety_dist", safety_dist_, 0.10);
00086 n_.param("repelling_dist", repelling_dist_, 0.20);
00087 n_.param("repelling_gain", repelling_gain_, 0.5);
00088 n_.param("repelling_gain_max", repelling_gain_max_, 0.015);
00089 ROS_INFO("## safe=%f slow=%f..%f repell=%f repell_gain=%f\n", safety_dist_, slowdown_near_, slowdown_far_, repelling_dist_, repelling_gain_);
00090 n_.param("complete_blind_spots", complete_blind_spots_, true);
00091 n_.param("blind_spot_threshold", blind_spot_threshold_, 0.85);
00092 n_.param("marker_size", marker_size_, 0.1);
00093
00094 marker_pub_ = n_.advertise<visualization_msgs::Marker>("visualization_marker", 0);
00095 laser_points_pub_ = n_.advertise<sensor_msgs::PointCloud>("laser_points", 0);
00096 debug_pub_ = n_.advertise<std_msgs::Float64MultiArray>("debug_channels", 0);
00097
00098 laser_subscriptions_[0] = n_.subscribe<sensor_msgs::LaserScan>
00099 ("laser_1", 2, boost::bind(&BaseDistance::laserCallback, this, 0, _1));
00100 if(n_lasers_ > 1)
00101 laser_subscriptions_[1] = n_.subscribe<sensor_msgs::LaserScan>
00102 ("laser_2", 2, boost::bind(&BaseDistance::laserCallback, this, 1, _1));
00103
00104 calculateEarlyRejectDistance();
00105 }
00106
00107
00108 bool BaseDistance::fresh_scans(double watchdog_timeout)
00109 {
00110
00111 ros::Time now = ros::Time::now();
00112 if (n_lasers_ == 1) {
00113 if (now - laser_0_last_msg_time_ < ros::Duration(watchdog_timeout))
00114 return true;
00115 else
00116 return false;
00117 }
00118
00119 if (n_lasers_ == 2) {
00120 if ( (now - laser_0_last_msg_time_ < ros::Duration(watchdog_timeout))
00121 and (now - laser_1_last_msg_time_ < ros::Duration(watchdog_timeout)) )
00122 return true;
00123 else
00124 return false;
00125 }
00126
00127
00128 }
00129
00130
00131 void BaseDistance::calculateEarlyRejectDistance()
00132 {
00133
00134 double movement_tolerance = 0.2;
00135
00136 double diameter = sqrt((front_ - rear_) * (front_ - rear_) + (right_ - left_) * (right_ - left_));
00137 early_reject_distance_ = diameter + slowdown_far_ + tolerance_ + movement_tolerance;
00138 }
00139
00140
00141 void BaseDistance::setFootprint(double front, double rear, double left, double right, double tolerance)
00142 {
00143 ROS_INFO("setting footprint. x : %f .. %f y : %f .. %f", rear, front, right, left);
00144
00145 rear_ = rear;
00146 front_ = front;
00147 left_ = left;
00148 right_ = right;
00149 tolerance_ = tolerance;
00150
00151 calculateEarlyRejectDistance();
00152 }
00153
00154
00155 void BaseDistance::setSafetyLimits(double safety_dist, double slowdown_near, double slowdown_far, double rate)
00156 {
00157 d_ = 1.0 / rate;
00158 safety_dist_ = safety_dist;
00159 slowdown_near_ = slowdown_near;
00160 slowdown_far_ = slowdown_far;
00161 }
00162
00163
00164 BaseDistance::Vector2 BaseDistance::transform(const Vector2 &v, double x, double y, double th)
00165 {
00166 return Vector2(v.x*cos(th) - v.y*sin(th) + x,
00167 v.x*sin(th) + v.y*cos(th) + y);
00168 }
00169
00170
00171 bool BaseDistance::compute_pose2d(const char* from, const char* to, const ros::Time time, double *x, double *y, double *th)
00172 {
00173 tf::StampedTransform pose;
00174 try
00175 {
00176 tf_.lookupTransform(from, to, time, pose);
00177 }
00178 catch(tf::TransformException& ex)
00179 {
00180 ROS_WARN("no localization information yet (%s -> %s)", from, to);
00181 return false;
00182 }
00183
00184 *x = pose.getOrigin().x();
00185 *y = pose.getOrigin().y();
00186
00187 tf::Matrix3x3 m = pose.getBasis();
00188 *th = atan2(m[1][0], m[0][0]);
00189
00190 return true;
00191 }
00192
00193
00194 void BaseDistance::laserCallback(int index, const sensor_msgs::LaserScan::ConstPtr &scan)
00195 {
00196
00197 boost::shared_ptr<std::vector<Vector2> > points(new std::vector<Vector2>);
00198
00199 points->reserve(scan->ranges.size());
00200
00201
00202 double x, y, th;
00203 compute_pose2d(odom_frame_.c_str(), scan->header.frame_id.c_str(), ros::Time(0), &x, &y, &th);
00204
00205 double angle;
00206 int i, first_scan = 0, last_scan = 0;
00207
00208
00209
00210
00211
00212 for(int i = scan->ranges.size() - 1; i >= 0; i--)
00213 {
00214 if(scan->ranges[i] > scan->range_min &&
00215 scan->ranges[i] < scan->range_max)
00216 {
00217 last_scan = i;
00218 break;
00219 }
00220 }
00221
00222 for(angle = scan->angle_min, i = 0;
00223 i < (int) scan->ranges.size();
00224 i++, angle += scan->angle_increment)
00225 {
00226
00227 if(scan->ranges[i] <= scan->range_min ||
00228 scan->ranges[i] >= scan->range_max)
00229 {
00230 first_scan++;
00231 continue;
00232 }
00233
00234
00235 if(scan->ranges[i] >= early_reject_distance_ && i != first_scan && i != last_scan)
00236 continue;
00237
00238 first_scan = -1;
00239
00240
00241 double xl = scan->ranges[i] * cos(angle);
00242 double yl = scan->ranges[i] * sin(angle);
00243 points->push_back(transform(Vector2(xl, yl), x, y, th));
00244 }
00245
00246
00247
00248
00249
00250 laser_points_[index] = points;
00251
00252
00253
00254 if(complete_blind_spots_ && laser_points_[0] && laser_points_[1])
00255 {
00256 blind_spots_.clear();
00257
00258 if(interpolateBlindPoints(10, laser_points_[0]->front(), laser_points_[1]->back()))
00259 {
00260 publishLaserMarker(laser_points_[0]->front(), "blind_spots", 0);
00261 publishLaserMarker(laser_points_[1]->back(), "blind_spots", 1);
00262 }
00263
00264 if(interpolateBlindPoints(10, laser_points_[0]->back(), laser_points_[1]->front()))
00265 {
00266 publishLaserMarker(laser_points_[0]->back(), "blind_spots", 2);
00267 publishLaserMarker(laser_points_[1]->front(), "blind_spots", 3);
00268 }
00270 }
00271
00272 if (index == 0) {
00273 laser_0_last_msg_time_ = ros::Time(scan->header.stamp);
00274 } else if (index == 1) {
00275 laser_1_last_msg_time_ = ros::Time(scan->header.stamp);;
00276 }
00277
00278 }
00279
00280
00281 bool BaseDistance::interpolateBlindPoints(int n, const Vector2 &pt1, const Vector2 &pt2)
00282 {
00283
00284 Vector2 p1_rob = transform(pt1, rob_x_, rob_y_, rob_th_);
00285 Vector2 p2_rob = transform(pt2, rob_x_, rob_y_, rob_th_);
00286
00287
00288 if(p1_rob.len2() < blind_spot_threshold_ * blind_spot_threshold_ ||
00289 p2_rob.len2() < blind_spot_threshold_ * blind_spot_threshold_)
00290 {
00291 for(int i = 0; i < n; i++)
00292 {
00293
00294 double t = (i / (n - 1.0));
00295 blind_spots_.push_back(Vector2(t * pt1.x + (1.0 - t) * pt2.x,
00296 t * pt1.y + (1.0 - t) * pt2.y));
00297 }
00298 return true;
00299 }
00300 else
00301 {
00302 return false;
00303 }
00304 }
00305
00306
00307 #define LEFT 1
00308 #define RIGHT 2
00309 #define REAR 4
00310 #define FRONT 8
00311
00312 double BaseDistance::distance(std::vector<Vector2> &points, Vector2 *nearest, double dx, double dy, double dth)
00313 {
00314
00315
00316 Vector2 rnearest(0, 0), lnearest(0, 0);
00317 double rqdistance=INFINITY, ldistance=INFINITY;
00318
00319
00320
00321 if(points.size() == 0)
00322 ROS_WARN("No points received. Maybe the laser topic is wrong?");
00323
00324
00325 tf::Matrix3x3 rob(cos(rob_th_), -sin(rob_th_), rob_x_,
00326 sin(rob_th_), cos(rob_th_), rob_y_,
00327 0, 0, 1);
00328
00329
00330 tf::Matrix3x3 adj(cos(dth), -sin(dth), dx,
00331 sin(dth), cos(dth), dy,
00332 0, 0, 1);
00333
00334
00335 tf::Matrix3x3 m = adj*rob;
00336
00337
00338
00339
00340
00341
00342 for(unsigned int i=0; i < points.size(); i++) {
00343
00344 double px = points[i].x * m[0][0] + points[i].y * m[0][1] + m[0][2];
00345 double py = points[i].x * m[1][0] + points[i].y * m[1][1] + m[1][2];
00346
00347
00348 double dright = -py + right_;
00349 double dleft = py - left_;
00350 double drear = -px + rear_;
00351 double dfront = px - front_;
00352
00353
00354
00355 int area = 0;
00356
00357 area |= RIGHT * (dright > -tolerance_);
00358 area |= LEFT * (dleft > -tolerance_);
00359 area |= REAR * (drear > -tolerance_);
00360 area |= FRONT * (dfront > -tolerance_);
00361
00362 double rqdist=INFINITY, ldist=INFINITY;
00363 switch(area) {
00364 case(RIGHT): ldist = dright; break;
00365 case(LEFT): ldist = dleft; break;
00366 case(REAR): ldist = drear; break;
00367 case(FRONT): ldist = dfront; break;
00368
00369 case(LEFT | REAR): rqdist = dleft*dleft + drear*drear; break;
00370 case(LEFT | FRONT): rqdist = dleft*dleft + dfront*dfront; break;
00371 case(RIGHT | REAR): rqdist = dright*dright + drear*drear; break;
00372 case(RIGHT | FRONT): rqdist = dright*dright + dfront*dfront; break;
00373 }
00374
00375 if(ldist < ldistance) {
00376 ldistance = ldist;
00377 lnearest = Vector2(px, py);
00378
00379 }
00380
00381 if(rqdist < rqdistance) {
00382 rqdistance = rqdist;
00383 rnearest = Vector2(px, py);
00384
00385 }
00386 }
00387
00388
00389 double rdistance = sqrt(rqdistance);
00390 if(rdistance < ldistance) {
00391
00392 if(nearest)
00393 *nearest = rnearest;
00394 return rdistance;
00395 } else {
00396
00397 if(nearest)
00398 *nearest = lnearest;
00399 return ldistance;
00400 }
00401 }
00402
00403
00404 #define CLAMP(x, min, max) (x < min) ? min : ((x > max) ? max : x)
00405
00406 double BaseDistance::grad(std::vector<Vector2> &points, double *gx, double *gy, double *gth)
00407 {
00408 if(!gx || !gy || !gth)
00409 return 0;
00410
00411 double d0, dx_p, dy_p, dth_p, dx_n, dy_n, dth_n;
00412
00413
00414
00415 double v_len = sqrt(vx_last_*vx_last_ + vy_last_*vy_last_ + vth_last_*vth_last_);
00416
00417
00418 double dd = CLAMP(v_len*d_*2, 0.005, 0.15);
00419
00420
00421 d0 = distance(points, &nearest_, 0, 0, 0);
00422
00423
00424 dx_p = distance(points, 0, dd, 0, 0);
00425 dx_n = distance(points, 0, -dd, 0, 0);
00426
00427 dy_p = distance(points, 0, 0, dd, 0);
00428 dy_n = distance(points, 0, 0, -dd, 0);
00429
00430 dth_p = distance(points, 0, 0, 0, dd);
00431 dth_n = distance(points, 0, 0, 0, -dd);
00432
00433 *gx = (dx_p - dx_n) / (2.0 * dd);
00434 *gy = (dy_p - dy_n) / (2.0 * dd);
00435 *gth = (dth_p - dth_n) / (2.0 * dd);
00436
00437
00438 double g2x = (dx_p + dx_n - 2*d0) / (dd*dd);
00439 double g2y = (dy_p + dy_n - 2*d0) / (dd*dd);
00440 double g2th = (dth_p + dth_n - 2*d0) / (dd*dd);
00441
00442
00443
00444
00445
00446 double g2_scaledown = 2.0;
00447 double gx_damp = (fabs(g2x) < g2_scaledown) ? 1.0 : g2_scaledown / fabs(g2x);
00448 double gy_damp = (fabs(g2y) < g2_scaledown) ? 1.0 : g2_scaledown / fabs(g2y);
00449 double gth_damp = (fabs(g2th) < g2_scaledown) ? 1.0 : g2_scaledown / fabs(g2th);
00450
00451 *gx = *gx * gx_damp;
00452 *gy = *gy * gy_damp;
00453 *gth = *gth * gth_damp;
00454
00455 std_msgs::Float64MultiArray msg;
00456 msg.data.resize(7);
00457 msg.data[0] = dd;
00458
00459 msg.data[1] = *gx;
00460 msg.data[2] = *gy;
00461 msg.data[3] = *gth;
00462
00463 msg.data[4] = g2x;
00464 msg.data[5] = g2y;
00465 msg.data[6] = g2th;
00466
00467 debug_pub_.publish(msg);
00468
00469 return d0;
00470 }
00471
00472
00473 double BaseDistance::brake(std::vector<Vector2> &points, double *vx, double *vy, double *vth)
00474 {
00475 double factor = 1.5;
00476 double d = distance(points, 0, -*vx*d_*factor, -*vy*d_*factor, -*vth*d_*factor);
00477 if(d < safety_dist_) {
00478 mode_ |= MODE_BRAKING;
00479 *vx = 0.0;
00480 *vy = 0.0;
00481 *vth = 0.0;
00482 }
00483 return d;
00484 }
00485
00486
00487 double BaseDistance::project(std::vector<Vector2> &points, double *vx, double *vy, double *vth)
00488 {
00489 double d, gx, gy, gth, factor = 0;
00490 d = grad(points, &gx, &gy, >h);
00491
00492
00493 double l_grad = 1/sqrt(gx*gx + gy*gy + gth*gth);
00494 gx*=l_grad;
00495 gy*=l_grad;
00496 gth*=l_grad;
00497
00498 if(d < slowdown_far_) {
00499
00500 double dp = *vx*gx + *vy*gy + *vth*gth;
00501 if(dp > 0) {
00502 if(d < slowdown_near_)
00503 {
00504 mode_ |= MODE_HARD_PROJECTING;
00505 factor = 1;
00506 }
00507 else
00508 {
00509 mode_ |= MODE_PROJECTING;
00510 factor = (d - slowdown_far_)/(slowdown_near_ - slowdown_far_);
00511 }
00512
00513 *vx -= gx *dp*factor;
00514 *vy -= gy *dp*factor;
00515 *vth -= gth*dp*factor;
00516 }
00517 }
00518
00519 if(d < repelling_dist_) {
00520 mode_ |= MODE_REPELLING;
00521 double l_grad_2d = 1/sqrt(gx*gx + gy*gy);
00522 double a = (1.0/d - 1.0/repelling_dist_)
00523 * (1.0/d - 1.0/repelling_dist_)
00524 * 0.5 * repelling_gain_;
00525
00526 if(a > repelling_gain_max_)
00527 a = repelling_gain_max_;
00528 *vx -= gx * l_grad_2d * a;
00529 *vy -= gy * l_grad_2d * a;
00530 }
00531
00532 return d;
00533 }
00534
00535
00536 void BaseDistance::compute_distance_keeping(double *vx, double *vy, double *vth)
00537 {
00538
00539
00540 compute_pose2d(base_link_frame_.c_str(), odom_frame_.c_str(), ros::Time(0), &rob_x_, &rob_y_, &rob_th_);
00541
00542
00543 std::vector<Vector2> current_points;
00544
00545 {
00546
00547
00548
00549 current_points.reserve((laser_points_[0] ? laser_points_[0]->size() : 0) +
00550 (laser_points_[1] ? laser_points_[1]->size() : 0) +
00551 blind_spots_.size());
00552
00553 if(laser_points_[0])
00554 {
00555 std::copy(laser_points_[0]->begin(), laser_points_[0]->end(),
00556 std::back_insert_iterator<std::vector<Vector2> >(current_points));
00557 }
00558 if(laser_points_[1])
00559 {
00560 std::copy(laser_points_[1]->begin(), laser_points_[1]->end(),
00561 std::back_insert_iterator<std::vector<Vector2> >(current_points));
00562 }
00563 std::copy(blind_spots_.begin(), blind_spots_.end(),
00564 std::back_insert_iterator<std::vector<Vector2> >(current_points));
00565 }
00566
00567 mode_ = MODE_FREE;
00568
00569
00570 project(current_points, vx, vy, vth);
00571
00572
00573 brake(current_points, vx, vy, vth);
00574
00575 vx_last_ = *vx;
00576 vy_last_ = *vy;
00577 vth_last_ = *vth;
00578
00579 publishNearestPoint();
00580 publishBaseMarker();
00581 publishPoints(current_points);
00582 }
00583
00584
00585 void BaseDistance::publishLaserMarker(const Vector2 &pt, const std::string &ns, int id)
00586 {
00587 visualization_msgs::Marker marker;
00588 marker.header.frame_id = odom_frame_;
00589 marker.header.stamp = ros::Time::now();
00590 marker.ns = ns;
00591 marker.type = visualization_msgs::Marker::CUBE;
00592 marker.action = visualization_msgs::Marker::ADD;
00593 marker.pose.position.z = 0.55;
00594 marker.pose.orientation.x = 0.0;
00595 marker.pose.orientation.y = 0.0;
00596 marker.pose.orientation.z = 0.0;
00597 marker.pose.orientation.w = 1.0;
00598 marker.scale.x = marker_size_;
00599 marker.scale.y = marker_size_;
00600 marker.scale.z = marker_size_;
00601 marker.color.r = 1;
00602 marker.color.g = 0;
00603 marker.color.b = 0;
00604 marker.color.a = 1.0;
00605 marker.lifetime = ros::Duration(0.2);
00606 marker.id = id;
00607 marker.pose.position.x = pt.x;
00608 marker.pose.position.y = pt.y;
00609 marker.pose.orientation.w = 1.0;
00610 marker_pub_.publish(marker);
00611 }
00612
00613
00614 void BaseDistance::publishNearestPoint()
00615 {
00616
00617 visualization_msgs::Marker marker;
00618 marker.header.frame_id = base_link_frame_;
00619 marker.header.stamp = ros::Time::now();
00620 marker.ns = "nearest_point";
00621 marker.id = 0;
00622
00623 if(mode_ & MODE_REPELLING)
00624 marker.type = visualization_msgs::Marker::SPHERE;
00625 else
00626 marker.type = visualization_msgs::Marker::CUBE;
00627
00628 marker.action = visualization_msgs::Marker::ADD;
00629 marker.pose.position.x = nearest_.x;
00630 marker.pose.position.y = nearest_.y;
00631 marker.pose.position.z = 0.55;
00632 marker.pose.orientation.x = 0.0;
00633 marker.pose.orientation.y = 0.0;
00634 marker.pose.orientation.z = 0.0;
00635 marker.pose.orientation.w = 1.0;
00636 marker.scale.x = marker_size_*2;
00637 marker.scale.y = marker_size_*2;
00638 marker.scale.z = marker_size_*2;
00639
00640 switch(mode_ & MODE_PROJECTION_MASK)
00641 {
00642 case(MODE_FREE):
00643 marker.color.r = 0.0f;
00644 marker.color.g = 1.0f;
00645 break;
00646 case(MODE_PROJECTING):
00647 marker.color.r = 0.0f;
00648 marker.color.g = 1.0f;
00649 break;
00650 case(MODE_HARD_PROJECTING):
00651 marker.color.r = 1.0f;
00652 marker.color.g = 0.5f;
00653 break;
00654 case(MODE_BRAKING):
00655 marker.color.r = 1.0f;
00656 marker.color.g = 0.0f;
00657 break;
00658 }
00659 marker.color.b = 0.0f;
00660 marker.color.a = 1.0;
00661
00662 marker.lifetime = ros::Duration(0.1);
00663 marker_pub_.publish(marker);
00664 }
00665
00666
00667 void BaseDistance::publishBaseMarker()
00668 {
00669 visualization_msgs::Marker marker;
00670 marker.header.frame_id = base_link_frame_;
00671 marker.header.stamp = ros::Time::now();
00672 marker.ns = "base_footprint";
00673 marker.id = 0;
00674 marker.type = visualization_msgs::Marker::CUBE;
00675 marker.action = visualization_msgs::Marker::ADD;
00676 marker.pose.position.x = (front_ + rear_) * 0.5;
00677 marker.pose.position.y = (right_ + left_) * 0.5;
00678 marker.pose.position.z = 0.3;
00679 marker.pose.orientation.x = 0.0;
00680 marker.pose.orientation.y = 0.0;
00681 marker.pose.orientation.z = 0.0;
00682 marker.pose.orientation.w = 1.0;
00683 marker.scale.x = front_ - rear_;
00684 marker.scale.y = right_ - left_;
00685 marker.scale.z = 0.6;
00686 marker.color.r = 0.5f;
00687 marker.color.g = 0.5f;
00688 marker.color.b = 1.0f;
00689 marker.color.a = 0.5;
00690 marker.lifetime = ros::Duration();
00691 marker_pub_.publish(marker);
00692 }
00693
00694
00695 void BaseDistance::publishPoints(const std::vector<Vector2> &points)
00696 {
00697 sensor_msgs::PointCloud cloud;
00698
00699 cloud.points.resize(points.size());
00700
00701 std::vector<Vector2>::const_iterator src_it;
00702 sensor_msgs::PointCloud::_points_type::iterator dest_it;
00703
00704 cloud.header.stamp = ros::Time::now();
00705 cloud.header.frame_id = odom_frame_;
00706 for(src_it=points.begin(), dest_it=cloud.points.begin();
00707 src_it != points.end();
00708 src_it++, dest_it++)
00709 {
00710 dest_it->x = src_it->x;
00711 dest_it->y = src_it->y;
00712 dest_it->z = 0.3;
00713 }
00714
00715
00716 if(points.size() == 0)
00717 {
00718 cloud.points.resize(1);
00719 cloud.points[0].x = 0.0;
00720 cloud.points[0].y = 0.0;
00721 cloud.points[0].z = 0.0;
00722 }
00723
00724 laser_points_pub_.publish(cloud);
00725 }