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 <base_local_planner/trajectory_planner.h>
00039
00040 using namespace std;
00041 using namespace costmap_2d;
00042
00043 namespace base_local_planner{
00044 TrajectoryPlanner::TrajectoryPlanner(WorldModel& world_model,
00045 const Costmap2D& costmap,
00046 std::vector<geometry_msgs::Point> footprint_spec,
00047 double inscribed_radius, double circumscribed_radius,
00048 double acc_lim_x, double acc_lim_y, double acc_lim_theta,
00049 double sim_time, double sim_granularity,
00050 int vx_samples, int vtheta_samples,
00051 double pdist_scale, double gdist_scale, double occdist_scale,
00052 double heading_lookahead, double oscillation_reset_dist,
00053 double escape_reset_dist, double escape_reset_theta,
00054 bool holonomic_robot,
00055 double max_vel_x, double min_vel_x,
00056 double max_vel_th, double min_vel_th, double min_in_place_vel_th,
00057 double backup_vel,
00058 bool dwa, bool heading_scoring, double heading_scoring_timestep, bool simple_attractor,
00059 vector<double> y_vels, double stop_time_buffer, double sim_period, double angular_sim_granularity)
00060 : map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()), costmap_(costmap),
00061 world_model_(world_model), footprint_spec_(footprint_spec),
00062 inscribed_radius_(inscribed_radius), circumscribed_radius_(circumscribed_radius),
00063 sim_time_(sim_time), sim_granularity_(sim_granularity), angular_sim_granularity_(angular_sim_granularity),
00064 vx_samples_(vx_samples), vtheta_samples_(vtheta_samples),
00065 pdist_scale_(pdist_scale), gdist_scale_(gdist_scale), occdist_scale_(occdist_scale),
00066 acc_lim_x_(acc_lim_x), acc_lim_y_(acc_lim_y), acc_lim_theta_(acc_lim_theta),
00067 prev_x_(0), prev_y_(0), escape_x_(0), escape_y_(0), escape_theta_(0), heading_lookahead_(heading_lookahead),
00068 oscillation_reset_dist_(oscillation_reset_dist), escape_reset_dist_(escape_reset_dist),
00069 escape_reset_theta_(escape_reset_theta), holonomic_robot_(holonomic_robot),
00070 max_vel_x_(max_vel_x), min_vel_x_(min_vel_x),
00071 max_vel_th_(max_vel_th), min_vel_th_(min_vel_th), min_in_place_vel_th_(min_in_place_vel_th),
00072 backup_vel_(backup_vel),
00073 dwa_(dwa), heading_scoring_(heading_scoring), heading_scoring_timestep_(heading_scoring_timestep),
00074 simple_attractor_(simple_attractor), y_vels_(y_vels), stop_time_buffer_(stop_time_buffer), sim_period_(sim_period)
00075 {
00076
00077 stuck_left = false;
00078 stuck_right = false;
00079 stuck_left_strafe = false;
00080 stuck_right_strafe = false;
00081 rotating_left = false;
00082 rotating_right = false;
00083 strafe_left = false;
00084 strafe_right = false;
00085
00086 escaping_ = false;
00087
00088 }
00089
00090 TrajectoryPlanner::~TrajectoryPlanner(){}
00091
00092 bool TrajectoryPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
00093 MapCell cell = map_(cx, cy);
00094 if (cell.within_robot) {
00095 return false;
00096 }
00097 occ_cost = costmap_.getCost(cx, cy);
00098 if (cell.path_dist >= map_.map_.size() || cell.goal_dist >= map_.map_.size() || occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
00099 return false;
00100 }
00101 path_cost = cell.path_dist;
00102 goal_cost = cell.goal_dist;
00103 total_cost = pdist_scale_ * path_cost + gdist_scale_ * goal_cost + occdist_scale_ * occ_cost;
00104 return true;
00105 }
00106
00107
00108 void TrajectoryPlanner::generateTrajectory(double x, double y, double theta, double vx, double vy,
00109 double vtheta, double vx_samp, double vy_samp, double vtheta_samp,
00110 double acc_x, double acc_y, double acc_theta, double impossible_cost,
00111 Trajectory& traj){
00112 double x_i = x;
00113 double y_i = y;
00114 double theta_i = theta;
00115
00116 double vx_i, vy_i, vtheta_i;
00117
00118 vx_i = vx;
00119 vy_i = vy;
00120 vtheta_i = vtheta;
00121
00122
00123 double vmag = sqrt(vx_samp * vx_samp + vy_samp * vy_samp);
00124
00125
00126 int num_steps;
00127 if(!heading_scoring_)
00128 num_steps = int(max((vmag * sim_time_) / sim_granularity_, fabs(vtheta_samp) / angular_sim_granularity_) + 0.5);
00129 else
00130 num_steps = int(sim_time_ / sim_granularity_ + 0.5);
00131
00132
00133 if(num_steps == 0)
00134 num_steps = 1;
00135
00136 double dt = sim_time_ / num_steps;
00137 double time = 0.0;
00138
00139
00140 traj.resetPoints();
00141 traj.xv_ = vx_samp;
00142 traj.yv_ = vy_samp;
00143 traj.thetav_ = vtheta_samp;
00144 traj.cost_ = -1.0;
00145
00146
00147 double path_dist = 0.0;
00148 double goal_dist = 0.0;
00149 double occ_cost = 0.0;
00150 double heading_diff = 0.0;
00151
00152 for(int i = 0; i < num_steps; ++i){
00153
00154 unsigned int cell_x, cell_y;
00155
00156
00157 if(!costmap_.worldToMap(x_i, y_i, cell_x, cell_y)){
00158 traj.cost_ = -1.0;
00159 return;
00160 }
00161
00162
00163 double footprint_cost = footprintCost(x_i, y_i, theta_i);
00164
00165
00166 if(footprint_cost < 0){
00167 traj.cost_ = -1.0;
00168 return;
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190 }
00191
00192 occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y)));
00193
00194 double cell_pdist = map_(cell_x, cell_y).path_dist;
00195 double cell_gdist = map_(cell_x, cell_y).goal_dist;
00196
00197
00198 if(!heading_scoring_){
00199 path_dist = cell_pdist;
00200 goal_dist = cell_gdist;
00201 }
00202 else if(time >= heading_scoring_timestep_ && time < heading_scoring_timestep_ + dt){
00203 heading_diff = headingDiff(cell_x, cell_y, x_i, y_i, theta_i);
00204
00205 path_dist = cell_pdist;
00206 goal_dist = cell_gdist;
00207 }
00208
00209
00210 if(simple_attractor_){
00211 goal_dist = (x_i - global_plan_[global_plan_.size() -1].pose.position.x) *
00212 (x_i - global_plan_[global_plan_.size() -1].pose.position.x) +
00213 (y_i - global_plan_[global_plan_.size() -1].pose.position.y) *
00214 (y_i - global_plan_[global_plan_.size() -1].pose.position.y);
00215 path_dist = 0.0;
00216 }
00217 else{
00218
00219 if(impossible_cost <= goal_dist || impossible_cost <= path_dist){
00220 ROS_DEBUG("No path to goal with goal distance = %f, path_distance = %f and max cost = %f",
00221 goal_dist, path_dist, impossible_cost);
00222 traj.cost_ = -2.0;
00223 return;
00224 }
00225 }
00226
00227
00228
00229 traj.addPoint(x_i, y_i, theta_i);
00230
00231
00232 vx_i = computeNewVelocity(vx_samp, vx_i, acc_x, dt);
00233 vy_i = computeNewVelocity(vy_samp, vy_i, acc_y, dt);
00234 vtheta_i = computeNewVelocity(vtheta_samp, vtheta_i, acc_theta, dt);
00235
00236
00237 x_i = computeNewXPosition(x_i, vx_i, vy_i, theta_i, dt);
00238 y_i = computeNewYPosition(y_i, vx_i, vy_i, theta_i, dt);
00239 theta_i = computeNewThetaPosition(theta_i, vtheta_i, dt);
00240
00241
00242 time += dt;
00243 }
00244
00245
00246 double cost = -1.0;
00247 if(!heading_scoring_)
00248 cost = pdist_scale_ * path_dist + goal_dist * gdist_scale_ + occdist_scale_ * occ_cost;
00249 else
00250 cost = occdist_scale_ * occ_cost + pdist_scale_ * path_dist + 0.3 * heading_diff + goal_dist * gdist_scale_;
00251
00252 traj.cost_ = cost;
00253 }
00254
00255 double TrajectoryPlanner::headingDiff(int cell_x, int cell_y, double x, double y, double heading){
00256 double heading_diff = DBL_MAX;
00257 unsigned int goal_cell_x, goal_cell_y;
00258
00259 for(int i = global_plan_.size() - 1; i >=0; --i){
00260 if(costmap_.worldToMap(global_plan_[i].pose.position.x, global_plan_[i].pose.position.y, goal_cell_x, goal_cell_y)){
00261 if(lineCost(cell_x, goal_cell_x, cell_y, goal_cell_y) >= 0){
00262 double gx, gy;
00263 costmap_.mapToWorld(goal_cell_x, goal_cell_y, gx, gy);
00264 double v1_x = gx - x;
00265 double v1_y = gy - y;
00266 double v2_x = cos(heading);
00267 double v2_y = sin(heading);
00268
00269 double perp_dot = v1_x * v2_y - v1_y * v2_x;
00270 double dot = v1_x * v2_x + v1_y * v2_y;
00271
00272
00273 double vector_angle = atan2(perp_dot, dot);
00274
00275 heading_diff = fabs(vector_angle);
00276 return heading_diff;
00277
00278 }
00279 }
00280 }
00281 return heading_diff;
00282 }
00283
00284
00285 double TrajectoryPlanner::lineCost(int x0, int x1,
00286 int y0, int y1){
00287
00288 int deltax = abs(x1 - x0);
00289 int deltay = abs(y1 - y0);
00290 int x = x0;
00291 int y = y0;
00292
00293 int xinc1, xinc2, yinc1, yinc2;
00294 int den, num, numadd, numpixels;
00295
00296 double line_cost = 0.0;
00297 double point_cost = -1.0;
00298
00299 if (x1 >= x0)
00300 {
00301 xinc1 = 1;
00302 xinc2 = 1;
00303 }
00304 else
00305 {
00306 xinc1 = -1;
00307 xinc2 = -1;
00308 }
00309
00310 if (y1 >= y0)
00311 {
00312 yinc1 = 1;
00313 yinc2 = 1;
00314 }
00315 else
00316 {
00317 yinc1 = -1;
00318 yinc2 = -1;
00319 }
00320
00321 if (deltax >= deltay)
00322 {
00323 xinc1 = 0;
00324 yinc2 = 0;
00325 den = deltax;
00326 num = deltax / 2;
00327 numadd = deltay;
00328 numpixels = deltax;
00329 }
00330 else
00331 {
00332 xinc2 = 0;
00333 yinc1 = 0;
00334 den = deltay;
00335 num = deltay / 2;
00336 numadd = deltax;
00337 numpixels = deltay;
00338 }
00339
00340 for (int curpixel = 0; curpixel <= numpixels; curpixel++)
00341 {
00342 point_cost = pointCost(x, y);
00343
00344 if(point_cost < 0)
00345 return -1;
00346
00347 if(line_cost < point_cost)
00348 line_cost = point_cost;
00349
00350 num += numadd;
00351 if (num >= den)
00352 {
00353 num -= den;
00354 x += xinc1;
00355 y += yinc1;
00356 }
00357 x += xinc2;
00358 y += yinc2;
00359 }
00360
00361 return line_cost;
00362 }
00363
00364 double TrajectoryPlanner::pointCost(int x, int y){
00365 unsigned char cost = costmap_.getCost(x, y);
00366
00367 if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION){
00368 return -1;
00369 }
00370
00371 return cost;
00372 }
00373
00374 void TrajectoryPlanner::updatePlan(const vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists){
00375 global_plan_.resize(new_plan.size());
00376 for(unsigned int i = 0; i < new_plan.size(); ++i){
00377 global_plan_[i] = new_plan[i];
00378 }
00379
00380 if(compute_dists){
00381
00382 map_.resetPathDist();
00383
00384
00385 map_.setPathCells(costmap_, global_plan_);
00386 ROS_DEBUG("Path/Goal distance computed");
00387 }
00388 }
00389
00390 bool TrajectoryPlanner::checkTrajectory(double x, double y, double theta, double vx, double vy,
00391 double vtheta, double vx_samp, double vy_samp, double vtheta_samp){
00392 Trajectory t;
00393
00394 double cost = scoreTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp);
00395
00396
00397 if(cost >= 0)
00398 return true;
00399
00400
00401 return false;
00402 }
00403
00404 double TrajectoryPlanner::scoreTrajectory(double x, double y, double theta, double vx, double vy,
00405 double vtheta, double vx_samp, double vy_samp, double vtheta_samp){
00406 Trajectory t;
00407 double impossible_cost = map_.map_.size();
00408 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00409 acc_lim_x_, acc_lim_y_, acc_lim_theta_, impossible_cost, t);
00410
00411
00412 return double( t.cost_ );
00413 }
00414
00415
00416 Trajectory TrajectoryPlanner::createTrajectories(double x, double y, double theta,
00417 double vx, double vy, double vtheta,
00418 double acc_x, double acc_y, double acc_theta){
00419
00420 double max_vel_x, max_vel_theta;
00421 double min_vel_x, min_vel_theta;
00422
00423
00424 if(dwa_){
00425 max_vel_x = max(min(max_vel_x_, vx + acc_x * sim_period_), min_vel_x_);
00426 min_vel_x = max(min_vel_x_, vx - acc_x * sim_period_);
00427
00428 max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_period_);
00429 min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_period_);
00430 }
00431 else{
00432 max_vel_x = max(min(max_vel_x_, vx + acc_x * sim_time_), min_vel_x_);
00433 min_vel_x = max(min_vel_x_, vx - acc_x * sim_time_);
00434
00435 max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_time_);
00436 min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_time_);
00437 }
00438
00439
00440
00441 double dvx = (max_vel_x - min_vel_x) / (vx_samples_ - 1);
00442 double dvtheta = (max_vel_theta - min_vel_theta) / (vtheta_samples_ - 1);
00443
00444 double vx_samp = min_vel_x;
00445 double vtheta_samp = min_vel_theta;
00446 double vy_samp = 0.0;
00447
00448
00449 Trajectory* best_traj = &traj_one;
00450 best_traj->cost_ = -1.0;
00451
00452 Trajectory* comp_traj = &traj_two;
00453 comp_traj->cost_ = -1.0;
00454
00455 Trajectory* swap = NULL;
00456
00457
00458 double impossible_cost = map_.map_.size();
00459
00460
00461 if(!escaping_){
00462
00463 for(int i = 0; i < vx_samples_; ++i){
00464 vtheta_samp = 0;
00465
00466 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00467 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00468
00469
00470 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00471 swap = best_traj;
00472 best_traj = comp_traj;
00473 comp_traj = swap;
00474 }
00475
00476 vtheta_samp = min_vel_theta;
00477
00478 for(int j = 0; j < vtheta_samples_ - 1; ++j){
00479 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00480 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00481
00482
00483 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00484 swap = best_traj;
00485 best_traj = comp_traj;
00486 comp_traj = swap;
00487 }
00488 vtheta_samp += dvtheta;
00489 }
00490 vx_samp += dvx;
00491 }
00492
00493
00494 if(holonomic_robot_){
00495
00496 vx_samp = 0.1;
00497 vy_samp = 0.1;
00498 vtheta_samp = 0.0;
00499 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00500 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00501
00502
00503 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00504 swap = best_traj;
00505 best_traj = comp_traj;
00506 comp_traj = swap;
00507 }
00508
00509 vx_samp = 0.1;
00510 vy_samp = -0.1;
00511 vtheta_samp = 0.0;
00512 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00513 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00514
00515
00516 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00517 swap = best_traj;
00518 best_traj = comp_traj;
00519 comp_traj = swap;
00520 }
00521 }
00522 }
00523
00524
00525 vtheta_samp = min_vel_theta;
00526 vx_samp = 0.0;
00527 vy_samp = 0.0;
00528
00529
00530 double heading_dist = DBL_MAX;
00531
00532 for(int i = 0; i < vtheta_samples_; ++i){
00533
00534 double vtheta_samp_limited = vtheta_samp > 0 ? max(vtheta_samp, min_in_place_vel_th_)
00535 : min(vtheta_samp, -1.0 * min_in_place_vel_th_);
00536
00537 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp_limited,
00538 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00539
00540
00541
00542 if(comp_traj->cost_ >= 0
00543 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0 || best_traj->yv_ != 0.0)
00544 && (vtheta_samp > dvtheta || vtheta_samp < -1 * dvtheta)){
00545 double x_r, y_r, th_r;
00546 comp_traj->getEndpoint(x_r, y_r, th_r);
00547 x_r += heading_lookahead_ * cos(th_r);
00548 y_r += heading_lookahead_ * sin(th_r);
00549 unsigned int cell_x, cell_y;
00550
00551
00552 if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)){
00553 double ahead_gdist = map_(cell_x, cell_y).goal_dist;
00554 if(ahead_gdist < heading_dist){
00555
00556 if(vtheta_samp < 0 && !stuck_left){
00557 swap = best_traj;
00558 best_traj = comp_traj;
00559 comp_traj = swap;
00560 heading_dist = ahead_gdist;
00561 }
00562
00563 else if(vtheta_samp > 0 && !stuck_right){
00564 swap = best_traj;
00565 best_traj = comp_traj;
00566 comp_traj = swap;
00567 heading_dist = ahead_gdist;
00568 }
00569 }
00570 }
00571 }
00572
00573 vtheta_samp += dvtheta;
00574 }
00575
00576
00577 if(best_traj->cost_ >= 0){
00578 if(!(best_traj->xv_ > 0)){
00579 if(best_traj->thetav_ < 0){
00580 if(rotating_right){
00581 stuck_right = true;
00582 }
00583 rotating_left = true;
00584 }
00585 else if(best_traj->thetav_ > 0){
00586 if(rotating_left){
00587 stuck_left = true;
00588 }
00589 rotating_right = true;
00590 }
00591 else if(best_traj->yv_ > 0){
00592 if(strafe_right){
00593 stuck_right_strafe = true;
00594 }
00595 strafe_left = true;
00596 }
00597 else if(best_traj->yv_ < 0){
00598 if(strafe_left){
00599 stuck_left_strafe = true;
00600 }
00601 strafe_right = true;
00602 }
00603
00604
00605 prev_x_ = x;
00606 prev_y_ = y;
00607 }
00608
00609 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_));
00610 if(dist > oscillation_reset_dist_){
00611 rotating_left = false;
00612 rotating_right = false;
00613 strafe_left = false;
00614 strafe_right = false;
00615 stuck_left = false;
00616 stuck_right = false;
00617 stuck_left_strafe = false;
00618 stuck_right_strafe = false;
00619 }
00620
00621 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_));
00622 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){
00623 escaping_ = false;
00624 }
00625
00626 return *best_traj;
00627 }
00628
00629
00630
00631
00632 if(holonomic_robot_){
00633
00634 vtheta_samp = min_vel_theta;
00635 vx_samp = 0.0;
00636
00637
00638 for(unsigned int i = 0; i < y_vels_.size(); ++i){
00639 vtheta_samp = 0;
00640 vy_samp = y_vels_[i];
00641
00642 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00643 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00644
00645
00646 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0)){
00647 double x_r, y_r, th_r;
00648 comp_traj->getEndpoint(x_r, y_r, th_r);
00649 x_r += heading_lookahead_ * cos(th_r);
00650 y_r += heading_lookahead_ * sin(th_r);
00651 unsigned int cell_x, cell_y;
00652
00653
00654 if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)){
00655 double ahead_gdist = map_(cell_x, cell_y).goal_dist;
00656 if(ahead_gdist < heading_dist){
00657
00658 if(vy_samp > 0 && !stuck_left_strafe){
00659 swap = best_traj;
00660 best_traj = comp_traj;
00661 comp_traj = swap;
00662 heading_dist = ahead_gdist;
00663 }
00664
00665 else if(vy_samp < 0 && !stuck_right_strafe){
00666 swap = best_traj;
00667 best_traj = comp_traj;
00668 comp_traj = swap;
00669 heading_dist = ahead_gdist;
00670 }
00671 }
00672 }
00673 }
00674 }
00675 }
00676
00677
00678 if(best_traj->cost_ >= 0){
00679 if(!(best_traj->xv_ > 0)){
00680 if(best_traj->thetav_ < 0){
00681 if(rotating_right){
00682 stuck_right = true;
00683 }
00684 rotating_left = true;
00685 }
00686 else if(best_traj->thetav_ > 0){
00687 if(rotating_left){
00688 stuck_left = true;
00689 }
00690 rotating_right = true;
00691 }
00692 else if(best_traj->yv_ > 0){
00693 if(strafe_right){
00694 stuck_right_strafe = true;
00695 }
00696 strafe_left = true;
00697 }
00698 else if(best_traj->yv_ < 0){
00699 if(strafe_left){
00700 stuck_left_strafe = true;
00701 }
00702 strafe_right = true;
00703 }
00704
00705
00706 prev_x_ = x;
00707 prev_y_ = y;
00708
00709 }
00710
00711 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_));
00712 if(dist > oscillation_reset_dist_){
00713 rotating_left = false;
00714 rotating_right = false;
00715 strafe_left = false;
00716 strafe_right = false;
00717 stuck_left = false;
00718 stuck_right = false;
00719 stuck_left_strafe = false;
00720 stuck_right_strafe = false;
00721 }
00722
00723 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_));
00724 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){
00725 escaping_ = false;
00726 }
00727
00728 return *best_traj;
00729 }
00730
00731
00732 vtheta_samp = 0.0;
00733 vx_samp = backup_vel_;
00734 vy_samp = 0.0;
00735 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00736 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00737
00738
00739
00740
00741
00742
00743
00744
00745
00746
00747
00748 swap = best_traj;
00749 best_traj = comp_traj;
00750 comp_traj = swap;
00751
00752 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_));
00753 if(dist > oscillation_reset_dist_){
00754 rotating_left = false;
00755 rotating_right = false;
00756 strafe_left = false;
00757 strafe_right = false;
00758 stuck_left = false;
00759 stuck_right = false;
00760 stuck_left_strafe = false;
00761 stuck_right_strafe = false;
00762 }
00763
00764
00765 if(!escaping_ && best_traj->cost_ > -2.0){
00766 escape_x_ = x;
00767 escape_y_ = y;
00768 escape_theta_ = theta;
00769 escaping_ = true;
00770 }
00771
00772 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_));
00773
00774 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){
00775 escaping_ = false;
00776 }
00777
00778
00779
00780 if(best_traj->cost_ == -1.0)
00781 best_traj->cost_ = 1.0;
00782
00783 return *best_traj;
00784
00785 }
00786
00787
00788 Trajectory TrajectoryPlanner::findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00789 tf::Stamped<tf::Pose>& drive_velocities){
00790
00791 double yaw = tf::getYaw(global_pose.getRotation());
00792 double vel_yaw = tf::getYaw(global_vel.getRotation());
00793
00794 double x = global_pose.getOrigin().getX();
00795 double y = global_pose.getOrigin().getY();
00796 double theta = yaw;
00797
00798 double vx = global_vel.getOrigin().getX();
00799 double vy = global_vel.getOrigin().getY();
00800 double vtheta = vel_yaw;
00801
00802
00803 map_.resetPathDist();
00804
00805
00806 vector<base_local_planner::Position2DInt> footprint_list = getFootprintCells(x, y, theta, true);
00807
00808
00809 for(unsigned int i = 0; i < footprint_list.size(); ++i){
00810 map_(footprint_list[i].x, footprint_list[i].y).within_robot = true;
00811 }
00812
00813
00814 map_.setPathCells(costmap_, global_plan_);
00815 ROS_DEBUG("Path/Goal distance computed");
00816
00817
00818 Trajectory best = createTrajectories(x, y, theta,
00819 vx, vy, vtheta,
00820 acc_lim_x_, acc_lim_y_, acc_lim_theta_);
00821 ROS_DEBUG("Trajectories created");
00822
00823
00824
00825
00826
00827
00828
00829
00830
00831
00832
00833
00834
00835
00836
00837
00838
00839
00840
00841
00842
00843
00844
00845
00846
00847
00848 if(best.cost_ < 0){
00849 drive_velocities.setIdentity();
00850 }
00851 else{
00852 btVector3 start(best.xv_, best.yv_, 0);
00853 drive_velocities.setOrigin(start);
00854 btMatrix3x3 matrix;
00855 matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_));
00856 drive_velocities.setBasis(matrix);
00857 }
00858
00859 return best;
00860 }
00861
00862
00863 double TrajectoryPlanner::footprintCost(double x_i, double y_i, double theta_i){
00864
00865 double cos_th = cos(theta_i);
00866 double sin_th = sin(theta_i);
00867 vector<geometry_msgs::Point> oriented_footprint;
00868 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){
00869 geometry_msgs::Point new_pt;
00870 new_pt.x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th);
00871 new_pt.y = y_i + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th);
00872 oriented_footprint.push_back(new_pt);
00873 }
00874
00875 geometry_msgs::Point robot_position;
00876 robot_position.x = x_i;
00877 robot_position.y = y_i;
00878
00879
00880 double footprint_cost = world_model_.footprintCost(robot_position, oriented_footprint, inscribed_radius_, circumscribed_radius_);
00881
00882 return footprint_cost;
00883 }
00884
00885 void TrajectoryPlanner::getLineCells(int x0, int x1, int y0, int y1, vector<base_local_planner::Position2DInt>& pts){
00886
00887 int deltax = abs(x1 - x0);
00888 int deltay = abs(y1 - y0);
00889 int x = x0;
00890 int y = y0;
00891
00892 int xinc1, xinc2, yinc1, yinc2;
00893 int den, num, numadd, numpixels;
00894
00895 base_local_planner::Position2DInt pt;
00896
00897 if (x1 >= x0)
00898 {
00899 xinc1 = 1;
00900 xinc2 = 1;
00901 }
00902 else
00903 {
00904 xinc1 = -1;
00905 xinc2 = -1;
00906 }
00907
00908 if (y1 >= y0)
00909 {
00910 yinc1 = 1;
00911 yinc2 = 1;
00912 }
00913 else
00914 {
00915 yinc1 = -1;
00916 yinc2 = -1;
00917 }
00918
00919 if (deltax >= deltay)
00920 {
00921 xinc1 = 0;
00922 yinc2 = 0;
00923 den = deltax;
00924 num = deltax / 2;
00925 numadd = deltay;
00926 numpixels = deltax;
00927 }
00928 else
00929 {
00930 xinc2 = 0;
00931 yinc1 = 0;
00932 den = deltay;
00933 num = deltay / 2;
00934 numadd = deltax;
00935 numpixels = deltay;
00936 }
00937
00938 for (int curpixel = 0; curpixel <= numpixels; curpixel++)
00939 {
00940 pt.x = x;
00941 pt.y = y;
00942 pts.push_back(pt);
00943
00944 num += numadd;
00945 if (num >= den)
00946 {
00947 num -= den;
00948 x += xinc1;
00949 y += yinc1;
00950 }
00951 x += xinc2;
00952 y += yinc2;
00953 }
00954 }
00955
00956
00957 vector<base_local_planner::Position2DInt> TrajectoryPlanner::getFootprintCells(double x_i, double y_i, double theta_i, bool fill){
00958 vector<base_local_planner::Position2DInt> footprint_cells;
00959
00960
00961 if(footprint_spec_.size() <= 1){
00962 unsigned int mx, my;
00963 if(costmap_.worldToMap(x_i, y_i, mx, my)){
00964 Position2DInt center;
00965 center.x = mx;
00966 center.y = my;
00967 footprint_cells.push_back(center);
00968 }
00969 return footprint_cells;
00970 }
00971
00972
00973 double cos_th = cos(theta_i);
00974 double sin_th = sin(theta_i);
00975 double new_x, new_y;
00976 unsigned int x0, y0, x1, y1;
00977 unsigned int last_index = footprint_spec_.size() - 1;
00978
00979 for(unsigned int i = 0; i < last_index; ++i){
00980
00981 new_x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th);
00982 new_y = y_i + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th);
00983 if(!costmap_.worldToMap(new_x, new_y, x0, y0))
00984 return footprint_cells;
00985
00986
00987 new_x = x_i + (footprint_spec_[i + 1].x * cos_th - footprint_spec_[i + 1].y * sin_th);
00988 new_y = y_i + (footprint_spec_[i + 1].x * sin_th + footprint_spec_[i + 1].y * cos_th);
00989 if(!costmap_.worldToMap(new_x, new_y, x1, y1))
00990 return footprint_cells;
00991
00992 getLineCells(x0, x1, y0, y1, footprint_cells);
00993 }
00994
00995
00996 new_x = x_i + (footprint_spec_[last_index].x * cos_th - footprint_spec_[last_index].y * sin_th);
00997 new_y = y_i + (footprint_spec_[last_index].x * sin_th + footprint_spec_[last_index].y * cos_th);
00998 if(!costmap_.worldToMap(new_x, new_y, x0, y0))
00999 return footprint_cells;
01000
01001 new_x = x_i + (footprint_spec_[0].x * cos_th - footprint_spec_[0].y * sin_th);
01002 new_y = y_i + (footprint_spec_[0].x * sin_th + footprint_spec_[0].y * cos_th);
01003 if(!costmap_.worldToMap(new_x, new_y, x1, y1))
01004 return footprint_cells;
01005
01006 getLineCells(x0, x1, y0, y1, footprint_cells);
01007
01008 if(fill)
01009 getFillCells(footprint_cells);
01010
01011 return footprint_cells;
01012 }
01013
01014 void TrajectoryPlanner::getFillCells(vector<base_local_planner::Position2DInt>& footprint){
01015
01016 base_local_planner::Position2DInt swap, pt;
01017 unsigned int i = 0;
01018 while(i < footprint.size() - 1){
01019 if(footprint[i].x > footprint[i + 1].x){
01020 swap = footprint[i];
01021 footprint[i] = footprint[i + 1];
01022 footprint[i + 1] = swap;
01023 if(i > 0)
01024 --i;
01025 }
01026 else
01027 ++i;
01028 }
01029
01030 i = 0;
01031 base_local_planner::Position2DInt min_pt;
01032 base_local_planner::Position2DInt max_pt;
01033 unsigned int min_x = footprint[0].x;
01034 unsigned int max_x = footprint[footprint.size() -1].x;
01035
01036 for(unsigned int x = min_x; x <= max_x; ++x){
01037 if(i >= footprint.size() - 1)
01038 break;
01039
01040 if(footprint[i].y < footprint[i + 1].y){
01041 min_pt = footprint[i];
01042 max_pt = footprint[i + 1];
01043 }
01044 else{
01045 min_pt = footprint[i + 1];
01046 max_pt = footprint[i];
01047 }
01048
01049 i += 2;
01050 while(i < footprint.size() && footprint[i].x == x){
01051 if(footprint[i].y < min_pt.y)
01052 min_pt = footprint[i];
01053 else if(footprint[i].y > max_pt.y)
01054 max_pt = footprint[i];
01055 ++i;
01056 }
01057
01058
01059 for(unsigned int y = min_pt.y; y < max_pt.y; ++y){
01060 pt.x = x;
01061 pt.y = y;
01062 footprint.push_back(pt);
01063 }
01064 }
01065 }
01066
01067 void TrajectoryPlanner::getLocalGoal(double& x, double& y){
01068 x = map_.goal_x_;
01069 y = map_.goal_y_;
01070 }
01071
01072 };
01073
01074