ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
11

dwa_planner vs. base_local_planner

asked 2011-07-25 08:24:34 -0500

KruseT gravatar image

The navigation stack contains the trajectory planner and the dwa local planner. Which one should one rather use? Which one will most effort in the future go into?

The wiki provides only very sparse information about those two, and from it it seems strange that the two planners don't share more common code. Also it seems one copied a lot from the other, so there is a lot of duplicate similar code anyway, which for me would be a reason to unify the sources, so that bugfixes and improvements to one also affect the other.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
29

answered 2011-07-25 13:51:15 -0500

eitan gravatar image

I'll try to answer your questions with a set of bullets below:

  • The dwa_local_planner supports velocity constraints specified in x,y, and theta while the base_local_planner only supports constraints specified in x and theta. There is some support for y velocities, but users are limited to a pre-specified list of valid y velocity commands. This makes the dwa_local_planner a better choice for robots that are holonomic or pseudo-holonomic because it allows for better sampling of the velocity space.

  • The dwa_local_planner is essentially a re-write of the base_local_planner's DWA (Dynamic Window Approach) option. The code is, in my opinion, a lot cleaner and easier to understand, particularly in the way that trajectories are simulated. I believe that much of the overlapping code between the two packages is factored out and shared. However, its true that there is some more work that could be done to pull out common functionality. For applications that use the DWA approach for local planning, the dwa_local_planner is probaly the best choice.

  • Robots with low acceleration limits may wish to use Trajectory Rollout over DWA. This option is only available through the base_local_planner package. Documentation on the differences between Trajectory Rollout and DWA is available here.

  • Both the base_local_planner and dwa_local_planner packages are actively maintained and stable though no new features are planned for either at the moment. As of the electric release, both planners can be tuned via dynamic_reconfigure.

edit flag offensive delete link more

Comments

Does this remain true? Both maintained.

"The groovy release of ROS includes a new implementation of the dwa_local_planner package. The implementation attempts to be more modular, to allow easier creation of custom local planners while reusing a lot of code." http://wiki.ros.org/base_local_planne

Mr-Yellow gravatar image Mr-Yellow  ( 2015-05-23 22:07:05 -0500 )edit
4

answered 2012-05-21 22:14:47 -0500

KruseT gravatar image

Having looked at the code in detail, there are some more minor differences. The trajectory_planner_ros considers trajectories with positive x velocities and in place rotations first. And only if no valid trajectory is found that way does it consider strafing. This helps for robots which have obstacle sensors in front mostly, like the PR2. Also there is a mechanism to unstuck the robot by moving backwards discarding map obstacles in the trajectory_planner_ros.

In my personal opinion, the dwa_planner is the one that should be used when you are not sure, as the code base is cleaner and easier to bugfix and extend.

edit flag offensive delete link more

Question Tools

9 followers

Stats

Asked: 2011-07-25 08:24:34 -0500

Seen: 15,165 times

Last updated: May 21 '12