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_rviz.png Note: In the picture above, the red cells represent obstacles in the costmap, the blue cells represent obstacles inflated by the inscribed radius of the robot, and the red polygon represents the footprint of the robot. For the robot to avoid collision, the footprint of the robot should never intersect a red cell and the center point of the robot should never cross a blue cell.

The costmap_2d package provides a configurable structure that maintains information about where the robot should navigate in the form of an occupancy grid. The costmap uses sensor data and information from the static map to store and update information about obstacles in the world through the costmap_2d::Costmap2DROS object. The costmap_2d::Costmap2DROS object provides a purely two dimensional interface to its users, meaning that queries about obstacles can only be made in columns. 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. This is designed to help planning in planar spaces.

As of the Hydro release, the underlying methods used to write data to the costmap is fully configurable. Each bit of functionality exists in a layer. For instance, the static map is one layer, and the obstacles are another layer. By default, the obstacle layer maintains information three dimensionally (see voxel_grid). Maintaining 3D obstacle data allows the layer to deal with marking and clearing more intelligently.

The main interface is costmap_2d::Costmap2DROS which maintains much of the ROS related functionality. It contains a costmap_2d::LayeredCostmap which is used to keep track of each of the layers. Each layer is instantiated in the Costmap2DROS using pluginlib and is added to the LayeredCostmap. The layers themselves may be compiled individually, allowing arbitrary changes to the costmap to be made through the C++ interface. The costmap_2d::Costmap2D class implements the basic data structure for storing and accessing the two dimensional costmap.

The details about how the Costmap updates the occupancy grid are described below, along with links to separate pages describing how the individual layers work.

Marking and Clearing

The costmap automatically subscribes to sensors topics over ROS and updates itself accordingly. Each sensor is used to either mark (insert obstacle information into the costmap), clear (remove obstacle information from the costmap), or both. A marking operation is just an index into an array to change the cost of a cell. A clearing operation, however, consists of raytracing through a grid from the origin of the sensor outwards for each observation reported. If a three dimensional structure is used to store obstacle information, obstacle information from each column is projected down into two dimensions when put into the costmap.

Occupied, Free, and Unknown Space

While each cell in the costmap can have one of 255 different cost values (see the inflation section), the underlying structure that it uses is capable of representing only three. Specifically, each cell in this structure can be either free, occupied, or unknown. Each status has a special cost value assigned to it upon projection into the costmap. Columns that have a certain number of occupied cells (see mark_threshold parameter) are assigned a costmap_2d::LETHAL_OBSTACLE cost, columns that have a certain number of unknown cells (see unknown_threshold parameter) are assigned a costmap_2d::NO_INFORMATION cost, and other columns are assigned a costmap_2d::FREE_SPACE cost.

Map Updates

The costmap performs map update cycles at the rate specified by the update_frequency parameter. Each cycle, sensor data comes in, marking and clearing operations are perfomed in the underlying occupancy structure of the costmap, and this structure is projected into the costmap where the appropriate cost values are assigned as described above. After this, each obstacle inflation is performed on each cell with a costmap_2d::LETHAL_OBSTACLE cost. This consists of propagating cost values outwards from each occupied cell out to a user-specified inflation radius. The details of this inflation process are outlined below.

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.

Inflation

costmapspec.png

Inflation is the process of propagating cost values out from occupied cells that decrease with distance. For this purpose, we define 5 specific symbols for costmap values as they relate to a robot.

  • "Lethal" cost means that there is an actual (workspace) obstacle in a cell. So if the robot's center were in that cell, the robot would obviously be in collision.
  • "Inscribed" cost means that a cell is less than the robot's inscribed radius away from an actual obstacle. So the robot is certainly in collision with some obstacle if the robot center is in a cell that is at or above the inscribed cost.
  • "Possibly circumscribed" cost is similar to "inscribed", but using the robot's circumscribed radius as cutoff distance. Thus, if the robot center lies in a cell at or above this value, then it depends on the orientation of the robot whether it collides with an obstacle or not. We use the term "possibly" because it might be that it is not really an obstacle cell, but some user-preference, that put that particular cost value into the map. For example, if a user wants to express that a robot should attempt to avoid a particular area of a building, they may inset their own costs into the costmap for that region independent of any obstacles. Note, that although the value is 128 is used as an example in the diagram above, the true value is influenced by both the inscribed_radius and inflation_radius parameters as defined in the code.

  • "Freespace" cost is assumed to be zero, and it means that there is nothing that should keep the robot from going there.
  • "Unknown" cost means there is no information about a given cell. The user of the costmap can interpret this as they see fit.
  • All other costs are assigned a value between "Freespace" and "Possibly circumscribed" depending on their distance from a "Lethal" cell and the decay function provided by the user.

The rationale behind these definitions is that we leave it up to planner implementations to care or not about the exact footprint, yet give them enough information that they can incur the cost of tracing out the footprint only in situations where the orientation actually matters.

Map Types

There are two main ways to initialize a costmap_2d::Costmap2DROS object. The first is to seed it with a user-generated static map (see the map_server package for documentation on building a map). In this case, the costmap is initialized to match the width, height, and obstacle information provided by the static map. 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.

