dwb_local_planner.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <nav_core2/exceptions.h>
40 #include <nav_2d_utils/tf_help.h>
41 #include <nav_2d_msgs/Twist2D.h>
42 #include <dwb_msgs/CriticScore.h>
44 #include <algorithm>
45 #include <memory>
46 #include <string>
47 #include <utility>
48 #include <vector>
49 
50 namespace dwb_local_planner
51 {
52 
54  traj_gen_loader_("dwb_local_planner", "dwb_local_planner::TrajectoryGenerator"),
55  goal_checker_loader_("dwb_local_planner", "dwb_local_planner::GoalChecker"),
56  critic_loader_("dwb_local_planner", "dwb_local_planner::TrajectoryCritic")
57 {
58 }
59 
60 void DWBLocalPlanner::initialize(const ros::NodeHandle& parent, const std::string& name,
62 {
63  tf_ = tf;
64  costmap_ = costmap;
65  planner_nh_ = ros::NodeHandle(parent, name);
66 
67  // This is needed when using the CostmapAdapter to ensure that the costmap's info matches the rolling window
68  planner_nh_.param("update_costmap_before_planning", update_costmap_before_planning_, true);
69 
70  planner_nh_.param("prune_plan", prune_plan_, true);
71  planner_nh_.param("prune_distance", prune_distance_, 1.0);
72  planner_nh_.param("short_circuit_trajectory_evaluation", short_circuit_trajectory_evaluation_, true);
73  planner_nh_.param("debug_trajectory_details", debug_trajectory_details_, false);
75 
76  // Plugins
77  std::string traj_generator_name;
78  planner_nh_.param("trajectory_generator_name", traj_generator_name,
80  ROS_INFO_NAMED("DWBLocalPlanner", "Using Trajectory Generator \"%s\"", traj_generator_name.c_str());
81  traj_generator_ = std::move(traj_gen_loader_.createUniqueInstance(traj_generator_name));
82  traj_generator_->initialize(planner_nh_);
83 
84  std::string goal_checker_name;
85  planner_nh_.param("goal_checker_name", goal_checker_name, std::string("dwb_plugins::SimpleGoalChecker"));
86  ROS_INFO_NAMED("DWBLocalPlanner", "Using Goal Checker \"%s\"", goal_checker_name.c_str());
87  goal_checker_ = std::move(goal_checker_loader_.createUniqueInstance(goal_checker_name));
88  goal_checker_->initialize(planner_nh_);
89 
90  loadCritics(name);
91 }
92 
93 std::string DWBLocalPlanner::resolveCriticClassName(std::string base_name)
94 {
95  if (base_name.find("Critic") == std::string::npos)
96  {
97  base_name = base_name + "Critic";
98  }
99 
100  if (base_name.find("::") == std::string::npos)
101  {
102  for (unsigned int j = 0; j < default_critic_namespaces_.size(); j++)
103  {
104  std::string full_name = default_critic_namespaces_[j] + "::" + base_name;
105  if (critic_loader_.isClassAvailable(full_name))
106  {
107  return full_name;
108  }
109  }
110  }
111  return base_name;
112 }
113 
114 void DWBLocalPlanner::loadCritics(const std::string name)
115 {
116  planner_nh_.param("default_critic_namespaces", default_critic_namespaces_);
117  if (default_critic_namespaces_.size() == 0)
118  {
119  default_critic_namespaces_.push_back("dwb_critics");
120  }
121 
122  if (!planner_nh_.hasParam("critics"))
123  {
125  }
126 
127  std::vector<std::string> critic_names;
128  planner_nh_.getParam("critics", critic_names);
129  for (unsigned int i = 0; i < critic_names.size(); i++)
130  {
131  std::string plugin_name = critic_names[i];
132  std::string plugin_class;
133  planner_nh_.param(plugin_name + "/class", plugin_class, plugin_name);
134  plugin_class = resolveCriticClassName(plugin_class);
135 
136  TrajectoryCritic::Ptr plugin = std::move(critic_loader_.createUniqueInstance(plugin_class));
137  ROS_INFO_NAMED("DWBLocalPlanner", "Using critic \"%s\" (%s)", plugin_name.c_str(), plugin_class.c_str());
138  critics_.push_back(plugin);
139  plugin->initialize(planner_nh_, plugin_name, costmap_);
140  }
141 }
142 
143 bool DWBLocalPlanner::isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity)
144 {
145  if (goal_pose_.header.frame_id == "")
146  {
147  ROS_WARN_NAMED("DWBLocalPlanner", "Cannot check if the goal is reached without the goal being set!");
148  return false;
149  }
150 
151  // Update time stamp of goal pose
152  goal_pose_.header.stamp = pose.header.stamp;
153 
154  bool ret = goal_checker_->isGoalReached(transformPoseToLocal(pose), transformPoseToLocal(goal_pose_), velocity);
155  if (ret)
156  {
157  ROS_INFO_THROTTLE_NAMED(1.0, "DWBLocalPlanner", "Goal reached!");
158  }
159  return ret;
160 }
161 
162 void DWBLocalPlanner::setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose)
163 {
164  ROS_INFO_NAMED("DWBLocalPlanner", "New Goal Received.");
165  goal_pose_ = goal_pose;
166  traj_generator_->reset();
167  goal_checker_->reset();
168  for (TrajectoryCritic::Ptr critic : critics_)
169  {
170  critic->reset();
171  }
172 }
173 
174 void DWBLocalPlanner::setPlan(const nav_2d_msgs::Path2D& path)
175 {
176  pub_.publishGlobalPlan(path);
177  global_plan_ = path;
178 }
179 
180 nav_2d_msgs::Twist2DStamped DWBLocalPlanner::computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
181  const nav_2d_msgs::Twist2D& velocity)
182 {
183  std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results = nullptr;
185  {
186  results = std::make_shared<dwb_msgs::LocalPlanEvaluation>();
187  }
188 
189  try
190  {
191  nav_2d_msgs::Twist2DStamped cmd_vel = computeVelocityCommands(pose, velocity, results);
192  pub_.publishEvaluation(results);
193  return cmd_vel;
194  }
195  catch (const nav_core2::PlannerException& e)
196  {
197  pub_.publishEvaluation(results);
198  throw;
199  }
200 }
201 
202 void DWBLocalPlanner::prepare(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity)
203 {
205  {
206  costmap_->update();
207  }
208 
209  nav_2d_msgs::Path2D transformed_plan = transformGlobalPlan(pose);
210  pub_.publishTransformedPlan(transformed_plan);
211 
212  // Update time stamp of goal pose
213  goal_pose_.header.stamp = pose.header.stamp;
214 
215  geometry_msgs::Pose2D local_start_pose = transformPoseToLocal(pose),
216  local_goal_pose = transformPoseToLocal(goal_pose_);
217 
218  pub_.publishInputParams(costmap_->getInfo(), local_start_pose, velocity, local_goal_pose);
219 
220  for (TrajectoryCritic::Ptr critic : critics_)
221  {
222  if (!critic->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan))
223  {
224  ROS_WARN_NAMED("DWBLocalPlanner", "Critic \"%s\" failed to prepare", critic->getName().c_str());
225  }
226  }
227 }
228 
229 nav_2d_msgs::Twist2DStamped DWBLocalPlanner::computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
230  const nav_2d_msgs::Twist2D& velocity, std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results)
231 {
232  if (results)
233  {
234  results->header.frame_id = pose.header.frame_id;
235  results->header.stamp = ros::Time::now();
236  }
237 
238  prepare(pose, velocity);
239 
240  try
241  {
242  dwb_msgs::TrajectoryScore best = coreScoringAlgorithm(pose.pose, velocity, results);
243 
244  // Return Value
245  nav_2d_msgs::Twist2DStamped cmd_vel;
246  cmd_vel.header.stamp = ros::Time::now();
247  cmd_vel.velocity = best.traj.velocity;
248 
249  // debrief stateful critics
250  for (TrajectoryCritic::Ptr critic : critics_)
251  {
252  critic->debrief(cmd_vel.velocity);
253  }
254 
255  pub_.publishLocalPlan(pose.header, best.traj);
256  pub_.publishCostGrid(costmap_, critics_);
257 
258  return cmd_vel;
259  }
260  catch (const NoLegalTrajectoriesException& e)
261  {
262  nav_2d_msgs::Twist2D empty_cmd;
263  dwb_msgs::Trajectory2D empty_traj;
264  // debrief stateful scoring functions
265  for (TrajectoryCritic::Ptr critic : critics_)
266  {
267  critic->debrief(empty_cmd);
268  }
269  pub_.publishLocalPlan(pose.header, empty_traj);
270  pub_.publishCostGrid(costmap_, critics_);
271 
272  throw;
273  }
274 }
275 
276 dwb_msgs::TrajectoryScore DWBLocalPlanner::coreScoringAlgorithm(const geometry_msgs::Pose2D& pose,
277  const nav_2d_msgs::Twist2D velocity,
278  std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results)
279 {
280  nav_2d_msgs::Twist2D twist;
281  dwb_msgs::Trajectory2D traj;
282  dwb_msgs::TrajectoryScore best, worst;
283  best.total = -1;
284  worst.total = -1;
285  IllegalTrajectoryTracker tracker;
286 
287  traj_generator_->startNewIteration(velocity);
288  while (traj_generator_->hasMoreTwists())
289  {
290  twist = traj_generator_->nextTwist();
291  traj = traj_generator_->generateTrajectory(pose, velocity, twist);
292 
293  try
294  {
295  dwb_msgs::TrajectoryScore score = scoreTrajectory(traj, best.total);
296  tracker.addLegalTrajectory();
297  if (results)
298  {
299  results->twists.push_back(score);
300  }
301  if (best.total < 0 || score.total < best.total)
302  {
303  best = score;
304  if (results)
305  {
306  results->best_index = results->twists.size() - 1;
307  }
308  }
309  if (worst.total < 0 || score.total > worst.total)
310  {
311  worst = score;
312  if (results)
313  {
314  results->worst_index = results->twists.size() - 1;
315  }
316  }
317  }
319  {
320  if (results)
321  {
322  dwb_msgs::TrajectoryScore failed_score;
323  failed_score.traj = traj;
324 
325  dwb_msgs::CriticScore cs;
326  cs.name = e.getCriticName();
327  cs.raw_score = -1.0;
328  failed_score.scores.push_back(cs);
329  failed_score.total = -1.0;
330  results->twists.push_back(failed_score);
331  }
332  tracker.addIllegalTrajectory(e);
333  }
334  }
335 
336  if (best.total < 0)
337  {
339  {
340  ROS_ERROR_NAMED("DWBLocalPlanner", "%s", tracker.getMessage().c_str());
341  for (auto const& x : tracker.getPercentages())
342  {
343  ROS_ERROR_NAMED("DWBLocalPlanner", "%.2f: %10s/%s", x.second, x.first.first.c_str(), x.first.second.c_str());
344  }
345  }
346  throw NoLegalTrajectoriesException(tracker);
347  }
348 
349  return best;
350 }
351 
352 dwb_msgs::TrajectoryScore DWBLocalPlanner::scoreTrajectory(const dwb_msgs::Trajectory2D& traj,
353  double best_score)
354 {
355  dwb_msgs::TrajectoryScore score;
356  score.traj = traj;
357 
358  for (TrajectoryCritic::Ptr critic : critics_)
359  {
360  dwb_msgs::CriticScore cs;
361  cs.name = critic->getName();
362  cs.scale = critic->getScale();
363 
364  if (cs.scale == 0.0)
365  {
366  score.scores.push_back(cs);
367  continue;
368  }
369 
370  double critic_score = critic->scoreTrajectory(traj);
371  cs.raw_score = critic_score;
372  score.scores.push_back(cs);
373  score.total += critic_score * cs.scale;
374  if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score)
375  {
376  // since we keep adding positives, once we are worse than the best, we will stay worse
377  break;
378  }
379  }
380 
381  return score;
382 }
383 
384 double getSquareDistance(const geometry_msgs::Pose2D& pose_a, const geometry_msgs::Pose2D& pose_b)
385 {
386  double x_diff = pose_a.x - pose_b.x;
387  double y_diff = pose_a.y - pose_b.y;
388  return x_diff * x_diff + y_diff * y_diff;
389 }
390 
391 nav_2d_msgs::Path2D DWBLocalPlanner::transformGlobalPlan(const nav_2d_msgs::Pose2DStamped& pose)
392 {
393  nav_2d_msgs::Path2D transformed_plan;
394  if (global_plan_.poses.size() == 0)
395  {
396  throw nav_core2::PlannerException("Received plan with zero length");
397  }
398 
399  // let's get the pose of the robot in the frame of the plan
400  nav_2d_msgs::Pose2DStamped robot_pose;
401  if (!nav_2d_utils::transformPose(tf_, global_plan_.header.frame_id, pose, robot_pose))
402  {
403  throw nav_core2::PlannerTFException("Unable to transform robot pose into global plan's frame");
404  }
405 
406  transformed_plan.header.frame_id = costmap_->getFrameId();
407  transformed_plan.header.stamp = pose.header.stamp;
408 
409  // we'll discard points on the plan that are outside the local costmap
410  double dist_threshold = std::max(costmap_->getWidth(), costmap_->getHeight()) * costmap_->getResolution() / 2.0;
411  double sq_dist_threshold = dist_threshold * dist_threshold;
412  nav_2d_msgs::Pose2DStamped stamped_pose;
413  stamped_pose.header.frame_id = global_plan_.header.frame_id;
414 
415  for (unsigned int i = 0; i < global_plan_.poses.size(); i++)
416  {
417  bool should_break = false;
418  if (getSquareDistance(robot_pose.pose, global_plan_.poses[i]) > sq_dist_threshold)
419  {
420  if (transformed_plan.poses.size() == 0)
421  {
422  // we need to skip to a point on the plan that is within a certain distance of the robot
423  continue;
424  }
425  else
426  {
427  // we're done transforming points
428  should_break = true;
429  }
430  }
431 
432  // now we'll transform until points are outside of our distance threshold
433  stamped_pose.pose = global_plan_.poses[i];
434  transformed_plan.poses.push_back(transformPoseToLocal(stamped_pose));
435  if (should_break) break;
436  }
437 
438  // Prune both plans based on robot position
439  // Note that this part of the algorithm assumes that the global plan starts near the robot (at one point)
440  // Otherwise it may take a few iterations to converge to the proper behavior
441  if (prune_plan_)
442  {
443  // let's get the pose of the robot in the frame of the transformed_plan/costmap
444  nav_2d_msgs::Pose2DStamped costmap_pose;
445  if (!nav_2d_utils::transformPose(tf_, transformed_plan.header.frame_id, pose, costmap_pose))
446  {
447  throw nav_core2::PlannerTFException("Unable to transform robot pose into costmap's frame");
448  }
449 
450  ROS_ASSERT(global_plan_.poses.size() >= transformed_plan.poses.size());
451  std::vector<geometry_msgs::Pose2D>::iterator it = transformed_plan.poses.begin();
452  std::vector<geometry_msgs::Pose2D>::iterator global_it = global_plan_.poses.begin();
453  double sq_prune_dist = prune_distance_ * prune_distance_;
454  while (it != transformed_plan.poses.end())
455  {
456  const geometry_msgs::Pose2D& w = *it;
457  // Fixed error bound of 1 meter for now. Can reduce to a portion of the map size or based on the resolution
458  if (getSquareDistance(costmap_pose.pose, w) < sq_prune_dist)
459  {
460  ROS_DEBUG_NAMED("DWBLocalPlanner", "Nearest waypoint to <%f, %f> is <%f, %f>\n",
461  costmap_pose.pose.x, costmap_pose.pose.y, w.x, w.y);
462  break;
463  }
464  it = transformed_plan.poses.erase(it);
465  global_it = global_plan_.poses.erase(global_it);
466  }
468  }
469 
470  if (transformed_plan.poses.size() == 0)
471  {
472  throw nav_core2::PlannerException("Resulting plan has 0 poses in it.");
473  }
474  return transformed_plan;
475 }
476 
477 geometry_msgs::Pose2D DWBLocalPlanner::transformPoseToLocal(const nav_2d_msgs::Pose2DStamped& pose)
478 {
479  return nav_2d_utils::transformStampedPose(tf_, pose, costmap_->getFrameId());
480 }
481 
482 } // namespace dwb_local_planner
483 
484 
485 // register this planner as a LocalPlanner plugin
void addIllegalTrajectory(const nav_core2::IllegalTrajectoryException &e)
void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
Definition: publisher.cpp:162
std::map< std::pair< std::string, std::string >, double > getPercentages() const
#define ROS_INFO_NAMED(name,...)
pluginlib::ClassLoader< TrajectoryCritic > critic_loader_
#define ROS_WARN_NAMED(name,...)
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
void publishGlobalPlan(const nav_2d_msgs::Path2D plan)
Definition: publisher.cpp:213
void publishTransformedPlan(const nav_2d_msgs::Path2D plan)
Definition: publisher.cpp:218
std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle &nh)
bool transformPose(const TFListenerPtr tf, const std::string frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose, const bool extrapolation_fallback=true)
TrajectoryGenerator::Ptr traj_generator_
virtual void prepare(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)
Helper method for preparing for the core scoring algorithm.
double getSquareDistance(const geometry_msgs::Pose2D &pose_a, const geometry_msgs::Pose2D &pose_b)
void publishInputParams(const nav_grid::NavGridInfo &info, const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &velocity, const geometry_msgs::Pose2D &goal_pose)
Definition: publisher.cpp:235
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
nav_core2 initialization
nav_2d_msgs::Pose2DStamped goal_pose_
Saved Goal Pose.
Plugin-based flexible local_planner.
#define ROS_INFO_THROTTLE_NAMED(rate, name,...)
nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity ...
#define ROS_DEBUG_NAMED(name,...)
pluginlib::ClassLoader< GoalChecker > goal_checker_loader_
void loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Load parameters to emulate dwa_local_planner.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
pluginlib::ClassLoader< TrajectoryGenerator > traj_gen_loader_
void publishEvaluation(std::shared_ptr< dwb_msgs::LocalPlanEvaluation > results)
If the pointer is not null, publish the evaluation and trajectories as needed.
Definition: publisher.cpp:88
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setPlan(const nav_2d_msgs::Path2D &path) override
nav_core2 setPlan - Sets the global plan
bool isGoalReached(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 isGoalReached - Check whether the robot has reached its goal, given the current pose & velo...
nav_2d_msgs::Path2D global_plan_
Saved Global Plan.
TFSIMD_FORCE_INLINE const tfScalar & w() const
virtual void loadCritics(const std::string name)
Load the critic parameters from the namespace.
void publishLocalPlan(const std_msgs::Header &header, const dwb_msgs::Trajectory2D &traj)
Definition: publisher.cpp:153
std::vector< std::string > default_critic_namespaces_
std::string resolveCriticClassName(std::string base_name)
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic" ...
bool getParam(const std::string &key, std::string &s) const
virtual nav_2d_msgs::Path2D transformGlobalPlan(const nav_2d_msgs::Pose2DStamped &pose)
Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses...
#define ROS_ERROR_NAMED(name,...)
static Time now()
geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped &pose, const std::string &frame_id)
Thrown when all the trajectories explored are illegal.
std::vector< TrajectoryCritic::Ptr > critics_
std::shared_ptr< Costmap > Ptr
bool hasParam(const std::string &key) const
std::shared_ptr< tf::TransformListener > TFListenerPtr
virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D velocity, std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &results)
Iterate through all the twists and find the best one.
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped &pose)
Helper method to transform a given pose to the local costmap frame.
bool shouldRecordEvaluation()
Does the publisher require that the LocalPlanEvaluation be saved.
Definition: publisher.h:73
virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing.
void setGoalPose(const nav_2d_msgs::Pose2DStamped &goal_pose) override
nav_core2 setGoalPose - Sets the global goal pose
void initialize(ros::NodeHandle &nh)
Load the parameters and advertise topics as needed.
Definition: publisher.cpp:47
DWBLocalPlanner()
Constructor that brings up pluginlib loaders.


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun Jan 10 2021 04:08:34