$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2009, 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 Willow Garage, Inc. 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 #include <dwa_local_planner/dwa_planner.h> 00038 #include <angles/angles.h> 00039 00040 namespace dwa_local_planner { 00041 void DWAPlanner::reconfigureCB(DWAPlannerConfig &config, uint32_t level) 00042 { 00043 if(setup_ && config.restore_defaults) { 00044 config = default_config_; 00045 config.restore_defaults = false; 00046 } 00047 00048 if(!setup_) { 00049 default_config_ = config; 00050 setup_ = true; 00051 } 00052 boost::mutex::scoped_lock l(configuration_mutex_); 00053 00054 max_vel_x_ = config.max_vel_x; 00055 min_vel_x_ = config.min_vel_x; 00056 00057 max_vel_y_ = config.max_vel_y; 00058 min_vel_y_ = config.min_vel_y; 00059 00060 min_vel_trans_ = config.min_trans_vel; 00061 max_vel_trans_ = config.max_trans_vel; 00062 00063 max_vel_th_ = config.max_rot_vel; 00064 min_vel_th_ = -1.0 * max_vel_th_; 00065 00066 min_rot_vel_ = config.min_rot_vel; 00067 00068 sim_time_ = config.sim_time; 00069 sim_granularity_ = config.sim_granularity; 00070 pdist_scale_ = config.path_distance_bias; 00071 gdist_scale_ = config.goal_distance_bias; 00072 occdist_scale_ = config.occdist_scale; 00073 00074 stop_time_buffer_ = config.stop_time_buffer; 00075 oscillation_reset_dist_ = config.oscillation_reset_dist; 00076 forward_point_distance_ = config.forward_point_distance; 00077 00078 scaling_speed_ = config.scaling_speed; 00079 max_scaling_factor_ = config.max_scaling_factor; 00080 00081 int vx_samp, vy_samp, vth_samp; 00082 vx_samp = config.vx_samples; 00083 vy_samp = config.vy_samples; 00084 vth_samp = config.vth_samples; 00085 00086 if(vx_samp <= 0){ 00087 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"); 00088 vx_samp = 1; 00089 config.vx_samples = vx_samp; 00090 } 00091 00092 if(vy_samp <= 0){ 00093 ROS_WARN("You've specified that you don't want any samples in the y dimension. We'll at least assume that you want to sample one value... so we're going to set vy_samples to 1 instead"); 00094 vy_samp = 1; 00095 config.vy_samples = vy_samp; 00096 } 00097 00098 if(vth_samp <= 0){ 00099 ROS_WARN("You've specified that you don't want any samples in the th dimension. We'll at least assume that you want to sample one value... so we're going to set vth_samples to 1 instead"); 00100 vth_samp = 1; 00101 config.vth_samples = vth_samp; 00102 } 00103 00104 vsamples_[0] = vx_samp; 00105 vsamples_[1] = vy_samp; 00106 vsamples_[2] = vth_samp; 00107 00108 penalize_negative_x_ = config.penalize_negative_x; 00109 } 00110 00111 DWAPlanner::DWAPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros) : costmap_ros_(NULL), world_model_(NULL), dsrv_(ros::NodeHandle("~/" + name)), setup_(false), penalize_negative_x_(true) { 00112 costmap_ros_ = costmap_ros; 00113 costmap_ros_->getCostmapCopy(costmap_); 00114 00115 map_ = base_local_planner::MapGrid(costmap_.getSizeInCellsX(), costmap_.getSizeInCellsY(), 00116 costmap_.getResolution(), costmap_.getOriginX(), costmap_.getOriginY()); 00117 front_map_ = base_local_planner::MapGrid(costmap_.getSizeInCellsX(), costmap_.getSizeInCellsY(), 00118 costmap_.getResolution(), costmap_.getOriginX(), costmap_.getOriginY()); 00119 ros::NodeHandle pn("~/" + name); 00120 00121 double acc_lim_x, acc_lim_y, acc_lim_th; 00122 pn.param("acc_lim_x", acc_lim_x, 2.5); 00123 pn.param("acc_lim_y", acc_lim_y, 2.5); 00124 pn.param("acc_lim_th", acc_lim_th, 3.2); 00125 00126 //Assuming this planner is being run within the navigation stack, we can 00127 //just do an upward search for the frequency at which its being run. This 00128 //also allows the frequency to be overwritten locally. 00129 std::string controller_frequency_param_name; 00130 if(!pn.searchParam("controller_frequency", controller_frequency_param_name)) 00131 sim_period_ = 0.05; 00132 else 00133 { 00134 double controller_frequency = 0; 00135 pn.param(controller_frequency_param_name, controller_frequency, 20.0); 00136 if(controller_frequency > 0) 00137 sim_period_ = 1.0 / controller_frequency; 00138 else 00139 { 00140 ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz"); 00141 sim_period_ = 0.05; 00142 } 00143 } 00144 ROS_INFO("Sim period is set to %.2f", sim_period_); 00145 00146 acc_lim_[0] = acc_lim_x; 00147 acc_lim_[1] = acc_lim_y; 00148 acc_lim_[2] = acc_lim_th; 00149 00150 dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = boost::bind(&DWAPlanner::reconfigureCB, this, _1, _2); 00151 dsrv_.setCallback(cb); 00152 00153 footprint_spec_ = costmap_ros_->getRobotFootprint(); 00154 00155 world_model_ = new base_local_planner::CostmapModel(costmap_); 00156 00157 prev_stationary_pos_ = Eigen::Vector3f::Zero(); 00158 resetOscillationFlags(); 00159 00160 map_viz_.initialize(name, &costmap_, boost::bind(&DWAPlanner::getCellCosts, this, _1, _2, _3, _4, _5, _6)); 00161 } 00162 00163 bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) { 00164 base_local_planner::MapCell cell = map_(cx, cy); 00165 if (cell.within_robot) { 00166 return false; 00167 } 00168 occ_cost = costmap_.getCost(cx, cy); 00169 if (cell.path_dist >= map_.map_.size() || cell.goal_dist >= map_.map_.size() || occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) { 00170 return false; 00171 } 00172 path_cost = cell.path_dist; 00173 goal_cost = cell.goal_dist; 00174 00175 double resolution = costmap_.getResolution(); 00176 total_cost = pdist_scale_ * resolution * path_cost + gdist_scale_ * resolution * goal_cost + occdist_scale_ * occ_cost; 00177 return true; 00178 } 00179 00180 Eigen::Vector3f DWAPlanner::computeNewPositions(const Eigen::Vector3f& pos, 00181 const Eigen::Vector3f& vel, double dt){ 00182 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero(); 00183 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt; 00184 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt; 00185 new_pos[2] = pos[2] + vel[2] * dt; 00186 return new_pos; 00187 } 00188 00189 void DWAPlanner::selectBestTrajectory(base_local_planner::Trajectory* &best, base_local_planner::Trajectory* &comp){ 00190 //check if the comp trajectory is better than the current best and, if so, swap them 00191 bool best_valid = best->cost_ >= 0.0; 00192 bool best_forward = best->xv_ >= 0.0; 00193 bool comp_valid = comp->cost_ >= 0.0; 00194 bool comp_forward = comp->xv_ >= 0.0; 00195 00196 //if we don't have a valid trajecotry... then do nothing 00197 if(!comp_valid) 00198 return; 00199 00201 if(penalize_negative_x_ && best_valid && best_forward && !comp_forward) 00202 return; 00203 00204 00205 if(comp_valid && ((comp->cost_ < best->cost_ || !best_valid) || (penalize_negative_x_ && comp_forward && !best_forward))){ 00206 base_local_planner::Trajectory* swap = best; 00207 best = comp; 00208 comp = swap; 00209 } 00210 } 00211 00212 bool DWAPlanner::oscillationCheck(const Eigen::Vector3f& vel){ 00213 if(forward_pos_only_ && vel[0] < 0.0) 00214 return true; 00215 00216 if(forward_neg_only_ && vel[0] > 0.0) 00217 return true; 00218 00219 if(strafe_pos_only_ && vel[1] < 0.0) 00220 return true; 00221 00222 if(strafe_neg_only_ && vel[1] > 0.0) 00223 return true; 00224 00225 if(rot_pos_only_ && vel[2] < 0.0) 00226 return true; 00227 00228 if(rot_neg_only_ && vel[2] > 0.0) 00229 return true; 00230 00231 return false; 00232 } 00233 00234 base_local_planner::Trajectory DWAPlanner::computeTrajectories(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel){ 00235 tf::Stamped<tf::Pose> robot_pose_tf; 00236 geometry_msgs::PoseStamped robot_pose; 00237 00238 //compute the distance between the robot and the last point on the global_plan 00239 costmap_ros_->getRobotPose(robot_pose_tf); 00240 tf::poseStampedTFToMsg(robot_pose_tf, robot_pose); 00241 00242 double sq_dist = squareDist(robot_pose, global_plan_.back()); 00243 00244 bool two_point_scoring = true; 00245 if(sq_dist < forward_point_distance_ * forward_point_distance_) 00246 two_point_scoring = false; 00247 00248 //compute the feasible velocity space based on the rate at which we run 00249 Eigen::Vector3f max_vel = Eigen::Vector3f::Zero(); 00250 max_vel[0] = std::min(max_vel_x_, vel[0] + acc_lim_[0] * sim_period_); 00251 max_vel[1] = std::min(max_vel_y_, vel[1] + acc_lim_[1] * sim_period_); 00252 max_vel[2] = std::min(max_vel_th_, vel[2] + acc_lim_[2] * sim_period_); 00253 00254 Eigen::Vector3f min_vel = Eigen::Vector3f::Zero(); 00255 min_vel[0] = std::max(min_vel_x_, vel[0] - acc_lim_[0] * sim_period_); 00256 min_vel[1] = std::max(min_vel_y_, vel[1] - acc_lim_[1] * sim_period_); 00257 min_vel[2] = std::max(min_vel_th_, vel[2] - acc_lim_[2] * sim_period_); 00258 00259 Eigen::Vector3f dv = Eigen::Vector3f::Zero(); 00260 //we want to sample the velocity space regularly 00261 for(unsigned int i = 0; i < 3; ++i){ 00262 dv[i] = (max_vel[i] - min_vel[i]) / (std::max(1.0, double(vsamples_[i]) - 1)); 00263 } 00264 00265 //keep track of the best trajectory seen so far... we'll re-use two memeber vars for efficiency 00266 base_local_planner::Trajectory* best_traj = &traj_one_; 00267 best_traj->cost_ = -1.0; 00268 00269 base_local_planner::Trajectory* comp_traj = &traj_two_; 00270 comp_traj->cost_ = -1.0; 00271 00272 Eigen::Vector3f vel_samp = Eigen::Vector3f::Zero(); 00273 00274 //ROS_ERROR("x(%.2f, %.2f), y(%.2f, %.2f), th(%.2f, %.2f)", min_vel[0], max_vel[0], min_vel[1], max_vel[1], min_vel[2], max_vel[2]); 00275 //ROS_ERROR("x(%.2f, %.2f), y(%.2f, %.2f), th(%.2f, %.2f)", min_vel_x_, max_vel_x_, min_vel_y_, max_vel_y_, min_vel_th_, max_vel_th_); 00276 //ROS_ERROR("dv %.2f %.2f %.2f", dv[0], dv[1], dv[2]); 00277 00278 for(VelocityIterator x_it(min_vel[0], max_vel[0], dv[0]); !x_it.isFinished(); x_it++){ 00279 vel_samp[0] = x_it.getVelocity(); 00280 for(VelocityIterator y_it(min_vel[1], max_vel[1], dv[1]); !y_it.isFinished(); y_it++){ 00281 vel_samp[1] = y_it.getVelocity(); 00282 for(VelocityIterator th_it(min_vel[2], max_vel[2], dv[2]); !th_it.isFinished(); th_it++){ 00283 vel_samp[2] = th_it.getVelocity(); 00284 generateTrajectory(pos, vel_samp, *comp_traj, two_point_scoring); 00285 selectBestTrajectory(best_traj, comp_traj); 00286 } 00287 } 00288 } 00289 00290 ROS_DEBUG_NAMED("oscillation_flags", "forward_pos_only: %d, forward_neg_only: %d, strafe_pos_only: %d, strafe_neg_only: %d, rot_pos_only: %d, rot_neg_only: %d", 00291 forward_pos_only_, forward_neg_only_, strafe_pos_only_, strafe_neg_only_, rot_pos_only_, rot_neg_only_); 00292 00293 //ok... now we have our best trajectory 00294 if(best_traj->cost_ >= 0){ 00295 //we want to check if we need to set any oscillation flags 00296 if(setOscillationFlags(best_traj)){ 00297 prev_stationary_pos_ = pos; 00298 } 00299 00300 //if we've got restrictions... check if we can reset any oscillation flags 00301 if(forward_pos_only_ || forward_neg_only_ 00302 || strafe_pos_only_ || strafe_neg_only_ 00303 || rot_pos_only_ || rot_neg_only_){ 00304 resetOscillationFlagsIfPossible(pos, prev_stationary_pos_); 00305 } 00306 } 00307 00308 //TODO: Think about whether we want to try to do things like back up when a valid trajectory is not found 00309 00310 return *best_traj; 00311 00312 } 00313 00314 void DWAPlanner::resetOscillationFlagsIfPossible(const Eigen::Vector3f& pos, const Eigen::Vector3f& prev){ 00315 double x_diff = pos[0] - prev[0]; 00316 double y_diff = pos[1] - prev[1]; 00317 double sq_dist = x_diff * x_diff + y_diff * y_diff; 00318 00319 //if we've moved far enough... we can reset our flags 00320 if(sq_dist > oscillation_reset_dist_ * oscillation_reset_dist_){ 00321 resetOscillationFlags(); 00322 } 00323 } 00324 00325 void DWAPlanner::resetOscillationFlags(){ 00326 strafe_pos_only_ = false; 00327 strafe_neg_only_ = false; 00328 strafing_pos_ = false; 00329 strafing_neg_ = false; 00330 00331 rot_pos_only_ = false; 00332 rot_neg_only_ = false; 00333 rotating_pos_ = false; 00334 rotating_neg_ = false; 00335 00336 forward_pos_only_ = false; 00337 forward_neg_only_ = false; 00338 forward_pos_ = false; 00339 forward_neg_ = false; 00340 } 00341 00342 bool DWAPlanner::setOscillationFlags(base_local_planner::Trajectory* t){ 00343 bool flag_set = false; 00344 //set oscillation flags for moving forward and backward 00345 if(t->xv_ < 0.0){ 00346 if(forward_pos_){ 00347 forward_neg_only_ = true; 00348 flag_set = true; 00349 } 00350 forward_pos_ = false; 00351 forward_neg_ = true; 00352 } 00353 if(t->xv_ > 0.0){ 00354 if(forward_neg_){ 00355 forward_pos_only_ = true; 00356 flag_set = true; 00357 } 00358 forward_neg_ = false; 00359 forward_pos_ = true; 00360 } 00361 00362 //we'll only set flags for strafing and rotating when we're not moving forward at all 00363 if(fabs(t->xv_) <= min_vel_trans_){ 00364 //check negative strafe 00365 if(t->yv_ < 0){ 00366 if(strafing_pos_){ 00367 strafe_neg_only_ = true; 00368 flag_set = true; 00369 } 00370 strafing_pos_ = false; 00371 strafing_neg_ = true; 00372 } 00373 00374 //check positive strafe 00375 if(t->yv_ > 0){ 00376 if(strafing_neg_){ 00377 strafe_pos_only_ = true; 00378 flag_set = true; 00379 } 00380 strafing_neg_ = false; 00381 strafing_pos_ = true; 00382 } 00383 00384 //check negative rotation 00385 if(t->thetav_ < 0){ 00386 if(rotating_pos_){ 00387 rot_neg_only_ = true; 00388 flag_set = true; 00389 } 00390 rotating_pos_ = false; 00391 rotating_neg_ = true; 00392 } 00393 00394 //check positive rotation 00395 if(t->thetav_ > 0){ 00396 if(rotating_neg_){ 00397 rot_pos_only_ = true; 00398 flag_set = true; 00399 } 00400 rotating_neg_ = false; 00401 rotating_pos_ = true; 00402 } 00403 } 00404 return flag_set; 00405 } 00406 00407 double DWAPlanner::footprintCost(const Eigen::Vector3f& pos, double scale){ 00408 double cos_th = cos(pos[2]); 00409 double sin_th = sin(pos[2]); 00410 00411 std::vector<geometry_msgs::Point> scaled_oriented_footprint; 00412 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){ 00413 geometry_msgs::Point new_pt; 00414 new_pt.x = pos[0] + (scale * footprint_spec_[i].x * cos_th - scale * footprint_spec_[i].y * sin_th); 00415 new_pt.y = pos[1] + (scale * footprint_spec_[i].x * sin_th + scale * footprint_spec_[i].y * cos_th); 00416 scaled_oriented_footprint.push_back(new_pt); 00417 } 00418 00419 geometry_msgs::Point robot_position; 00420 robot_position.x = pos[0]; 00421 robot_position.y = pos[1]; 00422 00423 //check if the footprint is legal 00424 double footprint_cost = world_model_->footprintCost(robot_position, scaled_oriented_footprint, costmap_.getInscribedRadius(), costmap_.getCircumscribedRadius()); 00425 00426 return footprint_cost; 00427 } 00428 00429 void DWAPlanner::generateTrajectory(Eigen::Vector3f pos, const Eigen::Vector3f& vel, base_local_planner::Trajectory& traj, bool two_point_scoring){ 00430 //ROS_ERROR("%.2f, %.2f, %.2f - %.2f %.2f", vel[0], vel[1], vel[2], sim_time_, sim_granularity_); 00431 double impossible_cost = map_.map_.size(); 00432 00433 double vmag = sqrt(vel[0] * vel[0] + vel[1] * vel[1]); 00434 double eps = 1e-4; 00435 00436 //make sure that the robot is at least moving with one of the required velocities 00437 if((vmag + eps < min_vel_trans_ && fabs(vel[2]) + eps < min_rot_vel_) || 00438 vmag - eps > max_vel_trans_ || 00439 oscillationCheck(vel)){ 00440 traj.cost_ = -1.0; 00441 return; 00442 } 00443 00444 //compute the number of steps we must take along this trajectory to be "safe" 00445 int num_steps = ceil(std::max((vmag * sim_time_) / sim_granularity_, fabs(vel[2]) / sim_granularity_)); 00446 00447 //compute a timestep 00448 double dt = sim_time_ / num_steps; 00449 double time = 0.0; 00450 00451 //initialize the costs for the trajectory 00452 double path_dist = 0.0; 00453 double goal_dist = 0.0; 00454 double occ_cost = 0.0; 00455 00456 //we'll also be scoring a point infront of the robot 00457 double front_path_dist = 0.0; 00458 double front_goal_dist = 0.0; 00459 00460 //create a potential trajectory... it might be reused so we'll make sure to reset it 00461 traj.resetPoints(); 00462 traj.xv_ = vel[0]; 00463 traj.yv_ = vel[1]; 00464 traj.thetav_ = vel[2]; 00465 traj.cost_ = -1.0; 00466 00467 //if we're not actualy going to simulate... we may as well just return now 00468 if(num_steps == 0){ 00469 traj.cost_ = -1.0; 00470 return; 00471 } 00472 00473 //we want to check against the absolute value of the velocities for collisions later 00474 Eigen::Vector3f abs_vel = vel.array().abs(); 00475 00476 //simulate the trajectory and check for collisions, updating costs along the way 00477 for(int i = 0; i < num_steps; ++i){ 00478 //get the mapp coordinates of a point 00479 unsigned int cell_x, cell_y; 00480 00481 //we won't allow trajectories that go off the map... shouldn't happen that often anyways 00482 if(!costmap_.worldToMap(pos[0], pos[1], cell_x, cell_y)){ 00483 //we're off the map 00484 traj.cost_ = -1.0; 00485 return; 00486 } 00487 00488 double front_x = pos[0] + forward_point_distance_ * cos(pos[2]); 00489 double front_y = pos[1] + forward_point_distance_ * sin(pos[2]); 00490 00491 unsigned int front_cell_x, front_cell_y; 00492 //we won't allow trajectories that go off the map... shouldn't happen that often anyways 00493 if(!costmap_.worldToMap(front_x, front_y, front_cell_x, front_cell_y)){ 00494 //we're off the map 00495 traj.cost_ = -1.0; 00496 return; 00497 } 00498 00499 00500 //if we're over a certain speed threshold, we'll scale the robot's 00501 //footprint to make it either slow down or stay further from walls 00502 double scale = 1.0; 00503 if(vmag > scaling_speed_){ 00504 //scale up to the max scaling factor linearly... this could be changed later 00505 double ratio = (vmag - scaling_speed_) / (max_vel_trans_ - scaling_speed_); 00506 scale = max_scaling_factor_ * ratio + 1.0; 00507 } 00508 00509 //we want to find the cost of the footprint 00510 double footprint_cost = footprintCost(pos, scale); 00511 00512 //if the footprint hits an obstacle... we'll check if we can stop before we hit it... given the time to get there 00513 if(footprint_cost < 0){ 00514 traj.cost_ = -1.0; 00515 return; 00516 00517 /* TODO: I'm not convinced this code is working properly 00518 //we want to compute the max allowable speeds to be able to stop 00519 //to be safe... we'll make sure we can stop some time before we actually hit 00520 Eigen::Vector3f max_vel = getMaxSpeedToStopInTime(time - stop_time_buffer_); 00521 00522 //check if we can stop in time 00523 if(abs_vel[0] < max_vel[0] && abs_vel[1] < max_vel[1] && abs_vel[2] < max_vel[2]){ 00524 //if we can, then we'll just break out of the loop here.. no point in checking future points 00525 break; 00526 } 00527 else{ 00528 //if we can't... then this trajectory is invalid 00529 traj.cost_ = -1.0; 00530 return; 00531 } 00532 */ 00533 } 00534 00535 //compute the costs for this point on the trajectory 00536 occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y))); 00537 path_dist = map_(cell_x, cell_y).path_dist; 00538 goal_dist = map_(cell_x, cell_y).goal_dist; 00539 00540 front_path_dist = front_map_(front_cell_x, front_cell_y).path_dist; 00541 front_goal_dist = front_map_(front_cell_x, front_cell_y).goal_dist; 00542 00543 //if a point on this trajectory has no clear path to the goal... it is invalid 00544 if(impossible_cost <= goal_dist || impossible_cost <= path_dist){ 00545 traj.cost_ = -2.0; //-2.0 means that we were blocked because propagation failed 00546 return; 00547 } 00548 00549 //add the point to the trajectory so we can draw it later if we want 00550 traj.addPoint(pos[0], pos[1], pos[2]); 00551 00552 //update the position of the robot using the velocities passed in 00553 pos = computeNewPositions(pos, vel, dt); 00554 time += dt; 00555 } 00556 00557 double resolution = costmap_.getResolution(); 00558 //if we're not at the last point in the plan, then we can just score 00559 if(two_point_scoring) 00560 traj.cost_ = pdist_scale_ * resolution * ((front_path_dist + path_dist) / 2.0) + gdist_scale_ * resolution * ((front_goal_dist + goal_dist) / 2.0) + occdist_scale_ * occ_cost; 00561 else 00562 traj.cost_ = pdist_scale_ * resolution * path_dist + gdist_scale_ * resolution * goal_dist + occdist_scale_ * occ_cost; 00563 //ROS_ERROR("%.2f, %.2f, %.2f, %.2f", vel[0], vel[1], vel[2], traj.cost_); 00564 } 00565 00566 bool DWAPlanner::checkTrajectory(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel){ 00567 resetOscillationFlags(); 00568 base_local_planner::Trajectory t; 00569 generateTrajectory(pos, vel, t, false); 00570 00571 //if the trajectory is a legal one... the check passes 00572 if(t.cost_ >= 0) 00573 return true; 00574 00575 //otherwise the check fails 00576 return false; 00577 } 00578 00579 void DWAPlanner::updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan){ 00580 global_plan_.resize(new_plan.size()); 00581 for(unsigned int i = 0; i < new_plan.size(); ++i){ 00582 global_plan_[i] = new_plan[i]; 00583 } 00584 } 00585 00586 //given the current state of the robot, find a good trajectory 00587 base_local_planner::Trajectory DWAPlanner::findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel, 00588 tf::Stamped<tf::Pose>& drive_velocities){ 00589 00590 //make sure that our configuration doesn't change mid-run 00591 boost::mutex::scoped_lock l(configuration_mutex_); 00592 00593 //make sure to get an updated copy of the costmap before computing trajectories 00594 costmap_ros_->getCostmapCopy(costmap_); 00595 00596 Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation())); 00597 Eigen::Vector3f vel(global_vel.getOrigin().getX(), global_vel.getOrigin().getY(), tf::getYaw(global_vel.getRotation())); 00598 00599 //reset the map for new operations 00600 map_.resetPathDist(); 00601 front_map_.resetPathDist(); 00602 00603 //make sure that we update our path based on the global plan and compute costs 00604 map_.setPathCells(costmap_, global_plan_); 00605 00606 std::vector<geometry_msgs::PoseStamped> front_global_plan = global_plan_; 00607 front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x + forward_point_distance_ * cos(tf::getYaw(front_global_plan.back().pose.orientation)); 00608 front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y + forward_point_distance_ * sin(tf::getYaw(front_global_plan.back().pose.orientation)); 00609 front_map_.setPathCells(costmap_, front_global_plan); 00610 ROS_DEBUG_NAMED("dwa_local_planner", "Path/Goal distance computed"); 00611 00612 //rollout trajectories and find the minimum cost one 00613 base_local_planner::Trajectory best = computeTrajectories(pos, vel); 00614 ROS_DEBUG_NAMED("dwa_local_planner", "Trajectories created"); 00615 00616 //if we don't have a legal trajectory, we'll just command zero 00617 if(best.cost_ < 0){ 00618 drive_velocities.setIdentity(); 00619 } 00620 else{ 00621 btVector3 start(best.xv_, best.yv_, 0); 00622 drive_velocities.setOrigin(start); 00623 btMatrix3x3 matrix; 00624 matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_)); 00625 drive_velocities.setBasis(matrix); 00626 } 00627 00628 //we'll publish the visualization of the costs to rviz before returning our best trajectory 00629 map_viz_.publishCostCloud(); 00630 00631 return best; 00632 } 00633 };