$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00042 #include "cart_local_planner/cart_local_planner.h" 00043 #include <base_local_planner/goal_functions.h> 00044 #include <tf_conversions/tf_kdl.h> 00045 #include <pluginlib/class_list_macros.h> 00046 #include <vector> 00047 #include <boost/foreach.hpp> 00048 #include <boost/optional.hpp> 00049 00050 PLUGINLIB_DECLARE_CLASS(cart_local_planner, CartLocalPlanner, cart_local_planner::CartLocalPlanner, nav_core::BaseLocalPlanner) 00051 00052 namespace gm = geometry_msgs; 00053 00054 00055 namespace cart_pushing_msgs { 00056 00057 00058 bool operator==(const cart_pushing_msgs::RobotCartPath& sbpl_plan, 00059 const std::vector<gm::PoseStamped>& mb_plan) 00060 00061 { 00062 const unsigned n = sbpl_plan.path.size(); 00063 if (n != mb_plan.size()) 00064 { 00065 ROS_ERROR("Plans don't have the same size: %d, SBPL: %d",(int)mb_plan.size(),(int)sbpl_plan.path.size()); 00066 return false; 00067 } 00068 for (unsigned i = 0; i < n; i++) { 00069 // Check if poses are the same 00070 const gm::Pose& p = mb_plan[i].pose; 00071 const gm::Pose& p2 = sbpl_plan.path[i].robot_pose; 00072 if ((p.position.x != p2.position.x) || (p.position.y != p2.position.y) 00073 || (p.position.z != p2.position.z) || (p.orientation.x 00074 != p2.orientation.x) || (p.orientation.y != p2.orientation.y) 00075 || (p.orientation.z != p2.orientation.z) || (p.orientation.w 00076 != p2.orientation.w)) 00077 { 00078 ROS_ERROR("Plans don't have the same waypoint: %d",i); 00079 return false; 00080 } 00081 } 00082 return true; 00083 } 00084 } // namespace cart_pushing_msgs 00085 00086 namespace cart_local_planner { 00087 using std::vector; 00088 using std::max; 00089 using std::string; 00090 using boost::optional; 00091 const double SBPL_DTHRESH=-0.013; // SBPL mPrims translate about 0.0186 on a straight shot 00092 typedef tf::Stamped<tf::Pose> StampedPose; 00093 00094 template<class T> 00095 T clamp(T val, T abs_max) { 00096 return val > 0 ? (val > abs_max ? abs_max : val) 00097 : (val < -abs_max ? -abs_max : val); 00098 } 00099 00100 const gm::Twist operator+(const gm::Twist& t1, const gm::Twist& t2) 00101 { 00102 gm::Twist res; 00103 res.linear.x = t1.linear.x + t2.linear.x; 00104 res.linear.y = t1.linear.y + t2.linear.y; 00105 res.linear.z = t1.linear.z + t2.linear.z; 00106 res.angular.x = t1.angular.x + t2.angular.x; 00107 res.angular.y = t1.angular.y + t2.angular.y; 00108 res.angular.z = t1.angular.z + t2.angular.z; 00109 00110 return res; 00111 } 00112 00113 const gm::Twist operator-(const gm::Twist& t1, const gm::Twist& t2) 00114 { 00115 gm::Twist res; 00116 res.linear.x = t1.linear.x - t2.linear.x; 00117 res.linear.y = t1.linear.y - t2.linear.y; 00118 res.linear.z = t1.linear.z - t2.linear.z; 00119 res.angular.x = t1.angular.x - t2.angular.x; 00120 res.angular.y = t1.angular.y - t2.angular.y; 00121 res.angular.z = t1.angular.z - t2.angular.z; 00122 00123 return res; 00124 } 00125 00126 double mag(gm::Twist &t) { 00127 return sqrt(t.linear.x*t.linear.x + t.linear.y*t.linear.y + t.linear.z*t.linear.z + 00128 t.angular.x*t.angular.x + t.angular.y*t.angular.y + t.angular.z*t.angular.z); 00129 } 00130 00131 double mag(geometry_msgs::Pose2D &p) { 00132 return sqrt(p.x*p.x+p.y*p.y+p.theta*p.theta); 00133 } 00134 00135 CartLocalPlanner::CartLocalPlanner() : 00136 tf_(NULL), nh_("cart_planner_costmap"), costmap_ros_(NULL), initialized_(false) 00137 { 00138 } 00139 00140 template <typename T> 00141 void getParam (const ros::NodeHandle nh, const string& name, T* place) 00142 { 00143 bool found = nh.getParam(name, *place); 00144 ROS_ASSERT_MSG (found, "Did not find parameter %s", nh.resolveName(name).c_str()); 00145 } 00146 00147 void CartLocalPlanner::initialize(std::string name, tf::TransformListener* tf, 00148 costmap_2d::Costmap2DROS* costmap_ros) { 00149 tf_ = tf; 00150 costmap_ros_ = costmap_ros; 00151 current_waypoint_ = 0; 00152 goal_reached_time_ = ros::Time::now(); 00153 ros::NodeHandle cart_nh("cart_pushing"); 00154 ros::NodeHandle nh("~/"+name); 00155 00156 // Get a nodehandle for reading cart params 00157 std::string cart_param_ns; 00158 getParam(nh, "cart_param_namespace", &cart_param_ns); 00159 ros::NodeHandle cart_param_nh(cart_param_ns); 00160 00161 // initialize robot collision checker 00162 robot_collision_checker_.initialize(costmap_ros_, "robot_trajectory"); 00163 00164 // Get twist saturation limits 00165 getParam(cart_nh, "max_vel_base_x", &twist_base_max_.linear.x); 00166 getParam(cart_nh, "max_vel_base_y", &twist_base_max_.linear.y); 00167 getParam(cart_nh, "max_vel_base_theta", &twist_base_max_.angular.z); 00168 getParam(cart_nh, "max_vel_cart_x", &twist_cart_max_.linear.x); 00169 getParam(cart_nh, "max_vel_cart_y", &twist_cart_max_.linear.y); 00170 getParam(cart_nh, "max_vel_cart_theta", &twist_cart_max_.angular.z); 00171 00172 // Get trajectory rollout params 00173 getParam(nh, "dt", &dt_); 00174 getParam(nh, "num_traj_steps", &num_traj_steps_); 00175 00176 // Get cart footprint dimensions 00177 getParam(cart_param_nh, "length", &cart_length_); 00178 getParam(cart_param_nh, "width", &cart_width_); 00179 getParam(cart_param_nh, "footprint_x_offset", &cart_x_offset_); 00180 getParam(cart_param_nh, "footprint_y_offset", &cart_y_offset_); 00181 cart_collision_checker_.initialize(costmap_ros_, "cart_trajectory"); 00182 cart_collision_checker_.setFootprint(cart_length_, cart_width_, cart_x_offset_, cart_y_offset_); 00183 cart_collision_checker_.setRobotFrameID("cart"); 00184 00185 getParam(nh, "k_trans_base", &K_trans_base_); 00186 getParam(nh, "k_rot_base", &K_rot_base_); 00187 getParam(nh, "k_trans_cart", &K_trans_cart_); 00188 getParam(nh, "k_rot_cart", &K_rot_cart_); 00189 00190 getParam(nh, "subscribe_sbpl_plan", &subscribe_sbpl_plan_); 00191 00192 ros::NodeHandle node; 00193 odom_sub_ = node.subscribe<nav_msgs::Odometry> ("odom", 1, &CartLocalPlanner::odomCallback, this); 00194 invalid_pose_sub_ = node.subscribe<std_msgs::Empty> ("cart_pushing/articulate_cart_server/invalid_pose", 00195 1, &CartLocalPlanner::invalidPoseCallback, this); 00196 vel_pub_ = node.advertise<gm::Twist> ("base_controller/command", 10); 00197 00198 if(subscribe_sbpl_plan_) 00199 { 00200 ROS_INFO("Setting up SBPL subscriber"); 00201 sbpl_subscriber_.reset(new cart_local_planner::SBPLSubscriber<cart_pushing_msgs::RobotCartPath>(node,"/move_base_node/SBPLCartPlanner/sbpl_robot_cart_plan")); 00202 } 00203 00204 // Attach to cart control topic 00205 std::string cart_articulation_ns; // Get a nodehandle for reading cart params 00206 getParam(nh, "cart_articulation_namespace", &cart_articulation_ns); 00207 cart_twist_pub_ = node.advertise<gm::TwistStamped>(cart_articulation_ns + "/command_twist", 10); 00208 00209 // Get workspace range params (for filtering cart commands as well as base commands) 00210 getParam(cart_param_nh, "x_min", &cart_range.x_min); 00211 getParam(cart_param_nh, "x_max", &cart_range.x_max); 00212 getParam(cart_param_nh, "y_min", &cart_range.y_min); 00213 getParam(cart_param_nh, "y_max", &cart_range.y_max); 00214 getParam(cart_param_nh, "t_min", &cart_range.t_min); 00215 getParam(cart_param_nh, "t_max", &cart_range.t_max); 00216 ROS_DEBUG("Loaded workspace range from %s: %.2lf %.2lf, %.2lf %.2lf, %.2lf %.2lf", cart_param_nh.getNamespace().c_str(), cart_range.x_min, cart_range.x_max, 00217 cart_range.y_min, cart_range.y_max, cart_range.t_min, cart_range.t_max); 00218 00219 // Get Termination and stop criteria params 00220 getParam(nh, "tolerance_trans", &tolerance_trans_); 00221 getParam(nh, "tolerance_rot", &tolerance_rot_); 00222 getParam(nh, "tolerance_timeout", &tolerance_timeout_); 00223 getParam(nh, "trans_stopped_velocity", &trans_stopped_velocity_); 00224 getParam(nh, "rot_stopped_velocity", &rot_stopped_velocity_); 00225 00226 // Apply any extra initialization 00227 initialization_extras(); 00228 00229 // Publishers for plotting poses and twists (mainly for debugging) 00230 pose2D_pub_ = nh.advertise<gm::Pose2D> ("debug_pose", 10); 00231 00232 cart_clear_pub_ = nh.advertise<geometry_msgs::PolygonStamped>("cart_cleared_footprint", 1, true); 00233 waypoint_pub_ = nh.advertise<geometry_msgs::PoseStamped>("current_waypoint", 1, true); 00234 00235 cleared_cart_footprint_ = clearCartFootprint(); 00236 00237 initialized_ = true; 00238 ROS_DEBUG("Initialized"); 00239 } 00240 00241 void CartLocalPlanner::initialization_extras() 00242 { 00243 } 00244 00245 bool CartLocalPlanner::clearCartFootprint() 00246 { 00247 tf::StampedTransform cart_pose; 00248 try { 00249 tf_->lookupTransform(costmap_ros_->getGlobalFrameID(), "cart", ros::Time(), cart_pose); 00250 } 00251 catch (tf::TransformException &ex) { 00252 ROS_ERROR("Unable to lookup \"cart\" in \"%s\" frame.", costmap_ros_->getGlobalFrameID().c_str()); 00253 return false; 00254 } 00255 00256 double front_padding = 0.01; 00257 double back_padding = 0.05; 00258 double side_padding = 0.02; 00259 00260 std::vector<tf::Point> cart_points; 00261 cart_points.push_back(tf::Point( - cart_x_offset_ - back_padding, - cart_y_offset_ - side_padding, 0.0)); 00262 cart_points.push_back(tf::Point(cart_length_ - cart_x_offset_ + front_padding, - cart_y_offset_ - side_padding, 0.0)); 00263 cart_points.push_back(tf::Point(cart_length_ - cart_x_offset_ + front_padding, cart_width_ - cart_y_offset_ + side_padding, 0.0)); 00264 cart_points.push_back(tf::Point( - cart_x_offset_ - back_padding, cart_width_ - cart_y_offset_ + side_padding, 0.0)); 00265 00266 // Transform to costmap frame 00267 for (size_t i = 0; i < cart_points.size(); ++i) { 00268 cart_points[i] = cart_pose * cart_points[i]; 00269 } 00270 00271 std::vector<geometry_msgs::Point> cart_pts_msg; 00272 cart_pts_msg.resize(cart_points.size()); 00273 for (size_t i = 0; i < cart_points.size(); ++i) { 00274 tf::pointTFToMsg(cart_points[i], cart_pts_msg[i]); 00275 } 00276 00277 costmap_ros_->setConvexPolygonCost(cart_pts_msg, 0); 00278 00279 ROS_DEBUG("Cleared cart footprint in costmap"); 00280 geometry_msgs::PolygonStamped msg; 00281 msg.header.frame_id = costmap_ros_->getGlobalFrameID(); 00282 msg.header.stamp = ros::Time::now(); 00283 msg.polygon.points.resize(cart_pts_msg.size()); 00284 for (size_t i = 0; i < msg.polygon.points.size(); ++i) 00285 { 00286 msg.polygon.points[i].x = cart_pts_msg[i].x; 00287 msg.polygon.points[i].y = cart_pts_msg[i].y; 00288 msg.polygon.points[i].z = cart_pts_msg[i].z; 00289 } 00290 geometry_msgs::Point32 last; 00291 last.x = cart_pts_msg[0].x; 00292 last.y = cart_pts_msg[0].y; 00293 last.z = cart_pts_msg[0].z; 00294 00295 msg.polygon.points.push_back(last); 00296 00297 cart_clear_pub_.publish(msg); 00298 00299 return true; 00300 } 00301 00302 bool CartLocalPlanner::computeVelocityCommands(gm::Twist& cmd_vel) 00303 { 00304 { // Check if we're printing debug messages, which happens every N iterations 00305 static unsigned debug_counter=0; 00306 debug_counter++; 00307 if (debug_counter > 100) { debug_counter = 0; } 00308 debug_print_ = !(debug_counter%20); 00309 } 00310 00311 if (global_plan_.empty()) { 00312 ROS_ERROR("No global plan. Unable to compute velocity commands"); 00313 return false; 00314 } 00315 00316 cleared_cart_footprint_ = cleared_cart_footprint_ || clearCartFootprint(); 00317 00319 tf::Stamped<tf::Pose> robot_pose; 00320 static ros::Time last_good_command; 00321 00322 ROS_DEBUG_COND_NAMED (debug_print_, "loop", "Computing velocity commands"); 00323 00324 // So if we get a pose that's too old, we'll freeze, but not actually signal failure unless it's 00325 // been a while since we succeeded 00326 if (!costmap_ros_->getRobotPose(robot_pose)) { 00327 freeze(); 00328 ros::Duration time_since_last_good_command = ros::Time::now()-last_good_command; 00329 ROS_WARN_STREAM("Can't get robot pose; time since last good command is " << time_since_last_good_command); 00330 return time_since_last_good_command < ros::Duration(2.0); 00331 } 00333 tf::StampedTransform cart_pose; 00334 try { 00335 tf_->lookupTransform("base_footprint", "cart", ros::Time(), cart_pose); 00336 } 00337 catch (tf::TransformException &ex) { 00338 ROS_ERROR("Unable to lookup \"cart\" in \"base_footprint\" frame."); 00339 return false; 00340 } 00341 00343 robot_pose_actual_.setBasis(robot_pose.getBasis()); 00344 robot_pose_actual_.setOrigin(robot_pose.getOrigin()); 00345 cart_pose_actual_.setBasis(cart_pose.getBasis()); 00346 cart_pose_actual_.setOrigin(cart_pose.getOrigin()); 00347 00349 twist_base_ = &cmd_vel; 00350 00352 // If goal too far away, unable to continue 00353 if (!setGoalPoses()) { 00354 return false; 00355 } 00356 00357 ROS_DEBUG_COND_NAMED (debug_print_, "loop", " Set goal poses"); 00358 00360 setControlMode(); 00361 00363 controlModeAction(); 00364 00365 ROS_DEBUG_COND_NAMED (debug_print_, "loop", " Generated controls"); 00366 00367 00368 bool found_good_vels = false; 00369 00370 /* if(!subscribe_sbpl_plan_) 00371 {*/ 00373 found_good_vels = checkTwists(); 00374 if (found_good_vels) 00375 { 00376 last_good_command = ros::Time::now(); 00377 twist_cart_.twist.linear.z = 0.0; 00378 twist_cart_.twist.angular.x = 0.0; 00379 twist_cart_.twist.angular.y = 0.0; 00380 cart_twist_pub_.publish(twist_cart_); 00381 } 00382 else 00383 { 00384 found_good_vels = checkTwistsMonotonic(); 00385 if (found_good_vels) 00386 { 00387 ROS_INFO("Twists are taking us away from collision"); 00388 last_good_command = ros::Time::now(); 00389 twist_cart_.twist.linear.z = 0.0; 00390 twist_cart_.twist.angular.x = 0.0; 00391 twist_cart_.twist.angular.y = 0.0; 00392 cart_twist_pub_.publish(twist_cart_); 00393 } 00394 else 00395 { 00396 ROS_WARN_THROTTLE(1, "Freezing because the twists are leading to collision"); 00397 freeze(); 00398 } 00399 } 00400 /* } 00401 else 00402 { 00403 std::vector<unsigned int> waypoint_indices; 00404 getNextFewWaypointsIndices(global_plan_,current_waypoint_,20,0.25,0.25,waypoint_indices); 00405 found_good_vels = checkTrajectoryMonotonic(waypoint_indices); 00406 if (found_good_vels) 00407 { 00408 ROS_DEBUG("Twists are taking us away from collision"); 00409 last_good_command = ros::Time::now(); 00410 twist_cart_.twist.linear.z = 0.0; 00411 twist_cart_.twist.angular.x = 0.0; 00412 twist_cart_.twist.angular.y = 0.0; 00413 cart_twist_pub_.publish(twist_cart_); 00414 } 00415 else 00416 { 00417 ROS_WARN_THROTTLE(1, "Freezing because the twists are leading to collision"); 00418 freeze(); 00419 } 00420 }*/ 00421 publishDebugPose(robot_pose_actual_); 00422 ROS_DEBUG_COND_NAMED(debug_print_, "loop", "final base twist: [%.3f,%.3f][%.3f]", 00423 twist_base_->linear.x, twist_base_->linear.y, twist_base_->angular.z); 00424 ROS_DEBUG_COND_NAMED(debug_print_, "loop", "final cart twist: [%.3f,%.3f][%.3f]", 00425 twist_cart_.twist.linear.x, twist_cart_.twist.linear.y, twist_cart_.twist.angular.z); 00426 00427 return found_good_vels; 00428 } 00429 00430 bool CartLocalPlanner::checkTrajectoryMonotonic(const std::vector<unsigned int> &indices) 00431 { 00432 boost::optional<cart_pushing_msgs::RobotCartPath> sbpl_plan = sbpl_subscriber_->lookupPlan(original_global_plan_); 00433 if(!sbpl_plan) 00434 { 00435 ROS_ERROR("Could not find SBPL plan"); 00436 return false; 00437 } 00438 std::vector<geometry_msgs::Pose2D> robot_path, cart_path; 00439 00440 for(unsigned int i=0; i <indices.size(); i++) 00441 { 00442 unsigned int index = indices[i]; 00443 00444 geometry_msgs::Pose2D robot_pose_2d; 00445 robot_pose_2d.x = global_plan_[index].pose.position.x; 00446 robot_pose_2d.y = global_plan_[index].pose.position.y; 00447 robot_pose_2d.theta = tf::getYaw(global_plan_[index].pose.orientation); 00448 robot_path.push_back(robot_pose_2d); 00449 00450 tf::Pose robot_pose, cart_pose_local, cart_pose_global; 00451 tf::poseMsgToTF(global_plan_[index].pose,robot_pose); 00452 tf::poseMsgToTF(sbpl_plan->path[index].cart_pose,cart_pose_local); 00453 cart_pose_global = robot_pose*cart_pose_local; 00454 00455 geometry_msgs::Pose2D cart_pose; 00456 cart_pose.x = cart_pose_global.getOrigin().x(); 00457 cart_pose.y = cart_pose_global.getOrigin().y(); 00458 cart_pose.theta = tf::getYaw(cart_pose_global.getRotation()); 00459 cart_path.push_back(cart_pose); 00460 00461 } 00462 00463 // Check base twist for collisions on the base footprint 00464 double base_footprint_cost=robot_collision_checker_.checkTrajectoryMonotonic(robot_path,true,true,5); 00465 if(base_footprint_cost < 0.0) 00466 { 00467 ROS_INFO("Base footprint in collision"); 00468 return false; 00469 } 00470 // Check the base+cart twists for collisions on the cart footprint 00471 double cart_footprint_cost=cart_collision_checker_.checkTrajectoryMonotonic(cart_path,true,true,5); 00472 if(cart_footprint_cost < 0.0) 00473 { 00474 ROS_INFO("Cart footprint in collision"); 00475 return false; 00476 } 00477 return true; 00478 } 00479 00480 bool CartLocalPlanner::getNextFewWaypointsIndices(const std::vector<geometry_msgs::PoseStamped> ¤t_plan, 00481 const int ¤t_waypoint_index, 00482 const int &max_num_waypoints, 00483 const double &max_translation, 00484 const double &max_rotation, 00485 std::vector<unsigned int> &waypoint_indices) 00486 { 00487 if(current_waypoint_index > (int)current_plan.size()-1) 00488 { 00489 ROS_ERROR("Current waypoint exceeds number of points in plan"); 00490 return false; 00491 } 00492 unsigned int num_waypoints = 0; 00493 waypoint_indices.clear(); 00494 00495 tf::Stamped<tf::Pose> current_waypoint; 00496 tf::poseStampedMsgToTF(current_plan[current_waypoint_index],current_waypoint); 00497 for(unsigned int i = current_waypoint_index; i < current_plan.size(); i++) 00498 { 00499 tf::Stamped<tf::Pose> next_waypoint; 00500 tf::poseStampedMsgToTF(current_plan[i],next_waypoint); 00501 tf::Pose error = current_waypoint.inverseTimes(next_waypoint); 00502 if(error.getOrigin().length() > max_translation) 00503 break; 00504 if(fabs(tf::getYaw(error.getRotation())) > max_rotation) 00505 break; 00506 waypoint_indices.push_back(i); 00507 num_waypoints++; 00508 if((int)num_waypoints > max_num_waypoints) 00509 break; 00510 } 00511 return true; 00512 } 00513 00514 void CartLocalPlanner::setRobotPoseGoal (const StampedPose& goal) 00515 { 00516 robot_pose_goal_ = goal; 00517 robot_pose_error_ = robot_pose_actual_.inverseTimes(robot_pose_goal_); 00518 } 00519 00520 void CartLocalPlanner::setCartPoseGoal (const StampedPose& goal) 00521 { 00522 cart_pose_goal_ = goal; 00523 cart_pose_error_.x = cart_pose_goal_.getOrigin().x() - cart_pose_actual_.getOrigin().x(); 00524 cart_pose_error_.y = cart_pose_goal_.getOrigin().y() - cart_pose_actual_.getOrigin().y(); 00525 const double dtheta = tf::getYaw(cart_pose_goal_.getRotation()) - tf::getYaw(cart_pose_actual_.getRotation()); 00526 cart_pose_error_.theta = angles::normalize_angle(dtheta); 00527 ROS_DEBUG_NAMED("cart_pose", "Cart pose error: %f %f %f",cart_pose_error_.x,cart_pose_error_.y,cart_pose_error_.theta); 00528 } 00529 00530 void CartLocalPlanner::setControlMode() 00531 { 00532 control_mode_ = REGULAR; 00533 } 00534 00535 void CartLocalPlanner::controlModeAction() 00536 { 00537 switch (control_mode_) { 00538 case REGULAR: 00539 { 00540 // Compute base twist 00541 baseTwistFromError(); 00542 00543 // Compute cart twist 00544 cartTwistFromError(); 00545 00546 // Coordinate base and cart velocities for smooth and safe action 00547 filterTwistsCombined(GLOBAL_SCALING); 00548 00549 if (robot_pose_error_.getOrigin().length() < tolerance_trans_ && current_waypoint_ < global_plan_.size()-1 && mag(cart_pose_error_) < 0.1) { 00550 current_waypoint_++; 00551 waypoint_pub_.publish(global_plan_[current_waypoint_]); 00552 } 00553 } 00554 break; 00555 default: 00556 ROS_WARN("Unrecognized control mode requested"); 00557 break; 00558 } 00559 } 00560 00561 bool CartLocalPlanner::setGoalPoses() 00562 { 00563 ros::Time now(ros::Time::now()); 00564 StampedPose robot_pose_goal; 00565 tf::poseStampedMsgToTF(global_plan_[current_waypoint_], robot_pose_goal); 00566 setRobotPoseGoal(robot_pose_goal); 00567 setCartGoalFromWaypoint((cart_range.x_max + cart_range.x_min)/2, cart_range.x_min); 00568 00569 tb_.sendTransform(tf::StampedTransform(robot_pose_goal_, now, costmap_ros_->getGlobalFrameID(), 00570 "base_target_pose")); 00571 tb_.sendTransform(tf::StampedTransform(cart_pose_goal_, now, "base_footprint", "cart_target_unfiltered")); 00572 00573 StampedPose cart_pose_goal = cart_pose_goal_; 00574 00575 // Filter cart pose 00576 if (cart_pose_goal.getOrigin().x() < cart_range.x_min) 00577 cart_pose_goal.getOrigin().setX(cart_range.x_min); 00578 if (cart_pose_goal.getOrigin().x() > cart_range.x_max) 00579 cart_pose_goal.getOrigin().setX(cart_range.x_max); 00580 00581 if (cart_pose_goal.getOrigin().y() < cart_range.y_min) 00582 cart_pose_goal.getOrigin().setY(cart_range.y_min); 00583 if (cart_pose_goal.getOrigin().y() > cart_range.y_max) 00584 cart_pose_goal.getOrigin().setY(cart_range.y_max); 00585 00586 double yaw, pitch, roll; 00587 cart_pose_goal.getBasis().getEulerYPR(yaw, pitch, roll); 00588 if (yaw < cart_range.t_min) 00589 cart_pose_goal.getBasis().setEulerYPR(cart_range.t_min, pitch, roll); 00590 if (yaw > cart_range.t_max) 00591 cart_pose_goal.getBasis().setEulerYPR(cart_range.t_max, pitch, roll); 00592 00593 // Update the cart pose and the error 00594 setCartPoseGoal(cart_pose_goal); 00595 00596 tb_.sendTransform(tf::StampedTransform(cart_pose_goal_, now, "base_footprint", "cart_target_pose")); 00597 00598 // We can drift away from the plan when teleop commands are present 00599 if (robot_pose_error_.getOrigin().length() > 0.5 || robot_pose_error_.getRotation().getAngle() > 0.5) { 00600 ROS_INFO_THROTTLE(0.5, "Robot pose error %.2fm / %.2f rads. Robot too far away from goal, must replan", 00601 robot_pose_error_.getOrigin().length(), robot_pose_error_.getRotation().getAngle()); 00602 return false; 00603 } 00604 00605 return true; 00606 } 00607 00608 void CartLocalPlanner::filterTwistsCombined(int filter_options) 00609 { 00611 if (filter_options & GLOBAL_SCALING) { 00612 double xv_scale = fabs(twist_base_->linear.x) / twist_base_max_.linear.x; 00613 double yv_scale = fabs(twist_base_->linear.y) / twist_base_max_.linear.y; 00614 double tv_scale = fabs(twist_base_->angular.z) / twist_base_max_.angular.z; 00615 00616 double base_scaling_factor = std::max(xv_scale, std::max(yv_scale, tv_scale)); 00617 00618 double xv_cart_scale = fabs(twist_cart_.twist.linear.x) / twist_cart_max_.linear.x; 00619 double yv_cart_scale = fabs(twist_cart_.twist.linear.y) / twist_cart_max_.linear.y; 00620 double tv_cart_scale = fabs(twist_cart_.twist.angular.z)/ twist_cart_max_.angular.z; 00621 00622 double cart_scaling_factor = std::max(xv_cart_scale, std::max(yv_cart_scale, tv_cart_scale)); 00623 double scaling_factor = std::max(base_scaling_factor, cart_scaling_factor); 00624 00625 // Scales both twists together such that none are above their limits 00626 if (scaling_factor > 1.0) { 00627 double scale_mult = 1.0 / scaling_factor; 00628 scaleTwist2D(*twist_base_, scale_mult); 00629 scaleTwist2D(twist_cart_.twist, scale_mult); 00630 ROS_DEBUG_STREAM_COND_NAMED (debug_print_, "twist_filter", 00631 "Scaling, to keep things in range, cart and base twists by " << scale_mult); 00632 } 00633 } 00634 00636 if (filter_options & CART_ERR_SCALING) { 00637 const double scaling_factor = pow(M_E, -50.0 * pow(mag(twist_cart_.twist), 2)); // falls off around .1 00638 scaleTwist2D(*twist_base_, scaling_factor); 00639 ROS_DEBUG_STREAM_COND_NAMED (debug_print_, "twist_filter", 00640 "Scaling, based on cart error, base velocity by a factor of " << scaling_factor); 00641 } 00642 } 00643 00644 00646 gm::Twist scaleTwist (const gm::Twist& twist, const double scaling_factor) 00647 { 00648 gm::Twist result; 00649 result.linear.x = twist.linear.x*scaling_factor; 00650 result.linear.y = twist.linear.y*scaling_factor; 00651 result.angular.z = twist.angular.z*scaling_factor; 00652 return result; 00653 } 00654 00655 bool CartLocalPlanner::checkTwists() 00656 { 00657 double base_footprint_cost, cart_footprint_cost; 00658 optional<double> cost_of_valid_twist; // has value iff last twist found is collision-free 00659 00660 for (double scaling_factor=1.0; scaling_factor > 0.7 && !cost_of_valid_twist; scaling_factor *= 0.9) { 00661 const gm::Twist scaled_base_twist = scaleTwist(*twist_base_, scaling_factor); 00662 const gm::Twist scaled_cart_twist = scaleTwist(twist_cart_.twist, scaling_factor); 00663 const gm::Twist base_twist_at_cart = mapBaseTwistToCart(scaled_base_twist); 00664 const gm::Twist net_twist = base_twist_at_cart + scaled_cart_twist; 00665 ROS_DEBUG_STREAM_COND_NAMED (debug_print_, "check_twists", "Checking twists scaled by " << scaling_factor << 00666 ": " << base_twist_at_cart << ", " << net_twist); 00667 00668 // Check base twist for collisions on the base footprint 00669 base_footprint_cost=robot_collision_checker_.checkTwist(scaled_base_twist, num_traj_steps_, dt_, true, true); 00670 // Check the base+cart twists for collisions on the cart footprint 00671 cart_footprint_cost=cart_collision_checker_.checkTwist(net_twist, num_traj_steps_, dt_, true, false); 00672 00673 if ((base_footprint_cost >= 0) && (cart_footprint_cost >= 0)) 00674 cost_of_valid_twist = max(base_footprint_cost, cart_footprint_cost); 00675 } 00676 00677 // We found a collision-free twist 00678 if (cost_of_valid_twist) { 00679 ROS_DEBUG_COND_NAMED (debug_print_, "check_twists", "Found collision-free twist with cost %.2f", 00680 *cost_of_valid_twist); 00681 return true; 00682 } 00683 else { 00684 ROS_DEBUG_COND_NAMED (debug_print_, "check_twists", "No valid twist found"); 00685 return false; 00686 } 00687 } 00688 00689 bool CartLocalPlanner::checkTwistsMonotonic() 00690 { 00691 double base_footprint_cost, cart_footprint_cost; 00692 optional<double> cost_of_valid_twist; // has value iff last twist found is collision-free 00693 robot_collision_checker_.clearFootprint(true); 00694 cart_collision_checker_.clearFootprint(false); 00695 gm::Twist scaled_base_twist = scaleTwist(*twist_base_, 1.0); 00696 gm::Twist scaled_cart_twist = scaleTwist(twist_cart_.twist, 1.0); 00697 gm::Twist base_twist_at_cart = mapBaseTwistToCart(scaled_base_twist); 00698 gm::Twist net_twist = base_twist_at_cart + scaled_cart_twist; 00699 for (double scaling_factor=1.0; scaling_factor > 0.7 && !cost_of_valid_twist; scaling_factor *= 0.9) { 00700 scaled_base_twist = scaleTwist(*twist_base_, scaling_factor); 00701 scaled_cart_twist = scaleTwist(twist_cart_.twist, scaling_factor); 00702 base_twist_at_cart = mapBaseTwistToCart(scaled_base_twist); 00703 net_twist = base_twist_at_cart + scaled_cart_twist; 00704 ROS_DEBUG_STREAM_COND_NAMED (debug_print_, "check_twists", "Checking twists scaled by " << scaling_factor << 00705 ": " << base_twist_at_cart << ", " << net_twist); 00706 00707 // Check base twist for collisions on the base footprint 00708 base_footprint_cost=robot_collision_checker_.checkTwistMonotonic(scaled_base_twist, num_traj_steps_, dt_, false, false); 00709 // Check the base+cart twists for collisions on the cart footprint 00710 cart_footprint_cost=cart_collision_checker_.checkTwistMonotonic(net_twist, num_traj_steps_, dt_, false, false); 00711 00712 if ((base_footprint_cost >= 0) && (cart_footprint_cost >= 0)) 00713 cost_of_valid_twist = max(base_footprint_cost, cart_footprint_cost); 00714 } 00715 00716 // We found a collision-free twist 00717 if (cost_of_valid_twist) { 00718 ROS_DEBUG_COND_NAMED (debug_print_, "check_twists", "Found collision-free twist with cost %.2f", 00719 *cost_of_valid_twist); 00720 twist_cart_.twist = scaled_cart_twist; 00721 *twist_base_ = scaled_base_twist; 00722 return true; 00723 } 00724 else { 00725 ROS_DEBUG_COND_NAMED (debug_print_, "check_twists", "No valid twist found"); 00726 return false; 00727 } 00728 } 00729 00730 00731 int CartLocalPlanner::setCartGoalFromWaypoint(double min_dist, double min_x_component) 00732 { 00733 StampedPose goal; 00734 if(subscribe_sbpl_plan_) 00735 { 00736 boost::optional<cart_pushing_msgs::RobotCartPath> sbpl_plan = sbpl_subscriber_->lookupPlan(original_global_plan_); 00737 if(sbpl_plan) 00738 { 00739 btTransform goal_transform; 00740 tf::poseMsgToTF(sbpl_plan->path[current_waypoint_].cart_pose,goal_transform);//assume this is in robot frame of reference 00741 ROS_DEBUG_NAMED("cart_pose", "Cart pose: %f %f %f, %f %f %f %f", 00742 sbpl_plan->path[current_waypoint_].cart_pose.position.x, 00743 sbpl_plan->path[current_waypoint_].cart_pose.position.y, 00744 sbpl_plan->path[current_waypoint_].cart_pose.position.z, 00745 sbpl_plan->path[current_waypoint_].cart_pose.orientation.x, 00746 sbpl_plan->path[current_waypoint_].cart_pose.orientation.y, 00747 sbpl_plan->path[current_waypoint_].cart_pose.orientation.z, 00748 sbpl_plan->path[current_waypoint_].cart_pose.orientation.w); 00749 goal.setRotation(goal_transform.getRotation()); 00750 goal.setOrigin(goal_transform.getOrigin()); 00751 setCartPoseGoal(goal); 00752 return current_waypoint_; 00753 } 00754 else 00755 { 00756 // DO NOTHING 00757 ROS_ERROR("Could not find sbpl plan"); 00758 return 0; 00759 } 00760 } 00761 // find the future waypoint that provides the closest relpose to ideal cart distance 00762 btTransform tr, rel_tr; 00763 for (uint i = current_waypoint_; i < global_plan_.size(); ++i) { 00764 tf::poseMsgToTF(global_plan_[i].pose, tr); 00765 rel_tr = robot_pose_actual_.inverseTimes(tr); 00766 if (rel_tr.getOrigin().length() > min_dist && rel_tr.getOrigin().x() 00767 > min_x_component) { 00768 goal.setRotation(rel_tr.getRotation()); 00769 goal.setOrigin(rel_tr.getOrigin()); 00770 setCartPoseGoal(goal); 00771 return i; 00772 } 00773 } 00774 // If we reached the end without satisfying the goal, set to relative pose of robot to last waypoint w/ standard offset 00775 goal.setRotation(rel_tr.getRotation()); 00776 goal.setOrigin(btVector3(min_dist, 0, 0)); 00777 setCartPoseGoal(goal); 00778 return 0; 00779 } 00780 00781 00782 double CartLocalPlanner::baseTwistFromError() 00783 { 00784 twist_base_->linear.x = robot_pose_error_.getOrigin().x() * K_trans_base_; 00785 twist_base_->linear.y = robot_pose_error_.getOrigin().y() * K_trans_base_; 00786 twist_base_->angular.z = tf::getYaw(robot_pose_error_.getRotation()) * K_rot_base_; 00787 00788 return mag(*twist_base_); 00789 } 00790 00791 double CartLocalPlanner::cartTwistFromError() 00792 { 00793 // Use relative pose as twist orientation errors 00794 twist_cart_.twist.linear.x = cart_pose_error_.x * K_trans_cart_; 00795 twist_cart_.twist.linear.y = cart_pose_error_.y * K_trans_cart_; 00796 twist_cart_.twist.angular.z = cart_pose_error_.theta * K_rot_cart_; 00797 twist_cart_.header.frame_id = "base_footprint"; 00798 twist_cart_.header.stamp = ros::Time::now(); 00799 00800 return mag(twist_cart_.twist); 00801 } 00802 00803 void CartLocalPlanner::setYawFromVec(const tf::Pose& pose1, const tf::Pose& pose2, tf::Pose& res) 00804 { 00805 res = pose1; 00806 // Extracts yaw using relative 00807 const btVector3 v = pose1.getOrigin() - pose2.getOrigin(); 00808 double yaw = 0; 00809 00810 const double waypoint_dist = v.length(); 00811 if (waypoint_dist < 0.01) { // 0.01 00812 // if points are super close by, just leave at pose1 yaw 00813 ROS_WARN("WAYPOINTS TOO CLOSE - HOLDING YAW FIXED"); 00814 yaw = tf::getYaw(pose1.getRotation()); 00815 } 00816 else { 00817 // otherwise set using v 00818 yaw = atan2(v.getY(), v.getX()); 00819 } 00820 00821 btQuaternion q; 00822 q.setRPY(0, 0, yaw); 00823 res.setRotation(q); 00824 } 00825 00826 bool CartLocalPlanner::setPlan( 00827 const std::vector<gm::PoseStamped>& global_plan) { 00828 current_waypoint_ = 0; 00829 goal_reached_time_ = ros::Time::now(); 00830 original_global_plan_ = global_plan; 00831 if (!transformGlobalPlan(*tf_, global_plan, *costmap_ros_, 00832 costmap_ros_->getGlobalFrameID(), global_plan_)) { 00833 ROS_ERROR("Could not transform the global plan to the frame of the controller"); 00834 return false; 00835 } 00836 00837 waypoint_pub_.publish(global_plan_[current_waypoint_]); 00838 return true; 00839 } 00840 00841 bool CartLocalPlanner::transformGlobalPlan(const tf::TransformListener& tf, 00842 const std::vector<gm::PoseStamped>& global_plan, 00843 const costmap_2d::Costmap2DROS& costmap, 00844 const std::string& global_frame, 00845 std::vector<gm::PoseStamped>& transformed_plan) { 00846 if (!global_plan.size() > 0) { 00847 ROS_ERROR("Received plan with zero length"); 00848 return false; 00849 } 00850 const gm::PoseStamped& pose = global_plan[0]; 00851 transformed_plan.clear(); 00852 00853 tf::StampedTransform transform; 00854 00855 try { 00856 tf.lookupTransform(global_frame, ros::Time(), 00857 pose.header.frame_id, pose.header.stamp, 00858 pose.header.frame_id, transform); 00859 } 00860 catch (const tf::TransformException& ex) { 00861 ROS_ERROR ("TF Exception while transforming global plan: %s", ex.what()); 00862 return false; 00863 } 00864 00865 tf::Stamped<tf::Pose> tf_pose; 00866 gm::PoseStamped newer_pose; 00867 //now we'll transform until points are outside of our distance threshold 00868 // (jon): what threshold? It looks like we're doing all of them 00869 // (jon): anyway, i'm gonna use this as an opportunity to do some path smoothing 00870 /* [logic being, since we're not taking SBPL's word for it on orientation, having 00871 waypoints that differ only in yaw are kinda pointless]*/ 00872 00873 tf::Stamped<tf::Pose> last_pose; 00874 // Do the first one alone 00875 poseStampedMsgToTF(pose, last_pose); 00876 last_pose.setData(transform * last_pose); 00877 last_pose.stamp_ = transform.stamp_; 00878 last_pose.frame_id_ = global_frame; 00879 poseStampedTFToMsg(last_pose, newer_pose); 00880 transformed_plan.push_back(newer_pose); 00881 00882 // now loop over the rest, and add them if they pass a translation threshold 00883 int pts_skipped = 0; 00884 for (unsigned int i = 1; i < global_plan.size(); ++i) { 00885 poseStampedMsgToTF(global_plan[i], tf_pose); 00886 const tf::Pose tmp_pose = tf_pose.inverseTimes(last_pose); 00887 const double dist = tmp_pose.getOrigin().length(); 00888 if (dist > SBPL_DTHRESH) { 00889 // Get transformed plan pose directly from global plan 00890 tf_pose.setData(transform * tf_pose); 00891 if(!subscribe_sbpl_plan_) 00892 // If requested, don't trust SBPL yaw param - compute yaw from vector difference from last pose 00893 setYawFromVec(tf_pose, last_pose, tf_pose); 00894 00895 //tf_pose.setData(transform * tf_pose); 00896 tf_pose.stamp_ = transform.stamp_; 00897 tf_pose.frame_id_ = global_frame; 00898 poseStampedTFToMsg(tf_pose, newer_pose); 00899 transformed_plan.push_back(newer_pose); 00900 00901 } 00902 else { 00903 pts_skipped++; 00904 } 00905 last_pose = tf_pose; 00906 } 00907 ROS_DEBUG_COND_NAMED(debug_print_, "transform_global_plan", "added %zu points (%d skipped)", 00908 global_plan.size()-pts_skipped, pts_skipped); 00909 return true; 00910 } 00911 00912 vector<gm::Point> CartLocalPlanner::transformFootprint( 00913 const gm::PolygonStamped& poly) const { 00914 vector<gm::Point> points; 00915 BOOST_FOREACH (const gm::Point32 p, poly.polygon.points) 00916 { 00917 gm::PointStamped in, out; 00918 in.header.frame_id = poly.header.frame_id; 00919 in.header.stamp = ros::Time(); // Should actually wait 00920 in.point.x = p.x; 00921 in.point.y = p.y; 00922 in.point.z = p.z; 00923 tf_->transformPoint(costmap_ros_->getGlobalFrameID(), in, 00924 out); 00925 points.push_back(out.point); 00926 } 00927 return points; 00928 } 00929 00930 void CartLocalPlanner::freeze() 00931 { 00932 ROS_WARN_THROTTLE(3.0, "Robot is in frozen state in cart local planner"); 00933 gm::Twist empty_twist; 00934 twist_base_->linear.x = empty_twist.linear.x; 00935 twist_base_->linear.y = empty_twist.linear.y; 00936 twist_base_->angular.z = empty_twist.angular.z; 00937 twist_cart_.twist = empty_twist; 00938 twist_cart_.header.stamp = ros::Time::now(); 00939 00940 cart_twist_pub_.publish(twist_cart_); 00941 } 00942 00943 void CartLocalPlanner::scaleTwist2D(gm::Twist &t, double scale) 00944 { 00945 t.linear.x *= scale; 00946 t.linear.y *= scale; 00947 t.angular.z *= scale; 00948 } 00949 00950 gm::Twist CartLocalPlanner::mapBaseTwistToCart(const gm::Twist &twist_base) 00951 { 00952 KDL::Frame cart_frame; 00953 tf::PoseTFToKDL(cart_pose_actual_.inverse(), cart_frame); 00954 00955 KDL::Twist twist_at_base; 00956 tf::TwistMsgToKDL(twist_base, twist_at_base); 00957 00958 KDL::Twist twist_at_cart = cart_frame * twist_at_base; 00959 00960 gm::Twist t; 00961 tf::TwistKDLToMsg(twist_at_cart, t); 00962 return t; 00963 } 00964 00965 void CartLocalPlanner::publishDebugPose(gm::Pose &p) { 00966 gm::Pose2D msg = gm::Pose2D(); 00967 msg.x = p.position.x; 00968 msg.y = p.position.y; 00969 msg.theta = tf::getYaw(btQuaternion(p.orientation.x, p.orientation.y, 00970 p.orientation.z, p.orientation.w)); 00971 pose2D_pub_.publish(msg); 00972 } 00973 00974 void CartLocalPlanner::publishDebugTwist(gm::Twist &t) { 00975 gm::Pose2D msg = gm::Pose2D(); 00976 msg.x = t.linear.x; 00977 msg.y = t.linear.y; 00978 msg.theta = t.angular.z; 00979 pose2D_pub_.publish(msg); 00980 } 00981 00982 void CartLocalPlanner::publishDebugPose(tf::Pose &p) { 00983 gm::Pose2D msg = gm::Pose2D(); 00984 msg.x = p.getOrigin().x(); 00985 msg.y = p.getOrigin().y(); 00986 msg.theta = tf::getYaw(p.getRotation()); 00987 pose2D_pub_.publish(msg); 00988 } 00989 00990 void CartLocalPlanner::odomCallback(const nav_msgs::Odometry::ConstPtr& msg) { 00991 //we assume that the odometry is published in the frame of the base 00992 boost::mutex::scoped_lock lock(odom_lock_); 00993 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x; 00994 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y; 00995 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z; 00996 } 00997 00998 void CartLocalPlanner::invalidPoseCallback (const std_msgs::Empty::ConstPtr& msg) 00999 { 01000 boost::mutex::scoped_lock lock(invalid_pose_mutex_); 01001 last_invalid_pose_time_ = ros::Time::now(); 01002 } 01003 01004 bool CartLocalPlanner::isGoalReached() { 01005 if (!initialized_) { 01006 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); 01007 return false; 01008 } 01009 01010 bool quick_check = current_waypoint_ == global_plan_.size() - 1; 01011 if (!quick_check) 01012 return false; 01013 else { 01014 ROS_DEBUG_COND_NAMED(debug_print_, "is_goal_reached", "Quick check passed, checking actual goal distance"); 01015 //copy over the odometry information 01016 nav_msgs::Odometry base_odom; 01017 { 01018 boost::recursive_mutex::scoped_lock(odom_lock_); 01019 base_odom = base_odom_; 01020 } 01021 01022 bool val = base_local_planner::isGoalReached(*tf_, global_plan_, 01023 *costmap_ros_, costmap_ros_->getGlobalFrameID(), base_odom, 01024 rot_stopped_velocity_, trans_stopped_velocity_, 01025 tolerance_trans_+0.1, tolerance_rot_+0.1); 01026 if (val) { 01027 ROS_DEBUG_COND_NAMED(debug_print_, "is_goal_reached", "Agreed with quick check... GOAL REACHED!"); 01028 freeze(); 01029 } 01030 else 01031 ROS_DEBUG("Tracking to last waypoint, should be at goal soon."); 01032 01033 return val; 01034 } 01035 } 01036 01037 }; // namespace cart_local_planner