(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Configuring Layered Costmaps

Description: How to create a Layered Costmap configuration from scratch

Keywords: navigation, layered costmaps

Tutorial Level: INTERMEDIATE

This tutorial intends to guide you through the creation of a customized set of layers for a costmap, This will be accomplished using the costmap_2d_node executable, although the parameters can be ported into move_base.

Step 1: Transforms

One basic thing that the costmap requires is a transformation from the frame of the costmap to the frame of the robot. For this purpose, one solution is to create a static transform publisher in a launch file.

   1     <node name="static_tf0" pkg="tf" type="static_transform_publisher" args="2 0 0 0 0 0 /map /base_link 100"/>

Step 2: Basic Parameters

Next, to specify the behavior of the costmap, we create a yaml file which will be loaded into the parameter space. Here its called minimal.yaml.

plugins: []
publish_frequency: 1.0
footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]]

We start out with no layers for simplicity. The publish_frequency is 1.0Hz for debugging purposes and we specify a simple footprint since the costmap expects some footprint to be defined.

These parameters can be loaded in with a line in your launch file such as

   1 <rosparam file="$(find simple_costmap_configuration)/params/minimal.yaml" command="load" ns="/costmap_node/costmap" />

Note: If you run the costmap without the plugins parameter, it will assume a pre-hydro style of parameter configuration, and automatically create layers based on what costmaps used to do.

Step 3: Plugins Specification

To actually specify the layers, we store dictionaries in the array of plugins. For example:

plugins: 
    - {name: static_map,       type: "costmap_2d::StaticLayer"}

(This of course assumes you have a static map being published, with something like the following)

    <node name="map_server" pkg="map_server" type="map_server" args="$(find simple_costmap_configuration)/realmap.yaml"/>

Additional layers can be added with additional dictionaries in the array.

plugins: 
    - {name: static_map,       type: "costmap_2d::StaticLayer"}
    - {name: obstacles,        type: "costmap_2d::VoxelLayer"}

The namespace for each of the layers is one level down from where the plugins are specified. So to specify the specifics for the obstacles layer, we would extend our parameter file as such.

plugins: 
    - {name: static_map,       type: "costmap_2d::StaticLayer"}
    - {name: obstacles,        type: "costmap_2d::VoxelLayer"}
publish_frequency: 1.0
obstacles:
    observation_sources: base_scan
    base_scan: {data_type: LaserScan, sensor_frame: /base_laser_link, clearing: true, marking: true, topic: /base_scan}

Wiki: costmap_2d/Tutorials/Configuring Layered Costmaps (last edited 2013-08-27 00:13:11 by DavidLu)