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
00039 #include <teb_local_planner/teb_local_planner_ros.h>
00040
00041 #include <tf_conversions/tf_eigen.h>
00042
00043 #include <boost/algorithm/string.hpp>
00044
00045
00046 #include <pluginlib/class_list_macros.h>
00047
00048 #include "g2o/core/sparse_optimizer.h"
00049 #include "g2o/core/block_solver.h"
00050 #include "g2o/core/factory.h"
00051 #include "g2o/core/optimization_algorithm_gauss_newton.h"
00052 #include "g2o/core/optimization_algorithm_levenberg.h"
00053 #include "g2o/solvers/csparse/linear_solver_csparse.h"
00054 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
00055
00056
00057
00058 PLUGINLIB_DECLARE_CLASS(teb_local_planner, TebLocalPlannerROS, teb_local_planner::TebLocalPlannerROS, nav_core::BaseLocalPlanner)
00059
00060 namespace teb_local_planner
00061 {
00062
00063
00064 TebLocalPlannerROS::TebLocalPlannerROS() : costmap_ros_(NULL), tf_(NULL), costmap_model_(NULL),
00065 costmap_converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"),
00066 dynamic_recfg_(NULL), goal_reached_(false), no_infeasible_plans_(0),
00067 initialized_(false)
00068 {
00069 }
00070
00071
00072 TebLocalPlannerROS::~TebLocalPlannerROS()
00073 {
00074 }
00075
00076 void TebLocalPlannerROS::reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level)
00077 {
00078 cfg_.reconfigure(config);
00079 }
00080
00081 void TebLocalPlannerROS::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
00082 {
00083
00084 if(!initialized_)
00085 {
00086
00087 ros::NodeHandle nh("~/" + name);
00088
00089
00090 cfg_.loadRosParamFromNodeHandle(nh);
00091
00092
00093 obstacles_.reserve(500);
00094
00095
00096 tf_ = tf;
00097 costmap_ros_ = costmap_ros;
00098 costmap_ = costmap_ros_->getCostmap();
00099
00100 costmap_model_ = boost::make_shared<base_local_planner::CostmapModel>(*costmap_);
00101
00102
00103 global_frame_ = costmap_ros_->getGlobalFrameID();
00104 cfg_.map_frame = global_frame_;
00105 robot_base_frame_ = costmap_ros_->getBaseFrameID();
00106
00107
00108 visualization_ = TebVisualizationPtr(new TebVisualization(nh, cfg_.map_frame));
00109
00110
00111 RobotFootprintModelPtr robot_model = getRobotFootprintFromParamServer(nh);
00112
00113
00114 if (cfg_.hcp.enable_homotopy_class_planning)
00115 {
00116 planner_ = PlannerInterfacePtr(new HomotopyClassPlanner(cfg_, &obstacles_, robot_model, visualization_, &via_points_));
00117 ROS_INFO("Parallel planning in distinctive topologies enabled.");
00118 }
00119 else
00120 {
00121 planner_ = PlannerInterfacePtr(new TebOptimalPlanner(cfg_, &obstacles_, robot_model, visualization_, &via_points_));
00122 ROS_INFO("Parallel planning in distinctive topologies disabled.");
00123 }
00124
00125
00126 if (!cfg_.obstacles.costmap_converter_plugin.empty())
00127 {
00128 try
00129 {
00130 costmap_converter_ = costmap_converter_loader_.createInstance(cfg_.obstacles.costmap_converter_plugin);
00131 std::string converter_name = costmap_converter_loader_.getName(cfg_.obstacles.costmap_converter_plugin);
00132
00133 boost::replace_all(converter_name, "::", "/");
00134 costmap_converter_->initialize(ros::NodeHandle(nh, "costmap_converter/" + converter_name));
00135 costmap_converter_->setCostmap2D(costmap_);
00136
00137 costmap_converter_->startWorker(ros::Rate(cfg_.obstacles.costmap_converter_rate), costmap_, cfg_.obstacles.costmap_converter_spin_thread);
00138 ROS_INFO_STREAM("Costmap conversion plugin " << cfg_.obstacles.costmap_converter_plugin << " loaded.");
00139 }
00140 catch(pluginlib::PluginlibException& ex)
00141 {
00142 ROS_WARN("The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error message: %s", ex.what());
00143 costmap_converter_.reset();
00144 }
00145 }
00146 else
00147 ROS_INFO("No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
00148
00149
00150
00151 footprint_spec_ = costmap_ros_->getRobotFootprint();
00152 costmap_2d::calculateMinAndMaxDistances(footprint_spec_, robot_inscribed_radius_, robot_circumscribed_radius);
00153
00154
00155 odom_helper_.setOdomTopic(cfg_.odom_topic);
00156
00157
00158 dynamic_recfg_ = boost::make_shared< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> >(nh);
00159 dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig>::CallbackType cb = boost::bind(&TebLocalPlannerROS::reconfigureCB, this, _1, _2);
00160 dynamic_recfg_->setCallback(cb);
00161
00162
00163 validateFootprints(robot_model->getInscribedRadius(), robot_inscribed_radius_, cfg_.obstacles.min_obstacle_dist);
00164
00165
00166 custom_obst_sub_ = nh.subscribe("obstacles", 1, &TebLocalPlannerROS::customObstacleCB, this);
00167
00168
00169 initialized_ = true;
00170
00171 ROS_DEBUG("teb_local_planner plugin initialized.");
00172 }
00173 else
00174 {
00175 ROS_WARN("teb_local_planner has already been initialized, doing nothing.");
00176 }
00177 }
00178
00179
00180
00181 bool TebLocalPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
00182 {
00183
00184 if(!initialized_)
00185 {
00186 ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner");
00187 return false;
00188 }
00189
00190
00191 global_plan_.clear();
00192 global_plan_ = orig_global_plan;
00193
00194
00195
00196
00197
00198 goal_reached_ = false;
00199
00200 return true;
00201 }
00202
00203
00204 bool TebLocalPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
00205 {
00206
00207 if(!initialized_)
00208 {
00209 ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner");
00210 return false;
00211 }
00212
00213 cmd_vel.linear.x = 0;
00214 cmd_vel.linear.y = 0;
00215 cmd_vel.angular.z = 0;
00216 goal_reached_ = false;
00217
00218
00219 tf::Stamped<tf::Pose> robot_pose;
00220 costmap_ros_->getRobotPose(robot_pose);
00221 robot_pose_ = PoseSE2(robot_pose);
00222
00223
00224 tf::Stamped<tf::Pose> robot_vel_tf;
00225 odom_helper_.getRobotVel(robot_vel_tf);
00226 robot_vel_.linear.x = robot_vel_tf.getOrigin().getX();
00227 robot_vel_.linear.y = robot_vel_tf.getOrigin().getY();
00228 robot_vel_.angular.z = tf::getYaw(robot_vel_tf.getRotation());
00229
00230
00231 pruneGlobalPlan(*tf_, robot_pose, global_plan_);
00232
00233
00234 std::vector<geometry_msgs::PoseStamped> transformed_plan;
00235 int goal_idx;
00236 tf::StampedTransform tf_plan_to_global;
00237 if (!transformGlobalPlan(*tf_, global_plan_, robot_pose, *costmap_, global_frame_, cfg_.trajectory.max_global_plan_lookahead_dist,
00238 transformed_plan, &goal_idx, &tf_plan_to_global))
00239 {
00240 ROS_WARN("Could not transform the global plan to the frame of the controller");
00241 return false;
00242 }
00243
00244
00245 tf::Stamped<tf::Pose> global_goal;
00246 tf::poseStampedMsgToTF(global_plan_.back(), global_goal);
00247 global_goal.setData( tf_plan_to_global * global_goal );
00248 double dx = global_goal.getOrigin().getX() - robot_pose_.x();
00249 double dy = global_goal.getOrigin().getY() - robot_pose_.y();
00250 double delta_orient = g2o::normalize_theta( tf::getYaw(global_goal.getRotation()) - robot_pose_.theta() );
00251 if(fabs(std::sqrt(dx*dx+dy*dy)) < cfg_.goal_tolerance.xy_goal_tolerance
00252 && fabs(delta_orient) < cfg_.goal_tolerance.yaw_goal_tolerance)
00253 {
00254 goal_reached_ = true;
00255 return true;
00256 }
00257
00258
00259
00260 configureBackupModes(transformed_plan, goal_idx);
00261
00262
00263
00264 if (transformed_plan.empty())
00265 {
00266 ROS_WARN("Transformed plan is empty. Cannot determine a local plan.");
00267 return false;
00268 }
00269
00270
00271 tf::Stamped<tf::Pose> goal_point;
00272 tf::poseStampedMsgToTF(transformed_plan.back(), goal_point);
00273 robot_goal_.x() = goal_point.getOrigin().getX();
00274 robot_goal_.y() = goal_point.getOrigin().getY();
00275 if (cfg_.trajectory.global_plan_overwrite_orientation)
00276 {
00277 robot_goal_.theta() = estimateLocalGoalOrientation(global_plan_, goal_point, goal_idx, tf_plan_to_global);
00278
00279 transformed_plan.back().pose.orientation = tf::createQuaternionMsgFromYaw(robot_goal_.theta());
00280 }
00281 else
00282 {
00283 robot_goal_.theta() = tf::getYaw(goal_point.getRotation());
00284 }
00285
00286
00287 if (transformed_plan.size()==1)
00288 {
00289 transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped());
00290 }
00291 tf::poseTFToMsg(robot_pose, transformed_plan.front().pose);
00292
00293
00294 obstacles_.clear();
00295
00296
00297 if (costmap_converter_)
00298 updateObstacleContainerWithCostmapConverter();
00299 else
00300 updateObstacleContainerWithCostmap();
00301
00302
00303 updateObstacleContainerWithCustomObstacles();
00304
00305
00306 updateViaPointsContainer(transformed_plan, cfg_.trajectory.global_plan_viapoint_sep);
00307
00308
00309 boost::mutex::scoped_lock cfg_lock(cfg_.configMutex());
00310
00311
00312
00313 bool success = planner_->plan(transformed_plan, &robot_vel_, cfg_.goal_tolerance.free_goal_vel);
00314 if (!success)
00315 {
00316 planner_->clearPlanner();
00317 ROS_WARN("teb_local_planner was not able to obtain a local plan for the current setting.");
00318
00319 ++no_infeasible_plans_;
00320 time_last_infeasible_plan_ = ros::Time::now();
00321 return false;
00322 }
00323
00324
00325 bool feasible = planner_->isTrajectoryFeasible(costmap_model_.get(), footprint_spec_, robot_inscribed_radius_, robot_circumscribed_radius, cfg_.trajectory.feasibility_check_no_poses);
00326 if (!feasible)
00327 {
00328 cmd_vel.linear.x = 0;
00329 cmd_vel.linear.y = 0;
00330 cmd_vel.angular.z = 0;
00331
00332
00333 planner_->clearPlanner();
00334 ROS_WARN("TebLocalPlannerROS: trajectory is not feasible. Resetting planner...");
00335
00336 ++no_infeasible_plans_;
00337 time_last_infeasible_plan_ = ros::Time::now();
00338 return false;
00339 }
00340
00341
00342 if (!planner_->getVelocityCommand(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z))
00343 {
00344 planner_->clearPlanner();
00345 ROS_WARN("TebLocalPlannerROS: velocity command invalid. Resetting planner...");
00346 ++no_infeasible_plans_;
00347 time_last_infeasible_plan_ = ros::Time::now();
00348 return false;
00349 }
00350
00351
00352 saturateVelocity(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z, cfg_.robot.max_vel_x, cfg_.robot.max_vel_y,
00353 cfg_.robot.max_vel_theta, cfg_.robot.max_vel_x_backwards);
00354
00355
00356
00357
00358 if (cfg_.robot.cmd_angle_instead_rotvel)
00359 {
00360 cmd_vel.angular.z = convertTransRotVelToSteeringAngle(cmd_vel.linear.x, cmd_vel.angular.z, cfg_.robot.wheelbase, 0.95*cfg_.robot.min_turning_radius);
00361 if (!std::isfinite(cmd_vel.angular.z))
00362 {
00363 cmd_vel.linear.x = cmd_vel.linear.y = cmd_vel.angular.z = 0;
00364 planner_->clearPlanner();
00365 ROS_WARN("TebLocalPlannerROS: Resulting steering angle is not finite. Resetting planner...");
00366 ++no_infeasible_plans_;
00367 time_last_infeasible_plan_ = ros::Time::now();
00368 return false;
00369 }
00370 }
00371
00372
00373 no_infeasible_plans_ = 0;
00374
00375
00376 planner_->visualize();
00377 visualization_->publishObstacles(obstacles_);
00378 visualization_->publishViaPoints(via_points_);
00379 visualization_->publishGlobalPlan(global_plan_);
00380 return true;
00381 }
00382
00383
00384 bool TebLocalPlannerROS::isGoalReached()
00385 {
00386 if (goal_reached_)
00387 {
00388 ROS_INFO("GOAL Reached!");
00389 planner_->clearPlanner();
00390 return true;
00391 }
00392 return false;
00393 }
00394
00395
00396
00397 void TebLocalPlannerROS::updateObstacleContainerWithCostmap()
00398 {
00399
00400 if (cfg_.obstacles.include_costmap_obstacles)
00401 {
00402 Eigen::Vector2d robot_orient = robot_pose_.orientationUnitVec();
00403
00404 for (unsigned int i=0; i<costmap_->getSizeInCellsX()-1; ++i)
00405 {
00406 for (unsigned int j=0; j<costmap_->getSizeInCellsY()-1; ++j)
00407 {
00408 if (costmap_->getCost(i,j) == costmap_2d::LETHAL_OBSTACLE)
00409 {
00410 Eigen::Vector2d obs;
00411 costmap_->mapToWorld(i,j,obs.coeffRef(0), obs.coeffRef(1));
00412
00413
00414 Eigen::Vector2d obs_dir = obs-robot_pose_.position();
00415 if ( obs_dir.dot(robot_orient) < 0 && obs_dir.norm() > cfg_.obstacles.costmap_obstacles_behind_robot_dist )
00416 continue;
00417
00418 obstacles_.push_back(ObstaclePtr(new PointObstacle(obs)));
00419 }
00420 }
00421 }
00422 }
00423 }
00424
00425 void TebLocalPlannerROS::updateObstacleContainerWithCostmapConverter()
00426 {
00427 if (!costmap_converter_)
00428 return;
00429
00430
00431 costmap_converter::PolygonContainerConstPtr polygons = costmap_converter_->getPolygons();
00432 if (!polygons)
00433 return;
00434
00435 for (std::size_t i=0; i<polygons->size(); ++i)
00436 {
00437 if (polygons->at(i).points.size()==1)
00438 {
00439 obstacles_.push_back(ObstaclePtr(new PointObstacle(polygons->at(i).points[0].x, polygons->at(i).points[0].y)));
00440 }
00441 else if (polygons->at(i).points.size()==2)
00442 {
00443 obstacles_.push_back(ObstaclePtr(new LineObstacle(polygons->at(i).points[0].x, polygons->at(i).points[0].y,
00444 polygons->at(i).points[1].x, polygons->at(i).points[1].y )));
00445 }
00446 else if (polygons->at(i).points.size()>2)
00447 {
00448 PolygonObstacle* polyobst = new PolygonObstacle;
00449 for (std::size_t j=0; j<polygons->at(i).points.size(); ++j)
00450 {
00451 polyobst->pushBackVertex(polygons->at(i).points[j].x, polygons->at(i).points[j].y);
00452 }
00453 polyobst->finalizePolygon();
00454 obstacles_.push_back(ObstaclePtr(polyobst));
00455 }
00456 }
00457 }
00458
00459
00460 void TebLocalPlannerROS::updateObstacleContainerWithCustomObstacles()
00461 {
00462
00463 boost::mutex::scoped_lock l(custom_obst_mutex_);
00464
00465 if (!custom_obstacle_msg_.obstacles.empty())
00466 {
00467
00468 Eigen::Affine3d obstacle_to_map_eig;
00469 try
00470 {
00471 tf::StampedTransform obstacle_to_map;
00472 tf_->waitForTransform(global_frame_, ros::Time(0),
00473 custom_obstacle_msg_.header.frame_id, ros::Time(0),
00474 custom_obstacle_msg_.header.frame_id, ros::Duration(0.5));
00475 tf_->lookupTransform(global_frame_, ros::Time(0),
00476 custom_obstacle_msg_.header.frame_id, ros::Time(0),
00477 custom_obstacle_msg_.header.frame_id, obstacle_to_map);
00478 tf::transformTFToEigen(obstacle_to_map, obstacle_to_map_eig);
00479 }
00480 catch (tf::TransformException ex)
00481 {
00482 ROS_ERROR("%s",ex.what());
00483 obstacle_to_map_eig.setIdentity();
00484 }
00485
00486 for (std::vector<geometry_msgs::PolygonStamped>::const_iterator obst_it = custom_obstacle_msg_.obstacles.begin(); obst_it != custom_obstacle_msg_.obstacles.end(); ++obst_it)
00487 {
00488 if (obst_it->polygon.points.size() == 1 )
00489 {
00490 Eigen::Vector3d pos( obst_it->polygon.points.front().x, obst_it->polygon.points.front().y, obst_it->polygon.points.front().z );
00491 obstacles_.push_back(ObstaclePtr(new PointObstacle( (obstacle_to_map_eig * pos).head(2) )));
00492 }
00493 else if (obst_it->polygon.points.size() == 2 )
00494 {
00495 Eigen::Vector3d line_start( obst_it->polygon.points.front().x, obst_it->polygon.points.front().y, obst_it->polygon.points.front().z );
00496 Eigen::Vector3d line_end( obst_it->polygon.points.back().x, obst_it->polygon.points.back().y, obst_it->polygon.points.back().z );
00497 obstacles_.push_back(ObstaclePtr(new LineObstacle( (obstacle_to_map_eig * line_start).head(2), (obstacle_to_map_eig * line_end).head(2) )));
00498 }
00499 else
00500 {
00501 PolygonObstacle* polyobst = new PolygonObstacle;
00502 for (int i=0; i<(int)obst_it->polygon.points.size(); ++i)
00503 {
00504 Eigen::Vector3d pos( obst_it->polygon.points[i].x, obst_it->polygon.points[i].y, obst_it->polygon.points[i].z );
00505 polyobst->pushBackVertex( (obstacle_to_map_eig * pos).head(2) );
00506 }
00507 polyobst->finalizePolygon();
00508 obstacles_.push_back(ObstaclePtr(polyobst));
00509 }
00510 }
00511 }
00512 }
00513
00514 void TebLocalPlannerROS::updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation)
00515 {
00516 via_points_.clear();
00517
00518 if (min_separation<0)
00519 return;
00520
00521 std::size_t prev_idx = 0;
00522 for (std::size_t i=1; i < transformed_plan.size(); ++i)
00523 {
00524
00525 if (distance_points2d( transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position ) < min_separation)
00526 continue;
00527
00528
00529 via_points_.push_back( Eigen::Vector2d( transformed_plan[i].pose.position.x, transformed_plan[i].pose.position.y ) );
00530 prev_idx = i;
00531 }
00532
00533 }
00534
00535 Eigen::Vector2d TebLocalPlannerROS::tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel)
00536 {
00537 Eigen::Vector2d vel;
00538 vel.coeffRef(0) = std::sqrt( tf_vel.getOrigin().getX() * tf_vel.getOrigin().getX() + tf_vel.getOrigin().getY() * tf_vel.getOrigin().getY() );
00539 vel.coeffRef(1) = tf::getYaw(tf_vel.getRotation());
00540 return vel;
00541 }
00542
00543
00544 bool TebLocalPlannerROS::pruneGlobalPlan(const tf::TransformListener& tf, const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot)
00545 {
00546 if (global_plan.empty())
00547 return true;
00548
00549 try
00550 {
00551
00552 tf::StampedTransform global_to_plan_transform;
00553 tf.lookupTransform(global_plan.front().header.frame_id, global_pose.frame_id_, ros::Time(0), global_to_plan_transform);
00554 tf::Stamped<tf::Pose> robot;
00555 robot.setData( global_to_plan_transform * global_pose );
00556
00557 double dist_thresh_sq = dist_behind_robot*dist_behind_robot;
00558
00559
00560 std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
00561 std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
00562 while (it != global_plan.end())
00563 {
00564 double dx = robot.getOrigin().x() - it->pose.position.x;
00565 double dy = robot.getOrigin().y() - it->pose.position.y;
00566 double dist_sq = dx * dx + dy * dy;
00567 if (dist_sq < dist_thresh_sq)
00568 {
00569 erase_end = it;
00570 break;
00571 }
00572 ++it;
00573 }
00574 if (erase_end == global_plan.end())
00575 return false;
00576
00577 if (erase_end != global_plan.begin())
00578 global_plan.erase(global_plan.begin(), erase_end);
00579 }
00580 catch (const tf::TransformException& ex)
00581 {
00582 ROS_DEBUG("Cannot prune path since no transform is available: %s\n", ex.what());
00583 return false;
00584 }
00585 return true;
00586 }
00587
00588
00589 bool TebLocalPlannerROS::transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
00590 const tf::Stamped<tf::Pose>& global_pose, const costmap_2d::Costmap2D& costmap, const std::string& global_frame, double max_plan_length,
00591 std::vector<geometry_msgs::PoseStamped>& transformed_plan, int* current_goal_idx, tf::StampedTransform* tf_plan_to_global) const
00592 {
00593
00594
00595 const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
00596
00597 transformed_plan.clear();
00598
00599 try
00600 {
00601 if (global_plan.empty())
00602 {
00603 ROS_ERROR("Received plan with zero length");
00604 *current_goal_idx = 0;
00605 return false;
00606 }
00607
00608
00609 tf::StampedTransform plan_to_global_transform;
00610 tf.waitForTransform(global_frame, ros::Time::now(),
00611 plan_pose.header.frame_id, plan_pose.header.stamp,
00612 plan_pose.header.frame_id, ros::Duration(0.5));
00613 tf.lookupTransform(global_frame, ros::Time(),
00614 plan_pose.header.frame_id, plan_pose.header.stamp,
00615 plan_pose.header.frame_id, plan_to_global_transform);
00616
00617
00618 tf::Stamped<tf::Pose> robot_pose;
00619 tf.transformPose(plan_pose.header.frame_id, global_pose, robot_pose);
00620
00621
00622 double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0,
00623 costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
00624 dist_threshold *= 0.85;
00625
00626
00627
00628 int i = 0;
00629 double sq_dist_threshold = dist_threshold * dist_threshold;
00630 double sq_dist = 1e10;
00631
00632
00633 while(i < (int)global_plan.size())
00634 {
00635 double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00636 double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00637 double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
00638 if (new_sq_dist > sq_dist && sq_dist < sq_dist_threshold)
00639 {
00640 sq_dist = new_sq_dist;
00641 break;
00642 }
00643 sq_dist = new_sq_dist;
00644 ++i;
00645 }
00646
00647 tf::Stamped<tf::Pose> tf_pose;
00648 geometry_msgs::PoseStamped newer_pose;
00649
00650 double plan_length = 0;
00651
00652
00653 while(i < (int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length<=0 || plan_length <= max_plan_length))
00654 {
00655 const geometry_msgs::PoseStamped& pose = global_plan[i];
00656 tf::poseStampedMsgToTF(pose, tf_pose);
00657 tf_pose.setData(plan_to_global_transform * tf_pose);
00658 tf_pose.stamp_ = plan_to_global_transform.stamp_;
00659 tf_pose.frame_id_ = global_frame;
00660 tf::poseStampedTFToMsg(tf_pose, newer_pose);
00661
00662 transformed_plan.push_back(newer_pose);
00663
00664 double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00665 double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00666 sq_dist = x_diff * x_diff + y_diff * y_diff;
00667
00668
00669 if (i>0 && max_plan_length>0)
00670 plan_length += distance_points2d(global_plan[i-1].pose.position, global_plan[i].pose.position);
00671
00672 ++i;
00673 }
00674
00675
00676
00677 if (transformed_plan.empty())
00678 {
00679 tf::poseStampedMsgToTF(global_plan.back(), tf_pose);
00680 tf_pose.setData(plan_to_global_transform * tf_pose);
00681 tf_pose.stamp_ = plan_to_global_transform.stamp_;
00682 tf_pose.frame_id_ = global_frame;
00683 tf::poseStampedTFToMsg(tf_pose, newer_pose);
00684
00685 transformed_plan.push_back(newer_pose);
00686
00687
00688 if (current_goal_idx) *current_goal_idx = int(global_plan.size())-1;
00689 }
00690 else
00691 {
00692
00693 if (current_goal_idx) *current_goal_idx = i-1;
00694 }
00695
00696
00697 if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
00698 }
00699 catch(tf::LookupException& ex)
00700 {
00701 ROS_ERROR("No Transform available Error: %s\n", ex.what());
00702 return false;
00703 }
00704 catch(tf::ConnectivityException& ex)
00705 {
00706 ROS_ERROR("Connectivity Error: %s\n", ex.what());
00707 return false;
00708 }
00709 catch(tf::ExtrapolationException& ex)
00710 {
00711 ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00712 if (global_plan.size() > 0)
00713 ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
00714
00715 return false;
00716 }
00717
00718 return true;
00719 }
00720
00721
00722
00723
00724 double TebLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, const tf::Stamped<tf::Pose>& local_goal,
00725 int current_goal_idx, const tf::StampedTransform& tf_plan_to_global, int moving_average_length) const
00726 {
00727 int n = (int)global_plan.size();
00728
00729
00730 if (current_goal_idx > n-moving_average_length-2)
00731 {
00732 if (current_goal_idx >= n-1)
00733 {
00734 return tf::getYaw(local_goal.getRotation());
00735 }
00736 else
00737 {
00738 tf::Quaternion global_orientation;
00739 tf::quaternionMsgToTF(global_plan.back().pose.orientation, global_orientation);
00740 return tf::getYaw(tf_plan_to_global.getRotation() * global_orientation );
00741 }
00742 }
00743
00744
00745 moving_average_length = std::min(moving_average_length, n-current_goal_idx-1 );
00746
00747 std::vector<double> candidates;
00748 tf::Stamped<tf::Pose> tf_pose_k = local_goal;
00749 tf::Stamped<tf::Pose> tf_pose_kp1;
00750
00751 int range_end = current_goal_idx + moving_average_length;
00752 for (int i = current_goal_idx; i < range_end; ++i)
00753 {
00754
00755 const geometry_msgs::PoseStamped& pose = global_plan.at(i+1);
00756 tf::poseStampedMsgToTF(pose, tf_pose_kp1);
00757 tf_pose_kp1.setData(tf_plan_to_global * tf_pose_kp1);
00758
00759
00760 candidates.push_back( std::atan2(tf_pose_kp1.getOrigin().getY() - tf_pose_k.getOrigin().getY(),
00761 tf_pose_kp1.getOrigin().getX() - tf_pose_k.getOrigin().getX() ) );
00762
00763 if (i<range_end-1)
00764 tf_pose_k = tf_pose_kp1;
00765 }
00766 return average_angles(candidates);
00767 }
00768
00769
00770 void TebLocalPlannerROS::saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double max_vel_y, double max_vel_theta, double max_vel_x_backwards) const
00771 {
00772
00773 if (vx > max_vel_x)
00774 vx = max_vel_x;
00775
00776
00777 if (vy > max_vel_y)
00778 vy = max_vel_y;
00779 else if (vy < -max_vel_y)
00780 vy = -max_vel_y;
00781
00782
00783 if (omega > max_vel_theta)
00784 omega = max_vel_theta;
00785 else if (omega < -max_vel_theta)
00786 omega = -max_vel_theta;
00787
00788
00789 if (max_vel_x_backwards<=0)
00790 {
00791 ROS_WARN_ONCE("TebLocalPlannerROS(): Do not choose max_vel_x_backwards to be <=0. Disable backwards driving by increasing the optimization weight for penalyzing backwards driving.");
00792 }
00793 else if (vx < -max_vel_x_backwards)
00794 vx = -max_vel_x_backwards;
00795 }
00796
00797
00798 double TebLocalPlannerROS::convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius) const
00799 {
00800 if (omega==0 || v==0)
00801 return 0;
00802
00803 double radius = v/omega;
00804
00805 if (fabs(radius) < min_turning_radius)
00806 radius = double(g2o::sign(radius)) * min_turning_radius;
00807
00808 return std::atan(wheelbase / radius);
00809 }
00810
00811
00812 void TebLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist)
00813 {
00814 ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
00815 "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller "
00816 "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). "
00817 "Infeasible optimziation results might occur frequently!", opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
00818 }
00819
00820
00821
00822 void TebLocalPlannerROS::configureBackupModes(std::vector<geometry_msgs::PoseStamped>& transformed_plan, int& goal_idx)
00823 {
00824 ros::Time current_time = ros::Time::now();
00825
00826
00827 if (cfg_.trajectory.shrink_horizon_backup &&
00828 goal_idx < (int)transformed_plan.size()-1 &&
00829 (no_infeasible_plans_>0 || (current_time - time_last_infeasible_plan_).toSec() < cfg_.trajectory.shrink_horizon_min_duration ))
00830 {
00831 ROS_INFO_COND(no_infeasible_plans_==1, "Activating reduced horizon backup mode for at least %.2f sec (infeasible trajectory detected).", cfg_.trajectory.shrink_horizon_min_duration);
00832
00833
00834
00835
00836 int horizon_reduction = goal_idx/2;
00837
00838 if (no_infeasible_plans_ > 9)
00839 {
00840 ROS_INFO_COND(no_infeasible_plans_==10, "Infeasible trajectory detected 10 times in a row: further reducing horizon...");
00841 horizon_reduction /= 2;
00842 }
00843
00844
00845
00846
00847 int new_goal_idx_transformed_plan = int(transformed_plan.size()) - horizon_reduction - 1;
00848 goal_idx -= horizon_reduction;
00849 if (new_goal_idx_transformed_plan>0 && goal_idx >= 0)
00850 transformed_plan.erase(transformed_plan.begin()+new_goal_idx_transformed_plan, transformed_plan.end());
00851 else
00852 goal_idx += horizon_reduction;
00853 }
00854
00855 }
00856
00857
00858 void TebLocalPlannerROS::customObstacleCB(const teb_local_planner::ObstacleMsg::ConstPtr& obst_msg)
00859 {
00860 boost::mutex::scoped_lock l(custom_obst_mutex_);
00861 custom_obstacle_msg_ = *obst_msg;
00862 }
00863
00864 RobotFootprintModelPtr TebLocalPlannerROS::getRobotFootprintFromParamServer(const ros::NodeHandle& nh)
00865 {
00866 std::string model_name;
00867 if (!nh.getParam("footprint_model/type", model_name))
00868 {
00869 ROS_INFO("No robot footprint model specified for trajectory optimization. Using point-shaped model.");
00870 return boost::make_shared<PointRobotFootprint>();
00871 }
00872
00873
00874 if (model_name.compare("point") == 0)
00875 {
00876 ROS_INFO("Footprint model 'point' loaded for trajectory optimization.");
00877 return boost::make_shared<PointRobotFootprint>();
00878 }
00879
00880
00881 if (model_name.compare("circular") == 0)
00882 {
00883
00884 double radius;
00885 if (!nh.getParam("footprint_model/radius", radius))
00886 {
00887 ROS_ERROR_STREAM("Footprint model 'circular' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
00888 << "/footprint_model/radius' does not exist. Using point-model instead.");
00889 return boost::make_shared<PointRobotFootprint>();
00890 }
00891 ROS_INFO_STREAM("Footprint model 'circular' (radius: " << radius <<"m) loaded for trajectory optimization.");
00892 return boost::make_shared<CircularRobotFootprint>(radius);
00893 }
00894
00895
00896 if (model_name.compare("line") == 0)
00897 {
00898
00899 if (!nh.hasParam("footprint_model/line_start") || !nh.hasParam("footprint_model/line_end"))
00900 {
00901 ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
00902 << "/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
00903 return boost::make_shared<PointRobotFootprint>();
00904 }
00905
00906 std::vector<double> line_start, line_end;
00907 nh.getParam("footprint_model/line_start", line_start);
00908 nh.getParam("footprint_model/line_end", line_end);
00909 if (line_start.size() != 2 || line_end.size() != 2)
00910 {
00911 ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
00912 << "/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
00913 return boost::make_shared<PointRobotFootprint>();
00914 }
00915
00916 ROS_INFO_STREAM("Footprint model 'line' (line_start: [" << line_start[0] << "," << line_start[1] <<"]m, line_end: ["
00917 << line_end[0] << "," << line_end[1] << "]m) loaded for trajectory optimization.");
00918 return boost::make_shared<LineRobotFootprint>(Eigen::Map<const Eigen::Vector2d>(line_start.data()), Eigen::Map<const Eigen::Vector2d>(line_end.data()));
00919 }
00920
00921
00922 if (model_name.compare("two_circles") == 0)
00923 {
00924
00925 if (!nh.hasParam("footprint_model/front_offset") || !nh.hasParam("footprint_model/front_radius")
00926 || !nh.hasParam("footprint_model/rear_offset") || !nh.hasParam("footprint_model/rear_radius"))
00927 {
00928 ROS_ERROR_STREAM("Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '" << nh.getNamespace()
00929 << "/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using point-model instead.");
00930 return boost::make_shared<PointRobotFootprint>();
00931 }
00932 double front_offset, front_radius, rear_offset, rear_radius;
00933 nh.getParam("footprint_model/front_offset", front_offset);
00934 nh.getParam("footprint_model/front_radius", front_radius);
00935 nh.getParam("footprint_model/rear_offset", rear_offset);
00936 nh.getParam("footprint_model/rear_radius", rear_radius);
00937 ROS_INFO_STREAM("Footprint model 'two_circles' (front_offset: " << front_offset <<"m, front_radius: " << front_radius
00938 << "m, rear_offset: " << rear_offset << "m, rear_radius: " << rear_radius << "m) loaded for trajectory optimization.");
00939 return boost::make_shared<TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
00940 }
00941
00942
00943 if (model_name.compare("polygon") == 0)
00944 {
00945
00946
00947 XmlRpc::XmlRpcValue footprint_xmlrpc;
00948 if (!nh.getParam("footprint_model/vertices", footprint_xmlrpc) )
00949 {
00950 ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
00951 << "/footprint_model/vertices' does not exist. Using point-model instead.");
00952 return boost::make_shared<PointRobotFootprint>();
00953 }
00954
00955 if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray)
00956 {
00957 try
00958 {
00959 Point2dContainer polygon = makeFootprintFromXMLRPC(footprint_xmlrpc, "/footprint_model/vertices");
00960 ROS_INFO_STREAM("Footprint model 'polygon' loaded for trajectory optimization.");
00961 return boost::make_shared<PolygonRobotFootprint>(polygon);
00962 }
00963 catch(const std::exception& ex)
00964 {
00965 ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what() << ". Using point-model instead.");
00966 return boost::make_shared<PointRobotFootprint>();
00967 }
00968 }
00969 else
00970 {
00971 ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
00972 << "/footprint_model/vertices' does not define an array of coordinates. Using point-model instead.");
00973 return boost::make_shared<PointRobotFootprint>();
00974 }
00975
00976 }
00977
00978
00979 ROS_WARN_STREAM("Unknown robot footprint model specified with parameter '" << nh.getNamespace() << "/footprint_model/type'. Using point model instead.");
00980 return boost::make_shared<PointRobotFootprint>();
00981 }
00982
00983
00984
00985
00986 Point2dContainer TebLocalPlannerROS::makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name)
00987 {
00988
00989 if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray ||
00990 footprint_xmlrpc.size() < 3)
00991 {
00992 ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s",
00993 full_param_name.c_str(), std::string(footprint_xmlrpc).c_str());
00994 throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least "
00995 "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
00996 }
00997
00998 Point2dContainer footprint;
00999 Eigen::Vector2d pt;
01000
01001 for (int i = 0; i < footprint_xmlrpc.size(); ++i)
01002 {
01003
01004 XmlRpc::XmlRpcValue point = footprint_xmlrpc[ i ];
01005 if (point.getType() != XmlRpc::XmlRpcValue::TypeArray ||
01006 point.size() != 2)
01007 {
01008 ROS_FATAL("The footprint (parameter %s) must be specified as list of lists on the parameter server eg: "
01009 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
01010 full_param_name.c_str());
01011 throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: "
01012 "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
01013 }
01014
01015 pt.x() = getNumberFromXMLRPC(point[ 0 ], full_param_name);
01016 pt.y() = getNumberFromXMLRPC(point[ 1 ], full_param_name);
01017
01018 footprint.push_back(pt);
01019 }
01020 return footprint;
01021 }
01022
01023 double TebLocalPlannerROS::getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name)
01024 {
01025
01026 if (value.getType() != XmlRpc::XmlRpcValue::TypeInt &&
01027 value.getType() != XmlRpc::XmlRpcValue::TypeDouble)
01028 {
01029 std::string& value_string = value;
01030 ROS_FATAL("Values in the footprint specification (param %s) must be numbers. Found value %s.",
01031 full_param_name.c_str(), value_string.c_str());
01032 throw std::runtime_error("Values in the footprint specification must be numbers");
01033 }
01034 return value.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(value) : (double)(value);
01035 }
01036
01037 }
01038
01039