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

Difference between DWA local_planner and TEB local_planner

asked 2017-10-30 09:45:28 -0500

Mobile_robot gravatar image

updated 2017-10-30 09:46:31 -0500

Hi there,

I'm new in ROS nav_stack. Currently, I'm working on navigation of a mobile robot (vehicular robot) and I am searching the "best" local planner for our application.

Currently, we are using TEB local planner and I am working on improving its performance of avoiding obstacles (dynamic and static obstacles).

But still it is not clear for me that beside of the mathematical algorithm to find the most optimized path, what is the difference between the DWA local planner (or the base local planner) and the TEB local planner? According to this question, they should have the same approach. Thus, I would like to know for a user that asks the robot to go from point A to point B, what is the difference, in user point of view, and the developer point of view, between the TEB local planner and the DWA local planner?

Also, according to this question there is no local planner for Dynamic obstacles and the only solution is to work on additional tracking and motion prediction on top of the costmap in TEB and DWA local planner. Do you have any other idea?

Thanks in advance,

edit retag flag offensive close merge delete

Comments

hello, have you found a solution for this? I would like to know as well. Please share if you do.

aarontan gravatar image aarontan  ( 2018-06-07 15:50:44 -0500 )edit

Not yet, unfortunately.

Mobile_robot gravatar image Mobile_robot  ( 2018-07-05 09:33:28 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
36

answered 2018-06-08 07:57:12 -0500

croesmann gravatar image

updated 2018-06-11 01:44:51 -0500

Hi,

the overall idea of both DWA and TEB is to predict/plan the motion of the robot along a given horizon while minimizing a given objective function and while adhering to kinodynamic constraints of the robot. After commanding only the first control action to the robot, the whole prediction/optimization is repeated. This principle is well known in control theory as receding horizon control or model predictive control. However, computing the optimal solution is computationally demanding and thus both approaches approximate the optimal solution in different ways and the actual optimization strategy differs.

Dynamic Window Approach (DWA)

The DWA performs a sample based optimization. It samples a control action in the feasible velocity space (usually a translational/angular velocity pair) and rolls out the trajectory for these particular sampled actions. Rollout means, that the trajectories are simulated according to the specified horizon length based on the robots motion model. One important detail is: the control action is kept constant along the whole prediction horizon. Hence it cannot predict motion reversals etc. After rolling out predictions for all samples, the best candidate is selected based on a specified cost function and constraints (including distance to global path, smoothness, obstacle clearance, ...).

Consequently, DWA includes two simplifications in order to keep the computation times low while achieving a certain amount of control performance. I will not go into the details regarding stability and recursive feasibility arising from the inherent suboptimality, but the approach works pretty well for differential-drive and omnidirectional robots. A benefit is, that the cost function can be non-smooth and so it is well-suited for grid-based evaluations. E.g. trajectories can be rasterized into the costmap in order to evaluate the cost (considering lethal grid cells and inflation cost). Furthermore, the DWA does not get stuck in local minima based on its initialization (of course, the robot can still get stuck due to a limited horizon length and fewer degrees of freedom in terms of control actions). Since DWA assumes constant control actions along the prediction horizon, the control of car-like robots is rather limited. There are some basic extensions to restrict the velocity search space to car-like compatible actions. But motion reversals are still not subject to optimization and hence parking maneuvers in confined spaces are intractable. Note, of course, motion reversals can occure during closed-loop control, but they are not part of the open-loop solution / prediction.

In Summary:

  • Suboptimal solutions without motion reversals (control actions are kept constant along the prediction horizon)
  • Well-suited for diff-drive/omnidirectional robots, but not for car-like robots
  • Supports non-smooth cost functions

Timed-Elastic-Band (TEB)

The TEB primarily tries to seek for the time-optimal solution, but you can also configure it for global reference path fidelity. The approach discretzies the trajectory along the prediction horizon in terms of time and applies a continuous numerical optimization scheme. Consequently, depending on the discretization resolution, the degrees of freedom along the prediciton horizon can be very high and motion reversals are supported. Furthermore, the constrained optimization problem is ... (more)

edit flag offensive delete link more
5

answered 2020-04-30 04:18:35 -0500

Rufus gravatar image

updated 2020-05-11 02:33:57 -0500

Just leaving my 2 cents here...

Strictly speaking from my experience using the 2 planners on a diff drive robot.

It seems TEB provides more "intelligent" paths around obstacles whilst DWA sometimes get stuck at a local optima, especially when the the path around the obstacle requires the robot to temporarily move away from the goal.

Also I found that configuring DWA to perform rotation on spot properly was a pain, with tuning to the point that it felt like it was a hack, while TEB achieved it out of the box. DWA seemed to struggle particularly when the current orientation of the robot is around 90 degrees to the global plan it needs to move towards.

However, I did have to tune TEB to reduce the computation cost in order to have it running at a reasonable frequency. (I was running on a medium-sized local costmap and TEB was running at 1Hz out of the box, though other factors may have affected it)

Tweaks I made to have it work at a reasonable frequency (I was relying on the global planner for more sophisticated obstacle avoidance to I could afford less exploring in the local space):

no_inner_iterations: 1
no_outer_iterations: 1
enable_homotopy_class_planning: false
max_number_classes: 1

I might be doing something wrong with both planners, would gladly discuss further / appreciate any pointers!

edit flag offensive delete link more

Comments

1 Hz out of the box sounds really slow to me. Should be between 10 and 100 Hz on a reasonably recent i5/i7 CPU. What specs do you have? Also the costmap resolution is important as each occupied cell is treated as single obstacle by default.

croesmann gravatar image croesmann  ( 2020-04-30 04:24:55 -0500 )edit

I was running it on a fairly powerful i9 CPU, on a 160x160 costmap.

Rufus gravatar image Rufus  ( 2020-05-03 20:35:03 -0500 )edit
2

Hi, yes I can definitely verify the rotation problem with DWA planner. It was so hard to get it to perform spot turns and always seemed to prefer moving back and forth like a car until it aligned itself to the new orientation, which feels much slower than a spot turn. It achieved less than 5Hz for DWA planner on an intel celeron based SBC that was mounted on my small robot (many other nodes were running on the SBC as well).

hashirzahir gravatar image hashirzahir  ( 2020-05-03 22:36:51 -0500 )edit

I'm facing completely the same issues, as @Rufus mentioned. Especially when you don't want robot moving backward and setting min_vel_trans to positive, things never get resolved. Also, no in-place velocity theta offered, as It's offered in TrajectoryPlannerROS. Btw, there's something called DWB_local_planner, maybe this could be helpful if you are still considering going for DWA.

artemiialessandrini gravatar image artemiialessandrini  ( 2020-05-11 02:27:03 -0500 )edit

@artemiialessandrini I updated my answer on the tweaks I made to have it work at a higher frequency, not sure if it would be helpful for you. Also, I believe the documentation states that enforcing forward motion is done by penalizing backward motion via the weight_kinematics_forward_drive parameter.

Rufus gravatar image Rufus  ( 2020-05-11 02:36:21 -0500 )edit

Thanks for a quick response, @Rufus Initially I was talking about dwa_local_planner, but I'm likely to migrate to teb_local_planner, since I'm not satisfied with dwa performance, your advice is more than helpful!

artemiialessandrini gravatar image artemiialessandrini  ( 2020-05-11 03:12:09 -0500 )edit

@Rufus Hi, it seems you have a decent grasp on teb_local_planner, could you please spare some of your time to help me with this question here

distro gravatar image distro  ( 2022-01-11 21:44:52 -0500 )edit

Question Tools

8 followers

Stats

Asked: 2017-10-30 09:45:28 -0500

Seen: 12,190 times

Last updated: May 11 '20