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

Wiki: costmap_2d/flat (last edited 2014-04-16 15:40:05 by PaulBovbel)