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 #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 TrajectoryPlanner::~TrajectoryPlanner(){}
00188
00189 bool TrajectoryPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
00190 MapCell cell = path_map_(cx, cy);
00191 MapCell goal_cell = goal_map_(cx, cy);
00192 if (cell.within_robot) {
00193 return false;
00194 }
00195 occ_cost = costmap_.getCost(cx, cy);
00196 if (cell.target_dist == path_map_.obstacleCosts() ||
00197 cell.target_dist == path_map_.unreachableCellCosts() ||
00198 occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
00199 return false;
00200 }
00201 path_cost = cell.target_dist;
00202 goal_cost = goal_cell.target_dist;
00203 total_cost = pdist_scale_ * path_cost + gdist_scale_ * goal_cost + occdist_scale_ * occ_cost;
00204 return true;
00205 }
00206
00210 void TrajectoryPlanner::generateTrajectory(
00211 double x, double y, double theta,
00212 double vx, double vy, double vtheta,
00213 double vx_samp, double vy_samp, double vtheta_samp,
00214 double acc_x, double acc_y, double acc_theta,
00215 double impossible_cost,
00216 Trajectory& traj) {
00217
00218
00219 boost::mutex::scoped_lock l(configuration_mutex_);
00220
00221 double x_i = x;
00222 double y_i = y;
00223 double theta_i = theta;
00224
00225 double vx_i, vy_i, vtheta_i;
00226
00227 vx_i = vx;
00228 vy_i = vy;
00229 vtheta_i = vtheta;
00230
00231
00232 double vmag = sqrt(vx_samp * vx_samp + vy_samp * vy_samp);
00233
00234
00235 int num_steps;
00236 if(!heading_scoring_) {
00237 num_steps = int(max((vmag * sim_time_) / sim_granularity_, fabs(vtheta_samp) / angular_sim_granularity_) + 0.5);
00238 } else {
00239 num_steps = int(sim_time_ / sim_granularity_ + 0.5);
00240 }
00241
00242
00243 if(num_steps == 0) {
00244 num_steps = 1;
00245 }
00246
00247 double dt = sim_time_ / num_steps;
00248 double time = 0.0;
00249
00250
00251 traj.resetPoints();
00252 traj.xv_ = vx_samp;
00253 traj.yv_ = vy_samp;
00254 traj.thetav_ = vtheta_samp;
00255 traj.cost_ = -1.0;
00256
00257
00258 double path_dist = 0.0;
00259 double goal_dist = 0.0;
00260 double occ_cost = 0.0;
00261 double heading_diff = 0.0;
00262
00263 for(int i = 0; i < num_steps; ++i){
00264
00265 unsigned int cell_x, cell_y;
00266
00267
00268 if(!costmap_.worldToMap(x_i, y_i, cell_x, cell_y)){
00269 traj.cost_ = -1.0;
00270 return;
00271 }
00272
00273
00274 double footprint_cost = footprintCost(x_i, y_i, theta_i);
00275
00276
00277 if(footprint_cost < 0){
00278 traj.cost_ = -1.0;
00279 return;
00280
00281
00282
00283
00284
00285
00286
00287
00288
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298
00299
00300
00301 }
00302
00303 occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y)));
00304
00305
00306 if (simple_attractor_) {
00307 goal_dist = (x_i - global_plan_[global_plan_.size() -1].pose.position.x) *
00308 (x_i - global_plan_[global_plan_.size() -1].pose.position.x) +
00309 (y_i - global_plan_[global_plan_.size() -1].pose.position.y) *
00310 (y_i - global_plan_[global_plan_.size() -1].pose.position.y);
00311 } else {
00312
00313 bool update_path_and_goal_distances = true;
00314
00315
00316
00317 if (heading_scoring_) {
00318 if (time >= heading_scoring_timestep_ && time < heading_scoring_timestep_ + dt) {
00319 heading_diff = headingDiff(cell_x, cell_y, x_i, y_i, theta_i);
00320 } else {
00321 update_path_and_goal_distances = false;
00322 }
00323 }
00324
00325 if (update_path_and_goal_distances) {
00326
00327 path_dist = path_map_(cell_x, cell_y).target_dist;
00328 goal_dist = goal_map_(cell_x, cell_y).target_dist;
00329
00330
00331 if(impossible_cost <= goal_dist || impossible_cost <= path_dist){
00332
00333
00334 traj.cost_ = -2.0;
00335 return;
00336 }
00337 }
00338 }
00339
00340
00341
00342 traj.addPoint(x_i, y_i, theta_i);
00343
00344
00345 vx_i = computeNewVelocity(vx_samp, vx_i, acc_x, dt);
00346 vy_i = computeNewVelocity(vy_samp, vy_i, acc_y, dt);
00347 vtheta_i = computeNewVelocity(vtheta_samp, vtheta_i, acc_theta, dt);
00348
00349
00350 x_i = computeNewXPosition(x_i, vx_i, vy_i, theta_i, dt);
00351 y_i = computeNewYPosition(y_i, vx_i, vy_i, theta_i, dt);
00352 theta_i = computeNewThetaPosition(theta_i, vtheta_i, dt);
00353
00354
00355 time += dt;
00356 }
00357
00358
00359 double cost = -1.0;
00360 if (!heading_scoring_) {
00361 cost = pdist_scale_ * path_dist + goal_dist * gdist_scale_ + occdist_scale_ * occ_cost;
00362 } else {
00363 cost = occdist_scale_ * occ_cost + pdist_scale_ * path_dist + 0.3 * heading_diff + goal_dist * gdist_scale_;
00364 }
00365 traj.cost_ = cost;
00366 }
00367
00368 double TrajectoryPlanner::headingDiff(int cell_x, int cell_y, double x, double y, double heading){
00369 double heading_diff = DBL_MAX;
00370 unsigned int goal_cell_x, goal_cell_y;
00371
00372 for (int i = global_plan_.size() - 1; i >=0; --i) {
00373 if (costmap_.worldToMap(global_plan_[i].pose.position.x, global_plan_[i].pose.position.y, goal_cell_x, goal_cell_y)) {
00374 if (lineCost(cell_x, goal_cell_x, cell_y, goal_cell_y) >= 0) {
00375 double gx, gy;
00376 costmap_.mapToWorld(goal_cell_x, goal_cell_y, gx, gy);
00377 double v1_x = gx - x;
00378 double v1_y = gy - y;
00379 double v2_x = cos(heading);
00380 double v2_y = sin(heading);
00381
00382 double perp_dot = v1_x * v2_y - v1_y * v2_x;
00383 double dot = v1_x * v2_x + v1_y * v2_y;
00384
00385
00386 double vector_angle = atan2(perp_dot, dot);
00387
00388 heading_diff = fabs(vector_angle);
00389 return heading_diff;
00390
00391 }
00392 }
00393 }
00394 return heading_diff;
00395 }
00396
00397
00398 double TrajectoryPlanner::lineCost(int x0, int x1,
00399 int y0, int y1){
00400
00401 int deltax = abs(x1 - x0);
00402 int deltay = abs(y1 - y0);
00403 int x = x0;
00404 int y = y0;
00405
00406 int xinc1, xinc2, yinc1, yinc2;
00407 int den, num, numadd, numpixels;
00408
00409 double line_cost = 0.0;
00410 double point_cost = -1.0;
00411
00412 if (x1 >= x0)
00413 {
00414 xinc1 = 1;
00415 xinc2 = 1;
00416 }
00417 else
00418 {
00419 xinc1 = -1;
00420 xinc2 = -1;
00421 }
00422
00423 if (y1 >= y0)
00424 {
00425 yinc1 = 1;
00426 yinc2 = 1;
00427 }
00428 else
00429 {
00430 yinc1 = -1;
00431 yinc2 = -1;
00432 }
00433
00434 if (deltax >= deltay)
00435 {
00436 xinc1 = 0;
00437 yinc2 = 0;
00438 den = deltax;
00439 num = deltax / 2;
00440 numadd = deltay;
00441 numpixels = deltax;
00442 } else {
00443 xinc2 = 0;
00444 yinc1 = 0;
00445 den = deltay;
00446 num = deltay / 2;
00447 numadd = deltax;
00448 numpixels = deltay;
00449 }
00450
00451 for (int curpixel = 0; curpixel <= numpixels; curpixel++) {
00452 point_cost = pointCost(x, y);
00453
00454 if (point_cost < 0) {
00455 return -1;
00456 }
00457
00458 if (line_cost < point_cost) {
00459 line_cost = point_cost;
00460 }
00461
00462 num += numadd;
00463 if (num >= den) {
00464 num -= den;
00465 x += xinc1;
00466 y += yinc1;
00467 }
00468 x += xinc2;
00469 y += yinc2;
00470 }
00471
00472 return line_cost;
00473 }
00474
00475 double TrajectoryPlanner::pointCost(int x, int y){
00476 unsigned char cost = costmap_.getCost(x, y);
00477
00478 if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION){
00479 return -1;
00480 }
00481
00482 return cost;
00483 }
00484
00485 void TrajectoryPlanner::updatePlan(const vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists){
00486 global_plan_.resize(new_plan.size());
00487 for(unsigned int i = 0; i < new_plan.size(); ++i){
00488 global_plan_[i] = new_plan[i];
00489 }
00490
00491 if( global_plan_.size() > 0 ){
00492 geometry_msgs::PoseStamped& final_goal_pose = global_plan_[ global_plan_.size() - 1 ];
00493 final_goal_x_ = final_goal_pose.pose.position.x;
00494 final_goal_y_ = final_goal_pose.pose.position.y;
00495 final_goal_position_valid_ = true;
00496 } else {
00497 final_goal_position_valid_ = false;
00498 }
00499
00500 if (compute_dists) {
00501
00502 path_map_.resetPathDist();
00503 goal_map_.resetPathDist();
00504
00505
00506 path_map_.setTargetCells(costmap_, global_plan_);
00507 goal_map_.setLocalGoal(costmap_, global_plan_);
00508 ROS_DEBUG("Path/Goal distance computed");
00509 }
00510 }
00511
00512 bool TrajectoryPlanner::checkTrajectory(double x, double y, double theta, double vx, double vy,
00513 double vtheta, double vx_samp, double vy_samp, double vtheta_samp){
00514 Trajectory t;
00515
00516 double cost = scoreTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp);
00517
00518
00519 if(cost >= 0) {
00520 return true;
00521 }
00522 ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vx_samp, vy_samp, vtheta_samp, cost);
00523
00524
00525 return false;
00526 }
00527
00528 double TrajectoryPlanner::scoreTrajectory(double x, double y, double theta, double vx, double vy,
00529 double vtheta, double vx_samp, double vy_samp, double vtheta_samp) {
00530 Trajectory t;
00531 double impossible_cost = path_map_.obstacleCosts();
00532 generateTrajectory(x, y, theta,
00533 vx, vy, vtheta,
00534 vx_samp, vy_samp, vtheta_samp,
00535 acc_lim_x_, acc_lim_y_, acc_lim_theta_,
00536 impossible_cost, t);
00537
00538
00539 return double( t.cost_ );
00540 }
00541
00542
00543
00544
00545 Trajectory TrajectoryPlanner::createTrajectories(double x, double y, double theta,
00546 double vx, double vy, double vtheta,
00547 double acc_x, double acc_y, double acc_theta) {
00548
00549 double max_vel_x = max_vel_x_, max_vel_theta;
00550 double min_vel_x, min_vel_theta;
00551
00552 if( final_goal_position_valid_ ){
00553 double final_goal_dist = hypot( final_goal_x_ - x, final_goal_y_ - y );
00554 max_vel_x = min( max_vel_x, final_goal_dist / sim_time_ );
00555 }
00556
00557
00558 if (dwa_) {
00559 max_vel_x = max(min(max_vel_x, vx + acc_x * sim_period_), min_vel_x_);
00560 min_vel_x = max(min_vel_x_, vx - acc_x * sim_period_);
00561
00562 max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_period_);
00563 min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_period_);
00564 } else {
00565 max_vel_x = max(min(max_vel_x, vx + acc_x * sim_time_), min_vel_x_);
00566 min_vel_x = max(min_vel_x_, vx - acc_x * sim_time_);
00567
00568 max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_time_);
00569 min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_time_);
00570 }
00571
00572
00573
00574 double dvx = (max_vel_x - min_vel_x) / (vx_samples_ - 1);
00575 double dvtheta = (max_vel_theta - min_vel_theta) / (vtheta_samples_ - 1);
00576
00577 double vx_samp = min_vel_x;
00578 double vtheta_samp = min_vel_theta;
00579 double vy_samp = 0.0;
00580
00581
00582 Trajectory* best_traj = &traj_one;
00583 best_traj->cost_ = -1.0;
00584
00585 Trajectory* comp_traj = &traj_two;
00586 comp_traj->cost_ = -1.0;
00587
00588 Trajectory* swap = NULL;
00589
00590
00591 double impossible_cost = path_map_.obstacleCosts();
00592
00593
00594 if (!escaping_) {
00595
00596 for(int i = 0; i < vx_samples_; ++i) {
00597 vtheta_samp = 0;
00598
00599 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00600 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00601
00602
00603 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00604 swap = best_traj;
00605 best_traj = comp_traj;
00606 comp_traj = swap;
00607 }
00608
00609 vtheta_samp = min_vel_theta;
00610
00611 for(int j = 0; j < vtheta_samples_ - 1; ++j){
00612 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00613 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00614
00615
00616 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00617 swap = best_traj;
00618 best_traj = comp_traj;
00619 comp_traj = swap;
00620 }
00621 vtheta_samp += dvtheta;
00622 }
00623 vx_samp += dvx;
00624 }
00625
00626
00627 if (holonomic_robot_) {
00628
00629 vx_samp = 0.1;
00630 vy_samp = 0.1;
00631 vtheta_samp = 0.0;
00632 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00633 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00634
00635
00636 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00637 swap = best_traj;
00638 best_traj = comp_traj;
00639 comp_traj = swap;
00640 }
00641
00642 vx_samp = 0.1;
00643 vy_samp = -0.1;
00644 vtheta_samp = 0.0;
00645 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00646 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00647
00648
00649 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
00650 swap = best_traj;
00651 best_traj = comp_traj;
00652 comp_traj = swap;
00653 }
00654 }
00655 }
00656
00657
00658 vtheta_samp = min_vel_theta;
00659 vx_samp = 0.0;
00660 vy_samp = 0.0;
00661
00662
00663 double heading_dist = DBL_MAX;
00664
00665 for(int i = 0; i < vtheta_samples_; ++i) {
00666
00667 double vtheta_samp_limited = vtheta_samp > 0 ? max(vtheta_samp, min_in_place_vel_th_)
00668 : min(vtheta_samp, -1.0 * min_in_place_vel_th_);
00669
00670 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp_limited,
00671 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00672
00673
00674
00675 if(comp_traj->cost_ >= 0
00676 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0 || best_traj->yv_ != 0.0)
00677 && (vtheta_samp > dvtheta || vtheta_samp < -1 * dvtheta)){
00678 double x_r, y_r, th_r;
00679 comp_traj->getEndpoint(x_r, y_r, th_r);
00680 x_r += heading_lookahead_ * cos(th_r);
00681 y_r += heading_lookahead_ * sin(th_r);
00682 unsigned int cell_x, cell_y;
00683
00684
00685 if (costmap_.worldToMap(x_r, y_r, cell_x, cell_y)) {
00686 double ahead_gdist = goal_map_(cell_x, cell_y).target_dist;
00687 if (ahead_gdist < heading_dist) {
00688
00689 if (vtheta_samp < 0 && !stuck_left) {
00690 swap = best_traj;
00691 best_traj = comp_traj;
00692 comp_traj = swap;
00693 heading_dist = ahead_gdist;
00694 }
00695
00696 else if(vtheta_samp > 0 && !stuck_right) {
00697 swap = best_traj;
00698 best_traj = comp_traj;
00699 comp_traj = swap;
00700 heading_dist = ahead_gdist;
00701 }
00702 }
00703 }
00704 }
00705
00706 vtheta_samp += dvtheta;
00707 }
00708
00709
00710 if (best_traj->cost_ >= 0) {
00711
00712 if ( ! (best_traj->xv_ > 0)) {
00713 if (best_traj->thetav_ < 0) {
00714 if (rotating_right) {
00715 stuck_right = true;
00716 }
00717 rotating_left = true;
00718 } else if (best_traj->thetav_ > 0) {
00719 if (rotating_left){
00720 stuck_left = true;
00721 }
00722 rotating_right = true;
00723 } else if(best_traj->yv_ > 0) {
00724 if (strafe_right) {
00725 stuck_right_strafe = true;
00726 }
00727 strafe_left = true;
00728 } else if(best_traj->yv_ < 0){
00729 if (strafe_left) {
00730 stuck_left_strafe = true;
00731 }
00732 strafe_right = true;
00733 }
00734
00735
00736 prev_x_ = x;
00737 prev_y_ = y;
00738 }
00739
00740 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_));
00741 if (dist > oscillation_reset_dist_) {
00742 rotating_left = false;
00743 rotating_right = false;
00744 strafe_left = false;
00745 strafe_right = false;
00746 stuck_left = false;
00747 stuck_right = false;
00748 stuck_left_strafe = false;
00749 stuck_right_strafe = false;
00750 }
00751
00752 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_));
00753 if(dist > escape_reset_dist_ ||
00754 fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){
00755 escaping_ = false;
00756 }
00757
00758 return *best_traj;
00759 }
00760
00761
00762
00763
00764 if (holonomic_robot_) {
00765
00766 vtheta_samp = min_vel_theta;
00767 vx_samp = 0.0;
00768
00769
00770 for(unsigned int i = 0; i < y_vels_.size(); ++i){
00771 vtheta_samp = 0;
00772 vy_samp = y_vels_[i];
00773
00774 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00775 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00776
00777
00778 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0)){
00779 double x_r, y_r, th_r;
00780 comp_traj->getEndpoint(x_r, y_r, th_r);
00781 x_r += heading_lookahead_ * cos(th_r);
00782 y_r += heading_lookahead_ * sin(th_r);
00783 unsigned int cell_x, cell_y;
00784
00785
00786 if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)) {
00787 double ahead_gdist = goal_map_(cell_x, cell_y).target_dist;
00788 if (ahead_gdist < heading_dist) {
00789
00790 if (vy_samp > 0 && !stuck_left_strafe) {
00791 swap = best_traj;
00792 best_traj = comp_traj;
00793 comp_traj = swap;
00794 heading_dist = ahead_gdist;
00795 }
00796
00797 else if(vy_samp < 0 && !stuck_right_strafe) {
00798 swap = best_traj;
00799 best_traj = comp_traj;
00800 comp_traj = swap;
00801 heading_dist = ahead_gdist;
00802 }
00803 }
00804 }
00805 }
00806 }
00807 }
00808
00809
00810 if (best_traj->cost_ >= 0) {
00811 if (!(best_traj->xv_ > 0)) {
00812 if (best_traj->thetav_ < 0) {
00813 if (rotating_right){
00814 stuck_right = true;
00815 }
00816 rotating_left = true;
00817 } else if(best_traj->thetav_ > 0) {
00818 if(rotating_left){
00819 stuck_left = true;
00820 }
00821 rotating_right = true;
00822 } else if(best_traj->yv_ > 0) {
00823 if(strafe_right){
00824 stuck_right_strafe = true;
00825 }
00826 strafe_left = true;
00827 } else if(best_traj->yv_ < 0) {
00828 if(strafe_left){
00829 stuck_left_strafe = true;
00830 }
00831 strafe_right = true;
00832 }
00833
00834
00835 prev_x_ = x;
00836 prev_y_ = y;
00837
00838 }
00839
00840 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_));
00841 if(dist > oscillation_reset_dist_) {
00842 rotating_left = false;
00843 rotating_right = false;
00844 strafe_left = false;
00845 strafe_right = false;
00846 stuck_left = false;
00847 stuck_right = false;
00848 stuck_left_strafe = false;
00849 stuck_right_strafe = false;
00850 }
00851
00852 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_));
00853 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_) {
00854 escaping_ = false;
00855 }
00856
00857 return *best_traj;
00858 }
00859
00860
00861 vtheta_samp = 0.0;
00862 vx_samp = backup_vel_;
00863 vy_samp = 0.0;
00864 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
00865 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
00866
00867
00868
00869
00870
00871
00872
00873
00874
00875
00876
00877 swap = best_traj;
00878 best_traj = comp_traj;
00879 comp_traj = swap;
00880
00881 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_));
00882 if (dist > oscillation_reset_dist_) {
00883 rotating_left = false;
00884 rotating_right = false;
00885 strafe_left = false;
00886 strafe_right = false;
00887 stuck_left = false;
00888 stuck_right = false;
00889 stuck_left_strafe = false;
00890 stuck_right_strafe = false;
00891 }
00892
00893
00894 if (!escaping_ && best_traj->cost_ > -2.0) {
00895 escape_x_ = x;
00896 escape_y_ = y;
00897 escape_theta_ = theta;
00898 escaping_ = true;
00899 }
00900
00901 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_));
00902
00903 if (dist > escape_reset_dist_ ||
00904 fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_) {
00905 escaping_ = false;
00906 }
00907
00908
00909
00910 if(best_traj->cost_ == -1.0)
00911 best_traj->cost_ = 1.0;
00912
00913 return *best_traj;
00914
00915 }
00916
00917
00918 Trajectory TrajectoryPlanner::findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00919 tf::Stamped<tf::Pose>& drive_velocities){
00920
00921 Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation()));
00922 Eigen::Vector3f vel(global_vel.getOrigin().getX(), global_vel.getOrigin().getY(), tf::getYaw(global_vel.getRotation()));
00923
00924
00925 path_map_.resetPathDist();
00926 goal_map_.resetPathDist();
00927
00928
00929 std::vector<base_local_planner::Position2DInt> footprint_list =
00930 footprint_helper_.getFootprintCells(
00931 pos,
00932 footprint_spec_,
00933 costmap_,
00934 true);
00935
00936
00937 for (unsigned int i = 0; i < footprint_list.size(); ++i) {
00938 path_map_(footprint_list[i].x, footprint_list[i].y).within_robot = true;
00939 }
00940
00941
00942 path_map_.setTargetCells(costmap_, global_plan_);
00943 goal_map_.setLocalGoal(costmap_, global_plan_);
00944 ROS_DEBUG("Path/Goal distance computed");
00945
00946
00947 Trajectory best = createTrajectories(pos[0], pos[1], pos[2],
00948 vel[0], vel[1], vel[2],
00949 acc_lim_x_, acc_lim_y_, acc_lim_theta_);
00950 ROS_DEBUG("Trajectories created");
00951
00952
00953
00954
00955
00956
00957
00958
00959
00960
00961
00962
00963
00964
00965
00966
00967
00968
00969
00970
00971
00972
00973
00974
00975
00976
00977 if(best.cost_ < 0){
00978 drive_velocities.setIdentity();
00979 }
00980 else{
00981 tf::Vector3 start(best.xv_, best.yv_, 0);
00982 drive_velocities.setOrigin(start);
00983 tf::Matrix3x3 matrix;
00984 matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_));
00985 drive_velocities.setBasis(matrix);
00986 }
00987
00988 return best;
00989 }
00990
00991
00992 double TrajectoryPlanner::footprintCost(double x_i, double y_i, double theta_i){
00993
00994 double cos_th = cos(theta_i);
00995 double sin_th = sin(theta_i);
00996 vector<geometry_msgs::Point> oriented_footprint;
00997 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){
00998 geometry_msgs::Point new_pt;
00999 new_pt.x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th);
01000 new_pt.y = y_i + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th);
01001 oriented_footprint.push_back(new_pt);
01002 }
01003
01004 geometry_msgs::Point robot_position;
01005 robot_position.x = x_i;
01006 robot_position.y = y_i;
01007
01008
01009 double footprint_cost = world_model_.footprintCost(robot_position, oriented_footprint, costmap_.getInscribedRadius(), costmap_.getCircumscribedRadius());
01010
01011 return footprint_cost;
01012 }
01013
01014
01015 void TrajectoryPlanner::getLocalGoal(double& x, double& y){
01016 x = path_map_.goal_x_;
01017 y = path_map_.goal_y_;
01018 }
01019
01020 };
01021
01022