00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <base_local_planner/trajectory_planner_ros.h>
00039
00040 #include <sys/time.h>
00041 #include <boost/tokenizer.hpp>
00042
00043 #include <Eigen/Core>
00044 #include <cmath>
00045
00046 #include <ros/console.h>
00047
00048 #include <pluginlib/class_list_macros.h>
00049
00050 #include <base_local_planner/goal_functions.h>
00051 #include <geometry_msgs/PolygonStamped.h>
00052 #include <nav_msgs/Path.h>
00053
00054
00055
00056
00057 PLUGINLIB_EXPORT_CLASS( base_local_planner::TrajectoryPlannerROS, nav_core::BaseLocalPlanner)
00058
00059 namespace base_local_planner {
00060
00061 void TrajectoryPlannerROS::reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level) {
00062 if (setup_ && config.restore_defaults) {
00063 config = default_config_;
00064
00065 config.restore_defaults = false;
00066 }
00067 if ( ! setup_) {
00068 default_config_ = config;
00069 setup_ = true;
00070 }
00071 tc_->reconfigure(config);
00072 }
00073
00074 TrajectoryPlannerROS::TrajectoryPlannerROS() :
00075 world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), setup_(false), initialized_(false), odom_helper_("odom") {}
00076
00077 TrajectoryPlannerROS::TrajectoryPlannerROS(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros) :
00078 world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), setup_(false), initialized_(false), odom_helper_("odom") {
00079
00080
00081 initialize(name, tf, costmap_ros);
00082 }
00083
00084 void TrajectoryPlannerROS::initialize(
00085 std::string name,
00086 tf::TransformListener* tf,
00087 costmap_2d::Costmap2DROS* costmap_ros){
00088 if (! isInitialized()) {
00089
00090 ros::NodeHandle private_nh("~/" + name);
00091 g_plan_pub_ = private_nh.advertise<nav_msgs::Path>("global_plan", 1);
00092 l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
00093
00094
00095 tf_ = tf;
00096 costmap_ros_ = costmap_ros;
00097 rot_stopped_velocity_ = 1e-2;
00098 trans_stopped_velocity_ = 1e-2;
00099 double sim_time, sim_granularity, angular_sim_granularity;
00100 int vx_samples, vtheta_samples;
00101 double pdist_scale, gdist_scale, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta;
00102 bool holonomic_robot, dwa, simple_attractor, heading_scoring;
00103 double heading_scoring_timestep;
00104 double max_vel_x, min_vel_x;
00105 double backup_vel;
00106 double stop_time_buffer;
00107 std::string world_model_type;
00108 rotating_to_goal_ = false;
00109
00110
00111 costmap_ros_->getCostmapCopy(costmap_);
00112
00113
00114 global_frame_ = costmap_ros_->getGlobalFrameID();
00115 robot_base_frame_ = costmap_ros_->getBaseFrameID();
00116 private_nh.param("prune_plan", prune_plan_, true);
00117
00118 private_nh.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05);
00119 private_nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.10);
00120
00121
00122 inflation_radius_ = costmap_ros_->getInflationRadius();
00123
00124 private_nh.param("acc_lim_x", acc_lim_x_, 2.5);
00125 private_nh.param("acc_lim_y", acc_lim_y_, 2.5);
00126 private_nh.param("acc_lim_th", acc_lim_theta_, 3.2);
00127
00128 private_nh.param("stop_time_buffer", stop_time_buffer, 0.2);
00129
00130 private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false);
00131
00132
00133
00134 if(private_nh.hasParam("acc_limit_x"))
00135 ROS_ERROR("You are using acc_limit_x where you should be using acc_lim_x. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
00136
00137 if(private_nh.hasParam("acc_limit_y"))
00138 ROS_ERROR("You are using acc_limit_y where you should be using acc_lim_y. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
00139
00140 if(private_nh.hasParam("acc_limit_th"))
00141 ROS_ERROR("You are using acc_limit_th where you should be using acc_lim_th. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
00142
00143
00144
00145
00146 std::string controller_frequency_param_name;
00147 if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name))
00148 sim_period_ = 0.05;
00149 else
00150 {
00151 double controller_frequency = 0;
00152 private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
00153 if(controller_frequency > 0)
00154 sim_period_ = 1.0 / controller_frequency;
00155 else
00156 {
00157 ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
00158 sim_period_ = 0.05;
00159 }
00160 }
00161 ROS_INFO("Sim period is set to %.2f", sim_period_);
00162
00163 private_nh.param("sim_time", sim_time, 1.0);
00164 private_nh.param("sim_granularity", sim_granularity, 0.025);
00165 private_nh.param("angular_sim_granularity", angular_sim_granularity, sim_granularity);
00166 private_nh.param("vx_samples", vx_samples, 3);
00167 private_nh.param("vtheta_samples", vtheta_samples, 20);
00168
00169 private_nh.param("path_distance_bias", pdist_scale, 0.6);
00170 private_nh.param("goal_distance_bias", gdist_scale, 0.8);
00171 private_nh.param("occdist_scale", occdist_scale, 0.01);
00172
00173 bool meter_scoring;
00174 if ( ! private_nh.hasParam("meter_scoring")) {
00175 ROS_WARN("Trajectory Rollout planner initialized with param meter_scoring not set. Set it to true to make your settins robust against changes of costmap resolution.");
00176 } else {
00177 private_nh.param("meter_scoring", meter_scoring, false);
00178
00179 if(meter_scoring) {
00180
00181 double resolution = costmap_ros_->getResolution();
00182 gdist_scale *= resolution;
00183 pdist_scale *= resolution;
00184 occdist_scale *= resolution;
00185 } else {
00186 ROS_WARN("Trajectory Rollout planner initialized with param meter_scoring set to false. Set it to true to make your settins robust against changes of costmap resolution.");
00187 }
00188 }
00189
00190 private_nh.param("heading_lookahead", heading_lookahead, 0.325);
00191 private_nh.param("oscillation_reset_dist", oscillation_reset_dist, 0.05);
00192 private_nh.param("escape_reset_dist", escape_reset_dist, 0.10);
00193 private_nh.param("escape_reset_theta", escape_reset_theta, M_PI_4);
00194 private_nh.param("holonomic_robot", holonomic_robot, true);
00195 private_nh.param("max_vel_x", max_vel_x, 0.5);
00196 private_nh.param("min_vel_x", min_vel_x, 0.1);
00197
00198 double max_rotational_vel;
00199 private_nh.param("max_rotational_vel", max_rotational_vel, 1.0);
00200 max_vel_th_ = max_rotational_vel;
00201 min_vel_th_ = -1.0 * max_rotational_vel;
00202 private_nh.param("min_in_place_rotational_vel", min_in_place_vel_th_, 0.4);
00203
00204 backup_vel = -0.1;
00205 if(private_nh.getParam("backup_vel", backup_vel))
00206 ROS_WARN("The backup_vel parameter has been deprecated in favor of the escape_vel parameter. To switch, just change the parameter name in your configuration files.");
00207
00208
00209 private_nh.getParam("escape_vel", backup_vel);
00210
00211 if(backup_vel >= 0.0)
00212 ROS_WARN("You've specified a positive escape velocity. This is probably not what you want and will cause the robot to move forward instead of backward. You should probably change your escape_vel parameter to be negative");
00213
00214 private_nh.param("world_model", world_model_type, std::string("costmap"));
00215 private_nh.param("dwa", dwa, true);
00216 private_nh.param("heading_scoring", heading_scoring, false);
00217 private_nh.param("heading_scoring_timestep", heading_scoring_timestep, 0.8);
00218
00219 simple_attractor = false;
00220
00221
00222 double min_pt_separation, max_obstacle_height, grid_resolution;
00223 private_nh.param("point_grid/max_sensor_range", max_sensor_range_, 2.0);
00224 private_nh.param("point_grid/min_pt_separation", min_pt_separation, 0.01);
00225 private_nh.param("point_grid/max_obstacle_height", max_obstacle_height, 2.0);
00226 private_nh.param("point_grid/grid_resolution", grid_resolution, 0.2);
00227
00228 ROS_ASSERT_MSG(world_model_type == "costmap", "At this time, only costmap world models are supported by this controller");
00229 world_model_ = new CostmapModel(costmap_);
00230 std::vector<double> y_vels = loadYVels(private_nh);
00231
00232 tc_ = new TrajectoryPlanner(*world_model_, costmap_, costmap_ros_->getRobotFootprint(),
00233 acc_lim_x_, acc_lim_y_, acc_lim_theta_, sim_time, sim_granularity, vx_samples, vtheta_samples, pdist_scale,
00234 gdist_scale, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta, holonomic_robot,
00235 max_vel_x, min_vel_x, max_vel_th_, min_vel_th_, min_in_place_vel_th_, backup_vel,
00236 dwa, heading_scoring, heading_scoring_timestep, meter_scoring, simple_attractor, y_vels, stop_time_buffer, sim_period_, angular_sim_granularity);
00237
00238 map_viz_.initialize(name, boost::bind(&TrajectoryPlanner::getCellCosts, tc_, _1, _2, _3, _4, _5, _6));
00239 initialized_ = true;
00240
00241 dsrv_ = new dynamic_reconfigure::Server<BaseLocalPlannerConfig>(private_nh);
00242 dynamic_reconfigure::Server<BaseLocalPlannerConfig>::CallbackType cb = boost::bind(&TrajectoryPlannerROS::reconfigureCB, this, _1, _2);
00243 dsrv_->setCallback(cb);
00244
00245 } else {
00246 ROS_WARN("This planner has already been initialized, doing nothing");
00247 }
00248 }
00249
00250 std::vector<double> TrajectoryPlannerROS::loadYVels(ros::NodeHandle node){
00251 std::vector<double> y_vels;
00252
00253 std::string y_vel_list;
00254 if(node.getParam("y_vels", y_vel_list)){
00255 typedef boost::tokenizer<boost::char_separator<char> > tokenizer;
00256 boost::char_separator<char> sep("[], ");
00257 tokenizer tokens(y_vel_list, sep);
00258
00259 for(tokenizer::iterator i = tokens.begin(); i != tokens.end(); i++){
00260 y_vels.push_back(atof((*i).c_str()));
00261 }
00262 }
00263 else{
00264
00265 y_vels.push_back(-0.3);
00266 y_vels.push_back(-0.1);
00267 y_vels.push_back(0.1);
00268 y_vels.push_back(0.3);
00269 }
00270
00271 return y_vels;
00272 }
00273
00274 TrajectoryPlannerROS::~TrajectoryPlannerROS() {
00275
00276 delete dsrv_;
00277
00278 if(tc_ != NULL)
00279 delete tc_;
00280
00281 if(world_model_ != NULL)
00282 delete world_model_;
00283 }
00284
00285 bool TrajectoryPlannerROS::stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, geometry_msgs::Twist& cmd_vel){
00286
00287
00288 double vx = sign(robot_vel.getOrigin().x()) * std::max(0.0, (fabs(robot_vel.getOrigin().x()) - acc_lim_x_ * sim_period_));
00289 double vy = sign(robot_vel.getOrigin().y()) * std::max(0.0, (fabs(robot_vel.getOrigin().y()) - acc_lim_y_ * sim_period_));
00290
00291 double vel_yaw = tf::getYaw(robot_vel.getRotation());
00292 double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim_theta_ * sim_period_));
00293
00294
00295 double yaw = tf::getYaw(global_pose.getRotation());
00296 bool valid_cmd = tc_->checkTrajectory(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw,
00297 robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw, vx, vy, vth);
00298
00299
00300 if(valid_cmd){
00301 ROS_DEBUG("Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth);
00302 cmd_vel.linear.x = vx;
00303 cmd_vel.linear.y = vy;
00304 cmd_vel.angular.z = vth;
00305 return true;
00306 }
00307
00308 cmd_vel.linear.x = 0.0;
00309 cmd_vel.linear.y = 0.0;
00310 cmd_vel.angular.z = 0.0;
00311 return false;
00312 }
00313
00314 bool TrajectoryPlannerROS::rotateToGoal(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel){
00315 double yaw = tf::getYaw(global_pose.getRotation());
00316 double vel_yaw = tf::getYaw(robot_vel.getRotation());
00317 cmd_vel.linear.x = 0;
00318 cmd_vel.linear.y = 0;
00319 double ang_diff = angles::shortest_angular_distance(yaw, goal_th);
00320
00321 double v_theta_samp = ang_diff > 0.0 ? std::min(max_vel_th_,
00322 std::max(min_in_place_vel_th_, ang_diff)) : std::max(min_vel_th_,
00323 std::min(-1.0 * min_in_place_vel_th_, ang_diff));
00324
00325
00326 double max_acc_vel = fabs(vel_yaw) + acc_lim_theta_ * sim_period_;
00327 double min_acc_vel = fabs(vel_yaw) - acc_lim_theta_ * sim_period_;
00328
00329 v_theta_samp = sign(v_theta_samp) * std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
00330
00331
00332 double max_speed_to_stop = sqrt(2 * acc_lim_theta_ * fabs(ang_diff));
00333
00334 v_theta_samp = sign(v_theta_samp) * std::min(max_speed_to_stop, fabs(v_theta_samp));
00335
00336
00337 v_theta_samp = v_theta_samp > 0.0
00338 ? std::min( max_vel_th_, std::max( min_in_place_vel_th_, v_theta_samp ))
00339 : std::max( min_vel_th_, std::min( -1.0 * min_in_place_vel_th_, v_theta_samp ));
00340
00341
00342 bool valid_cmd = tc_->checkTrajectory(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw,
00343 robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw, 0.0, 0.0, v_theta_samp);
00344
00345 ROS_DEBUG("Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd);
00346
00347 if(valid_cmd){
00348 cmd_vel.angular.z = v_theta_samp;
00349 return true;
00350 }
00351
00352 cmd_vel.angular.z = 0.0;
00353 return false;
00354
00355 }
00356
00357 bool TrajectoryPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan){
00358 if (! isInitialized()) {
00359 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00360 return false;
00361 }
00362
00363
00364 global_plan_.clear();
00365 global_plan_ = orig_global_plan;
00366
00367
00368 xy_tolerance_latch_ = false;
00369
00370 return true;
00371 }
00372
00373 bool TrajectoryPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
00374 if (! isInitialized()) {
00375 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00376 return false;
00377 }
00378
00379 std::vector<geometry_msgs::PoseStamped> local_plan;
00380 tf::Stamped<tf::Pose> global_pose;
00381 if (!costmap_ros_->getRobotPose(global_pose)) {
00382 return false;
00383 }
00384
00385 std::vector<geometry_msgs::PoseStamped> transformed_plan;
00386
00387 if (!transformGlobalPlan(*tf_, global_plan_, global_pose, costmap_, global_frame_, transformed_plan)) {
00388 ROS_WARN("Could not transform the global plan to the frame of the controller");
00389 return false;
00390 }
00391
00392
00393 if(prune_plan_)
00394 prunePlan(global_pose, transformed_plan, global_plan_);
00395
00396
00397
00398 costmap_ros_->clearRobotFootprint();
00399
00400
00401 costmap_ros_->getCostmapCopy(costmap_);
00402
00403 tf::Stamped<tf::Pose> drive_cmds;
00404 drive_cmds.frame_id_ = robot_base_frame_;
00405
00406 tf::Stamped<tf::Pose> robot_vel;
00407 odom_helper_.getRobotVel(robot_vel);
00408
00409
00410
00411
00412
00413
00414
00415
00416 if(transformed_plan.empty())
00417 return false;
00418
00419 tf::Stamped<tf::Pose> goal_point;
00420 tf::poseStampedMsgToTF(transformed_plan.back(), goal_point);
00421
00422 double goal_x = goal_point.getOrigin().getX();
00423 double goal_y = goal_point.getOrigin().getY();
00424
00425 double yaw = tf::getYaw(goal_point.getRotation());
00426
00427 double goal_th = yaw;
00428
00429
00430 if (xy_tolerance_latch_ || (getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance_)) {
00431
00432
00433
00434 if (latch_xy_goal_tolerance_) {
00435 xy_tolerance_latch_ = true;
00436 }
00437
00438 double angle = getGoalOrientationAngleDifference(global_pose, goal_th);
00439
00440 if (fabs(angle) <= yaw_goal_tolerance_) {
00441
00442 cmd_vel.linear.x = 0.0;
00443 cmd_vel.linear.y = 0.0;
00444 cmd_vel.angular.z = 0.0;
00445 rotating_to_goal_ = false;
00446 xy_tolerance_latch_ = false;
00447 } else {
00448
00449
00450 tc_->updatePlan(transformed_plan);
00451 Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds);
00452 map_viz_.publishCostCloud(costmap_);
00453
00454
00455 nav_msgs::Odometry base_odom;
00456 odom_helper_.getOdom(base_odom);
00457
00458
00459 if ( ! rotating_to_goal_ && !base_local_planner::stopped(base_odom, rot_stopped_velocity_, trans_stopped_velocity_)) {
00460 if ( ! stopWithAccLimits(global_pose, robot_vel, cmd_vel)) {
00461 return false;
00462 }
00463 }
00464
00465 else{
00466
00467 rotating_to_goal_ = true;
00468 if(!rotateToGoal(global_pose, robot_vel, goal_th, cmd_vel)) {
00469 return false;
00470 }
00471 }
00472 }
00473
00474
00475 publishPlan(transformed_plan, g_plan_pub_);
00476 publishPlan(local_plan, l_plan_pub_);
00477
00478
00479 return true;
00480 }
00481
00482 tc_->updatePlan(transformed_plan);
00483
00484
00485 Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds);
00486
00487 map_viz_.publishCostCloud(costmap_);
00488
00489
00490
00491
00492
00493
00494
00495
00496
00497 cmd_vel.linear.x = drive_cmds.getOrigin().getX();
00498 cmd_vel.linear.y = drive_cmds.getOrigin().getY();
00499 cmd_vel.angular.z = tf::getYaw(drive_cmds.getRotation());
00500
00501
00502 if (path.cost_ < 0) {
00503 ROS_DEBUG_NAMED("trajectory_planner_ros",
00504 "The rollout planner failed to find a valid plan. This means that the footprint of the robot was in collision for all simulated trajectories.");
00505 local_plan.clear();
00506 publishPlan(transformed_plan, g_plan_pub_);
00507 publishPlan(local_plan, l_plan_pub_);
00508 return false;
00509 }
00510
00511 ROS_DEBUG_NAMED("trajectory_planner_ros", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.",
00512 cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
00513
00514
00515 for (unsigned int i = 0; i < path.getPointsSize(); ++i) {
00516 double p_x, p_y, p_th;
00517 path.getPoint(i, p_x, p_y, p_th);
00518 tf::Stamped<tf::Pose> p =
00519 tf::Stamped<tf::Pose>(tf::Pose(
00520 tf::createQuaternionFromYaw(p_th),
00521 tf::Point(p_x, p_y, 0.0)),
00522 ros::Time::now(),
00523 global_frame_);
00524 geometry_msgs::PoseStamped pose;
00525 tf::poseStampedTFToMsg(p, pose);
00526 local_plan.push_back(pose);
00527 }
00528
00529
00530 publishPlan(transformed_plan, g_plan_pub_);
00531 publishPlan(local_plan, l_plan_pub_);
00532 return true;
00533 }
00534
00535 bool TrajectoryPlannerROS::checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){
00536 tf::Stamped<tf::Pose> global_pose;
00537 if(costmap_ros_->getRobotPose(global_pose)){
00538 if(update_map){
00539
00540 costmap_ros_->clearRobotFootprint();
00541
00542
00543 costmap_ros_->getCostmapCopy(costmap_);
00544
00545
00546
00547 std::vector<geometry_msgs::PoseStamped> plan;
00548 geometry_msgs::PoseStamped pose_msg;
00549 tf::poseStampedTFToMsg(global_pose, pose_msg);
00550 plan.push_back(pose_msg);
00551 tc_->updatePlan(plan, true);
00552 }
00553
00554
00555 nav_msgs::Odometry base_odom;
00556 {
00557 boost::recursive_mutex::scoped_lock lock(odom_lock_);
00558 base_odom = base_odom_;
00559 }
00560
00561 return tc_->checkTrajectory(global_pose.getOrigin().x(), global_pose.getOrigin().y(), tf::getYaw(global_pose.getRotation()),
00562 base_odom.twist.twist.linear.x,
00563 base_odom.twist.twist.linear.y,
00564 base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp);
00565
00566 }
00567 ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
00568 return false;
00569 }
00570
00571
00572 double TrajectoryPlannerROS::scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){
00573
00574 tf::Stamped<tf::Pose> global_pose;
00575 if(costmap_ros_->getRobotPose(global_pose)){
00576 if(update_map){
00577
00578 costmap_ros_->clearRobotFootprint();
00579
00580
00581 costmap_ros_->getCostmapCopy(costmap_);
00582
00583
00584
00585 std::vector<geometry_msgs::PoseStamped> plan;
00586 geometry_msgs::PoseStamped pose_msg;
00587 tf::poseStampedTFToMsg(global_pose, pose_msg);
00588 plan.push_back(pose_msg);
00589 tc_->updatePlan(plan, true);
00590 }
00591
00592
00593 nav_msgs::Odometry base_odom;
00594 {
00595 boost::recursive_mutex::scoped_lock lock(odom_lock_);
00596 base_odom = base_odom_;
00597 }
00598
00599 return tc_->scoreTrajectory(global_pose.getOrigin().x(), global_pose.getOrigin().y(), tf::getYaw(global_pose.getRotation()),
00600 base_odom.twist.twist.linear.x,
00601 base_odom.twist.twist.linear.y,
00602 base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp);
00603
00604 }
00605 ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
00606 return -1.0;
00607 }
00608
00609 bool TrajectoryPlannerROS::isGoalReached() {
00610 if (! isInitialized()) {
00611 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00612 return false;
00613 }
00614
00615
00616 nav_msgs::Odometry base_odom;
00617 odom_helper_.getOdom(base_odom);
00618 tf::Stamped<tf::Pose> global_pose;
00619 costmap_ros_->getRobotPose(global_pose);
00620 return base_local_planner::isGoalReached(*tf_,
00621 global_plan_,
00622 costmap_,
00623 global_frame_,
00624 global_pose,
00625 base_odom,
00626 rot_stopped_velocity_, trans_stopped_velocity_,
00627 xy_goal_tolerance_, yaw_goal_tolerance_);
00628 }
00629 };