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

The Crazy DWAPlannerROS is confusing on global path's some parts

asked 2016-03-11 10:25:33 -0600

Orhan gravatar image

updated 2016-03-23 07:54:10 -0600

Hi Roboticists,

Here is video, I'm using dwa_local_planner and it confuses at near to goal position. Especially, when goal point's X and footprint center's X are close, it confuses.

Changed /move_base/base_local_planner/dwa_local_planner's logger level from Info to Debug and now, rqt_console says something at struggling:

...
Velocity -0.600, 0.000, 0.189 discarded by cost function  0 with cost: -5.000000
Velocity -0.600, 0.000, 0.063 discarded by cost function  0 with cost: -5.000000
Evaluated 62 trajectories, found 32 valid
Velocity 0.600, 0.000, 1.200 discarded by cost function  0 with cost: -5.000000
Velocity 0.600, 0.000, 1.074 discarded by cost function  0 with cost: -5.000000
Velocity 0.600, 0.000, 0.947 discarded by cost function  0 with cost: -5.000000
Velocity 0.600, 0.000, 0.821 discarded by cost function  0 with cost: -5.000000
...

Here is new video.

Changed use_dwa parameter to false and now, only latest struggling on the end of the path (at very close to goal) problem solved.

At struggling, I'm tuning path and goal distance parameters and robot is surviving from that point. And also tuning acceleration and velocity parameters on stuck point can survive robot.

I've replaced footprint to square but the result didn't change. Here is dwa_local_planner's parameters:

DWAPlannerROS:
  # Robot Configuration Parameters
  acc_lim_x: 10.0 # (double, default: 2.5) The x acceleration limit of the robot in meters/sec^2
  acc_lim_y: 0.0 # (double, default: 2.5)
  acc_lim_theta: 20.0 # (double, default: 3.2)
  acc_limit_trans: 1.0 # 
  max_trans_vel: 0.6 # (double, default: 0.55)
  min_trans_vel: 0.02 # (double, default: 0.1)
  trans_stopped_vel: 0.02 # 
  rot_stopped_vel: 0.02 # 
  max_vel_x: 0.6 # (double, default: 0.55)
  min_vel_x: -0.6 # (double, default: 0.0)
  max_vel_y: 0.0 # (double, default: 0.1)
  min_vel_y: 0.0 # (double, default: -0.1)
  max_rot_vel: 1.2 # (double, default: 1.0)
  min_rot_vel: 0.02 # (double, default: 0.4)
  # Goal Tolerance Parameters
  yaw_goal_tolerance: 0.01 # (double, default: 0.05) 
  xy_goal_tolerance: 0.07 # (double, default: 0.10)
  latch_xy_goal_tolerance: false # (bool, default: false)
  # Forward Simulation Parameters
  sim_time: 0.5
  sim_granularity: 0.05
  angular_sim_granularity: 0.05
  vx_samples: 3 # (integer, default: 3)
  vy_samples: 1 # (integer, default: 10)
  vtheta_samples: 20 # (integer, default: 20)
  # controller_frequency: 10.0 # (double, default: 20.0)
  # Trajectory Scoring Parameters
  path_distance_bias: 32.0 # (double, default: 32.0)
  goal_distance_bias: 24.0 # (double, default: 24.0)
  occdist_scale: 0.01 # (double, default: 0.01)
  # pdist_scale: 0.75  
  # gdist_scale: 0.8 
  forward_point_distance: 0.0 # 2.0 # 0.325 
  stop_time_buffer: 0.2 # (double, default: 0.2)
  scaling_speed: 0.25 # (double, default: 0.25)
  max_scaling_factor: 0.2 # (double, default: 0.2) 
  use_dwa: true
  #Oscillation Prevention Parameters
  oscillation_reset_dist: 0.05 # (double, default: 0.05)
  oscillation_reset_angle: 0.05 # 
  prune_plan: false # (bool, default: true) 
TrajectoryPlannerROS:
  yaw_goal_tolerance: 0.01
  acc_lim_th: 10.0
  max_rotational_vel: 1.2
  min_in_place_rotational_vel: 0.02
  holonomic_robot: false
  meter_scoring: true

Thank you.

UPDATE5: removed screenhots, Shortened question, added new temporary solution (only for some cases).

edit retag flag offensive close merge delete

Comments

Any answer / response / help will be appreciated.

Orhan gravatar image Orhan  ( 2016-03-15 08:18:07 -0600 )edit
1

you can try to increase oscillation_reset_dist and/or oscillation_reset_angle

DavidN gravatar image DavidN  ( 2016-03-17 00:02:15 -0600 )edit

Thank you bro but increasing or decreasing this parameters doesn't make sense, I've tried this before :/

Orhan gravatar image Orhan  ( 2016-03-17 01:41:35 -0600 )edit
1

Can you visualize the costmap via rviz and post a screenshot here? I usually had the same problem if the local goal was at 90 degrees compared to robot orientation.

DavidN gravatar image DavidN  ( 2016-03-17 03:23:32 -0600 )edit

I'm adding screenshots with different costmap parameters. If you usually had the same problem, please upvote and follow question for more visitors.

Orhan gravatar image Orhan  ( 2016-03-17 03:51:38 -0600 )edit
1

Setting latch_xy_goal_tolerance will keep it from doing anything other than rotating in place once it reaches the goal.

ahendrix gravatar image ahendrix  ( 2016-03-17 13:08:25 -0600 )edit
1

Might also want to try increasing the forward_point_distance and/or adjusting the scaling_speed.

ahendrix gravatar image ahendrix  ( 2016-03-17 13:12:05 -0600 )edit

Thank you Sir. I've just tried all combinations of your suggestions. But not worked, only sometimes rescuing from stuck. And I can recover robot from stuck point via adjusting path-goal distance parameters. But it rescuing with lazy parameters and needs changing these parameters dynamically.

Orhan gravatar image Orhan  ( 2016-03-17 15:14:10 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-03-23 07:53:45 -0600

Orhan gravatar image

updated 2016-03-23 07:55:13 -0600

After 12 days and 13 question revisions, finally, I found solution when I was poking rqt_reconfigure :)

~planner_frequency (double, default: 0.0)

The rate in Hz at which to run the global planning loop. If the frequency is set to 0.0, the global planner will only run when a new goal is received or the local planner reports that its path is blocked. New in navigation 1.6.0

Changed /move_base/planner_frequency from 0.0 to 10.0.

Now It doesn't stuck with its new plan. But I think It's still an issue.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-03-11 10:25:33 -0600

Seen: 1,184 times

Last updated: Mar 23 '16