The second way to initialize a costmap_2d::Costmap2DROS object is to give it a width and height and to set the rolling_window parameter to be true. 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.

Component API

Pre-hydro only

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:

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

API Stability

  • The ROS API is stable.
  • The C++ API is stable.

Published Topics

~<name>/obstacles (nav_msgs/GridCells)
  • The occupied cells in the costmap.
~<name>/inflated_obstacles (nav_msgs/GridCells)
  • The cells in the costmap that correspond to the occupied cells inflated by the inscribed radius of the robot.
~<name>/unknown_space (nav_msgs/GridCells)
  • The unknown cells in 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.

Subscribed Topics

<point_cloud_topic> (sensor_msgs/PointCloud)
  • For each "PointCloud" source listed in the observation_sources parameter list, information from that source is used to update the costmap.
<point_cloud2_topic> (sensor_msgs/PointCloud2)
  • For each "PointCloud2" source listed in the observation_sources parameter list, information from that source is used to update the costmap.
<laser_scan_topic> (sensor_msgs/LaserScan)
  • For each "LaserScan" source listed in the observation_sources parameter list, information from that source is used to update the costmap.
"map" (nav_msgs/OccupancyGrid)
  • The costmap has the option of being initialized from a user-generated static map (see the static_map parameter). If this option is selected, the costmap makes a service call to the map_server to obtain this map.

Parameters

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

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.

Global costmap parameters

~<name>/max_obstacle_height (double, default: 2.0)

  • The maximum height of any obstacle to be inserted into the costmap in meters. This parameter should be set to be slightly higher than the height of your robot.
~<name>/obstacle_range (double, default: 2.5)
  • The default maximum distance from the robot at which an obstacle will be inserted into the cost map in meters. This can be over-ridden on a per-sensor basis.
~<name>/raytrace_range (double, default: 3.0)
  • The default range in meters at which to raytrace out obstacles from the map using sensor data. This can be over-ridden on a per-sensor basis.
~<name>/cost_scaling_factor (double, default: 10.0)
  • A scaling factor to apply to cost values during inflation. The cost function is computed as follows for all cells in the costmap further than the inscribed radius distance and closer than the inflation radius distance away from an actual obstacle: exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1), where costmap_2d::INSCRIBED_INFLATED_OBSTACLE is currently 254. NOTE: since the cost_scaling_factor is multiplied by a negative in the formula, increasing the factor will decrease the resulting cost values.

Robot description parameters

~<name>/inflation_radius (double, default: 0.55)

  • The radius in meters to which the map inflates obstacle cost values.
~<name>/footprint (list, default: [])
  • The footprint of the robot specified in the robot_base_frame coordinate frame as a list in the format: [ [x1, y1], [x2, y2], ...., [xn, yn] ]. The footprint specification assumes the center point of the robot is at (0.0, 0.0) in the robot_base_frame and that the points are specified in meters, both clockwise and counter-clockwise orderings of points are supported.

The following parameters are overwritten if the "footprint" parameter is set:

~<name>/robot_radius (double, default: 0.46)

  • The radius of the robot in meters, this parameter should only be set for circular robots, all others should use the "footprint" parameter described above.

Sensor management parameters

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

  • A list of observation source names separated by spaces. This defines each of the <source_name> namespaces defined below.

Each source_name in observation_sources defines a namespace in which parameters can be set:

~<name>/<source_name>/topic (string, default: source_name)

  • The topic on which sensor data comes in for this source. Defaults to the name of the source.
~<name>/<source_name>/sensor_frame (string, default: "")
  • The frame of the origin of the sensor. Leave empty to attempt to read the frame from sensor data. The frame can be read from both sensor_msgs/LaserScan, sensor_msgs/PointCloud, and sensor_msgs/PointCloud2 messages.
~<name>/<source_name>/observation_persistence (double, default: 0.0)
  • How long to keep each sensor reading in seconds. A value of 0.0 will only keep the most recent reading.
~<name>/<source_name>/expected_update_rate (double, default: 0.0)
  • How often to expect a reading from a sensor in seconds. A value of 0.0 will allow infinite time between readings. This parameter is used as a failsafe to keep the navigation stack from commanding the robot when a sensor has failed. It should be set to a value that is slightly more permissive than the actual rate of the sensor. For example, if we expect a scan from a laser every 0.05 seconds we might set this parameter to be 0.1 seconds to give a generous buffer and account for some amount of system latency.
~<name>/<source_name>/data_type (string, default: "PointCloud")
  • The data type associated with the topic, right now only "PointCloud", "PointCloud2", and "LaserScan" are supported.
~<name>/<source_name>/clearing (bool, default: false)
  • Whether or not this observation should be used to clear out freespace.
~<name>/<source_name>/marking (bool, default: true)
  • Whether or not this observation should be used to mark obstacles.
~<name>/<source_name>/max_obstacle_height (double, default: 2.0)
  • The maximum height in meters of a sensor reading considered valid. This is usually set to be slightly higher than the height of the robot. Setting this parameter to a value greater than the global max_obstacle_height parameter has no effect. Setting this parameter to a value less than the global max_obstacle_height will filter out points from this sensor above that height.
