Costmap2DROS

The costmap_2d::Costmap2DROS object is a wrapper for a costmap_2d::Costmap2D object that exposes its functionality as a C++ ROS Wrapper. It operates within a ROS namespace (assumed to be name from here on) specified on initialization.

Example creation of a costmap_2d::Costmap2DROS object specifying the my_costmap namespace:

   1 #include <tf/transform_listener.h>
   2 #include <costmap_2d/costmap_2d_ros.h>
   3 
   4 ...
   5 
   6 tf::TransformListener tf(ros::Duration(10));
   7 costmap_2d::Costmap2DROS costmap("my_costmap", tf);

If you rosrun or roslaunch the costmap_2d node directly it will run in the costmap namespace. In this case all references to name below should be replaced with costmap.

The more common case is to run the full navigation stack by launching the move_base node. This will create 2 costmaps, each with its own namespace: local_costmap and global_costmap. You may need to set some parameters twice, once for each costmap.

ROS API

The C++ API has changed as of Hydro.

Subscribed Topics

~<name>/footprint (geometry_msgs/Polygon)
  • Specification for the footprint of the robot. This replaces the previous parameter specification of the footprint.

Published Topics

~<name>/costmap (nav_msgs/OccupancyGrid)
  • The values in the costmap
~<name>/costmap_updates (map_msgs/OccupancyGridUpdate)
  • The value of the updated area of the costmap
~<name>/voxel_grid (costmap_2d/VoxelGrid)
  • Optionally advertised when the underlying occupancy grid uses voxels and the user requests the voxel grid be published.

Parameters

Pre-Hydro Parameters

Hydro and later releases use plugins for all costmap_2d layers. If you don't provide a plugins parameter then the initialization code will assume that your configuration is pre-Hydro and will load a default set of plugins with default namespaces. Your parameters will be moved to the new namespaces automagically. The default namespaces are static_layer, obstacle_layer and inflation_layer. Some tutorials (and books) still refer to pre-Hydro parameters, so pay close attention. To be safe, be sure to provide a plugins parameter.

Plugins

~<name>/plugins (sequence, default: pre-Hydro behavior)

  • Sequence of plugin specifications, one per layer. Each specification is a dictionary with name and type fields. The name is used to define the parameter namespace for the plugin. See the tutorials for examples.

Coordinate frame and tf parameters

~<name>/global_frame (string, default: "/map")

  • The global frame for the costmap to operate in.
~<name>/robot_base_frame (string, default: "base_link")
  • The name of the frame for the base link of the robot.
~<name>/transform_tolerance (double, default: 0.2)
  • Specifies the delay in transform (tf) data that is tolerable in seconds. This parameter serves as a safeguard to losing a link in the tf tree while still allowing an amount of latency the user is comfortable with to exist in the system. For example, a transform being 0.2 seconds out-of-date may be tolerable, but a transform being 8 seconds out of date is not. If the tf transform between the coordinate frames specified by the global_frame and robot_base_frame parameters is transform_tolerance seconds older than ros::Time::now(), then the navigation stack will stop the robot.

Rate parameters

~<name>/update_frequency (double, default: 5.0)

  • The frequency in Hz for the map to be updated.
~<name>/publish_frequency (double, default: 0.0)
  • The frequency in Hz for the map to be publish display information.

Map management parameters

~<name>/rolling_window (bool, default: false)

  • Whether or not to use a rolling window version of the costmap. If the static_map parameter is set to true, this parameter must be set to false.
~<name>/always_send_full_costmap (bool, default: false)
  • If true the full costmap is published to "~<name>/costmap" every update. If false only the part of the costmap that has changed is published on the "~<name>/costmap_updates" topic.

The following parameters can be overwritten by some layers, namely the static map layer.

  • ~<name>/width (int, default: 10)
    • The width of the map in meters.
    ~<name>/height (int, default: 10)
    • The height of the map in meters.
    ~<name>/resolution (double, default: 0.05)
    • The resolution of the map in meters/cell.
    ~<name>/origin_x (double, default: 0.0)
    • The x origin of the map in the global frame in meters.
    ~<name>/origin_y (double, default: 0.0)
    • The y origin of the map in the global frame in meters.

Required tf Transforms

(value of global_frame parameter)(value of robot_base_frame parameter)
  • Usually provided by a node responsible for odometry or localization such as amcl.

C++ API

For C++ level API documentation on the costmap_2d::Costmap2DROS class, please see the following page: Costmap2DROS C++ API

Layer Specifications

Static Map Layer

The static map layer represents a largely unchanging portion of the costmap, like those generated by SLAM.

Obstacle Map Layer

The obstacle layer tracks the obstacles as read by the sensor data. The ObstacleCostmapPlugin marks and raytraces obstacles in two dimensions, while the VoxelCostmapPlugin does so in three dimensions.

Inflation Layer

The inflation layer is an optimization that adds new values around lethal obstacles (i.e. inflates the obstacles) in order to make the costmap represent the configuration space of the robot.

Other Layers

Other layers can be implemented and used in the costmap via pluginlib. Any additional plugins are welcomed to be listed and linked to below.

Wiki: costmap_2d/layered (last edited 2018-03-28 16:04:02 by RomainReignier)