dwa_planner.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
39 #include <cmath>
40 
41 //for computing path distance
42 #include <queue>
43 
44 #include <angles/angles.h>
45 
46 #include <ros/ros.h>
47 #include <tf2/utils.h>
48 #include <sensor_msgs/PointCloud2.h>
50 
51 namespace dwa_local_planner {
52  void DWAPlanner::reconfigure(DWAPlannerConfig &config)
53  {
54 
55  boost::mutex::scoped_lock l(configuration_mutex_);
56 
58  config.sim_time,
59  config.sim_granularity,
60  config.angular_sim_granularity,
61  config.use_dwa,
62  sim_period_);
63 
64  double resolution = planner_util_->getCostmap()->getResolution();
65  path_distance_bias_ = resolution * config.path_distance_bias;
66  // pdistscale used for both path and alignment, set forward_point_distance to zero to discard alignment
69 
70  goal_distance_bias_ = resolution * config.goal_distance_bias;
73 
74  occdist_scale_ = config.occdist_scale;
76 
77  stop_time_buffer_ = config.stop_time_buffer;
78  oscillation_costs_.setOscillationResetDist(config.oscillation_reset_dist, config.oscillation_reset_angle);
79  forward_point_distance_ = config.forward_point_distance;
82 
83  // obstacle costs can vary due to scaling footprint feature
84  obstacle_costs_.setParams(config.max_vel_trans, config.max_scaling_factor, config.scaling_speed);
85 
86  twirling_costs_.setScale(config.twirling_scale);
87 
88  int vx_samp, vy_samp, vth_samp;
89  vx_samp = config.vx_samples;
90  vy_samp = config.vy_samples;
91  vth_samp = config.vth_samples;
92 
93  if (vx_samp <= 0) {
94  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");
95  vx_samp = 1;
96  config.vx_samples = vx_samp;
97  }
98 
99  if (vy_samp <= 0) {
100  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");
101  vy_samp = 1;
102  config.vy_samples = vy_samp;
103  }
104 
105  if (vth_samp <= 0) {
106  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");
107  vth_samp = 1;
108  config.vth_samples = vth_samp;
109  }
110 
111  vsamples_[0] = vx_samp;
112  vsamples_[1] = vy_samp;
113  vsamples_[2] = vth_samp;
114 
115 
116  }
117 
119  planner_util_(planner_util),
120  obstacle_costs_(planner_util->getCostmap()),
121  path_costs_(planner_util->getCostmap()),
122  goal_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
123  goal_front_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
124  alignment_costs_(planner_util->getCostmap())
125  {
126  ros::NodeHandle private_nh("~/" + name);
127 
130 
131  //Assuming this planner is being run within the navigation stack, we can
132  //just do an upward search for the frequency at which its being run. This
133  //also allows the frequency to be overwritten locally.
134  std::string controller_frequency_param_name;
135  if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name)) {
136  sim_period_ = 0.05;
137  } else {
138  double controller_frequency = 0;
139  private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
140  if(controller_frequency > 0) {
141  sim_period_ = 1.0 / controller_frequency;
142  } else {
143  ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
144  sim_period_ = 0.05;
145  }
146  }
147  ROS_INFO("Sim period is set to %.2f", sim_period_);
148 
150 
151  bool sum_scores;
152  private_nh.param("sum_scores", sum_scores, false);
153  obstacle_costs_.setSumScores(sum_scores);
154 
155 
156  private_nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
157  map_viz_.initialize(name, planner_util->getGlobalFrame(), boost::bind(&DWAPlanner::getCellCosts, this, _1, _2, _3, _4, _5, _6));
158 
159  private_nh.param("global_frame_id", frame_id_, std::string("odom"));
160 
161  traj_cloud_pub_ = private_nh.advertise<sensor_msgs::PointCloud2>("trajectory_cloud", 1);
162  private_nh.param("publish_traj_pc", publish_traj_pc_, false);
163 
164  // set up all the cost functions that will be applied in order
165  // (any function returning negative values will abort scoring, so the order can improve performance)
166  std::vector<base_local_planner::TrajectoryCostFunction*> critics;
167  critics.push_back(&oscillation_costs_); // discards oscillating motions (assisgns cost -1)
168  critics.push_back(&obstacle_costs_); // discards trajectories that move into obstacles
169  critics.push_back(&goal_front_costs_); // prefers trajectories that make the nose go towards (local) nose goal
170  critics.push_back(&alignment_costs_); // prefers trajectories that keep the robot nose on nose path
171  critics.push_back(&path_costs_); // prefers trajectories on global path
172  critics.push_back(&goal_costs_); // prefers trajectories that go towards (local) goal, based on wave propagation
173  critics.push_back(&twirling_costs_); // optionally prefer trajectories that don't spin
174 
175  // trajectory generators
176  std::vector<base_local_planner::TrajectorySampleGenerator*> generator_list;
177  generator_list.push_back(&generator_);
178 
180 
181  private_nh.param("cheat_factor", cheat_factor_, 1.0);
182  }
183 
184  // used for visualization only, total_costs are not really total costs
185  bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
186 
187  path_cost = path_costs_.getCellCosts(cx, cy);
188  goal_cost = goal_costs_.getCellCosts(cx, cy);
189  occ_cost = planner_util_->getCostmap()->getCost(cx, cy);
190  if (path_cost == path_costs_.obstacleCosts() ||
191  path_cost == path_costs_.unreachableCellCosts() ||
193  return false;
194  }
195 
196  total_cost =
197  path_distance_bias_ * path_cost +
198  goal_distance_bias_ * goal_cost +
199  occdist_scale_ * occ_cost;
200  return true;
201  }
202 
203  bool DWAPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
205  return planner_util_->setPlan(orig_global_plan);
206  }
207 
213  Eigen::Vector3f pos,
214  Eigen::Vector3f vel,
215  Eigen::Vector3f vel_samples){
218  geometry_msgs::PoseStamped goal_pose = global_plan_.back();
219  Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf2::getYaw(goal_pose.pose.orientation));
222  vel,
223  goal,
224  &limits,
225  vsamples_);
226  generator_.generateTrajectory(pos, vel, vel_samples, traj);
227  double cost = scored_sampling_planner_.scoreTrajectory(traj, -1);
228  //if the trajectory is a legal one... the check passes
229  if(cost >= 0) {
230  return true;
231  }
232  ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost);
233 
234  //otherwise the check fails
235  return false;
236  }
237 
238 
240  const geometry_msgs::PoseStamped& global_pose,
241  const std::vector<geometry_msgs::PoseStamped>& new_plan,
242  const std::vector<geometry_msgs::Point>& footprint_spec) {
243  global_plan_.resize(new_plan.size());
244  for (unsigned int i = 0; i < new_plan.size(); ++i) {
245  global_plan_[i] = new_plan[i];
246  }
247 
248  obstacle_costs_.setFootprint(footprint_spec);
249 
250  // costs for going away from path
252 
253  // costs for not going towards the local goal as much as possible
255 
256  // alignment costs
257  geometry_msgs::PoseStamped goal_pose = global_plan_.back();
258 
259  Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation));
260  double sq_dist =
261  (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) +
262  (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y);
263 
264  // we want the robot nose to be drawn to its final position
265  // (before robot turns towards goal orientation), not the end of the
266  // path for the robot center. Choosing the final position after
267  // turning towards goal orientation causes instability when the
268  // robot needs to make a 180 degree turn at the end
269  std::vector<geometry_msgs::PoseStamped> front_global_plan = global_plan_;
270  double angle_to_goal = atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]);
271  front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x +
272  forward_point_distance_ * cos(angle_to_goal);
273  front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y + forward_point_distance_ *
274  sin(angle_to_goal);
275 
276  goal_front_costs_.setTargetPoses(front_global_plan);
277 
278  // keeping the nose on the path
281  // costs for robot being aligned with path (nose on path, not ju
283  } else {
284  // once we are close to goal, trying to keep the nose close to anything destabilizes behavior.
286  }
287  }
288 
289 
290  /*
291  * given the current state of the robot, find a good trajectory
292  */
294  const geometry_msgs::PoseStamped& global_pose,
295  const geometry_msgs::PoseStamped& global_vel,
296  geometry_msgs::PoseStamped& drive_velocities) {
297 
298  //make sure that our configuration doesn't change mid-run
299  boost::mutex::scoped_lock l(configuration_mutex_);
300 
301  Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation));
302  Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y, tf2::getYaw(global_vel.pose.orientation));
303  geometry_msgs::PoseStamped goal_pose = global_plan_.back();
304  Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf2::getYaw(goal_pose.pose.orientation));
306 
307  // prepare cost functions and generators for this run
309  vel,
310  goal,
311  &limits,
312  vsamples_);
313 
314  result_traj_.cost_ = -7;
315  // find best trajectory by sampling and scoring the samples
316  std::vector<base_local_planner::Trajectory> all_explored;
318 
319  if(publish_traj_pc_)
320  {
321  sensor_msgs::PointCloud2 traj_cloud;
322  traj_cloud.header.frame_id = frame_id_;
323  traj_cloud.header.stamp = ros::Time::now();
324 
325  sensor_msgs::PointCloud2Modifier cloud_mod(traj_cloud);
326  cloud_mod.setPointCloud2Fields(5, "x", 1, sensor_msgs::PointField::FLOAT32,
327  "y", 1, sensor_msgs::PointField::FLOAT32,
328  "z", 1, sensor_msgs::PointField::FLOAT32,
329  "theta", 1, sensor_msgs::PointField::FLOAT32,
330  "cost", 1, sensor_msgs::PointField::FLOAT32);
331 
332  unsigned int num_points = 0;
333  for(std::vector<base_local_planner::Trajectory>::iterator t=all_explored.begin(); t != all_explored.end(); ++t)
334  {
335  if (t->cost_<0)
336  continue;
337  num_points += t->getPointsSize();
338  }
339 
340  cloud_mod.resize(num_points);
341  sensor_msgs::PointCloud2Iterator<float> iter_x(traj_cloud, "x");
342  for(std::vector<base_local_planner::Trajectory>::iterator t=all_explored.begin(); t != all_explored.end(); ++t)
343  {
344  if(t->cost_<0)
345  continue;
346  // Fill out the plan
347  for(unsigned int i = 0; i < t->getPointsSize(); ++i) {
348  double p_x, p_y, p_th;
349  t->getPoint(i, p_x, p_y, p_th);
350  iter_x[0] = p_x;
351  iter_x[1] = p_y;
352  iter_x[2] = 0.0;
353  iter_x[3] = p_th;
354  iter_x[4] = t->cost_;
355  ++iter_x;
356  }
357  }
358  traj_cloud_pub_.publish(traj_cloud);
359  }
360 
361  // verbose publishing of point clouds
362  if (publish_cost_grid_pc_) {
363  //we'll publish the visualization of the costs to rviz before returning our best trajectory
365  }
366 
367  // debrief stateful scoring functions
369 
370  //if we don't have a legal trajectory, we'll just command zero
371  if (result_traj_.cost_ < 0) {
372  drive_velocities.pose.position.x = 0;
373  drive_velocities.pose.position.y = 0;
374  drive_velocities.pose.position.z = 0;
375  drive_velocities.pose.orientation.w = 1;
376  drive_velocities.pose.orientation.x = 0;
377  drive_velocities.pose.orientation.y = 0;
378  drive_velocities.pose.orientation.z = 0;
379  } else {
380  drive_velocities.pose.position.x = result_traj_.xv_;
381  drive_velocities.pose.position.y = result_traj_.yv_;
382  drive_velocities.pose.position.z = 0;
383  tf2::Quaternion q;
384  q.setRPY(0, 0, result_traj_.thetav_);
385  tf2::convert(q, drive_velocities.pose.orientation);
386  }
387 
388  return result_traj_;
389  }
390 };
void initialise(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, const Eigen::Vector3f &goal, base_local_planner::LocalPlannerLimits *limits, const Eigen::Vector3f &vsamples, std::vector< Eigen::Vector3f > additional_samples, bool discretize_by_time=false)
void setFootprint(std::vector< geometry_msgs::Point > footprint_spec)
void reconfigure(DWAPlannerConfig &cfg)
Reconfigures the trajectory planner.
Definition: dwa_planner.cpp:52
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
bool generateTrajectory(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f sample_target_vel, base_local_planner::Trajectory &traj)
base_local_planner::MapGridCostFunction goal_front_costs_
Definition: dwa_planner.h:178
void publishCostCloud(const costmap_2d::Costmap2D *costmap_p_)
base_local_planner::MapGridCostFunction goal_costs_
Definition: dwa_planner.h:177
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
Definition: dwa_planner.h:155
costmap_2d::Costmap2D * getCostmap()
base_local_planner::OscillationCostFunction oscillation_costs_
Definition: dwa_planner.h:174
base_local_planner::LocalPlannerUtil * planner_util_
Definition: dwa_planner.h:149
bool publish_cost_grid_pc_
Whether or not to build and publish a PointCloud.
Definition: dwa_planner.h:165
void setPointCloud2Fields(int n_fields,...)
bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)
Compute the components and total cost for a map grid cell.
void initialize(const std::string &name, std::string frame, boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function)
base_local_planner::TwirlingCostFunction twirling_costs_
Definition: dwa_planner.h:180
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: dwa_planner.h:160
double scoreTrajectory(Trajectory &traj, double best_traj_cost)
void setStopOnFailure(bool stop_on_failure)
base_local_planner::MapGridCostFunction alignment_costs_
Definition: dwa_planner.h:179
DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util)
Constructor for the planner.
base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_
Definition: dwa_planner.h:182
bool findBestTrajectory(Trajectory &traj, std::vector< Trajectory > *all_explored=0)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
ros::Publisher traj_cloud_pub_
Definition: dwa_planner.h:164
base_local_planner::ObstacleCostFunction obstacle_costs_
Definition: dwa_planner.h:175
base_local_planner::MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
Definition: dwa_planner.h:170
#define ROS_INFO(...)
LocalPlannerLimits getCurrentLimits()
base_local_planner::MapGridCostFunction path_costs_
Definition: dwa_planner.h:176
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setParameters(double sim_time, double sim_granularity, double angular_sim_granularity, bool use_dwa=false, double sim_period=0.0)
double getYaw(const A &a)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
bool searchParam(const std::string &key, std::string &result) const
void setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
void setTargetPoses(std::vector< geometry_msgs::PoseStamped > target_poses)
base_local_planner::Trajectory result_traj_
Definition: dwa_planner.h:156
base_local_planner::SimpleTrajectoryGenerator generator_
Definition: dwa_planner.h:173
static Time now()
void convert(const A &a, B &b)
double getResolution() const
double stop_time_buffer_
How long before hitting something we&#39;re going to enforce that the robot stop.
Definition: dwa_planner.h:151
double getCellCosts(unsigned int cx, unsigned int cy)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
void updatePlanAndLocalCosts(const geometry_msgs::PoseStamped &global_pose, const std::vector< geometry_msgs::PoseStamped > &new_plan, const std::vector< geometry_msgs::Point > &footprint_spec)
Update the cost functions before planning.
base_local_planner::Trajectory findBestPath(const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &global_vel, geometry_msgs::PoseStamped &drive_velocities)
Given the current position and velocity of the robot, find the best trajectory to exectue...
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
unsigned char getCost(unsigned int mx, unsigned int my) const
void updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory *traj, double min_vel_trans)
void setOscillationResetDist(double dist, double angle)
bool checkTrajectory(const Eigen::Vector3f pos, const Eigen::Vector3f vel, const Eigen::Vector3f vel_samples)
Check if a trajectory is legal for a position/velocity pair.


dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:15