~<name>/<source_name>/min_obstacle_height (double, default: 0.0)
  • The minimum height in meters of a sensor reading considered valid. This is usually set to be at ground height, but can be set higher or lower based on the noise model of your sensor.
~<name>/<source_name>/obstacle_range (double, default: 2.5)
  • The maximum range in meters at which to insert obstacles into the costmap using sensor data.
~<name>/<source_name>/raytrace_range (double, default: 3.0)
  • The maximum range in meters at which to raytrace out obstacles from the map using sensor data.

Map management parameters

~<name>/static_map (bool, default: true)

  • Whether or not to use the static map to initialize the costmap. If the rolling_window parameter is set to true, this parameter must be set to false.
~<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>/unknown_cost_value (int, default: "0")
  • The value for which a cost should be considered unknown when reading in a map from the map server. If the costmap is not tracking unknown space, costs of this value will be considered occupied. A value of zero also results in this parameter being unused.
~<name>/publish_voxel_map (bool, default: false)
  • Whether or not to publish the underlying voxel grid for visualization purposes.
~<name>/lethal_cost_threshold (int, default: 100)
  • The threshold value at which to consider a cost lethal when reading in a map from the map server.
~<name>/map_topic (string, default: "map")
  • The topic that the costmap subscribes to for the static 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

The following parameters are overwritten if "static_map" is set to true, and their original values will be restored when "static_map" is set back to false.

  • ~<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.

Map type parameters

~<name>/map_type (string, default: "voxel")

  • What map type to use. "voxel" or "costmap" are the supported types, with the difference between them being a 3D-view of the world vs. a 2D-view of the world.

The following parameters are only used if map_type is set to "voxel"

  • ~<name>/origin_z (double, default: 0.0)
    • The z origin of the map in meters.
    ~<name>/z_resolution (double, default: 0.2)
    • The z resolution of the map in meters/cell.
    ~<name>/z_voxels (int, default: 10)
    • The number of voxels to in each vertical column, the height of the grid is z_resolution * z_voxels.
    ~<name>/unknown_threshold (int, default: ~<name>/z_voxels)
    • The number of unknown cells allowed in a column considered to be "known"
    ~<name>/mark_threshold (int, default: 0)
    • The maximum number of marked cells allowed in a column considered to be "free".

The following parameters are only used if map_type is set to "costmap"

  • ~<name>/track_unknown_space (bool, default: false)
    • Specifies whether or not to track what space in the costmap is unknown, meaning that no observation about a cell has been seen from any sensor source.

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

Costmap2DPublisher

The costmap_2d::Costmap2DPublisher periodically publishes visualization information about a 2D costmap over ROS and exposes its functionality as a C++ ROS Wrapper

API Stability

  • The ROS API is stable.
  • The C++ API is stable.

Published Topics

raw_obstacles (nav_msgs/GridCells)
  • The occupied cells in the costmap.
inflated_obstacles (nav_msgs/GridCells)
  • The cells in the costmap that correspond to the occupied cells inflated by the inscribed radius of the robot.
unknown_space (nav_msgs/GridCells)
  • The unknown cells in the costmap.

C++ API

For C++-level API documentation on the Costmap2DPublisher class, please see the following page: Costmap2DPublisher C++ API

Costmap2D

The costmap_2d::Costmap2D provides a mapping between points in the world and their associated costs. It takes in observations about the world, uses them to both mark and clear in an occupancy grid, and inflates costs outward from obstacles as specified by a decay function. Most users will have creation of costmap_2d::Costmap2D objects handled automatically by a costmap_2d::Costmap2DROS object, but those with special needs may choose to create their own.

API Stability

  • The C++ API is stable.

C++ API

For C++-level API documentation on the cosmtap_2d::Costmap2D class, please see the following page: Costmap2D C++ API

VoxelCostmap2D

The costmap_2d::VoxelCostmap2D serves the same purpose as the Costmap2D object above, but uses a 3D-voxel grid for its underlying occupancy grid implementation. This means that the costmap_2d::VoxelCostmap2D is better suited for dealing with truly 3D environments because it accounts for obstacle height as it marks and clears its occupancy grid. For cost inflation, the 3D-occupancy grid is projected down into 2D and costs propagate outward as specified by a decay function. Most users will have creation of costmap_2d::VoxelCostmap2D objects handled automatically by a costmap_2d::Costmap2DROS object, but those with special needs may choose to create their own.

API Stability

  • The C++ API is stable.

C++ API

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

ObservationBuffer

An costmap_2d::ObservationBuffer is used to take in point clouds from sensors, transform them to the desired coordinate frame using tf, and store them until they are requested. Most users will have creation of costmap_2d::ObservationBuffers handled automatically by a costmap_2d::Costmap2DROS object, but those with special needs may choose to create their own.

API Stability

  • The C++ API is stable.

C++ API

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

New in ROS hydro

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 (last edited 2018-01-10 15:43:59 by NickLamprianidis)