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

Revision history [back]

I think this is a good way to add obstacle information.

To make a second map public with a topic other than "map", use the map_topic parameter.

map_topic (string, default: "map") This parameter is useful when you have multiple costmap instances within a single node that you want to use different static maps. New in navigation 1.3.1

Stacking cost maps can be achieved by using the use_maximum parameter.

use_maximum (bool, default: false) Only matters if the static layer is not the bottom layer. If true, only the maximum value will be written to the master costmap.

The above is taken from the documentation at http://wiki.ros.org/costmap_2d/hydro/staticmap.

For example, you can use the following

global_costmap configuration yaml file

global_costmap:
  plugins: 
    - {name: static_layer1, type: "costmap_2d::StaticLayer"}
    - {name: static_layer2, type: "costmap_2d::StaticLayer"}

  static_layer1:
    map_topic: "map" 

  static_layer2:
    map_topic: "map2"
    use_maximum: true

Excerpt from launch file

<node name="static_layer1" pkg="map_server" type="map_server" args="$(find XXX)/maps/YYY.yaml"/>
<node name="static_layer2" pkg="map_server" type="map_server" args="$(find XXX)/maps/ZZZ.yaml">
    <remap from="map" to="map2"/>
</node>