dwa_planner.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 #include <dwa_local_planner/dwa_planner.h>
00038 #include <cmath>
00039 
00040 //for computing path distance
00041 #include <queue>
00042 
00043 #include <angles/angles.h>
00044 
00045 #include <ros/ros.h>
00046 
00047 namespace dwa_local_planner {
00048   void DWAPlanner::reconfigure(DWAPlannerConfig &config)
00049   {
00050 
00051     boost::mutex::scoped_lock l(configuration_mutex_);
00052 
00053     generator_.setParameters(
00054         config.sim_time,
00055         config.sim_granularity,
00056         config.angular_sim_granularity,
00057         config.use_dwa,
00058         sim_period_);
00059 
00060     double resolution = planner_util_->getCostmap()->getResolution();
00061     pdist_scale_ = config.path_distance_bias;
00062     // pdistscale used for both path and alignment, set  forward_point_distance to zero to discard alignment
00063     path_costs_.setScale(resolution * pdist_scale_ * 0.5);
00064     alignment_costs_.setScale(resolution * pdist_scale_ * 0.5);
00065 
00066     gdist_scale_ = config.goal_distance_bias;
00067     goal_costs_.setScale(resolution * gdist_scale_ * 0.5);
00068     goal_front_costs_.setScale(resolution * gdist_scale_ * 0.5);
00069 
00070     occdist_scale_ = config.occdist_scale;
00071     obstacle_costs_.setScale(resolution * occdist_scale_);
00072 
00073     stop_time_buffer_ = config.stop_time_buffer;
00074     oscillation_costs_.setOscillationResetDist(config.oscillation_reset_dist, config.oscillation_reset_angle);
00075     forward_point_distance_ = config.forward_point_distance;
00076     goal_front_costs_.setXShift(forward_point_distance_);
00077     alignment_costs_.setXShift(forward_point_distance_);
00078  
00079     // obstacle costs can vary due to scaling footprint feature
00080     obstacle_costs_.setParams(config.max_trans_vel, config.max_scaling_factor, config.scaling_speed);
00081 
00082     int vx_samp, vy_samp, vth_samp;
00083     vx_samp = config.vx_samples;
00084     vy_samp = config.vy_samples;
00085     vth_samp = config.vth_samples;
00086  
00087     if (vx_samp <= 0) {
00088       ROS_WARN("You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead");
00089       vx_samp = 1;
00090       config.vx_samples = vx_samp;
00091     }
00092  
00093     if (vy_samp <= 0) {
00094       ROS_WARN("You've specified that you don't want any samples in the y dimension. We'll at least assume that you want to sample one value... so we're going to set vy_samples to 1 instead");
00095       vy_samp = 1;
00096       config.vy_samples = vy_samp;
00097     }
00098  
00099     if (vth_samp <= 0) {
00100       ROS_WARN("You've specified that you don't want any samples in the th dimension. We'll at least assume that you want to sample one value... so we're going to set vth_samples to 1 instead");
00101       vth_samp = 1;
00102       config.vth_samples = vth_samp;
00103     }
00104  
00105     vsamples_[0] = vx_samp;
00106     vsamples_[1] = vy_samp;
00107     vsamples_[2] = vth_samp;
00108  
00109 
00110   }
00111 
00112   DWAPlanner::DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util) :
00113       planner_util_(planner_util),
00114       obstacle_costs_(planner_util->getCostmap()),
00115       path_costs_(planner_util->getCostmap()),
00116       goal_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
00117       goal_front_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
00118       alignment_costs_(planner_util->getCostmap())
00119   {
00120     ros::NodeHandle private_nh("~/" + name);
00121 
00122     goal_front_costs_.setStopOnFailure( false );
00123     alignment_costs_.setStopOnFailure( false );
00124 
00125     //Assuming this planner is being run within the navigation stack, we can
00126     //just do an upward search for the frequency at which its being run. This
00127     //also allows the frequency to be overwritten locally.
00128     std::string controller_frequency_param_name;
00129     if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name)) {
00130       sim_period_ = 0.05;
00131     } else {
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         ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
00138         sim_period_ = 0.05;
00139       }
00140     }
00141     ROS_INFO("Sim period is set to %.2f", sim_period_);
00142 
00143     oscillation_costs_.resetOscillationFlags();
00144 
00145     private_nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
00146     map_viz_.initialize(name, boost::bind(&DWAPlanner::getCellCosts, this, _1, _2, _3, _4, _5, _6));
00147 
00148     std::string frame_id;
00149     private_nh.param("global_frame_id", frame_id, std::string("odom"));
00150 
00151     traj_cloud_.header.frame_id = frame_id;
00152     traj_cloud_pub_.advertise(private_nh, "trajectory_cloud", 1);
00153 
00154     // set up all the cost functions that will be applied in order
00155     // (any function returning negative values will abort scoring, so the order can improve performance)
00156     std::vector<base_local_planner::TrajectoryCostFunction*> critics;
00157     critics.push_back(&oscillation_costs_); // discards oscillating motions (assisgns cost -1)
00158     critics.push_back(&obstacle_costs_); // discards trajectories that move into obstacles
00159     critics.push_back(&goal_front_costs_); // prefers trajectories that make the nose go towards (local) nose goal
00160     critics.push_back(&alignment_costs_); // prefers trajectories that keep the robot nose on nose path
00161     critics.push_back(&path_costs_); // prefers trajectories on global path
00162     critics.push_back(&goal_costs_); // prefers trajectories that go towards (local) goal, based on wave propagation
00163 
00164     // trajectory generators
00165     std::vector<base_local_planner::TrajectorySampleGenerator*> generator_list;
00166     generator_list.push_back(&generator_);
00167 
00168     scored_sampling_planner_ = base_local_planner::SimpleScoredSamplingPlanner(generator_list, critics);
00169   }
00170 
00171   // used for visualization only, total_costs are not really total costs
00172   bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
00173 
00174     path_cost = path_costs_.getCellCosts(cx, cy);
00175     goal_cost = goal_costs_.getCellCosts(cx, cy);
00176     occ_cost = planner_util_->getCostmap()->getCost(cx, cy);
00177     if (path_cost == path_costs_.obstacleCosts() ||
00178         path_cost == path_costs_.unreachableCellCosts() ||
00179         occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
00180       return false;
00181     }
00182 
00183     double resolution = planner_util_->getCostmap()->getResolution();
00184     total_cost =
00185         pdist_scale_ * resolution * path_cost +
00186         gdist_scale_ * resolution * goal_cost +
00187         occdist_scale_ * occ_cost;
00188     return true;
00189   }
00190 
00191   bool DWAPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
00192     oscillation_costs_.resetOscillationFlags();
00193     return planner_util_->setPlan(orig_global_plan);
00194   }
00195 
00200   bool DWAPlanner::checkTrajectory(
00201       Eigen::Vector3f pos,
00202       Eigen::Vector3f vel,
00203       Eigen::Vector3f vel_samples){
00204     oscillation_costs_.resetOscillationFlags();
00205     base_local_planner::Trajectory traj;
00206     geometry_msgs::PoseStamped goal_pose = global_plan_.back();
00207     Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf::getYaw(goal_pose.pose.orientation));
00208     base_local_planner::LocalPlannerLimits limits = planner_util_->getCurrentLimits();
00209     generator_.initialise(pos,
00210         vel,
00211         goal,
00212         &limits,
00213         vsamples_);
00214     generator_.generateTrajectory(pos, vel, vel_samples, traj);
00215     double cost = scored_sampling_planner_.scoreTrajectory(traj, -1);
00216     //if the trajectory is a legal one... the check passes
00217     if(cost >= 0) {
00218       return true;
00219     }
00220     ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost);
00221 
00222     //otherwise the check fails
00223     return false;
00224   }
00225 
00226 
00227   void DWAPlanner::updatePlanAndLocalCosts(
00228       tf::Stamped<tf::Pose> global_pose,
00229       const std::vector<geometry_msgs::PoseStamped>& new_plan) {
00230     global_plan_.resize(new_plan.size());
00231     for (unsigned int i = 0; i < new_plan.size(); ++i) {
00232       global_plan_[i] = new_plan[i];
00233     }
00234 
00235     // costs for going away from path
00236     path_costs_.setTargetPoses(global_plan_);
00237 
00238     // costs for not going towards the local goal as much as possible
00239     goal_costs_.setTargetPoses(global_plan_);
00240 
00241     // alignment costs
00242     geometry_msgs::PoseStamped goal_pose = global_plan_.back();
00243 
00244     Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation()));
00245     double sq_dist =
00246         (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) +
00247         (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y);
00248 
00249     // we want the robot nose to be drawn to its final position
00250     // (before robot turns towards goal orientation), not the end of the
00251     // path for the robot center. Choosing the final position after
00252     // turning towards goal orientation causes instability when the
00253     // robot needs to make a 180 degree turn at the end
00254     std::vector<geometry_msgs::PoseStamped> front_global_plan = global_plan_;
00255     double angle_to_goal = atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]);
00256     front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x +
00257       forward_point_distance_ * cos(angle_to_goal);
00258     front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y + forward_point_distance_ *
00259       sin(angle_to_goal);
00260 
00261     goal_front_costs_.setTargetPoses(front_global_plan);
00262     
00263     // keeping the nose on the path
00264     if (sq_dist > forward_point_distance_ * forward_point_distance_ ) {
00265       alignment_costs_.setScale(1.0);
00266       // costs for robot being aligned with path (nose on path, not ju
00267       alignment_costs_.setTargetPoses(global_plan_);
00268     } else {
00269       // once we are close to goal, trying to keep the nose close to anything destabilizes behavior.
00270       alignment_costs_.setScale(0.0);
00271     }
00272   }
00273 
00274 
00275   /*
00276    * given the current state of the robot, find a good trajectory
00277    */
00278   base_local_planner::Trajectory DWAPlanner::findBestPath(
00279       tf::Stamped<tf::Pose> global_pose,
00280       tf::Stamped<tf::Pose> global_vel,
00281       tf::Stamped<tf::Pose>& drive_velocities,
00282       std::vector<geometry_msgs::Point> footprint_spec) {
00283 
00284     obstacle_costs_.setFootprint(footprint_spec);
00285 
00286     //make sure that our configuration doesn't change mid-run
00287     boost::mutex::scoped_lock l(configuration_mutex_);
00288 
00289     Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation()));
00290     Eigen::Vector3f vel(global_vel.getOrigin().getX(), global_vel.getOrigin().getY(), tf::getYaw(global_vel.getRotation()));
00291     geometry_msgs::PoseStamped goal_pose = global_plan_.back();
00292     Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf::getYaw(goal_pose.pose.orientation));
00293     base_local_planner::LocalPlannerLimits limits = planner_util_->getCurrentLimits();
00294 
00295     // prepare cost functions and generators for this run
00296     generator_.initialise(pos,
00297         vel,
00298         goal,
00299         &limits,
00300         vsamples_);
00301 
00302     result_traj_.cost_ = -7;
00303     // find best trajectory by sampling and scoring the samples
00304     scored_sampling_planner_.findBestTrajectory(result_traj_, NULL);
00305 
00306     // verbose publishing of point clouds
00307     if (publish_cost_grid_pc_) {
00308       //we'll publish the visualization of the costs to rviz before returning our best trajectory
00309       map_viz_.publishCostCloud(*(planner_util_->getCostmap()));
00310     }
00311 
00312     // debrief stateful scoring functions
00313     oscillation_costs_.updateOscillationFlags(pos, &result_traj_, planner_util_->getCurrentLimits().min_trans_vel);
00314 
00315     //if we don't have a legal trajectory, we'll just command zero
00316     if (result_traj_.cost_ < 0) {
00317       drive_velocities.setIdentity();
00318     } else {
00319       tf::Vector3 start(result_traj_.xv_, result_traj_.yv_, 0);
00320       drive_velocities.setOrigin(start);
00321       tf::Matrix3x3 matrix;
00322       matrix.setRotation(tf::createQuaternionFromYaw(result_traj_.thetav_));
00323       drive_velocities.setBasis(matrix);
00324     }
00325 
00326     return result_traj_;
00327   }
00328 };


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