$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * Author: Eitan Marder-Eppstein 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 void TrajectoryPlanner::reconfigure(BaseLocalPlannerConfig &cfg) 00045 { 00046 base_local_planner::BaseLocalPlannerConfig config(cfg); 00047 00048 boost::mutex::scoped_lock l(configuration_mutex_); 00049 00050 acc_lim_x_ = config.acc_lim_x; 00051 acc_lim_y_ = config.acc_lim_y; 00052 acc_lim_theta_ = config.acc_lim_theta; 00053 00054 max_vel_x_ = config.max_vel_x; 00055 min_vel_x_ = config.min_vel_x; 00056 max_vel_th_ = config.max_vel_theta; 00057 min_in_place_vel_th_ = config.min_in_place_vel_theta; 00058 00059 sim_time_ = config.sim_time; 00060 sim_granularity_ = config.sim_granularity; 00061 00062 pdist_scale_ = config.pdist_scale; 00063 gdist_scale_ = config.gdist_scale; 00064 occdist_scale_ = config.occdist_scale; 00065 00066 oscillation_reset_dist_ = config.oscillation_reset_dist; 00067 escape_reset_dist_ = config.escape_reset_dist; 00068 escape_reset_theta_ = config.escape_reset_theta; 00069 00070 vx_samples_ = config.vx_samples; 00071 vtheta_samples_ = config.vtheta_samples; 00072 00073 if (vx_samples_ <= 0) { 00074 config.vx_samples = 1; 00075 vx_samples_ = config.vx_samples; 00076 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"); 00077 } 00078 if(vtheta_samples_ <= 0) { 00079 config.vtheta_samples = 1; 00080 vtheta_samples_ = config.vtheta_samples; 00081 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"); 00082 } 00083 00084 heading_lookahead_ = config.heading_lookahead; 00085 00086 holonomic_robot_ = config.holonomic_robot; 00087 00088 backup_vel_ = config.escape_vel; 00089 00090 dwa_ = config.dwa; 00091 00092 heading_scoring_ = config.heading_scoring; 00093 heading_scoring_timestep_ = config.heading_scoring_timestep; 00094 00095 simple_attractor_ = config.simple_attractor; 00096 00097 angular_sim_granularity_ = config.angular_sim_granularity; 00098 00099 //y-vels 00100 string y_string = config.y_vels; 00101 vector<string> y_strs; 00102 boost::split(y_strs, y_string, boost::is_any_of(", "), boost::token_compress_on); 00103 00104 vector<double>y_vels; 00105 for(vector<string>::iterator it=y_strs.begin(); it != y_strs.end(); ++it) { 00106 istringstream iss(*it); 00107 double temp; 00108 iss >> temp; 00109 y_vels.push_back(temp); 00110 //ROS_INFO("Adding y_vel: %e", temp); 00111 } 00112 00113 y_vels_ = y_vels; 00114 00115 } 00116 00117 TrajectoryPlanner::TrajectoryPlanner(WorldModel& world_model, 00118 const Costmap2D& costmap, 00119 std::vector<geometry_msgs::Point> footprint_spec, 00120 double acc_lim_x, double acc_lim_y, double acc_lim_theta, 00121 double sim_time, double sim_granularity, 00122 int vx_samples, int vtheta_samples, 00123 double pdist_scale, double gdist_scale, double occdist_scale, 00124 double heading_lookahead, double oscillation_reset_dist, 00125 double escape_reset_dist, double escape_reset_theta, 00126 bool holonomic_robot, 00127 double max_vel_x, double min_vel_x, 00128 double max_vel_th, double min_vel_th, double min_in_place_vel_th, 00129 double backup_vel, 00130 bool dwa, bool heading_scoring, double heading_scoring_timestep, bool simple_attractor, 00131 vector<double> y_vels, double stop_time_buffer, double sim_period, double angular_sim_granularity) 00132 : map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()), costmap_(costmap), 00133 world_model_(world_model), footprint_spec_(footprint_spec), 00134 sim_time_(sim_time), sim_granularity_(sim_granularity), angular_sim_granularity_(angular_sim_granularity), 00135 vx_samples_(vx_samples), vtheta_samples_(vtheta_samples), 00136 pdist_scale_(pdist_scale), gdist_scale_(gdist_scale), occdist_scale_(occdist_scale), 00137 acc_lim_x_(acc_lim_x), acc_lim_y_(acc_lim_y), acc_lim_theta_(acc_lim_theta), 00138 prev_x_(0), prev_y_(0), escape_x_(0), escape_y_(0), escape_theta_(0), heading_lookahead_(heading_lookahead), 00139 oscillation_reset_dist_(oscillation_reset_dist), escape_reset_dist_(escape_reset_dist), 00140 escape_reset_theta_(escape_reset_theta), holonomic_robot_(holonomic_robot), 00141 max_vel_x_(max_vel_x), min_vel_x_(min_vel_x), 00142 max_vel_th_(max_vel_th), min_vel_th_(min_vel_th), min_in_place_vel_th_(min_in_place_vel_th), 00143 backup_vel_(backup_vel), 00144 dwa_(dwa), heading_scoring_(heading_scoring), heading_scoring_timestep_(heading_scoring_timestep), 00145 simple_attractor_(simple_attractor), y_vels_(y_vels), stop_time_buffer_(stop_time_buffer), sim_period_(sim_period) 00146 { 00147 //the robot is not stuck to begin with 00148 stuck_left = false; 00149 stuck_right = false; 00150 stuck_left_strafe = false; 00151 stuck_right_strafe = false; 00152 rotating_left = false; 00153 rotating_right = false; 00154 strafe_left = false; 00155 strafe_right = false; 00156 00157 escaping_ = false; 00158 } 00159 00160 TrajectoryPlanner::~TrajectoryPlanner(){} 00161 00162 bool TrajectoryPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) { 00163 MapCell cell = map_(cx, cy); 00164 if (cell.within_robot) { 00165 return false; 00166 } 00167 occ_cost = costmap_.getCost(cx, cy); 00168 if (cell.path_dist >= map_.map_.size() || cell.goal_dist >= map_.map_.size() || occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) { 00169 return false; 00170 } 00171 path_cost = cell.path_dist; 00172 goal_cost = cell.goal_dist; 00173 total_cost = pdist_scale_ * path_cost + gdist_scale_ * goal_cost + occdist_scale_ * occ_cost; 00174 return true; 00175 } 00176 00177 //create and score a trajectory given the current pose of the robot and selected velocities 00178 void TrajectoryPlanner::generateTrajectory(double x, double y, double theta, double vx, double vy, 00179 double vtheta, double vx_samp, double vy_samp, double vtheta_samp, 00180 double acc_x, double acc_y, double acc_theta, double impossible_cost, 00181 Trajectory& traj){ 00182 00183 // make sure the configuration doesn't change mid run 00184 boost::mutex::scoped_lock l(configuration_mutex_); 00185 00186 double x_i = x; 00187 double y_i = y; 00188 double theta_i = theta; 00189 00190 double vx_i, vy_i, vtheta_i; 00191 00192 vx_i = vx; 00193 vy_i = vy; 00194 vtheta_i = vtheta; 00195 00196 //compute the magnitude of the velocities 00197 double vmag = sqrt(vx_samp * vx_samp + vy_samp * vy_samp); 00198 00199 //compute the number of steps we must take along this trajectory to be "safe" 00200 int num_steps; 00201 if(!heading_scoring_) 00202 num_steps = int(max((vmag * sim_time_) / sim_granularity_, fabs(vtheta_samp) / angular_sim_granularity_) + 0.5); 00203 else 00204 num_steps = int(sim_time_ / sim_granularity_ + 0.5); 00205 00206 //we at least want to take one step... even if we won't move, we want to score our current position 00207 if(num_steps == 0) 00208 num_steps = 1; 00209 00210 double dt = sim_time_ / num_steps; 00211 double time = 0.0; 00212 00213 //create a potential trajectory 00214 traj.resetPoints(); 00215 traj.xv_ = vx_samp; 00216 traj.yv_ = vy_samp; 00217 traj.thetav_ = vtheta_samp; 00218 traj.cost_ = -1.0; 00219 00220 //initialize the costs for the trajectory 00221 double path_dist = 0.0; 00222 double goal_dist = 0.0; 00223 double occ_cost = 0.0; 00224 double heading_diff = 0.0; 00225 00226 for(int i = 0; i < num_steps; ++i){ 00227 //get map coordinates of a point 00228 unsigned int cell_x, cell_y; 00229 00230 //we don't want a path that goes off the know map 00231 if(!costmap_.worldToMap(x_i, y_i, cell_x, cell_y)){ 00232 traj.cost_ = -1.0; 00233 return; 00234 } 00235 00236 //check the point on the trajectory for legality 00237 double footprint_cost = footprintCost(x_i, y_i, theta_i); 00238 00239 //if the footprint hits an obstacle this trajectory is invalid 00240 if(footprint_cost < 0){ 00241 traj.cost_ = -1.0; 00242 return; 00243 //TODO: Really look at getMaxSpeedToStopInTime... dues to discretization errors and high acceleration limits, 00244 //it can actually cause the robot to hit obstacles. There may be something to be done to fix, but I'll have to 00245 //come back to it when I have time. Right now, pulling it out as it'll just make the robot a bit more conservative, 00246 //but safe. 00247 /* 00248 double max_vel_x, max_vel_y, max_vel_th; 00249 //we want to compute the max allowable speeds to be able to stop 00250 //to be safe... we'll make sure we can stop some time before we actually hit 00251 getMaxSpeedToStopInTime(time - stop_time_buffer_ - dt, max_vel_x, max_vel_y, max_vel_th); 00252 00253 //check if we can stop in time 00254 if(fabs(vx_samp) < max_vel_x && fabs(vy_samp) < max_vel_y && fabs(vtheta_samp) < max_vel_th){ 00255 ROS_ERROR("v: (%.2f, %.2f, %.2f), m: (%.2f, %.2f, %.2f) t:%.2f, st: %.2f, dt: %.2f", vx_samp, vy_samp, vtheta_samp, max_vel_x, max_vel_y, max_vel_th, time, stop_time_buffer_, dt); 00256 //if we can stop... we'll just break out of the loop here.. no point in checking future points 00257 break; 00258 } 00259 else{ 00260 traj.cost_ = -1.0; 00261 return; 00262 } 00263 */ 00264 } 00265 00266 occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y))); 00267 00268 double cell_pdist = map_(cell_x, cell_y).path_dist; 00269 double cell_gdist = map_(cell_x, cell_y).goal_dist; 00270 00271 //update path and goal distances 00272 if(!heading_scoring_){ 00273 path_dist = cell_pdist; 00274 goal_dist = cell_gdist; 00275 } 00276 else if(time >= heading_scoring_timestep_ && time < heading_scoring_timestep_ + dt){ 00277 heading_diff = headingDiff(cell_x, cell_y, x_i, y_i, theta_i); 00278 //update path and goal distances 00279 path_dist = cell_pdist; 00280 goal_dist = cell_gdist; 00281 } 00282 00283 //do we want to follow blindly 00284 if(simple_attractor_){ 00285 goal_dist = (x_i - global_plan_[global_plan_.size() -1].pose.position.x) * 00286 (x_i - global_plan_[global_plan_.size() -1].pose.position.x) + 00287 (y_i - global_plan_[global_plan_.size() -1].pose.position.y) * 00288 (y_i - global_plan_[global_plan_.size() -1].pose.position.y); 00289 path_dist = 0.0; 00290 } 00291 else{ 00292 //if a point on this trajectory has no clear path to goal it is invalid 00293 if(impossible_cost <= goal_dist || impossible_cost <= path_dist){ 00294 ROS_DEBUG("No path to goal with goal distance = %f, path_distance = %f and max cost = %f", 00295 goal_dist, path_dist, impossible_cost); 00296 traj.cost_ = -2.0; 00297 return; 00298 } 00299 } 00300 00301 00302 //the point is legal... add it to the trajectory 00303 traj.addPoint(x_i, y_i, theta_i); 00304 00305 //calculate velocities 00306 vx_i = computeNewVelocity(vx_samp, vx_i, acc_x, dt); 00307 vy_i = computeNewVelocity(vy_samp, vy_i, acc_y, dt); 00308 vtheta_i = computeNewVelocity(vtheta_samp, vtheta_i, acc_theta, dt); 00309 00310 //calculate positions 00311 x_i = computeNewXPosition(x_i, vx_i, vy_i, theta_i, dt); 00312 y_i = computeNewYPosition(y_i, vx_i, vy_i, theta_i, dt); 00313 theta_i = computeNewThetaPosition(theta_i, vtheta_i, dt); 00314 00315 //increment time 00316 time += dt; 00317 } 00318 00319 //ROS_INFO("OccCost: %f, vx: %.2f, vy: %.2f, vtheta: %.2f", occ_cost, vx_samp, vy_samp, vtheta_samp); 00320 double cost = -1.0; 00321 if(!heading_scoring_) 00322 cost = pdist_scale_ * path_dist + goal_dist * gdist_scale_ + occdist_scale_ * occ_cost; 00323 else 00324 cost = occdist_scale_ * occ_cost + pdist_scale_ * path_dist + 0.3 * heading_diff + goal_dist * gdist_scale_; 00325 00326 traj.cost_ = cost; 00327 } 00328 00329 double TrajectoryPlanner::headingDiff(int cell_x, int cell_y, double x, double y, double heading){ 00330 double heading_diff = DBL_MAX; 00331 unsigned int goal_cell_x, goal_cell_y; 00332 //find a clear line of sight from the robot's cell to a point on the path 00333 for(int i = global_plan_.size() - 1; i >=0; --i){ 00334 if(costmap_.worldToMap(global_plan_[i].pose.position.x, global_plan_[i].pose.position.y, goal_cell_x, goal_cell_y)){ 00335 if(lineCost(cell_x, goal_cell_x, cell_y, goal_cell_y) >= 0){ 00336 double gx, gy; 00337 costmap_.mapToWorld(goal_cell_x, goal_cell_y, gx, gy); 00338 double v1_x = gx - x; 00339 double v1_y = gy - y; 00340 double v2_x = cos(heading); 00341 double v2_y = sin(heading); 00342 00343 double perp_dot = v1_x * v2_y - v1_y * v2_x; 00344 double dot = v1_x * v2_x + v1_y * v2_y; 00345 00346 //get the signed angle 00347 double vector_angle = atan2(perp_dot, dot); 00348 00349 heading_diff = fabs(vector_angle); 00350 return heading_diff; 00351 00352 } 00353 } 00354 } 00355 return heading_diff; 00356 } 00357 00358 //calculate the cost of a ray-traced line 00359 double TrajectoryPlanner::lineCost(int x0, int x1, 00360 int y0, int y1){ 00361 //Bresenham Ray-Tracing 00362 int deltax = abs(x1 - x0); // The difference between the x's 00363 int deltay = abs(y1 - y0); // The difference between the y's 00364 int x = x0; // Start x off at the first pixel 00365 int y = y0; // Start y off at the first pixel 00366 00367 int xinc1, xinc2, yinc1, yinc2; 00368 int den, num, numadd, numpixels; 00369 00370 double line_cost = 0.0; 00371 double point_cost = -1.0; 00372 00373 if (x1 >= x0) // The x-values are increasing 00374 { 00375 xinc1 = 1; 00376 xinc2 = 1; 00377 } 00378 else // The x-values are decreasing 00379 { 00380 xinc1 = -1; 00381 xinc2 = -1; 00382 } 00383 00384 if (y1 >= y0) // The y-values are increasing 00385 { 00386 yinc1 = 1; 00387 yinc2 = 1; 00388 } 00389 else // The y-values are decreasing 00390 { 00391 yinc1 = -1; 00392 yinc2 = -1; 00393 } 00394 00395 if (deltax >= deltay) // There is at least one x-value for every y-value 00396 { 00397 xinc1 = 0; // Don't change the x when numerator >= denominator 00398 yinc2 = 0; // Don't change the y for every iteration 00399 den = deltax; 00400 num = deltax / 2; 00401 numadd = deltay; 00402 numpixels = deltax; // There are more x-values than y-values 00403 } 00404 else // There is at least one y-value for every x-value 00405 { 00406 xinc2 = 0; // Don't change the x for every iteration 00407 yinc1 = 0; // Don't change the y when numerator >= denominator 00408 den = deltay; 00409 num = deltay / 2; 00410 numadd = deltax; 00411 numpixels = deltay; // There are more y-values than x-values 00412 } 00413 00414 for (int curpixel = 0; curpixel <= numpixels; curpixel++) 00415 { 00416 point_cost = pointCost(x, y); //Score the current point 00417 00418 if(point_cost < 0) 00419 return -1; 00420 00421 if(line_cost < point_cost) 00422 line_cost = point_cost; 00423 00424 num += numadd; // Increase the numerator by the top of the fraction 00425 if (num >= den) // Check if numerator >= denominator 00426 { 00427 num -= den; // Calculate the new numerator value 00428 x += xinc1; // Change the x as appropriate 00429 y += yinc1; // Change the y as appropriate 00430 } 00431 x += xinc2; // Change the x as appropriate 00432 y += yinc2; // Change the y as appropriate 00433 } 00434 00435 return line_cost; 00436 } 00437 00438 double TrajectoryPlanner::pointCost(int x, int y){ 00439 unsigned char cost = costmap_.getCost(x, y); 00440 //if the cell is in an obstacle the path is invalid 00441 if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION){ 00442 return -1; 00443 } 00444 00445 return cost; 00446 } 00447 00448 void TrajectoryPlanner::updatePlan(const vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists){ 00449 global_plan_.resize(new_plan.size()); 00450 for(unsigned int i = 0; i < new_plan.size(); ++i){ 00451 global_plan_[i] = new_plan[i]; 00452 } 00453 00454 if(compute_dists){ 00455 //reset the map for new operations 00456 map_.resetPathDist(); 00457 00458 //make sure that we update our path based on the global plan and compute costs 00459 map_.setPathCells(costmap_, global_plan_); 00460 ROS_DEBUG("Path/Goal distance computed"); 00461 } 00462 } 00463 00464 bool TrajectoryPlanner::checkTrajectory(double x, double y, double theta, double vx, double vy, 00465 double vtheta, double vx_samp, double vy_samp, double vtheta_samp){ 00466 Trajectory t; 00467 00468 double cost = scoreTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp); 00469 00470 //if the trajectory is a legal one... the check passes 00471 if(cost >= 0) 00472 return true; 00473 00474 //otherwise the check fails 00475 return false; 00476 } 00477 00478 double TrajectoryPlanner::scoreTrajectory(double x, double y, double theta, double vx, double vy, 00479 double vtheta, double vx_samp, double vy_samp, double vtheta_samp){ 00480 Trajectory t; 00481 double impossible_cost = map_.map_.size(); 00482 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00483 acc_lim_x_, acc_lim_y_, acc_lim_theta_, impossible_cost, t); 00484 00485 // return the cost. 00486 return double( t.cost_ ); 00487 } 00488 00489 //create the trajectories we wish to score 00490 Trajectory TrajectoryPlanner::createTrajectories(double x, double y, double theta, 00491 double vx, double vy, double vtheta, 00492 double acc_x, double acc_y, double acc_theta){ 00493 //compute feasible velocity limits in robot space 00494 double max_vel_x, max_vel_theta; 00495 double min_vel_x, min_vel_theta; 00496 00497 //should we use the dynamic window approach? 00498 if(dwa_){ 00499 max_vel_x = max(min(max_vel_x_, vx + acc_x * sim_period_), min_vel_x_); 00500 min_vel_x = max(min_vel_x_, vx - acc_x * sim_period_); 00501 00502 max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_period_); 00503 min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_period_); 00504 } 00505 else{ 00506 max_vel_x = max(min(max_vel_x_, vx + acc_x * sim_time_), min_vel_x_); 00507 min_vel_x = max(min_vel_x_, vx - acc_x * sim_time_); 00508 00509 max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_time_); 00510 min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_time_); 00511 } 00512 00513 00514 //we want to sample the velocity space regularly 00515 double dvx = (max_vel_x - min_vel_x) / (vx_samples_ - 1); 00516 double dvtheta = (max_vel_theta - min_vel_theta) / (vtheta_samples_ - 1); 00517 00518 double vx_samp = min_vel_x; 00519 double vtheta_samp = min_vel_theta; 00520 double vy_samp = 0.0; 00521 00522 //keep track of the best trajectory seen so far 00523 Trajectory* best_traj = &traj_one; 00524 best_traj->cost_ = -1.0; 00525 00526 Trajectory* comp_traj = &traj_two; 00527 comp_traj->cost_ = -1.0; 00528 00529 Trajectory* swap = NULL; 00530 00531 //any cell with a cost greater than the size of the map is impossible 00532 double impossible_cost = map_.map_.size(); 00533 00534 //if we're performing an escape we won't allow moving forward 00535 if(!escaping_){ 00536 //loop through all x velocities 00537 for(int i = 0; i < vx_samples_; ++i){ 00538 vtheta_samp = 0; 00539 //first sample the straight trajectory 00540 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00541 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00542 00543 //if the new trajectory is better... let's take it 00544 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ 00545 swap = best_traj; 00546 best_traj = comp_traj; 00547 comp_traj = swap; 00548 } 00549 00550 vtheta_samp = min_vel_theta; 00551 //next sample all theta trajectories 00552 for(int j = 0; j < vtheta_samples_ - 1; ++j){ 00553 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00554 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00555 00556 //if the new trajectory is better... let's take it 00557 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ 00558 swap = best_traj; 00559 best_traj = comp_traj; 00560 comp_traj = swap; 00561 } 00562 vtheta_samp += dvtheta; 00563 } 00564 vx_samp += dvx; 00565 } 00566 00567 //only explore y velocities with holonomic robots 00568 if(holonomic_robot_){ 00569 //explore trajectories that move forward but also strafe slightly 00570 vx_samp = 0.1; 00571 vy_samp = 0.1; 00572 vtheta_samp = 0.0; 00573 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00574 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00575 00576 //if the new trajectory is better... let's take it 00577 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ 00578 swap = best_traj; 00579 best_traj = comp_traj; 00580 comp_traj = swap; 00581 } 00582 00583 vx_samp = 0.1; 00584 vy_samp = -0.1; 00585 vtheta_samp = 0.0; 00586 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00587 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00588 00589 //if the new trajectory is better... let's take it 00590 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ 00591 swap = best_traj; 00592 best_traj = comp_traj; 00593 comp_traj = swap; 00594 } 00595 } 00596 } 00597 00598 //next we want to generate trajectories for rotating in place 00599 vtheta_samp = min_vel_theta; 00600 vx_samp = 0.0; 00601 vy_samp = 0.0; 00602 00603 //let's try to rotate toward open space 00604 double heading_dist = DBL_MAX; 00605 00606 for(int i = 0; i < vtheta_samples_; ++i){ 00607 //enforce a minimum rotational velocity because the base can't handle small in-place rotations 00608 double vtheta_samp_limited = vtheta_samp > 0 ? max(vtheta_samp, min_in_place_vel_th_) 00609 : min(vtheta_samp, -1.0 * min_in_place_vel_th_); 00610 00611 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp_limited, 00612 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00613 00614 //if the new trajectory is better... let's take it... 00615 //note if we can legally rotate in place we prefer to do that rather than move with y velocity 00616 if(comp_traj->cost_ >= 0 00617 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0 || best_traj->yv_ != 0.0) 00618 && (vtheta_samp > dvtheta || vtheta_samp < -1 * dvtheta)){ 00619 double x_r, y_r, th_r; 00620 comp_traj->getEndpoint(x_r, y_r, th_r); 00621 x_r += heading_lookahead_ * cos(th_r); 00622 y_r += heading_lookahead_ * sin(th_r); 00623 unsigned int cell_x, cell_y; 00624 00625 //make sure that we'll be looking at a legal cell 00626 if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)){ 00627 double ahead_gdist = map_(cell_x, cell_y).goal_dist; 00628 if(ahead_gdist < heading_dist){ 00629 //if we haven't already tried rotating left since we've moved forward 00630 if(vtheta_samp < 0 && !stuck_left){ 00631 swap = best_traj; 00632 best_traj = comp_traj; 00633 comp_traj = swap; 00634 heading_dist = ahead_gdist; 00635 } 00636 //if we haven't already tried rotating right since we've moved forward 00637 else if(vtheta_samp > 0 && !stuck_right){ 00638 swap = best_traj; 00639 best_traj = comp_traj; 00640 comp_traj = swap; 00641 heading_dist = ahead_gdist; 00642 } 00643 } 00644 } 00645 } 00646 00647 vtheta_samp += dvtheta; 00648 } 00649 00650 //do we have a legal trajectory 00651 if(best_traj->cost_ >= 0){ 00652 if(!(best_traj->xv_ > 0)){ 00653 if(best_traj->thetav_ < 0){ 00654 if(rotating_right){ 00655 stuck_right = true; 00656 } 00657 rotating_left = true; 00658 } 00659 else if(best_traj->thetav_ > 0){ 00660 if(rotating_left){ 00661 stuck_left = true; 00662 } 00663 rotating_right = true; 00664 } 00665 else if(best_traj->yv_ > 0){ 00666 if(strafe_right){ 00667 stuck_right_strafe = true; 00668 } 00669 strafe_left = true; 00670 } 00671 else if(best_traj->yv_ < 0){ 00672 if(strafe_left){ 00673 stuck_left_strafe = true; 00674 } 00675 strafe_right = true; 00676 } 00677 00678 //set the position we must move a certain distance away from 00679 prev_x_ = x; 00680 prev_y_ = y; 00681 } 00682 00683 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_)); 00684 if(dist > oscillation_reset_dist_){ 00685 rotating_left = false; 00686 rotating_right = false; 00687 strafe_left = false; 00688 strafe_right = false; 00689 stuck_left = false; 00690 stuck_right = false; 00691 stuck_left_strafe = false; 00692 stuck_right_strafe = false; 00693 } 00694 00695 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_)); 00696 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){ 00697 escaping_ = false; 00698 } 00699 00700 return *best_traj; 00701 } 00702 00703 00704 00705 //only explore y velocities with holonomic robots 00706 if(holonomic_robot_){ 00707 //if we can't rotate in place or move forward... maybe we can move sideways and rotate 00708 vtheta_samp = min_vel_theta; 00709 vx_samp = 0.0; 00710 00711 //loop through all y velocities 00712 for(unsigned int i = 0; i < y_vels_.size(); ++i){ 00713 vtheta_samp = 0; 00714 vy_samp = y_vels_[i]; 00715 //sample completely horizontal trajectories 00716 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00717 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00718 00719 //if the new trajectory is better... let's take it 00720 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0)){ 00721 double x_r, y_r, th_r; 00722 comp_traj->getEndpoint(x_r, y_r, th_r); 00723 x_r += heading_lookahead_ * cos(th_r); 00724 y_r += heading_lookahead_ * sin(th_r); 00725 unsigned int cell_x, cell_y; 00726 00727 //make sure that we'll be looking at a legal cell 00728 if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)){ 00729 double ahead_gdist = map_(cell_x, cell_y).goal_dist; 00730 if(ahead_gdist < heading_dist){ 00731 //if we haven't already tried strafing left since we've moved forward 00732 if(vy_samp > 0 && !stuck_left_strafe){ 00733 swap = best_traj; 00734 best_traj = comp_traj; 00735 comp_traj = swap; 00736 heading_dist = ahead_gdist; 00737 } 00738 //if we haven't already tried rotating right since we've moved forward 00739 else if(vy_samp < 0 && !stuck_right_strafe){ 00740 swap = best_traj; 00741 best_traj = comp_traj; 00742 comp_traj = swap; 00743 heading_dist = ahead_gdist; 00744 } 00745 } 00746 } 00747 } 00748 } 00749 } 00750 00751 //do we have a legal trajectory 00752 if(best_traj->cost_ >= 0){ 00753 if(!(best_traj->xv_ > 0)){ 00754 if(best_traj->thetav_ < 0){ 00755 if(rotating_right){ 00756 stuck_right = true; 00757 } 00758 rotating_left = true; 00759 } 00760 else if(best_traj->thetav_ > 0){ 00761 if(rotating_left){ 00762 stuck_left = true; 00763 } 00764 rotating_right = true; 00765 } 00766 else if(best_traj->yv_ > 0){ 00767 if(strafe_right){ 00768 stuck_right_strafe = true; 00769 } 00770 strafe_left = true; 00771 } 00772 else if(best_traj->yv_ < 0){ 00773 if(strafe_left){ 00774 stuck_left_strafe = true; 00775 } 00776 strafe_right = true; 00777 } 00778 00779 //set the position we must move a certain distance away from 00780 prev_x_ = x; 00781 prev_y_ = y; 00782 00783 } 00784 00785 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_)); 00786 if(dist > oscillation_reset_dist_){ 00787 rotating_left = false; 00788 rotating_right = false; 00789 strafe_left = false; 00790 strafe_right = false; 00791 stuck_left = false; 00792 stuck_right = false; 00793 stuck_left_strafe = false; 00794 stuck_right_strafe = false; 00795 } 00796 00797 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_)); 00798 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){ 00799 escaping_ = false; 00800 } 00801 00802 return *best_traj; 00803 } 00804 00805 //and finally, if we can't do anything else, we want to generate trajectories that move backwards slowly 00806 vtheta_samp = 0.0; 00807 vx_samp = backup_vel_; 00808 vy_samp = 0.0; 00809 generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, 00810 acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); 00811 00812 //if the new trajectory is better... let's take it 00813 /* 00814 if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ 00815 swap = best_traj; 00816 best_traj = comp_traj; 00817 comp_traj = swap; 00818 } 00819 */ 00820 00821 //we'll allow moving backwards slowly even when the static map shows it as blocked 00822 swap = best_traj; 00823 best_traj = comp_traj; 00824 comp_traj = swap; 00825 00826 double dist = sqrt((x - prev_x_) * (x - prev_x_) + (y - prev_y_) * (y - prev_y_)); 00827 if(dist > oscillation_reset_dist_){ 00828 rotating_left = false; 00829 rotating_right = false; 00830 strafe_left = false; 00831 strafe_right = false; 00832 stuck_left = false; 00833 stuck_right = false; 00834 stuck_left_strafe = false; 00835 stuck_right_strafe = false; 00836 } 00837 00838 //only enter escape mode when the planner has given a valid goal point 00839 if(!escaping_ && best_traj->cost_ > -2.0){ 00840 escape_x_ = x; 00841 escape_y_ = y; 00842 escape_theta_ = theta; 00843 escaping_ = true; 00844 } 00845 00846 dist = sqrt((x - escape_x_) * (x - escape_x_) + (y - escape_y_) * (y - escape_y_)); 00847 00848 if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){ 00849 escaping_ = false; 00850 } 00851 00852 00853 //if the trajectory failed because the footprint hits something, we're still going to back up 00854 if(best_traj->cost_ == -1.0) 00855 best_traj->cost_ = 1.0; 00856 00857 return *best_traj; 00858 00859 } 00860 00861 //given the current state of the robot, find a good trajectory 00862 Trajectory TrajectoryPlanner::findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel, 00863 tf::Stamped<tf::Pose>& drive_velocities){ 00864 00865 double yaw = tf::getYaw(global_pose.getRotation()); 00866 double vel_yaw = tf::getYaw(global_vel.getRotation()); 00867 00868 double x = global_pose.getOrigin().getX(); 00869 double y = global_pose.getOrigin().getY(); 00870 double theta = yaw; 00871 00872 double vx = global_vel.getOrigin().getX(); 00873 double vy = global_vel.getOrigin().getY(); 00874 double vtheta = vel_yaw; 00875 00876 //reset the map for new operations 00877 map_.resetPathDist(); 00878 00879 //temporarily remove obstacles that are within the footprint of the robot 00880 vector<base_local_planner::Position2DInt> footprint_list = getFootprintCells(x, y, theta, true); 00881 00882 //mark cells within the initial footprint of the robot 00883 for(unsigned int i = 0; i < footprint_list.size(); ++i){ 00884 map_(footprint_list[i].x, footprint_list[i].y).within_robot = true; 00885 } 00886 00887 //make sure that we update our path based on the global plan and compute costs 00888 map_.setPathCells(costmap_, global_plan_); 00889 ROS_DEBUG("Path/Goal distance computed"); 00890 00891 //rollout trajectories and find the minimum cost one 00892 Trajectory best = createTrajectories(x, y, theta, 00893 vx, vy, vtheta, 00894 acc_lim_x_, acc_lim_y_, acc_lim_theta_); 00895 ROS_DEBUG("Trajectories created"); 00896 00897 /* 00898 //If we want to print a ppm file to draw goal dist 00899 char buf[4096]; 00900 sprintf(buf, "base_local_planner.ppm"); 00901 FILE *fp = fopen(buf, "w"); 00902 if(fp){ 00903 fprintf(fp, "P3\n"); 00904 fprintf(fp, "%d %d\n", map_.size_x_, map_.size_y_); 00905 fprintf(fp, "255\n"); 00906 for(int j = map_.size_y_ - 1; j >= 0; --j){ 00907 for(unsigned int i = 0; i < map_.size_x_; ++i){ 00908 int g_dist = 255 - int(map_(i, j).goal_dist); 00909 int p_dist = 255 - int(map_(i, j).path_dist); 00910 if(g_dist < 0) 00911 g_dist = 0; 00912 if(p_dist < 0) 00913 p_dist = 0; 00914 fprintf(fp, "%d 0 %d ", g_dist, 0); 00915 } 00916 fprintf(fp, "\n"); 00917 } 00918 fclose(fp); 00919 } 00920 */ 00921 00922 if(best.cost_ < 0){ 00923 drive_velocities.setIdentity(); 00924 } 00925 else{ 00926 btVector3 start(best.xv_, best.yv_, 0); 00927 drive_velocities.setOrigin(start); 00928 btMatrix3x3 matrix; 00929 matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_)); 00930 drive_velocities.setBasis(matrix); 00931 } 00932 00933 return best; 00934 } 00935 00936 //we need to take the footprint of the robot into account when we calculate cost to obstacles 00937 double TrajectoryPlanner::footprintCost(double x_i, double y_i, double theta_i){ 00938 //build the oriented footprint 00939 double cos_th = cos(theta_i); 00940 double sin_th = sin(theta_i); 00941 vector<geometry_msgs::Point> oriented_footprint; 00942 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){ 00943 geometry_msgs::Point new_pt; 00944 new_pt.x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th); 00945 new_pt.y = y_i + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th); 00946 oriented_footprint.push_back(new_pt); 00947 } 00948 00949 geometry_msgs::Point robot_position; 00950 robot_position.x = x_i; 00951 robot_position.y = y_i; 00952 00953 //check if the footprint is legal 00954 double footprint_cost = world_model_.footprintCost(robot_position, oriented_footprint, costmap_.getInscribedRadius(), costmap_.getCircumscribedRadius()); 00955 00956 return footprint_cost; 00957 } 00958 00959 void TrajectoryPlanner::getLineCells(int x0, int x1, int y0, int y1, vector<base_local_planner::Position2DInt>& pts){ 00960 //Bresenham Ray-Tracing 00961 int deltax = abs(x1 - x0); // The difference between the x's 00962 int deltay = abs(y1 - y0); // The difference between the y's 00963 int x = x0; // Start x off at the first pixel 00964 int y = y0; // Start y off at the first pixel 00965 00966 int xinc1, xinc2, yinc1, yinc2; 00967 int den, num, numadd, numpixels; 00968 00969 base_local_planner::Position2DInt pt; 00970 00971 if (x1 >= x0) // The x-values are increasing 00972 { 00973 xinc1 = 1; 00974 xinc2 = 1; 00975 } 00976 else // The x-values are decreasing 00977 { 00978 xinc1 = -1; 00979 xinc2 = -1; 00980 } 00981 00982 if (y1 >= y0) // The y-values are increasing 00983 { 00984 yinc1 = 1; 00985 yinc2 = 1; 00986 } 00987 else // The y-values are decreasing 00988 { 00989 yinc1 = -1; 00990 yinc2 = -1; 00991 } 00992 00993 if (deltax >= deltay) // There is at least one x-value for every y-value 00994 { 00995 xinc1 = 0; // Don't change the x when numerator >= denominator 00996 yinc2 = 0; // Don't change the y for every iteration 00997 den = deltax; 00998 num = deltax / 2; 00999 numadd = deltay; 01000 numpixels = deltax; // There are more x-values than y-values 01001 } 01002 else // There is at least one y-value for every x-value 01003 { 01004 xinc2 = 0; // Don't change the x for every iteration 01005 yinc1 = 0; // Don't change the y when numerator >= denominator 01006 den = deltay; 01007 num = deltay / 2; 01008 numadd = deltax; 01009 numpixels = deltay; // There are more y-values than x-values 01010 } 01011 01012 for (int curpixel = 0; curpixel <= numpixels; curpixel++) 01013 { 01014 pt.x = x; //Draw the current pixel 01015 pt.y = y; 01016 pts.push_back(pt); 01017 01018 num += numadd; // Increase the numerator by the top of the fraction 01019 if (num >= den) // Check if numerator >= denominator 01020 { 01021 num -= den; // Calculate the new numerator value 01022 x += xinc1; // Change the x as appropriate 01023 y += yinc1; // Change the y as appropriate 01024 } 01025 x += xinc2; // Change the x as appropriate 01026 y += yinc2; // Change the y as appropriate 01027 } 01028 } 01029 01030 //get the cellsof a footprint at a given position 01031 vector<base_local_planner::Position2DInt> TrajectoryPlanner::getFootprintCells(double x_i, double y_i, double theta_i, bool fill){ 01032 vector<base_local_planner::Position2DInt> footprint_cells; 01033 01034 //if we have no footprint... do nothing 01035 if(footprint_spec_.size() <= 1){ 01036 unsigned int mx, my; 01037 if(costmap_.worldToMap(x_i, y_i, mx, my)){ 01038 Position2DInt center; 01039 center.x = mx; 01040 center.y = my; 01041 footprint_cells.push_back(center); 01042 } 01043 return footprint_cells; 01044 } 01045 01046 //pre-compute cos and sin values 01047 double cos_th = cos(theta_i); 01048 double sin_th = sin(theta_i); 01049 double new_x, new_y; 01050 unsigned int x0, y0, x1, y1; 01051 unsigned int last_index = footprint_spec_.size() - 1; 01052 01053 for(unsigned int i = 0; i < last_index; ++i){ 01054 //find the cell coordinates of the first segment point 01055 new_x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th); 01056 new_y = y_i + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th); 01057 if(!costmap_.worldToMap(new_x, new_y, x0, y0)) 01058 return footprint_cells; 01059 01060 //find the cell coordinates of the second segment point 01061 new_x = x_i + (footprint_spec_[i + 1].x * cos_th - footprint_spec_[i + 1].y * sin_th); 01062 new_y = y_i + (footprint_spec_[i + 1].x * sin_th + footprint_spec_[i + 1].y * cos_th); 01063 if(!costmap_.worldToMap(new_x, new_y, x1, y1)) 01064 return footprint_cells; 01065 01066 getLineCells(x0, x1, y0, y1, footprint_cells); 01067 } 01068 01069 //we need to close the loop, so we also have to raytrace from the last pt to first pt 01070 new_x = x_i + (footprint_spec_[last_index].x * cos_th - footprint_spec_[last_index].y * sin_th); 01071 new_y = y_i + (footprint_spec_[last_index].x * sin_th + footprint_spec_[last_index].y * cos_th); 01072 if(!costmap_.worldToMap(new_x, new_y, x0, y0)) 01073 return footprint_cells; 01074 01075 new_x = x_i + (footprint_spec_[0].x * cos_th - footprint_spec_[0].y * sin_th); 01076 new_y = y_i + (footprint_spec_[0].x * sin_th + footprint_spec_[0].y * cos_th); 01077 if(!costmap_.worldToMap(new_x, new_y, x1, y1)) 01078 return footprint_cells; 01079 01080 getLineCells(x0, x1, y0, y1, footprint_cells); 01081 01082 if(fill) 01083 getFillCells(footprint_cells); 01084 01085 return footprint_cells; 01086 } 01087 01088 void TrajectoryPlanner::getFillCells(vector<base_local_planner::Position2DInt>& footprint){ 01089 //quick bubble sort to sort pts by x 01090 base_local_planner::Position2DInt swap, pt; 01091 unsigned int i = 0; 01092 while(i < footprint.size() - 1){ 01093 if(footprint[i].x > footprint[i + 1].x){ 01094 swap = footprint[i]; 01095 footprint[i] = footprint[i + 1]; 01096 footprint[i + 1] = swap; 01097 if(i > 0) 01098 --i; 01099 } 01100 else 01101 ++i; 01102 } 01103 01104 i = 0; 01105 base_local_planner::Position2DInt min_pt; 01106 base_local_planner::Position2DInt max_pt; 01107 unsigned int min_x = footprint[0].x; 01108 unsigned int max_x = footprint[footprint.size() -1].x; 01109 //walk through each column and mark cells inside the footprint 01110 for(unsigned int x = min_x; x <= max_x; ++x){ 01111 if(i >= footprint.size() - 1) 01112 break; 01113 01114 if(footprint[i].y < footprint[i + 1].y){ 01115 min_pt = footprint[i]; 01116 max_pt = footprint[i + 1]; 01117 } 01118 else{ 01119 min_pt = footprint[i + 1]; 01120 max_pt = footprint[i]; 01121 } 01122 01123 i += 2; 01124 while(i < footprint.size() && footprint[i].x == x){ 01125 if(footprint[i].y < min_pt.y) 01126 min_pt = footprint[i]; 01127 else if(footprint[i].y > max_pt.y) 01128 max_pt = footprint[i]; 01129 ++i; 01130 } 01131 01132 //loop though cells in the column 01133 for(unsigned int y = min_pt.y; y < max_pt.y; ++y){ 01134 pt.x = x; 01135 pt.y = y; 01136 footprint.push_back(pt); 01137 } 01138 } 01139 } 01140 01141 void TrajectoryPlanner::getLocalGoal(double& x, double& y){ 01142 x = map_.goal_x_; 01143 y = map_.goal_y_; 01144 } 01145 01146 }; 01147 01148