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