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

move_base planning to a Goal

asked 2012-11-11 06:10:43 -0500

Ammar gravatar image

updated 2012-11-12 02:13:24 -0500

Lorenz gravatar image

Hello All, I am using move_base to send simple goals to a robot within stage. Is it possible for the robot to execute goals that are beyond its current laser range? For example it executes goals, that are in a certain local vicinity, perfectly. However for goals on the other end of the map, it is unable to plan a path. It keeps giving me the error: Aborting because a valid plan could not be found. Even after executing all recovery behaviors

when the goals are not within the range of its ranger. I am publishing a map of the environment as well. Does anyone know how to use move_base for distant goals? Thanks

EDIT 1: To be honest I simply stole the move_base configurations from the navigation_stage package from the navigation-tutorials stack. Here are the files:

costmap_common_params.yaml:

origin_z: 0.0
z_resolution: 0.2
z_voxels: 10
unknown_threshold: 9
mark_threshold: 0

transform_tolerance: 0.3

obstacle_range: 2.5
max_obstacle_height: 2.0
raytrace_range: 3.0

footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]]
footprint_padding: 0.01

inflation_radius: 0.55
cost_scaling_factor: 10.0

lethal_cost_threshold: 100

observation_sources: base_scan
base_scan: {data_type: LaserScan, expected_update_rate: 0.4,
  observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}

local_costmap_param.yaml -

local_costmap:
  publish_voxel_map: true

  global_frame: odom
  robot_base_frame: base_link

  update_frequency: 5.0
  publish_frequency: 2.0

  static_map: false
  rolling_window: true
  width: 6.0
  height: 6.0
  resolution: 0.025
  origin_x: 0.0
  origin_y: 0.0

global_costmap_params.yaml -

global_costmap: 
  global_frame: /map
  robot_base_frame: base_link

  update_frequency: 5.0
  publish_frequency: 0.0

  static_map: true
  rolling_window: false

  footprint_padding: 0.02

base_local_planner.yaml -

TrajectoryPlannerROS:
  acc_lim_th: 3.2 
  acc_lim_x: 2.5
  acc_lim_y: 2.5

  max_vel_x: 0.65
  min_vel_x: 0.1
  max_rotational_vel: 1.0
  min_in_place_rotational_vel: 0.4

  escape_vel: -0.1

  holonomic_robot: true

  y_vels: [-0.3, -0.1, 0.1, -0.3]

  xy_goal_tolerance: 0.1
  yaw_goal_tolerance: 0.05

  sim_time: 1.7
  sim_granularity: 0.025
  vx_samples: 3
  vtheta_samples: 20

  goal_distance_bias: 0.8
  path_distance_bias: 0.6
  occdist_scale: 0.01
  heading_lookahead: 0.325

  dwa: true

  oscillation_reset_dist: 0.05

  prune_plan: true
edit retag flag offensive close merge delete

Comments

Probably, something with your configuration is wrong. move_base shouldn't have any problems planning paths as long as there exists one. Can you edit your post and add your move_base configuration?

Lorenz gravatar image Lorenz  ( 2012-11-11 07:28:18 -0500 )edit

Are you sure that there exist valid paths in your map? Maybe there are some tight doors and the robot is too big to drive through?

Lorenz gravatar image Lorenz  ( 2012-11-12 02:15:31 -0500 )edit

When move_base finds a map being published, it uses that to plan a path to goal right? The reason, I ask is I have used move_base previously to explore unknown spaces. And it would plan a path only within the visible region, even then.

Ammar gravatar image Ammar  ( 2012-11-12 02:48:36 -0500 )edit

So move_base should be able to plan in unknown space as well, if I set static map to false? Could you please elaborate more on the size and origin parameters? I really appreciate the help. I am unable to find description of the various parameters online.

Ammar gravatar image Ammar  ( 2012-11-12 03:31:37 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2012-11-12 02:50:42 -0500

Lorenz gravatar image

updated 2012-11-12 03:41:54 -0500

move_base can plan into unknown space if you do not use a static map as global costmap and set the map size and origin appropriately.

Normally, when using a static map, the size of the global costmap is set to the size of the map which normally is as small as possible in the default gmapping configuration and the global planner cannot plan outside this map. To make it work, you have two choices:

  1. Make your static map bigger, i.e. add a lot of unknown space around it. This can cost quite some memory though.

  2. Don't use a static map for planning, only the laser-based costmap created without SLAM. In that case, you need to make sure that the costmap is big enough to contain your goal point, for instance 100x100m. If you just set the size to 50x50m, the origin, i.e. the starting point of your odometry will be in one corner. Many laser scans will be outside and you can find plans only in one direction. To avoid that, you can set the origin of the map and move the point (0, 0) right in the middle of the costmap. The following configuration shows that:

x

global_costmap:
   global_frame: /map
   robot_base_frame: /base_link
   map_type: costmap
   update_frequency: 3.0
   publish_frequency: 0.0
   static_map: false
   transform_tolerance: 0.5
   width: 100
   height: 100
   resolution: 0.05
   origin_x: -50.0
   origin_y: -50.0
edit flag offensive delete link more

Comments

Awesome! That makes a lot of sense now. Just one last question. When I remove planning on the static map and not use map_server to publish, move_base says it is waiting on to find a transform between /base_link and /map. In stage I have ground truth pose, I would like move_base to use that. Thanks!

Ammar gravatar image Ammar  ( 2012-11-12 03:51:41 -0500 )edit

You might be able to use fake_localization, I'm not sure though. I would still just run map_server and amcl, it shouldn't interfere with move_base if you don't use a static costmap.

Lorenz gravatar image Lorenz  ( 2012-11-12 03:54:36 -0500 )edit

Hi... I am not sure what is exactly happening, though I get this error when I disable using a static map. "Waiting on transform from /robot_0/base_link to /map to become available before running costmap, tf error:" Do I need to manually publish to /tf or is there an easier way to specify? Thanks!

Ammar gravatar image Ammar  ( 2012-11-12 04:25:27 -0500 )edit
0

answered 2012-11-12 07:09:59 -0500

Ammar gravatar image

So I figured out why I was getting the "Waiting on transform from /robot_0/base_link to /map to become available before running costmap, tf error:"..... It was because I was launching move_base on a robot_0 namespace. However in my world file, I only had one robot and therefore topics were being published as /odom rather than /robot_0/odom, which is the case for having several robots.

Now, does anyone know how to get move_base to abort a goal beyond x secs, if it is just oscillating in place. I set the oscillation_timeout to 20.0. Even then the robot does not abort its goal and keeps oscillating in place? Thanks!

edit flag offensive delete link more

Comments

1

For subsequent questions, it's best to open a new question. The robot should never oscillate in place. You might have to tune a few parameters to avoid that. If you are using actionlib, you could also write a node that monitors the robot and cancels the goal if it detects oscillation.

Lorenz gravatar image Lorenz  ( 2012-11-12 07:15:54 -0500 )edit

Sounds good! Thank you for all the help.

Ammar gravatar image Ammar  ( 2012-11-12 07:29:28 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2012-11-11 06:10:43 -0500

Seen: 8,855 times

Last updated: Nov 12 '12