$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2009, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of Willow Garage, Inc. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * Author: Eitan Marder-Eppstein 00036 *********************************************************************/ 00037 #include <pluginlib/class_list_macros.h> 00038 00039 #include <dwa_local_planner/dwa_planner_ros.h> 00040 #include <base_local_planner/goal_functions.h> 00041 00042 //register this planner as a BaseLocalPlanner plugin 00043 PLUGINLIB_DECLARE_CLASS(dwa_local_planner, DWAPlannerROS, dwa_local_planner::DWAPlannerROS, nav_core::BaseLocalPlanner) 00044 00045 namespace dwa_local_planner { 00046 void DWAPlannerROS::initialize(std::string name, tf::TransformListener* tf, 00047 costmap_2d::Costmap2DROS* costmap_ros){ 00048 if(!initialized_){ 00049 tf_ = tf; 00050 rotating_to_goal_ = false; 00051 00052 costmap_ros_ = costmap_ros; 00053 00054 ros::NodeHandle pn("~/" + name); 00055 00056 g_plan_pub_ = pn.advertise<nav_msgs::Path>("global_plan", 1); 00057 l_plan_pub_ = pn.advertise<nav_msgs::Path>("local_plan", 1); 00058 00059 pn.param("prune_plan", prune_plan_, true); 00060 00061 pn.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05); 00062 pn.param("xy_goal_tolerance", xy_goal_tolerance_, 0.1); 00063 00064 pn.param("rot_stopped_vel", rot_stopped_vel_, 1e-2); 00065 pn.param("trans_stopped_vel", trans_stopped_vel_, 1e-2); 00066 00067 pn.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false); 00068 00069 //to get odometry information, we need to get a handle to the topic in the global namespace 00070 ros::NodeHandle gn; 00071 odom_sub_ = gn.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&DWAPlannerROS::odomCallback, this, _1)); 00072 00073 pn.param("max_rot_vel", max_vel_th_, 1.0); 00074 min_vel_th_ = -1.0 * max_vel_th_; 00075 00076 pn.param("min_rot_vel", min_rot_vel_, 0.4); 00077 00078 //create the actual planner that we'll use.. it'll configure itself from the parameter server 00079 dp_ = boost::shared_ptr<DWAPlanner>(new DWAPlanner(name, costmap_ros_)); 00080 00081 initialized_ = true; 00082 } 00083 else{ 00084 ROS_WARN("This planner has already been initialized, doing nothing."); 00085 } 00086 } 00087 00088 void DWAPlannerROS::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){ 00089 //we assume that the odometry is published in the frame of the base 00090 boost::mutex::scoped_lock lock(odom_mutex_); 00091 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x; 00092 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y; 00093 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z; 00094 ROS_DEBUG_NAMED("dwa_local_planner", "In the odometry callback with velocity values: (%.2f, %.2f, %.2f)", 00095 base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z); 00096 } 00097 00098 bool DWAPlannerROS::stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, geometry_msgs::Twist& cmd_vel){ 00099 Eigen::Vector3f acc_lim = dp_->getAccLimits(); 00100 //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible 00101 //but we'll use a tenth of a second to be consistent with the implementation of the local planner. 00102 double vx = sign(robot_vel.getOrigin().x()) * std::max(0.0, (fabs(robot_vel.getOrigin().x()) - acc_lim[0] * dp_->getSimPeriod())); 00103 double vy = sign(robot_vel.getOrigin().y()) * std::max(0.0, (fabs(robot_vel.getOrigin().y()) - acc_lim[1] * dp_->getSimPeriod())); 00104 00105 double vel_yaw = tf::getYaw(robot_vel.getRotation()); 00106 double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim[2] * dp_->getSimPeriod())); 00107 00108 //we do want to check whether or not the command is valid 00109 double yaw = tf::getYaw(global_pose.getRotation()); 00110 bool valid_cmd = dp_->checkTrajectory(Eigen::Vector3f(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw), 00111 Eigen::Vector3f(vx, vy, vth)); 00112 00113 //if we have a valid command, we'll pass it on, otherwise we'll command all zeros 00114 if(valid_cmd){ 00115 ROS_DEBUG_NAMED("dwa_local_planner", "Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth); 00116 cmd_vel.linear.x = vx; 00117 cmd_vel.linear.y = vy; 00118 cmd_vel.angular.z = vth; 00119 return true; 00120 } 00121 00122 cmd_vel.linear.x = 0.0; 00123 cmd_vel.linear.y = 0.0; 00124 cmd_vel.angular.z = 0.0; 00125 return false; 00126 } 00127 00128 bool DWAPlannerROS::rotateToGoal(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel){ 00129 Eigen::Vector3f acc_lim = dp_->getAccLimits(); 00130 double yaw = tf::getYaw(global_pose.getRotation()); 00131 double vel_yaw = tf::getYaw(robot_vel.getRotation()); 00132 cmd_vel.linear.x = 0; 00133 cmd_vel.linear.y = 0; 00134 double ang_diff = angles::shortest_angular_distance(yaw, goal_th); 00135 00136 double v_theta_samp = ang_diff > 0.0 ? std::min(max_vel_th_, 00137 std::max(min_rot_vel_, ang_diff)) : std::max(min_vel_th_, 00138 std::min(-1.0 * min_rot_vel_, ang_diff)); 00139 00140 //take the acceleration limits of the robot into account 00141 double max_acc_vel = fabs(vel_yaw) + acc_lim[2] * dp_->getSimPeriod(); 00142 double min_acc_vel = fabs(vel_yaw) - acc_lim[2] * dp_->getSimPeriod(); 00143 00144 v_theta_samp = sign(v_theta_samp) * std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel); 00145 00146 //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits 00147 double max_speed_to_stop = sqrt(2 * acc_lim[2] * fabs(ang_diff)); 00148 00149 v_theta_samp = sign(v_theta_samp) * std::min(max_speed_to_stop, fabs(v_theta_samp)); 00150 00151 if(fabs(v_theta_samp) < min_rot_vel_) 00152 v_theta_samp = sign(v_theta_samp) * min_rot_vel_; 00153 00154 //we still want to lay down the footprint of the robot and check if the action is legal 00155 bool valid_cmd = dp_->checkTrajectory(Eigen::Vector3f(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw), 00156 Eigen::Vector3f( 0.0, 0.0, v_theta_samp)); 00157 00158 ROS_DEBUG_NAMED("dwa_local_planner", "Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd); 00159 00160 if(valid_cmd){ 00161 cmd_vel.angular.z = v_theta_samp; 00162 return true; 00163 } 00164 00165 cmd_vel.angular.z = 0.0; 00166 return false; 00167 00168 } 00169 00170 bool DWAPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){ 00171 if(!initialized_){ 00172 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); 00173 return false; 00174 } 00175 00176 std::vector<geometry_msgs::PoseStamped> local_plan; 00177 tf::Stamped<tf::Pose> global_pose; 00178 if(!costmap_ros_->getRobotPose(global_pose)) 00179 return false; 00180 00181 costmap_2d::Costmap2D costmap; 00182 costmap_ros_->getCostmapCopy(costmap); 00183 std::vector<geometry_msgs::PoseStamped> transformed_plan; 00184 //get the global plan in our frame 00185 if(!base_local_planner::transformGlobalPlan(*tf_, global_plan_, *costmap_ros_, costmap_ros_->getGlobalFrameID(), transformed_plan)){ 00186 ROS_WARN("Could not transform the global plan to the frame of the controller"); 00187 return false; 00188 } 00189 00190 //now we'll prune the plan based on the position of the robot 00191 if(prune_plan_) 00192 base_local_planner::prunePlan(global_pose, transformed_plan, global_plan_); 00193 00194 00195 //we also want to clear the robot footprint from the costmap we're using 00196 costmap_ros_->clearRobotFootprint(); 00197 00198 // Set current velocities from odometry 00199 geometry_msgs::Twist global_vel; 00200 00201 { 00202 boost::mutex::scoped_lock lock(odom_mutex_); 00203 global_vel.linear.x = base_odom_.twist.twist.linear.x; 00204 global_vel.linear.y = base_odom_.twist.twist.linear.y; 00205 global_vel.angular.z = base_odom_.twist.twist.angular.z; 00206 } 00207 00208 tf::Stamped<tf::Pose> drive_cmds; 00209 drive_cmds.frame_id_ = costmap_ros_->getBaseFrameID(); 00210 00211 tf::Stamped<tf::Pose> robot_vel; 00212 robot_vel.setData(btTransform(tf::createQuaternionFromYaw(global_vel.angular.z), btVector3(global_vel.linear.x, global_vel.linear.y, 0))); 00213 robot_vel.frame_id_ = costmap_ros_->getBaseFrameID(); 00214 robot_vel.stamp_ = ros::Time(); 00215 00216 /* For timing uncomment 00217 struct timeval start, end; 00218 double start_t, end_t, t_diff; 00219 gettimeofday(&start, NULL); 00220 */ 00221 00222 //if the global plan passed in is empty... we won't do anything 00223 if(transformed_plan.empty()) 00224 return false; 00225 00226 tf::Stamped<tf::Pose> goal_point; 00227 tf::poseStampedMsgToTF(transformed_plan.back(), goal_point); 00228 //we assume the global goal is the last point in the global plan 00229 double goal_x = goal_point.getOrigin().getX(); 00230 double goal_y = goal_point.getOrigin().getY(); 00231 00232 double yaw = tf::getYaw(goal_point.getRotation()); 00233 00234 double goal_th = yaw; 00235 00236 //check to see if we've reached the goal position 00237 if(base_local_planner::goalPositionReached(global_pose, goal_x, goal_y, xy_goal_tolerance_) || xy_tolerance_latch_){ 00238 //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll 00239 //just rotate in place 00240 if(latch_xy_goal_tolerance_) 00241 xy_tolerance_latch_ = true; 00242 00243 //check to see if the goal orientation has been reached 00244 if(base_local_planner::goalOrientationReached(global_pose, goal_th, yaw_goal_tolerance_)){ 00245 //set the velocity command to zero 00246 cmd_vel.linear.x = 0.0; 00247 cmd_vel.linear.y = 0.0; 00248 cmd_vel.angular.z = 0.0; 00249 rotating_to_goal_ = false; 00250 xy_tolerance_latch_ = false; 00251 } 00252 else { 00253 //we need to call the next two lines to make sure that the dwa 00254 //planner updates its path distance and goal distance grids 00255 dp_->updatePlan(transformed_plan); 00256 base_local_planner::Trajectory path = dp_->findBestPath(global_pose, robot_vel, drive_cmds); 00257 00258 //copy over the odometry information 00259 nav_msgs::Odometry base_odom; 00260 { 00261 boost::mutex::scoped_lock lock(odom_mutex_); 00262 base_odom = base_odom_; 00263 } 00264 00265 //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot 00266 if(!rotating_to_goal_ && !base_local_planner::stopped(base_odom, rot_stopped_vel_, trans_stopped_vel_)){ 00267 if(!stopWithAccLimits(global_pose, robot_vel, cmd_vel)) 00268 return false; 00269 } 00270 //if we're stopped... then we want to rotate to goal 00271 else{ 00272 //set this so that we know its OK to be moving 00273 rotating_to_goal_ = true; 00274 if(!rotateToGoal(global_pose, robot_vel, goal_th, cmd_vel)) 00275 return false; 00276 } 00277 } 00278 00279 //publish an empty plan because we've reached our goal position 00280 base_local_planner::publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0); 00281 base_local_planner::publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0); 00282 00283 //we don't actually want to run the controller when we're just rotating to goal 00284 return true; 00285 } 00286 00287 ROS_DEBUG_NAMED("dwa_local_planner", "Received a transformed plan with %zu points.", transformed_plan.size()); 00288 dp_->updatePlan(transformed_plan); 00289 00290 //compute what trajectory to drive along 00291 base_local_planner::Trajectory path = dp_->findBestPath(global_pose, robot_vel, drive_cmds); 00292 //ROS_ERROR("Best: %.2f, %.2f, %.2f, %.2f", path.xv_, path.yv_, path.thetav_, path.cost_); 00293 00294 /* For timing uncomment 00295 gettimeofday(&end, NULL); 00296 start_t = start.tv_sec + double(start.tv_usec) / 1e6; 00297 end_t = end.tv_sec + double(end.tv_usec) / 1e6; 00298 t_diff = end_t - start_t; 00299 ROS_INFO("Cycle time: %.9f", t_diff); 00300 */ 00301 00302 //pass along drive commands 00303 cmd_vel.linear.x = drive_cmds.getOrigin().getX(); 00304 cmd_vel.linear.y = drive_cmds.getOrigin().getY(); 00305 yaw = tf::getYaw(drive_cmds.getRotation()); 00306 00307 cmd_vel.angular.z = yaw; 00308 00309 //if we cannot move... tell someone 00310 if(path.cost_ < 0){ 00311 ROS_DEBUG_NAMED("dwa_local_planner", 00312 "The dwa local planner failed to find a valid plan. This means that the footprint of the robot was in collision for all simulated trajectories."); 00313 local_plan.clear(); 00314 base_local_planner::publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0); 00315 base_local_planner::publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0); 00316 return false; 00317 } 00318 00319 ROS_DEBUG_NAMED("dwa_local_planner", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.", 00320 cmd_vel.linear.x, cmd_vel.linear.y, yaw); 00321 00322 // Fill out the local plan 00323 for(unsigned int i = 0; i < path.getPointsSize(); ++i){ 00324 double p_x, p_y, p_th; 00325 path.getPoint(i, p_x, p_y, p_th); 00326 00327 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(), costmap_ros_->getGlobalFrameID()); 00328 geometry_msgs::PoseStamped pose; 00329 tf::poseStampedTFToMsg(p, pose); 00330 local_plan.push_back(pose); 00331 } 00332 00333 //publish information to the visualizer 00334 base_local_planner::publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0); 00335 base_local_planner::publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0); 00336 return true; 00337 } 00338 00339 bool DWAPlannerROS::isGoalReached(){ 00340 if(!initialized_){ 00341 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); 00342 return false; 00343 } 00344 00345 //copy over the odometry information 00346 nav_msgs::Odometry base_odom; 00347 { 00348 boost::mutex::scoped_lock lock(odom_mutex_); 00349 base_odom = base_odom_; 00350 } 00351 00352 return base_local_planner::isGoalReached(*tf_, global_plan_, *costmap_ros_, costmap_ros_->getGlobalFrameID(), base_odom, 00353 rot_stopped_vel_, trans_stopped_vel_, xy_goal_tolerance_, yaw_goal_tolerance_); 00354 } 00355 00356 bool DWAPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan){ 00357 if(!initialized_){ 00358 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); 00359 return false; 00360 } 00361 00362 //reset the global plan 00363 global_plan_.clear(); 00364 global_plan_ = orig_global_plan; 00365 00366 //when we get a new plan, we also want to clear any latch we may have on goal tolerances 00367 xy_tolerance_latch_ = false; 00368 00369 return true; 00370 } 00371 00372 };