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

Questions about the Dynamic Window Approach in ROS

asked 2011-05-23 14:16:14 -0600

updated 2011-05-24 04:13:37 -0600

Hi ROS community! Some questions:

  1. Is the use of the Base_Local_Planner with dwa=true deprecated? I've read that the dwa_local_planner is more efficient.
  2. What is the difference between TR and DWA in the base_local_planner? I understand the differences explained in the Wiki, however looking the trajectory_planner.cpp I don't see them. The only difference I see in the source code is that each choice defines the dynamic window velocity limits using sim_period or sim_time (which are both customizable parameters). I suspect dwa=true also works as the TR algorithm (with non-circular trajectories) but I would like a second opinion.
  3. The original DWA method is a goal-directed reactive method, while this implementation uses the path_cost (based on the MapGrid class) to evaluate the cost of each local trajectory. Is this method documented in any known paper or it is considered a minor modification of the method made by WG?

Thanks!

edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
2

answered 2011-05-25 05:33:41 -0600

eitan gravatar image

OK, you're actually right here because dt is being computed based on the simulation granularity, and not the controller_frequency. This is important for safety, but in some cases, you're right that it would lead to a very short TR style simulation before the desired velocity is reached. You're also right that the dwa_local_planner doesn't do this TR simulation up to the desired speed, though to be more correct in terms of simulating what the robot will actually do based on acceleration limits, it probably should. However, I doubt that this short TR simulation, or lack there of in the dwa_local_planner, has any noticeable affect on performance. If a change were to be made, it'd probably be most proper to have the dwa_local_planner use the acceleration limits when forward simulating to ramp up to its desired speed.

edit flag offensive delete link more
5

answered 2011-05-24 11:04:23 -0600

eitan gravatar image
  1. Running the base_local_planner with dwa=true isn't deprecated, its a valid configuration for the planner and should work. However, if you're considering using DWA, its probably worth checking out the dwa_local_planner package. The dwa_local_planner is a cleaner implementation of the algorithm (from a code structure standpoint) that includes other goodies like optionally scaling the robot's footprint as it drives and supporting dynamic_reconfigure.

  2. As explained on the wiki, the difference between DWA and TR lies in the velocity space they explore while rolling out trajectories. DWA has a more restricted space since it only considers velocities that can be reached over one simulation step, corresponding to the controller_frequency parameter which is used to calculate the sim_period variable you've referred to. TR, on the other hand, explores velocities achievable over the entire trajectory simulation specified by the sim_time parameter. So, if controller_frequency is set to 10Hz and sim_time is set to 1.5 seconds, DWA will explore the velocities reachable (given the acceleration limits of the robot) in the next 0.1 seconds, while TR will explore velocities reachable in 1.5 seconds.

  3. The original DWA paper, I believe, scores trajectories based on the robot's heading relative to a goal point, distance to obstacles, and velocity. The WG implementation scores based on distance to a goal point, distance from a planned path, and distance to obstacles. There are a number of papers on using DWA in conjunction with global plans to avoid local minima, but I'm not positive that any of them use this exact method for scoring. I do know that the TR paper linked from the base_local_planner wiki page uses this scoring method, and that's where it comes from.

edit flag offensive delete link more

Comments

Thanks Eitan. I understand that DWA uses the controller_period to set the dynamic window limits. However I interpret from the TrajectoryPlanner::generateTrajectory method that DWA is also simulated in a non-circular trajectory with "num_steps=sim_time/sim_granularity+0.5" times. What didn't I catch?
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-05-24 11:50:03 -0600 )edit
I say that they are non-circular trajectories since sampled velocities are also integrated (TrajectoryPlanner::computeNewVelocity) hence they are not constant during the simulation and then the trajectory is not circular. If we look at the dwa_local_planner we can see velocities are not integrated.
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-05-24 11:56:03 -0600 )edit
The limits imposed on the velocities for DWA should lead to it being held constant during the simulation which, I believe, will lead to a circular trajectory. The computeNewVelocity method will return vx_samp every time because it should be achieved instantaneously.
eitan gravatar image eitan  ( 2011-05-24 12:54:16 -0600 )edit
Thanks Eitan. I'm not sure yet. The velocity limits just define the velocity samples nearness. Since num_steps defines the dt if it is enough small (even for very slow velocities) v(t+1)=v(t)+a·dt <=v_sampled. Nonetheless I'll do a thorough analysis of the code and I'll do little debug to check it.
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-05-24 20:50:18 -0600 )edit
1

answered 2011-05-24 22:57:34 -0600

Finally velocities are not constant even with dwa:true, so trajectories aren't circular. So dwa:true also executes the TR algorithm but in a shorter time. This does not happen in dwa_local_planner.

Try navigation_stage and modify the trajectory_planer.cpp before computeNewVelocitiess:

if(vx_samp!=vx_i && vx_i!=0) ROS_DEBUG("num_steps:%d, sampled candidate vel:%lf, step simvel: %lf",num_steps, vx_samp, vx_i );

edit flag offensive delete link more

Comments

I've read through the thread and I am now confused. So does setting dwa=true practically run dwa_local_planner or is it wrong? Thank you.

2ROS0 gravatar image 2ROS0  ( 2014-08-05 16:22:02 -0600 )edit

Question Tools

Stats

Asked: 2011-05-23 14:16:14 -0600

Seen: 2,864 times

Last updated: May 25 '11