DWA (Fox, Burgard, Thrun, 1997) is a reactive local controller that searches the dynamic-window of admissible (v, ω) commands at every control step, forward-simulates each candidate over a short horizon, and picks the one with the highest score. The score combines goal-direction, clearance from obstacles, and forward speed. DWA is not a global planner; in clutter it gets trapped in local minima. The honest framing (and the one used here) is that DWA tracks waypoints from a global planner like A* under the kinematic and dynamic constraints of a real robot.
At every control step the controller:
horizon sub-steps, checking collision against the world model and recording minimum clearance.J(v, ω) = α · target(v, ω) + β · clearance(v, ω) + γ · velocity(v, ω)
↳ negative distance ↳ min clearance ↳ forward speed
to next waypoint along trajectory
and apply the (v, ω) with the highest J for one control step. This implementation: 8 v-samples × 11 ω-samples = 88 trajectories per step, horizon = 6 sub-steps, dt = 0.4 s. Heading-error and a goal-direction term replace target distance when used as a free-running controller without waypoints; here we use waypoint distance because DWA is plumbed against an A* path.
The green trajectory below is DWA tracking A*'s waypoints on environment 0. The trajectory is smoother than A*'s grid-axial path because the controller respects the kinematic model. Where the A* path forces a sharp turn, the DWA trajectory rounds the corner.
| Environment | Outcome | Steps | Total compute | Path length |
|---|---|---|---|---|
| 0: scattered rectangles | success | 60 | 824 ms | 38.13 |
| 1: maze channels | stuck | 600 (cap) | 1785 ms | n/a |
| 2: bottleneck | success | 64 | 725 ms | 40.96 |
| 3: cluttered | success | 59 | 706 ms | 37.58 |
DWA on env 0, env 2, and env 3 produces shorter paths than A* on the same scenario (38.1 vs 39.9 on env 0): the kinematic smoothing recovers diagonal travel that the grid forces into stairstep moves. The maze (env 1) is DWA's natural failure mode: the windowed velocity search has no global view of the maze structure and the local cost surface has multiple equally-attractive headings, none of which thread the corridor.
The clearest demonstration of the local-vs-global tradeoff: DWA without waypoints fails on every one of these environments, regardless of cost-function tuning, because the controller cannot see past its dynamic window. Plug in A*'s waypoints and the same controller succeeds on three of four: the fourth (the maze) requires either a tighter waypoint cadence or a different controller entirely.
This is why production robot stacks (move_base, Nav2) layer DWA-style local controllers under a global planner, not in place of one.