dwa_planner_ros.cpp
Go to the documentation of this file.
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 
00038 #include <dwa_local_planner/dwa_planner_ros.h>
00039 
00040 #include <Eigen/Core>
00041 #include <cmath>
00042 
00043 #include <ros/console.h>
00044 
00045 #include <pluginlib/class_list_macros.h>
00046 
00047 #include <base_local_planner/goal_functions.h>
00048 #include <nav_msgs/Path.h>
00049 
00050 //register this planner as a BaseLocalPlanner plugin
00051 PLUGINLIB_EXPORT_CLASS( dwa_local_planner::DWAPlannerROS, nav_core::BaseLocalPlanner)
00052 
00053 namespace dwa_local_planner {
00054 
00055   void DWAPlannerROS::reconfigureCB(DWAPlannerConfig &config, uint32_t level) {
00056       if (setup_ && config.restore_defaults) {
00057         config = default_config_;
00058         config.restore_defaults = false;
00059       }
00060       if ( ! setup_) {
00061         default_config_ = config;
00062         setup_ = true;
00063       }
00064 
00065       // update generic local planner params
00066       base_local_planner::LocalPlannerLimits limits;
00067       limits.max_trans_vel = config.max_trans_vel;
00068       limits.min_trans_vel = config.min_trans_vel;
00069       limits.max_vel_x = config.max_vel_x;
00070       limits.min_vel_x = config.min_vel_x;
00071       limits.max_vel_y = config.max_vel_y;
00072       limits.min_vel_y = config.min_vel_y;
00073       limits.max_rot_vel = config.max_rot_vel;
00074       limits.min_rot_vel = config.min_rot_vel;
00075       limits.acc_lim_x = config.acc_lim_x;
00076       limits.acc_lim_y = config.acc_lim_y;
00077       limits.acc_lim_theta = config.acc_lim_theta;
00078       limits.acc_limit_trans = config.acc_limit_trans;
00079       limits.xy_goal_tolerance = config.xy_goal_tolerance;
00080       limits.yaw_goal_tolerance = config.yaw_goal_tolerance;
00081       limits.prune_plan = config.prune_plan;
00082       limits.trans_stopped_vel = config.trans_stopped_vel;
00083       limits.rot_stopped_vel = config.rot_stopped_vel;
00084       planner_util_.reconfigureCB(limits, config.restore_defaults);
00085 
00086       // update dwa specific configuration
00087       dp_->reconfigure(config);
00088   }
00089 
00090   DWAPlannerROS::DWAPlannerROS() : initialized_(false),
00091       odom_helper_("odom") {
00092 
00093   }
00094 
00095   void DWAPlannerROS::initialize(
00096       std::string name,
00097       tf::TransformListener* tf,
00098       costmap_2d::Costmap2DROS* costmap_ros) {
00099     if (! isInitialized()) {
00100 
00101       ros::NodeHandle private_nh("~/" + name);
00102       g_plan_pub_ = private_nh.advertise<nav_msgs::Path>("global_plan", 1);
00103       l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
00104       tf_ = tf;
00105       costmap_ros_ = costmap_ros;
00106       costmap_ros_->getRobotPose(current_pose_);
00107 
00108       // make sure to update the costmap we'll use for this cycle
00109       costmap_ros_->getCostmapCopy(costmap_);
00110 
00111       planner_util_.initialize(tf, &costmap_, costmap_ros_->getGlobalFrameID());
00112 
00113       //create the actual planner that we'll use.. it'll configure itself from the parameter server
00114       dp_ = boost::shared_ptr<DWAPlanner>(new DWAPlanner(name, &planner_util_));
00115 
00116       initialized_ = true;
00117 
00118       dsrv_ = new dynamic_reconfigure::Server<DWAPlannerConfig>(private_nh);
00119       dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = boost::bind(&DWAPlannerROS::reconfigureCB, this, _1, _2);
00120       dsrv_->setCallback(cb);
00121     }
00122     else{
00123       ROS_WARN("This planner has already been initialized, doing nothing.");
00124     }
00125   }
00126 
00127   bool DWAPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
00128     if (! isInitialized()) {
00129       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00130       return false;
00131     }
00132     //when we get a new plan, we also want to clear any latch we may have on goal tolerances
00133     latchedStopRotateController_.resetLatching();
00134 
00135     ROS_INFO("Got new plan");
00136     return dp_->setPlan(orig_global_plan);
00137   }
00138 
00139   bool DWAPlannerROS::isGoalReached() {
00140     if (! isInitialized()) {
00141       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00142       return false;
00143     }
00144     if ( ! costmap_ros_->getRobotPose(current_pose_)) {
00145       ROS_ERROR("Could not get robot pose");
00146       return false;
00147     }
00148     if(latchedStopRotateController_.isGoalReached(&planner_util_, odom_helper_, current_pose_)) {
00149       ROS_INFO("Goal reached");
00150       return true;
00151     } else {
00152       return false;
00153     }
00154   }
00155 
00156   void DWAPlannerROS::publishLocalPlan(std::vector<geometry_msgs::PoseStamped>& path) {
00157     base_local_planner::publishPlan(path, l_plan_pub_);
00158   }
00159 
00160 
00161   void DWAPlannerROS::publishGlobalPlan(std::vector<geometry_msgs::PoseStamped>& path) {
00162     base_local_planner::publishPlan(path, g_plan_pub_);
00163   }
00164 
00165   DWAPlannerROS::~DWAPlannerROS(){
00166     //make sure to clean things up
00167     delete dsrv_;
00168   }
00169 
00170 
00171 
00172   bool DWAPlannerROS::dwaComputeVelocityCommands(tf::Stamped<tf::Pose> &global_pose, geometry_msgs::Twist& cmd_vel) {
00173     // dynamic window sampling approach to get useful velocity commands
00174     if(! isInitialized()){
00175       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00176       return false;
00177     }
00178 
00179     tf::Stamped<tf::Pose> robot_vel;
00180     odom_helper_.getRobotVel(robot_vel);
00181 
00182     /* For timing uncomment
00183     struct timeval start, end;
00184     double start_t, end_t, t_diff;
00185     gettimeofday(&start, NULL);
00186     */
00187 
00188 
00189 
00190     //compute what trajectory to drive along
00191     tf::Stamped<tf::Pose> drive_cmds;
00192     drive_cmds.frame_id_ = costmap_ros_->getBaseFrameID();
00193     // call with updated footprint
00194     base_local_planner::Trajectory path = dp_->findBestPath(global_pose, robot_vel, drive_cmds, costmap_ros_->getRobotFootprint());
00195     //ROS_ERROR("Best: %.2f, %.2f, %.2f, %.2f", path.xv_, path.yv_, path.thetav_, path.cost_);
00196 
00197     /* For timing uncomment
00198     gettimeofday(&end, NULL);
00199     start_t = start.tv_sec + double(start.tv_usec) / 1e6;
00200     end_t = end.tv_sec + double(end.tv_usec) / 1e6;
00201     t_diff = end_t - start_t;
00202     ROS_INFO("Cycle time: %.9f", t_diff);
00203     */
00204 
00205     //pass along drive commands
00206     cmd_vel.linear.x = drive_cmds.getOrigin().getX();
00207     cmd_vel.linear.y = drive_cmds.getOrigin().getY();
00208     cmd_vel.angular.z = tf::getYaw(drive_cmds.getRotation());
00209 
00210     //if we cannot move... tell someone
00211     std::vector<geometry_msgs::PoseStamped> local_plan;
00212     if(path.cost_ < 0) {
00213       ROS_DEBUG_NAMED("dwa_local_planner",
00214           "The dwa local planner failed to find a valid plan, cost functions discarded all candidates. This can mean there is an obstacle too close to the robot.");
00215       local_plan.clear();
00216       publishLocalPlan(local_plan);
00217       return false;
00218     }
00219 
00220     ROS_DEBUG_NAMED("dwa_local_planner", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.", 
00221                     cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
00222 
00223     // Fill out the local plan
00224     for(unsigned int i = 0; i < path.getPointsSize(); ++i) {
00225       double p_x, p_y, p_th;
00226       path.getPoint(i, p_x, p_y, p_th);
00227 
00228       tf::Stamped<tf::Pose> p =
00229                   tf::Stamped<tf::Pose>(tf::Pose(
00230                                   tf::createQuaternionFromYaw(p_th),
00231                                   tf::Point(p_x, p_y, 0.0)),
00232                                   ros::Time::now(),
00233                                   costmap_ros_->getGlobalFrameID());
00234       geometry_msgs::PoseStamped pose;
00235       tf::poseStampedTFToMsg(p, pose);
00236       local_plan.push_back(pose);
00237     }
00238 
00239     //publish information to the visualizer
00240 
00241     publishLocalPlan(local_plan);
00242     return true;
00243   }
00244 
00245 
00246 
00247 
00248   bool DWAPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) {
00249     // dispatches to either dwa sampling control or stop and rotate control, depending on whether we have been close enough to goal
00250     if ( ! costmap_ros_->getRobotPose(current_pose_)) {
00251       ROS_ERROR("Could not get robot pose");
00252       return false;
00253     }
00254     std::vector<geometry_msgs::PoseStamped> transformed_plan;
00255     if ( ! planner_util_.getLocalPlan(current_pose_, transformed_plan)) {
00256       ROS_ERROR("Could not get local plan");
00257       return false;
00258     }
00259 
00260     //if the global plan passed in is empty... we won't do anything
00261     if(transformed_plan.empty()) {
00262       ROS_WARN_NAMED("dwa_local_planner", "Received an empty transformed plan.");
00263       return false;
00264     }
00265     ROS_DEBUG_NAMED("dwa_local_planner", "Received a transformed plan with %zu points.", transformed_plan.size());
00266 
00267     //we want to clear the robot footprint from the costmap we're using
00268     costmap_ros_->clearRobotFootprint();
00269 
00270     // make sure to update the costmap we'll use for this cycle
00271     costmap_ros_->getCostmapCopy(costmap_);
00272 
00273     // update plan in dwa_planner even if we just stop and rotate, to allow checkTrajectory
00274     dp_->updatePlanAndLocalCosts(current_pose_, transformed_plan);
00275 
00276     if (latchedStopRotateController_.isPositionReached(&planner_util_, current_pose_)) {
00277       //publish an empty plan because we've reached our goal position
00278       std::vector<geometry_msgs::PoseStamped> local_plan;
00279       std::vector<geometry_msgs::PoseStamped> transformed_plan;
00280       publishGlobalPlan(transformed_plan);
00281       publishLocalPlan(local_plan);
00282       base_local_planner::LocalPlannerLimits limits = planner_util_.getCurrentLimits();
00283       return latchedStopRotateController_.computeVelocityCommandsStopRotate(
00284           cmd_vel,
00285           limits.getAccLimits(),
00286           dp_->getSimPeriod(),
00287           &planner_util_,
00288           odom_helper_,
00289           current_pose_,
00290           boost::bind(&DWAPlanner::checkTrajectory, dp_, _1, _2, _3));
00291     } else {
00292       bool isOk = dwaComputeVelocityCommands(current_pose_, cmd_vel);
00293       if (isOk) {
00294         publishGlobalPlan(transformed_plan);
00295       } else {
00296         ROS_WARN_NAMED("dwa_local_planner", "DWA planner failed to produce path.");
00297         std::vector<geometry_msgs::PoseStamped> empty_plan;
00298         publishGlobalPlan(empty_plan);
00299       }
00300       return isOk;
00301     }
00302   }
00303 
00304 
00305 };


dwa_local_planner
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Oct 6 2014 02:47:33