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 #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 boost::mutex::scoped_lock l(configuration_mutex_);
00044
00045 max_vel_x_ = config.max_vel_x;
00046 min_vel_x_ = config.min_vel_x;
00047
00048 max_vel_y_ = config.max_vel_y;
00049 min_vel_y_ = config.min_vel_y;
00050
00051 min_vel_trans_ = config.min_trans_vel;
00052 max_vel_trans_ = config.max_trans_vel;
00053
00054 max_vel_th_ = config.max_rot_vel;
00055 min_vel_th_ = -1.0 * max_vel_th_;
00056
00057 min_rot_vel_ = config.min_rot_vel;
00058
00059 sim_time_ = config.sim_time;
00060 sim_granularity_ = config.sim_granularity;
00061 pdist_scale_ = config.path_distance_bias;
00062 gdist_scale_ = config.goal_distance_bias;
00063 occdist_scale_ = config.occdist_scale;
00064
00065 stop_time_buffer_ = config.stop_time_buffer;
00066 oscillation_reset_dist_ = config.oscillation_reset_dist;
00067 forward_point_distance_ = config.forward_point_distance;
00068
00069 scaling_speed_ = config.scaling_speed;
00070 max_scaling_factor_ = config.max_scaling_factor;
00071
00072 int vx_samp, vy_samp, vth_samp;
00073 vx_samp = config.vx_samples;
00074 vy_samp = config.vy_samples;
00075 vth_samp = config.vth_samples;
00076
00077 if(vx_samp <= 0){
00078 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");
00079 vx_samp = 1;
00080 config.vx_samples = vx_samp;
00081 }
00082
00083 if(vy_samp <= 0){
00084 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");
00085 vy_samp = 1;
00086 config.vy_samples = vy_samp;
00087 }
00088
00089 if(vth_samp <= 0){
00090 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");
00091 vth_samp = 1;
00092 config.vth_samples = vth_samp;
00093 }
00094
00095 vsamples_[0] = vx_samp;
00096 vsamples_[1] = vy_samp;
00097 vsamples_[2] = vth_samp;
00098
00099 penalize_negative_x_ = config.penalize_negative_x;
00100 }
00101
00102 DWAPlanner::DWAPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros) : costmap_ros_(NULL), world_model_(NULL), dsrv_(ros::NodeHandle("~/" + name)), penalize_negative_x_(true) {
00103 costmap_ros_ = costmap_ros;
00104 costmap_ros_->getCostmapCopy(costmap_);
00105
00106 map_ = base_local_planner::MapGrid(costmap_.getSizeInCellsX(), costmap_.getSizeInCellsY(),
00107 costmap_.getResolution(), costmap_.getOriginX(), costmap_.getOriginY());
00108 front_map_ = base_local_planner::MapGrid(costmap_.getSizeInCellsX(), costmap_.getSizeInCellsY(),
00109 costmap_.getResolution(), costmap_.getOriginX(), costmap_.getOriginY());
00110 ros::NodeHandle pn("~/" + name);
00111
00112 double acc_lim_x, acc_lim_y, acc_lim_th;
00113 pn.param("acc_lim_x", acc_lim_x, 2.5);
00114 pn.param("acc_lim_y", acc_lim_y, 2.5);
00115 pn.param("acc_lim_th", acc_lim_th, 3.2);
00116
00117
00118
00119
00120 std::string controller_frequency_param_name;
00121 if(!pn.searchParam("controller_frequency", controller_frequency_param_name))
00122 sim_period_ = 0.05;
00123 else
00124 {
00125 double controller_frequency = 0;
00126 pn.param(controller_frequency_param_name, controller_frequency, 20.0);
00127 if(controller_frequency > 0)
00128 sim_period_ = 1.0 / controller_frequency;
00129 else
00130 {
00131 ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
00132 sim_period_ = 0.05;
00133 }
00134 }
00135 ROS_INFO("Sim period is set to %.2f", sim_period_);
00136
00137 acc_lim_[0] = acc_lim_x;
00138 acc_lim_[1] = acc_lim_y;
00139 acc_lim_[2] = acc_lim_th;
00140
00141 dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = boost::bind(&DWAPlanner::reconfigureCB, this, _1, _2);
00142 dsrv_.setCallback(cb);
00143
00144 footprint_spec_ = costmap_ros_->getRobotFootprint();
00145
00146 world_model_ = new base_local_planner::CostmapModel(costmap_);
00147
00148 prev_stationary_pos_ = Eigen::Vector3f::Zero();
00149 resetOscillationFlags();
00150
00151 map_viz_.initialize(name, &costmap_, boost::bind(&DWAPlanner::getCellCosts, this, _1, _2, _3, _4, _5, _6));
00152 }
00153
00154 bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
00155 base_local_planner::MapCell cell = map_(cx, cy);
00156 if (cell.within_robot) {
00157 return false;
00158 }
00159 occ_cost = costmap_.getCost(cx, cy);
00160 if (cell.path_dist >= map_.map_.size() || cell.goal_dist >= map_.map_.size() || occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
00161 return false;
00162 }
00163 path_cost = cell.path_dist;
00164 goal_cost = cell.goal_dist;
00165
00166 double resolution = costmap_.getResolution();
00167 total_cost = pdist_scale_ * resolution * path_cost + gdist_scale_ * resolution * goal_cost + occdist_scale_ * occ_cost;
00168 return true;
00169 }
00170
00171 Eigen::Vector3f DWAPlanner::computeNewPositions(const Eigen::Vector3f& pos,
00172 const Eigen::Vector3f& vel, double dt){
00173 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();
00174 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;
00175 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;
00176 new_pos[2] = pos[2] + vel[2] * dt;
00177 return new_pos;
00178 }
00179
00180 void DWAPlanner::selectBestTrajectory(base_local_planner::Trajectory* &best, base_local_planner::Trajectory* &comp){
00181
00182 bool best_valid = best->cost_ >= 0.0;
00183 bool best_forward = best->xv_ >= 0.0;
00184 bool comp_valid = comp->cost_ >= 0.0;
00185 bool comp_forward = comp->xv_ >= 0.0;
00186
00187
00188 if(!comp_valid)
00189 return;
00190
00192 if(penalize_negative_x_ && best_valid && best_forward && !comp_forward)
00193 return;
00194
00195
00196 if(comp_valid && ((comp->cost_ < best->cost_ || !best_valid) || (penalize_negative_x_ && comp_forward && !best_forward))){
00197 base_local_planner::Trajectory* swap = best;
00198 best = comp;
00199 comp = swap;
00200 }
00201 }
00202
00203 bool DWAPlanner::oscillationCheck(const Eigen::Vector3f& vel){
00204 if(forward_pos_only_ && vel[0] < 0.0)
00205 return true;
00206
00207 if(forward_neg_only_ && vel[0] > 0.0)
00208 return true;
00209
00210 if(strafe_pos_only_ && vel[1] < 0.0)
00211 return true;
00212
00213 if(strafe_neg_only_ && vel[1] > 0.0)
00214 return true;
00215
00216 if(rot_pos_only_ && vel[2] < 0.0)
00217 return true;
00218
00219 if(rot_neg_only_ && vel[2] > 0.0)
00220 return true;
00221
00222 return false;
00223 }
00224
00225 base_local_planner::Trajectory DWAPlanner::computeTrajectories(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel){
00226 tf::Stamped<tf::Pose> robot_pose_tf;
00227 geometry_msgs::PoseStamped robot_pose;
00228
00229
00230 costmap_ros_->getRobotPose(robot_pose_tf);
00231 tf::poseStampedTFToMsg(robot_pose_tf, robot_pose);
00232
00233 double sq_dist = squareDist(robot_pose, global_plan_.back());
00234
00235 bool two_point_scoring = true;
00236 if(sq_dist < forward_point_distance_ * forward_point_distance_)
00237 two_point_scoring = false;
00238
00239
00240 Eigen::Vector3f max_vel = Eigen::Vector3f::Zero();
00241 max_vel[0] = std::min(max_vel_x_, vel[0] + acc_lim_[0] * sim_period_);
00242 max_vel[1] = std::min(max_vel_y_, vel[1] + acc_lim_[1] * sim_period_);
00243 max_vel[2] = std::min(max_vel_th_, vel[2] + acc_lim_[2] * sim_period_);
00244
00245 Eigen::Vector3f min_vel = Eigen::Vector3f::Zero();
00246 min_vel[0] = std::max(min_vel_x_, vel[0] - acc_lim_[0] * sim_period_);
00247 min_vel[1] = std::max(min_vel_y_, vel[1] - acc_lim_[1] * sim_period_);
00248 min_vel[2] = std::max(min_vel_th_, vel[2] - acc_lim_[2] * sim_period_);
00249
00250 Eigen::Vector3f dv = Eigen::Vector3f::Zero();
00251
00252 for(unsigned int i = 0; i < 3; ++i){
00253 dv[i] = (max_vel[i] - min_vel[i]) / (std::max(1.0, double(vsamples_[i]) - 1));
00254 }
00255
00256
00257 base_local_planner::Trajectory* best_traj = &traj_one_;
00258 best_traj->cost_ = -1.0;
00259
00260 base_local_planner::Trajectory* comp_traj = &traj_two_;
00261 comp_traj->cost_ = -1.0;
00262
00263 Eigen::Vector3f vel_samp = Eigen::Vector3f::Zero();
00264
00265
00266
00267
00268
00269 for(VelocityIterator x_it(min_vel[0], max_vel[0], dv[0]); !x_it.isFinished(); x_it++){
00270 vel_samp[0] = x_it.getVelocity();
00271 for(VelocityIterator y_it(min_vel[1], max_vel[1], dv[1]); !y_it.isFinished(); y_it++){
00272 vel_samp[1] = y_it.getVelocity();
00273 for(VelocityIterator th_it(min_vel[2], max_vel[2], dv[2]); !th_it.isFinished(); th_it++){
00274 vel_samp[2] = th_it.getVelocity();
00275 generateTrajectory(pos, vel_samp, *comp_traj, two_point_scoring);
00276 selectBestTrajectory(best_traj, comp_traj);
00277 }
00278 }
00279 }
00280
00281
00282 if(best_traj->cost_ >= 0){
00283
00284 if(setOscillationFlags(best_traj)){
00285 prev_stationary_pos_ = pos;
00286 }
00287
00288
00289 if(forward_pos_only_ || forward_neg_only_
00290 || strafe_pos_only_ || strafe_neg_only_
00291 || rot_pos_only_ || rot_neg_only_){
00292 resetOscillationFlagsIfPossible(pos, prev_stationary_pos_);
00293 }
00294 }
00295
00296
00297
00298 return *best_traj;
00299
00300 }
00301
00302 void DWAPlanner::resetOscillationFlagsIfPossible(const Eigen::Vector3f& pos, const Eigen::Vector3f& prev){
00303 double x_diff = pos[0] - prev[0];
00304 double y_diff = pos[1] - prev[1];
00305 double sq_dist = x_diff * x_diff + y_diff * y_diff;
00306
00307
00308 if(sq_dist > oscillation_reset_dist_ * oscillation_reset_dist_){
00309 resetOscillationFlags();
00310 }
00311 }
00312
00313 void DWAPlanner::resetOscillationFlags(){
00314 strafe_pos_only_ = false;
00315 strafe_neg_only_ = false;
00316 strafing_pos_ = false;
00317 strafing_neg_ = false;
00318
00319 rot_pos_only_ = false;
00320 rot_neg_only_ = false;
00321 rotating_pos_ = false;
00322 rotating_neg_ = false;
00323
00324 forward_pos_only_ = false;
00325 forward_neg_only_ = false;
00326 forward_pos_ = false;
00327 forward_neg_ = false;
00328 }
00329
00330 bool DWAPlanner::setOscillationFlags(base_local_planner::Trajectory* t){
00331 bool flag_set = false;
00332
00333 if(t->xv_ < 0.0){
00334 if(forward_pos_){
00335 forward_neg_only_ = true;
00336 flag_set = true;
00337 }
00338 forward_pos_ = false;
00339 forward_neg_ = true;
00340 }
00341 if(t->xv_ > 0.0){
00342 if(forward_neg_){
00343 forward_pos_only_ = true;
00344 flag_set = true;
00345 }
00346 forward_neg_ = false;
00347 forward_pos_ = true;
00348 }
00349
00350
00351 if(fabs(t->xv_) <= min_vel_trans_){
00352
00353 if(t->yv_ < 0){
00354 if(strafing_pos_){
00355 strafe_neg_only_ = true;
00356 flag_set = true;
00357 }
00358 strafing_pos_ = false;
00359 strafing_neg_ = true;
00360 }
00361
00362
00363 if(t->yv_ > 0){
00364 if(strafing_neg_){
00365 strafe_pos_only_ = true;
00366 flag_set = true;
00367 }
00368 strafing_neg_ = false;
00369 strafing_pos_ = true;
00370 }
00371
00372
00373 if(t->thetav_ < 0){
00374 if(rotating_pos_){
00375 rot_neg_only_ = true;
00376 flag_set = true;
00377 }
00378 rotating_pos_ = false;
00379 rotating_neg_ = true;
00380 }
00381
00382
00383 if(t->thetav_ > 0){
00384 if(rotating_neg_){
00385 rot_pos_only_ = true;
00386 flag_set = true;
00387 }
00388 rotating_neg_ = false;
00389 rotating_pos_ = true;
00390 }
00391 }
00392 return flag_set;
00393 }
00394
00395 double DWAPlanner::footprintCost(const Eigen::Vector3f& pos, double scale){
00396 double cos_th = cos(pos[2]);
00397 double sin_th = sin(pos[2]);
00398
00399 std::vector<geometry_msgs::Point> scaled_oriented_footprint;
00400 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){
00401 geometry_msgs::Point new_pt;
00402 new_pt.x = pos[0] + (scale * footprint_spec_[i].x * cos_th - scale * footprint_spec_[i].y * sin_th);
00403 new_pt.y = pos[1] + (scale * footprint_spec_[i].x * sin_th + scale * footprint_spec_[i].y * cos_th);
00404 scaled_oriented_footprint.push_back(new_pt);
00405 }
00406
00407 geometry_msgs::Point robot_position;
00408 robot_position.x = pos[0];
00409 robot_position.y = pos[1];
00410
00411
00412 double footprint_cost = world_model_->footprintCost(robot_position, scaled_oriented_footprint, costmap_.getInscribedRadius(), costmap_.getCircumscribedRadius());
00413
00414 return footprint_cost;
00415 }
00416
00417 void DWAPlanner::generateTrajectory(Eigen::Vector3f pos, const Eigen::Vector3f& vel, base_local_planner::Trajectory& traj, bool two_point_scoring){
00418
00419 double impossible_cost = map_.map_.size();
00420
00421 double vmag = sqrt(vel[0] * vel[0] + vel[1] * vel[1]);
00422 double eps = 1e-4;
00423
00424
00425 if((vmag + eps < min_vel_trans_ && fabs(vel[2]) + eps < min_rot_vel_) ||
00426 vmag - eps > max_vel_trans_ ||
00427 oscillationCheck(vel)){
00428 traj.cost_ = -1.0;
00429 return;
00430 }
00431
00432
00433 int num_steps = ceil(std::max((vmag * sim_time_) / sim_granularity_, fabs(vel[2]) / sim_granularity_));
00434
00435
00436 double dt = sim_time_ / num_steps;
00437 double time = 0.0;
00438
00439
00440 double path_dist = 0.0;
00441 double goal_dist = 0.0;
00442 double occ_cost = 0.0;
00443
00444
00445 double front_path_dist = 0.0;
00446 double front_goal_dist = 0.0;
00447
00448
00449 traj.resetPoints();
00450 traj.xv_ = vel[0];
00451 traj.yv_ = vel[1];
00452 traj.thetav_ = vel[2];
00453 traj.cost_ = -1.0;
00454
00455
00456 if(num_steps == 0){
00457 traj.cost_ = -1.0;
00458 return;
00459 }
00460
00461
00462 Eigen::Vector3f abs_vel = vel.array().abs();
00463
00464
00465 for(int i = 0; i < num_steps; ++i){
00466
00467 unsigned int cell_x, cell_y;
00468
00469
00470 if(!costmap_.worldToMap(pos[0], pos[1], cell_x, cell_y)){
00471
00472 traj.cost_ = -1.0;
00473 return;
00474 }
00475
00476 double front_x = pos[0] + forward_point_distance_ * cos(pos[2]);
00477 double front_y = pos[1] + forward_point_distance_ * sin(pos[2]);
00478
00479 unsigned int front_cell_x, front_cell_y;
00480
00481 if(!costmap_.worldToMap(front_x, front_y, front_cell_x, front_cell_y)){
00482
00483 traj.cost_ = -1.0;
00484 return;
00485 }
00486
00487
00488
00489
00490 double scale = 1.0;
00491 if(vmag > scaling_speed_){
00492
00493 double ratio = (vmag - scaling_speed_) / (max_vel_trans_ - scaling_speed_);
00494 scale = max_scaling_factor_ * ratio + 1.0;
00495 }
00496
00497
00498 double footprint_cost = footprintCost(pos, scale);
00499
00500
00501 if(footprint_cost < 0){
00502 traj.cost_ = -1.0;
00503 return;
00504
00505
00506
00507
00508
00509
00510
00511
00512
00513
00514
00515
00516
00517
00518
00519
00520
00521 }
00522
00523
00524 occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y)));
00525 path_dist = map_(cell_x, cell_y).path_dist;
00526 goal_dist = map_(cell_x, cell_y).goal_dist;
00527
00528 front_path_dist = front_map_(front_cell_x, front_cell_y).path_dist;
00529 front_goal_dist = front_map_(front_cell_x, front_cell_y).goal_dist;
00530
00531
00532 if(impossible_cost <= goal_dist || impossible_cost <= path_dist){
00533 traj.cost_ = -2.0;
00534 return;
00535 }
00536
00537
00538 traj.addPoint(pos[0], pos[1], pos[2]);
00539
00540
00541 pos = computeNewPositions(pos, vel, dt);
00542 time += dt;
00543 }
00544
00545 double resolution = costmap_.getResolution();
00546
00547 if(two_point_scoring)
00548 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;
00549 else
00550 traj.cost_ = pdist_scale_ * resolution * path_dist + gdist_scale_ * resolution * goal_dist + occdist_scale_ * occ_cost;
00551
00552 }
00553
00554 bool DWAPlanner::checkTrajectory(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel){
00555 resetOscillationFlags();
00556 base_local_planner::Trajectory t;
00557 generateTrajectory(pos, vel, t, false);
00558
00559
00560 if(t.cost_ >= 0)
00561 return true;
00562
00563
00564 return false;
00565 }
00566
00567 void DWAPlanner::updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan){
00568 global_plan_.resize(new_plan.size());
00569 for(unsigned int i = 0; i < new_plan.size(); ++i){
00570 global_plan_[i] = new_plan[i];
00571 }
00572 }
00573
00574
00575 base_local_planner::Trajectory DWAPlanner::findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00576 tf::Stamped<tf::Pose>& drive_velocities){
00577
00578
00579 boost::mutex::scoped_lock l(configuration_mutex_);
00580
00581
00582 costmap_ros_->getCostmapCopy(costmap_);
00583
00584 Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation()));
00585 Eigen::Vector3f vel(global_vel.getOrigin().getX(), global_vel.getOrigin().getY(), tf::getYaw(global_vel.getRotation()));
00586
00587
00588 map_.resetPathDist();
00589 front_map_.resetPathDist();
00590
00591
00592 map_.setPathCells(costmap_, global_plan_);
00593
00594 std::vector<geometry_msgs::PoseStamped> front_global_plan = global_plan_;
00595 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));
00596 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));
00597 front_map_.setPathCells(costmap_, front_global_plan);
00598 ROS_DEBUG("Path/Goal distance computed");
00599
00600
00601 base_local_planner::Trajectory best = computeTrajectories(pos, vel);
00602 ROS_DEBUG("Trajectories created");
00603
00604
00605 if(best.cost_ < 0){
00606 drive_velocities.setIdentity();
00607 }
00608 else{
00609 btVector3 start(best.xv_, best.yv_, 0);
00610 drive_velocities.setOrigin(start);
00611 btMatrix3x3 matrix;
00612 matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_));
00613 drive_velocities.setBasis(matrix);
00614 }
00615
00616
00617 map_viz_.publishCostCloud();
00618
00619 return best;
00620 }
00621 };