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