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

static_layer gets deleted by obstacle_layer in global_costmap

asked 2019-02-20 06:56:35 -0500

mgruhler gravatar image

updated 2019-02-22 03:55:36 -0500

Previously (i.e. pre-hydro) it has been possible to have a global_costmap that takes in sensor data as well as the static map from the map_server. If I remember correctly, this allowed to have the sensor data "clear" data of the static map to plan through, e.g., doors that had been closed during mapping.

With the current system, I haven't been able to reproduce this behaviour. Even stranger: as soon as I add an obstacle_layer to the global_costmap (even without receiving any data on the configured sensor), the global_costmap simply doesn't receive any data at all. I.e. the robot plans the direct path to the goal, through whatever is set in the map_server.

I'm not sure if this is a configuration issue on my end, or if this is really something that is not possible with the layered costmap approach. Even if the "clearing" behaviour is hard to realize, my current system should end up with an "overlay" of the single layers. I.e. the static_layer should still show. This is also how I understand this paper by @David Lu.

I created a minimal example (see below). This example is stand-alone and doesn't depend on Gazebo or a robot.

Any hint to where I have made a mistake would be highly appreciated!


Results

The trick was really the combination_method parameter in combination with the track_unknown_space parameter.

(Note: I used some fake laser which simply published a circle with radius 3m at 1° angular resolution. Also, the images only show the robot_footprint and the resulting global_costmap)

  • I: The behaviour I experienced. static_layer gets completely overwritten by obstacle_layer
  • II: behaviour I wanted. static_layer gets only overwritten by obstacle_layer where there are actually some measurements (see the light blue traces along the rays. It is not free space, but you see the effect). If you plan a path, it tries to follow any observations, if possible, and only cross unkown space if required (leads to some zigzag behaviour along the rays of the scans)
  • III: default behaviour: obstacles present in either static_layer or obstacle_layer are used
  • IV: afair, same as III for the costmap, though planning will happen as in II.

Below some pictures of the different combinations:

I: combination_method: 0, track_unkown_space: false image description II: combination_method: 0, track_unkown_space: true image description III: combination_method: 1, track_unkown_space: false image description IV: combination_method: 1, track_unkown_space: true image description


Minimal Example

Put the following files in your home. You'll need a map to pass to the map_server as well as rviz with a proper configuration (map, global_costmap, maybe robot_footprint).

Play around with using the obstacle_layer in the global_costmap to see the different results.

movebase.launch

<?xml version="1.0"?>
<launch>

  <!-- delete old parameters -->
  <rosparam command="delete" param="/move_base"/>

  <node name="map_server" pkg="map_server" type="map_server" args="/PATH/TO/MAP"/>

  <node name="map_to_odom" pkg="tf" type="static_transform_publisher" args="2 0 0 0 0 0 map odom 10"/>
  <node name="odom_to_base_link" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 odom base_link 10"/>

  <node pkg="move_base" type ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
7

answered 2019-02-21 13:00:12 -0500

David Lu gravatar image

I'm not able to run your example at the moment, but it is very helpful that you provided it.

The key parameter here is combination_method. You have it set to 0, which means overwrite. This means that whatever data is in the obstacle layer will be written into the master costmap, regardless of what is already in the master from the static costmap.

Try setting it to 1 for Maximum, which will combine the values.

Alternatively, you can set track_unknown_space to true so that only the values which your obstacle layer has marked as clear/occupied will be copied over.

edit flag offensive delete link more

Comments

1

great! Thanks @David Lu I really missed that I actually set this parameter. I guess that combination_method=1 seems to be the default then.

I'll update my question with some insights after testing this!

mgruhler gravatar image mgruhler  ( 2019-02-22 03:40:23 -0500 )edit
1

@David Lu as the combination_method parameter hasn't been documented, I took the liberty of adding it to the wiki If you feel this is incorrect, please adapt or let me know. Thanks!

mgruhler gravatar image mgruhler  ( 2019-02-22 04:42:04 -0500 )edit
1

thanks a lot for all the info and answers you have guys posted in this thread!

geoporus gravatar image geoporus  ( 2021-04-08 02:44:00 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2019-02-20 06:56:35 -0500

Seen: 2,436 times

Last updated: Feb 22 '19