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