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 
118  DWAPlanner::DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util) :
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);
154 
155 
156  private_nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
157  map_viz_.initialize(name,
158  planner_util->getGlobalFrame(),
159  [this](int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost){
160  return getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost);
161  });
162 
163  private_nh.param("global_frame_id", frame_id_, std::string("odom"));
164 
165  traj_cloud_pub_ = private_nh.advertise<sensor_msgs::PointCloud2>("trajectory_cloud", 1);
166  private_nh.param("publish_traj_pc", publish_traj_pc_, false);
167 
168  // set up all the cost functions that will be applied in order
169  // (any function returning negative values will abort scoring, so the order can improve performance)
170  std::vector<base_local_planner::TrajectoryCostFunction*> critics;
171  critics.push_back(&oscillation_costs_); // discards oscillating motions (assisgns cost -1)
172  critics.push_back(&obstacle_costs_); // discards trajectories that move into obstacles
173  critics.push_back(&goal_front_costs_); // prefers trajectories that make the nose go towards (local) nose goal
174  critics.push_back(&alignment_costs_); // prefers trajectories that keep the robot nose on nose path
175  critics.push_back(&path_costs_); // prefers trajectories on global path
176  critics.push_back(&goal_costs_); // prefers trajectories that go towards (local) goal, based on wave propagation
177  critics.push_back(&twirling_costs_); // optionally prefer trajectories that don't spin
178 
179  // trajectory generators
180  std::vector<base_local_planner::TrajectorySampleGenerator*> generator_list;
181  generator_list.push_back(&generator_);
182 
184 
185  private_nh.param("cheat_factor", cheat_factor_, 1.0);
186  }
187 
188  // used for visualization only, total_costs are not really total costs
189  bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
190 
191  path_cost = path_costs_.getCellCosts(cx, cy);
192  goal_cost = goal_costs_.getCellCosts(cx, cy);
193  occ_cost = planner_util_->getCostmap()->getCost(cx, cy);
194  if (path_cost == path_costs_.obstacleCosts() ||
195  path_cost == path_costs_.unreachableCellCosts() ||
197  return false;
198  }
199 
200  total_cost =
201  path_distance_bias_ * path_cost +
202  goal_distance_bias_ * goal_cost +
203  occdist_scale_ * occ_cost;
204  return true;
205  }
206 
207  bool DWAPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
209  return planner_util_->setPlan(orig_global_plan);
210  }
211 
217  Eigen::Vector3f pos,
218  Eigen::Vector3f vel,
219  Eigen::Vector3f vel_samples){
222  geometry_msgs::PoseStamped goal_pose = global_plan_.back();
223  Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf2::getYaw(goal_pose.pose.orientation));
226  vel,
227  goal,
228  &limits,
229  vsamples_);
230  generator_.generateTrajectory(pos, vel, vel_samples, traj);
231  double cost = scored_sampling_planner_.scoreTrajectory(traj, -1);
232  //if the trajectory is a legal one... the check passes
233  if(cost >= 0) {
234  return true;
235  }
236  ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost);
237 
238  //otherwise the check fails
239  return false;
240  }
241 
242 
244  const geometry_msgs::PoseStamped& global_pose,
245  const std::vector<geometry_msgs::PoseStamped>& new_plan,
246  const std::vector<geometry_msgs::Point>& footprint_spec) {
247  global_plan_.resize(new_plan.size());
248  for (unsigned int i = 0; i < new_plan.size(); ++i) {
249  global_plan_[i] = new_plan[i];
250  }
251 
252  obstacle_costs_.setFootprint(footprint_spec);
253 
254  // costs for going away from path
256 
257  // costs for not going towards the local goal as much as possible
259 
260  // alignment costs
261  geometry_msgs::PoseStamped goal_pose = global_plan_.back();
262 
263  Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation));
264  double sq_dist =
265  (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) +
266  (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y);
267 
268  // we want the robot nose to be drawn to its final position
269  // (before robot turns towards goal orientation), not the end of the
270  // path for the robot center. Choosing the final position after
271  // turning towards goal orientation causes instability when the
272  // robot needs to make a 180 degree turn at the end
273  std::vector<geometry_msgs::PoseStamped> front_global_plan = global_plan_;
274  double angle_to_goal = atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]);
275  front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x +
276  forward_point_distance_ * cos(angle_to_goal);
277  front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y + forward_point_distance_ *
278  sin(angle_to_goal);
279 
280  goal_front_costs_.setTargetPoses(front_global_plan);
281 
282  // keeping the nose on the path
285  // costs for robot being aligned with path (nose on path, not ju
287  } else {
288  // once we are close to goal, trying to keep the nose close to anything destabilizes behavior.
290  }
291  }
292 
293 
294  /*
295  * given the current state of the robot, find a good trajectory
296  */
298  const geometry_msgs::PoseStamped& global_pose,
299  const geometry_msgs::PoseStamped& global_vel,
300  geometry_msgs::PoseStamped& drive_velocities) {
301 
302  //make sure that our configuration doesn't change mid-run
303  boost::mutex::scoped_lock l(configuration_mutex_);
304 
305  Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation));
306  Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y, tf2::getYaw(global_vel.pose.orientation));
307  geometry_msgs::PoseStamped goal_pose = global_plan_.back();
308  Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf2::getYaw(goal_pose.pose.orientation));
310 
311  // prepare cost functions and generators for this run
313  vel,
314  goal,
315  &limits,
316  vsamples_);
317 
318  result_traj_.cost_ = -7;
319  // find best trajectory by sampling and scoring the samples
320  std::vector<base_local_planner::Trajectory> all_explored;
322 
323  if(publish_traj_pc_)
324  {
325  sensor_msgs::PointCloud2 traj_cloud;
326  traj_cloud.header.frame_id = frame_id_;
327  traj_cloud.header.stamp = ros::Time::now();
328 
329  sensor_msgs::PointCloud2Modifier cloud_mod(traj_cloud);
330  cloud_mod.setPointCloud2Fields(5, "x", 1, sensor_msgs::PointField::FLOAT32,
331  "y", 1, sensor_msgs::PointField::FLOAT32,
332  "z", 1, sensor_msgs::PointField::FLOAT32,
333  "theta", 1, sensor_msgs::PointField::FLOAT32,
334  "cost", 1, sensor_msgs::PointField::FLOAT32);
335 
336  unsigned int num_points = 0;
337  for(std::vector<base_local_planner::Trajectory>::iterator t=all_explored.begin(); t != all_explored.end(); ++t)
338  {
339  if (t->cost_<0)
340  continue;
341  num_points += t->getPointsSize();
342  }
343 
344  cloud_mod.resize(num_points);
345  sensor_msgs::PointCloud2Iterator<float> iter_x(traj_cloud, "x");
346  for(std::vector<base_local_planner::Trajectory>::iterator t=all_explored.begin(); t != all_explored.end(); ++t)
347  {
348  if(t->cost_<0)
349  continue;
350  // Fill out the plan
351  for(unsigned int i = 0; i < t->getPointsSize(); ++i) {
352  double p_x, p_y, p_th;
353  t->getPoint(i, p_x, p_y, p_th);
354  iter_x[0] = p_x;
355  iter_x[1] = p_y;
356  iter_x[2] = 0.0;
357  iter_x[3] = p_th;
358  iter_x[4] = t->cost_;
359  ++iter_x;
360  }
361  }
362  traj_cloud_pub_.publish(traj_cloud);
363  }
364 
365  // verbose publishing of point clouds
366  if (publish_cost_grid_pc_) {
367  //we'll publish the visualization of the costs to rviz before returning our best trajectory
369  }
370 
371  // debrief stateful scoring functions
373 
374  //if we don't have a legal trajectory, we'll just command zero
375  if (result_traj_.cost_ < 0) {
376  drive_velocities.pose.position.x = 0;
377  drive_velocities.pose.position.y = 0;
378  drive_velocities.pose.position.z = 0;
379  drive_velocities.pose.orientation.w = 1;
380  drive_velocities.pose.orientation.x = 0;
381  drive_velocities.pose.orientation.y = 0;
382  drive_velocities.pose.orientation.z = 0;
383  } else {
384  drive_velocities.pose.position.x = result_traj_.xv_;
385  drive_velocities.pose.position.y = result_traj_.yv_;
386  drive_velocities.pose.position.z = 0;
387  tf2::Quaternion q;
388  q.setRPY(0, 0, result_traj_.thetav_);
389  tf2::convert(q, drive_velocities.pose.orientation);
390  }
391 
392  return result_traj_;
393  }
394 };
dwa_local_planner::DWAPlanner::vsamples_
Eigen::Vector3f vsamples_
Definition: dwa_planner.h:188
base_local_planner::MapGridCostFunction::getCellCosts
double getCellCosts(unsigned int cx, unsigned int cy)
tf2::convert
void convert(const A &a, B &b)
point_cloud2_iterator.h
base_local_planner::Trajectory::xv_
double xv_
dwa_local_planner::DWAPlanner::cheat_factor_
double cheat_factor_
Definition: dwa_planner.h:203
dwa_local_planner::DWAPlanner::occdist_scale_
double occdist_scale_
Definition: dwa_planner.h:187
base_local_planner::SimpleScoredSamplingPlanner
tf2::getYaw
double getYaw(const A &a)
utils.h
dwa_local_planner::DWAPlanner::goal_costs_
base_local_planner::MapGridCostFunction goal_costs_
Definition: dwa_planner.h:212
ros.h
base_local_planner::LocalPlannerUtil
base_local_planner::ObstacleCostFunction::setSumScores
void setSumScores(bool score_sums)
base_local_planner::SimpleTrajectoryGenerator::setParameters
void setParameters(double sim_time, double sim_granularity, double angular_sim_granularity, bool use_dwa=false, double sim_period=0.0)
costmap_2d::INSCRIBED_INFLATED_OBSTACLE
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
dwa_local_planner::DWAPlanner::findBestPath
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.
Definition: dwa_planner.cpp:332
dwa_local_planner::DWAPlanner::checkTrajectory
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.
Definition: dwa_planner.cpp:251
base_local_planner::LocalPlannerUtil::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
dwa_local_planner::DWAPlanner::configuration_mutex_
boost::mutex configuration_mutex_
Definition: dwa_planner.h:197
goal_functions.h
base_local_planner::OscillationCostFunction::updateOscillationFlags
void updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory *traj, double min_vel_trans)
base_local_planner::SimpleTrajectoryGenerator::generateTrajectory
bool generateTrajectory(Eigen::Vector3f pos, Eigen::Vector3f vel, Eigen::Vector3f sample_target_vel, base_local_planner::Trajectory &traj)
dwa_local_planner::DWAPlanner::traj_cloud_pub_
ros::Publisher traj_cloud_pub_
Definition: dwa_planner.h:199
base_local_planner::MapGridCostFunction::obstacleCosts
double obstacleCosts()
dwa_local_planner::DWAPlanner::publish_traj_pc_
bool publish_traj_pc_
Definition: dwa_planner.h:201
dwa_local_planner::DWAPlanner::publish_cost_grid_pc_
bool publish_cost_grid_pc_
Whether or not to build and publish a PointCloud.
Definition: dwa_planner.h:200
dwa_local_planner::DWAPlanner::goal_front_costs_
base_local_planner::MapGridCostFunction goal_front_costs_
Definition: dwa_planner.h:213
base_local_planner::MapGridCostFunction::unreachableCellCosts
double unreachableCellCosts()
base_local_planner::TrajectoryCostFunction::setScale
void setScale(double scale)
base_local_planner::LocalPlannerLimits
dwa_local_planner::DWAPlanner::map_viz_
base_local_planner::MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
Definition: dwa_planner.h:205
dwa_local_planner::DWAPlanner::twirling_costs_
base_local_planner::TwirlingCostFunction twirling_costs_
Definition: dwa_planner.h:215
dwa_local_planner::DWAPlanner::scored_sampling_planner_
base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_
Definition: dwa_planner.h:217
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
base_local_planner::ObstacleCostFunction::setFootprint
void setFootprint(std::vector< geometry_msgs::Point > footprint_spec)
base_local_planner::ObstacleCostFunction::setParams
void setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed)
dwa_local_planner::DWAPlanner::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: dwa_planner.h:195
base_local_planner::SimpleTrajectoryGenerator::initialise
void initialise(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, const Eigen::Vector3f &goal, base_local_planner::LocalPlannerLimits *limits, const Eigen::Vector3f &vsamples, bool discretize_by_time=false)
dwa_planner.h
base_local_planner::SimpleScoredSamplingPlanner::findBestTrajectory
bool findBestTrajectory(Trajectory &traj, std::vector< Trajectory > *all_explored=0)
base_local_planner::MapGridCostFunction::setTargetPoses
void setTargetPoses(std::vector< geometry_msgs::PoseStamped > target_poses)
sensor_msgs::PointCloud2Iterator
dwa_local_planner::DWAPlanner::path_distance_bias_
double path_distance_bias_
Definition: dwa_planner.h:187
base_local_planner::Trajectory::cost_
double cost_
dwa_local_planner::DWAPlanner::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Definition: dwa_planner.cpp:242
dwa_local_planner::DWAPlanner::stop_time_buffer_
double stop_time_buffer_
How long before hitting something we're going to enforce that the robot stop.
Definition: dwa_planner.h:186
dwa_local_planner::DWAPlanner::DWAPlanner
DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util)
Constructor for the planner.
Definition: dwa_planner.cpp:153
base_local_planner::LocalPlannerUtil::getGlobalFrame
std::string getGlobalFrame()
base_local_planner::Trajectory::yv_
double yv_
dwa_local_planner::DWAPlanner::forward_point_distance_
double forward_point_distance_
Definition: dwa_planner.h:193
base_local_planner::LocalPlannerUtil::getCostmap
costmap_2d::Costmap2D * getCostmap()
dwa_local_planner::DWAPlanner::goal_distance_bias_
double goal_distance_bias_
Definition: dwa_planner.h:187
ROS_WARN
#define ROS_WARN(...)
dwa_local_planner::DWAPlanner::path_costs_
base_local_planner::MapGridCostFunction path_costs_
Definition: dwa_planner.h:211
dwa_local_planner::DWAPlanner::generator_
base_local_planner::SimpleTrajectoryGenerator generator_
Definition: dwa_planner.h:208
dwa_local_planner::DWAPlanner::updatePlanAndLocalCosts
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.
Definition: dwa_planner.cpp:278
base_local_planner::OscillationCostFunction::resetOscillationFlags
void resetOscillationFlags()
dwa_local_planner::DWAPlanner::alignment_costs_
base_local_planner::MapGridCostFunction alignment_costs_
Definition: dwa_planner.h:214
dwa_local_planner::DWAPlanner::planner_util_
base_local_planner::LocalPlannerUtil * planner_util_
Definition: dwa_planner.h:184
base_local_planner::OscillationCostFunction::setOscillationResetDist
void setOscillationResetDist(double dist, double angle)
base_local_planner::MapGridVisualizer::initialize
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)
dwa_local_planner
Definition: dwa_planner.h:65
sensor_msgs::PointCloud2Modifier
dwa_local_planner::DWAPlanner::sim_period_
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
Definition: dwa_planner.h:190
dwa_local_planner::DWAPlanner::frame_id_
std::string frame_id_
Definition: dwa_planner.h:198
base_local_planner::MapGridVisualizer::publishCostCloud
void publishCostCloud(const costmap_2d::Costmap2D *costmap_p_)
base_local_planner::Trajectory
base_local_planner::SimpleScoredSamplingPlanner::scoreTrajectory
double scoreTrajectory(Trajectory &traj, double best_traj_cost)
base_local_planner::MapGridCostFunction::setStopOnFailure
void setStopOnFailure(bool stop_on_failure)
dwa_local_planner::DWAPlanner::result_traj_
base_local_planner::Trajectory result_traj_
Definition: dwa_planner.h:191
tf2::Quaternion
costmap_2d::Costmap2D::getResolution
double getResolution() const
dwa_local_planner::DWAPlanner::obstacle_costs_
base_local_planner::ObstacleCostFunction obstacle_costs_
Definition: dwa_planner.h:210
base_local_planner::LocalPlannerUtil::getCurrentLimits
LocalPlannerLimits getCurrentLimits()
dwa_local_planner::DWAPlanner::reconfigure
void reconfigure(DWAPlannerConfig &cfg)
Reconfigures the trajectory planner.
Definition: dwa_planner.cpp:87
base_local_planner::LocalPlannerLimits::min_vel_trans
double min_vel_trans
ROS_INFO
#define ROS_INFO(...)
costmap_2d::Costmap2D::getCost
unsigned char getCost(unsigned int mx, unsigned int my) const
base_local_planner::Trajectory::thetav_
double thetav_
t
geometry_msgs::TransformStamped t
base_local_planner::MapGridCostFunction::setXShift
void setXShift(double xshift)
ros::NodeHandle
angles.h
dwa_local_planner::DWAPlanner::oscillation_costs_
base_local_planner::OscillationCostFunction oscillation_costs_
Definition: dwa_planner.h:209
ros::Time::now
static Time now()
dwa_local_planner::DWAPlanner::getCellCosts
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.
Definition: dwa_planner.cpp:224


dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:33