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