Show EOL distros: 

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: hydro-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: indigo-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mferguson AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: jade-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: kinetic-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: lunar)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: melodic-devel)
navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | global_planner | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | rotate_recovery | voxel_grid

Package Summary

This package provides an implementation of a 2D costmap that takes in sensor data from the world, builds a 2D or 3D occupancy grid of the data (depending on whether a voxel based implementation is used), and inflates costs in a 2D costmap based on the occupancy grid and a user specified inflation radius. This package also provides support for map_server based initialization of a costmap, rolling window based costmaps, and parameter based subscription to and configuration of sensor topics.

  • Maintainer status: maintained
  • Maintainer: David V. Lu!! <davidvlu AT gmail DOT com>, Michael Ferguson <mfergs7 AT gmail DOT com>, Aaron Hoy <ahoy AT fetchrobotics DOT com>
  • Author: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
  • License: BSD
  • Source: git https://github.com/ros-planning/navigation.git (branch: noetic-devel)

Overview

costmap_2d/Hydro.png Note: In the picture above, the red cells represent obstacles and their inflation in the costmap, the blue cells represent free space, and the colors in between represent the intermediate values of the costmap. The unknown values are in grey. A laser scan is shown in green. For the robot to avoid collision, the footprint of the center of the robot should never intersect a red cell.

The costmap_2d package provides a configurable structure that maintains an occupancy grid for guiding navigation. Typically, the values of the cells in the costmap are derived from the static map and/or sensor data to update information about obstacles in the world. This information is accessed through the costmap_2d::Costmap2DROS object. The costmap object provides a purely two dimensional interface to its users, meaning that queries about obstacles can be made for points in the XY plane. For example, a table and a shoe in the same position in the XY plane, but with different Z positions would result in the corresponding cell in the costmap_2d::Costmap2DROS object's costmap having an identical cost value.

As of the Hydro release, the methods for populating the values of the costmap are separated into separate layers. For instance, a typical configuration may have a static map layer, layer for the obstacles, and an inflation layer. Each of these layers can maintain their state in whatever data structures they choose. When the map is updated, each layer is queried and the information is written into the two dimensional occupancy grid. For example, the obstacle layer can maintain its information in either two or three dimensions, but ultimately that data is written into the two dimensional grid.

The costmap_2d::Costmap2DROS object maintains much of the ROS-specific functionality of the costmap. It contains a costmap_2d::LayeredCostmap which maintains each of the layers, which are instantiated in the Costmap2DROS using pluginlib and added to the LayeredCostmap. Each of the layers can be compiled independently, allowing for arbitrary functionality and costmap patterns to be added. The costmap_2d::Costmap2D implements the functionality for storing and accessing the actual occupancy grid itself.

The specific details of how the values of the costmap are added from each layer are described below. The functionality for each layer is described on a separate page.

Occupied, Free, and Unknown Space

Each cell in the costmap has a value in the range [0, 255] (integers). There are some special values frequently used in this range. (defined in include/costmap_2d/cost_values.h)

  • costmap_2d::NO_INFORMATION (255) - Reserved for cells where not enough information is sufficiently known.

  • costmap_2d::LETHAL_OBSTACLE (254) - Indicates a collision causing obstacle was sensed in this cell.

  • costmap_2d::INSCRIBED_INFLATED_OBSTACLE (253) - Indicates no obstacle, but moving the center of the robot to this location will result in a collision.

  • costmap_2d::FREE_SPACE (0) - Cells where there are no obstacles and the moving the center of the robot to this position will not result in a collision.

All values in the range (0, 253) represent grid cells where no collision will occur, but there is some other quality that makes being in that cell undesirable (e.g. being very close to a wall).

Map Updates

The costmap performs map update cycles at the rate specified by the update_frequency parameter. Each cycle, each layer is polled to figure out what area of the map it needs to update. This may require some processing to figure out, say, the extent of all the sensors' reach. The costmap then creates a bounding box that contains each layer's update area. Then each layer in turn changes values in the bounding box with the appropriate values.

The static map, for instance, will need to update the entire map on the first cycle. However, after that, it will respond with 0 bounds, since it has already added all its data to the map. The inflation layer will need to update the area that has updated values, plus inflation_radius*2 on each side (as explained further on the inflation page.).

tf

In order to insert data from sensor sources into the costmap, the costmap_2d::Costmap2DROS object makes extensive use of tf. Specifically, it assumes that all transforms between the coordinate frames specified by the global_frame parameter, the robot_base_frame parameter, and sensor sources are connected and up-to-date. The transform_tolerance parameter sets the maximum amount of latency allowed between these transforms. If the tf tree is not updated at this expected rate, the navigation stack stops the robot.

Map Types

There are two main ways to set the size of a costmap_2d::Costmap2DROS object. The first is to include the static map layer, which will automatically resize the costmap when a map is received. This configuration is normally used in conjunction with a localization system, like amcl, that allows the robot to register obstacles in the map frame and update its costmap from sensor data as it drives through its environment. This configuration is generally used as the global costmap.

The second way to set the size is to define the width and height in the parameters. This configuration is used with the local costmap, often in conjunction with the rolling_window parameter. The rolling_window parameter keeps the robot in the center of the costmap as it moves throughout the world, dropping obstacle information from the map as the robot moves too far from a given area. This type of configuration is most often used in an odometric coordinate frame where the robot only cares about obstacles within a local area.

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 withing a ROS namespace (assumed to be name from here on) specified on initialization.

Example creation of a costmap_2d::Costmap2DROS object:

   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);

Note that the C++ API has changed as of Hydro.

ROS API

Note on Old Parameters

Many of the parameters have changed locations from pre-Hydro releases in order to allow for maximal customization. Those namespaces for those original parameters will still work, so there is no need to reconfigure your robot. However, the first thing that will happen when the costmap code is run is that the parameters will be removed from their old locations and placed in the new locations with plugins properly added.

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>/grid (nav_msgs/OccupancyGrid)
  • The values in the costmap
~<name>/grid_updates (nav_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

The costmap_2d::Costmap2DROS is highly configurable with several categories of ROS Parameters: coordinate frame and tf, rate, robot description and map management.

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.

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/hydro (last edited 2013-04-25 01:06:34 by DavidLu)