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

robot unable to rotate in place for dwa_local_planner

asked 2015-06-09 16:30:36 -0600

Naman gravatar image

updated 2015-12-01 15:18:07 -0600

Hi all,

*UPDATED*

I am using dwa_local_planner as a local planner and is having some issues while the robot is turning (that is, rotating in place). The robot is able to go forward without any issues and is able to reach the goal within xy_tolerance and is able to rotate in place to correct its orientation so that it is within yaw_goal_tolerance. I have specified following parameters:

max_rot_vel: 1.0
min_rot_vel: 0.8

But I am having a problem when the robot has to go to the second goal once robot reaches the first goal and has to turn in place to move towards the second goal. The dwa_local_planner sends linear.x = 0.0 and angular.z = 0.31 in this case and hence the robot is unable to turn in place. This happens when min_trans_vel = 0.0. If I specify min_trans_vel as 0.1 or 0.2, then the robot is able to turn but in some cases, when the robot has to turn to go to the second goal, it is not able to turn and keeps on going straight at min_trans_vel till it reaches the wall and stops. It does not seem to have enough rotational velocity component.

I have specified min_rot_vel: 0.8 but it looks like the dwa_local_planner is not considering that. Is there any parameter similar to min_in_place_rotational_vel (which is there for TrajectoryPlannerROS) in case of dwa_local_planner which can be modified for in place rotation in case of dwa_local_planner? Or, does anyone have any idea why is this happening and how can it be solved?

dwa_local_planner_params.yaml

DWAPlannerROS:
  acc_lim_x: 2.0
  acc_lim_y: 0
  acc_lim_th: 3.0
  max_trans_vel: 0.5
  min_trans_vel: 0.0
  max_vel_x: 0.5
  min_vel_x: 0.0
  max_vel_y: 0
  min_vel_y: 0
  max_rot_vel: 1.0
  min_rot_vel: 0.8

  yaw_goal_tolerance: 0.17
  xy_goal_tolerance: 0.15
  latch_xy_goal_tolerance: false

  sim_time: 1.5
  sim_granularity: 0.025
  vx_samples: 10
  vy_samples: 0
  vtheta_samples: 20
  controller_frequency: 10
  penalize_negative_x: true

  path_distance_bias: 1.0
  goal_distance_bias: 0.8
  occdist_scale: 0.01
  forward_point_distance: 0.325
  stop_time_buffer: 0.2
  scaling_speed: 0.25
  max_scaling_factor: 0.2

  oscillation_reset_dist: 0.05

  prune_plan: false  

  sim_period: 0.1
  rot_stopped_vel: 0.01
  trans_stopped_vel: 0.01

Please let me know if you need more information from me. Any help will be appreciated.

Thanks in advance.
Naman Kumar

edit retag flag offensive close merge delete

Comments

So the robot always has to be rotating? What kind of physical setup is that?

David Lu gravatar image David Lu  ( 2015-06-09 19:37:58 -0600 )edit

Sorry if the question is not clear. I meant that robot is able to go straight without any issues but when it reaches the goal and has to correct its orientation, dwa_local_planner does not send enough angular velocity and the robot does not turn, I have improved/updated the original question. TIA

Naman gravatar image Naman  ( 2015-06-09 20:03:26 -0600 )edit

So your driver won't rotate if you send a velocity less than 0.8?

David Lu gravatar image David Lu  ( 2015-06-09 20:40:15 -0600 )edit

@David Lu yeah..if the velocity (angular.z) is less than 0.8 or 0.7, the robot does not rotate. So therefore I set minimum velocity as 0.8.

Naman gravatar image Naman  ( 2015-06-09 21:05:58 -0600 )edit

I also have the same problem,my robot does not like slow velocities,isnt it just a problem with the controller ?

miguel gravatar image miguel  ( 2015-07-23 12:23:39 -0600 )edit

3 Answers

Sort by ยป oldest newest most voted
4

answered 2015-12-29 19:56:52 -0600

updated 2015-12-29 19:59:39 -0600

We encountered similar problems recently. DWA cannot perform a rotate in spot motion. It will always trying to perform an arc motion, combining trans and rot velocity. However, with fined tuned parameters, it will try to U-turn in a very small radius.

Firstly, as you updated, do not set min_trans_vel to 0. I have some warnings in my yaml file.

# Warning! # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities # are non-negligible and small in place rotational velocities will be created.

After that, you may would like trying to tune

path_distance_bias: 1.0
goal_distance_bias: 0.8
occdist_scale: 0.01

These are most important three parameters mentioned in Fox's paper.

By maximizing solely the clearance and the velocity, the robot would always travel into free space but there would be no incentive to move towards a goal location. By solely maximizing the target heading the robot quickly would get stopped by the first obstacle that blocks its way, unable to move around it.

Hope this helps.

edit flag offensive delete link more
1

answered 2015-06-15 10:55:09 -0600

David Lu gravatar image

Try setting use_dwa to False.

edit flag offensive delete link more

Comments

I have updated my question based on your answer.. Please have a look.. TIA

Naman gravatar image Naman  ( 2015-06-18 09:06:50 -0600 )edit
0

answered 2021-07-29 04:36:18 -0600

HappySamuel gravatar image

I did some modifications to DWA local planner and Base local planner. My modified DWA local planner currently support to navigate the robot to the a goal that is opposite to its orientation. I have tested it in Gazebo and also on my real Robot.

I totally made 4 changes to both DWA local planner and Base local planner. The files I modified are:

  1. dwa_local_planner/include/dwa_local_planner/dwa_planner_ros.h
  2. dwa_local_planner/src/dwa_planner_ros.cpp
  3. base_local_planner/include/base_local_planner/latched_stop_rotate_controller.h
  4. base_local_planner/src/latched_stop_rotate_controller.cpp

You can refer to the changes of my fork of navigation stack:

https://github.com/HappySamuel/naviga...

I have marked the changes i added/modified with //SAMUEL in those files.

Hope this can help to solve your issue.

edit flag offensive delete link more

Comments

Your answer helped me a lot. But, I can't find the isHeadingCorrectionNeeded() method in your navigation stack source. What to check in isHeadingCorrectionNeeded() method?

dyha34 gravatar image dyha34  ( 2021-09-08 02:31:07 -0600 )edit

Hi dyha34

Thanks you for pointing out, i missed out that function, i just added the function back. You can try out, it's located at the same repository. The changes is dated on 14Sept2021.

Best, Samuel

HappySamuel gravatar image HappySamuel  ( 2021-09-13 23:19:02 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2015-06-09 16:30:36 -0600

Seen: 4,664 times

Last updated: Dec 29 '15