Overview

The obstacle and voxel layers incorporate information from the sensors in the form of PointClouds or LaserScans. The obstacle layer tracks in two dimensions, whereas the voxel layer tracks in three.

Marking and Clearing

The costmap automatically subscribes to sensors topics 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. The clearing operation performs raytracing through the grid from the origin of the sensor outwards for each observation reported. With the voxel layer, obstacle information from each column is projected down into two dimensions when put into the costmap.

ROS API

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.

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.
~<name>/<source_name>/inf_is_valid (bool, default: false)
  • Allows for Inf values in "LaserScan" observation messages. The Inf values are converted to the laser maximum range.

Global Filtering Parameters

These parameters apply to all sensors.

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

ObstacleCostmapPlugin

These parameters are used by the ObstacleCostmapPlugin.

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

  • If false, each pixel has one of 2 states: lethal obstacle or free. If true, each pixel has one of 3 states: lethal obstacle, free, or unknown.
~<name>/footprint_clearing_enabled (bool, default: true)
  • If true, the robot footprint will clear (mark as free) the space in which it travels.
~<name>/combination_method (enum, default: 1)
  • Changes the behaviour how the obstacle_layer handles incoming data from layers beyond it. Possible values are "Overwrite" (0), "Maximum" (1) and "Nothing" (99). "Overwrite" simply overwrites the data below, i.e. they are not used. "Maximum" is what you want most of the times. It takes the maximum of what is supplied in the obstacle_layer or the incoming data. "Nothing" doesn't change the incoming data at all. Note that this highly influences how the costmap behaves, depending on your setting of track_unkown_space.

For a discussion of the influence of the combination_method and track_unknown_space parameters, see this related discussion on ROS answers: https://answers.ros.org/question/316191

VoxelCostmapPlugin

The following parameters are used by the VoxelCostmapPlugin.

~<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".
~<name>/publish_voxel_map (bool, default: false)
  • Whether or not to publish the underlying voxel grid for visualization purposes.
~<name>/footprint_clearing_enabled (bool, default: true)
  • If true, the robot footprint will clear (mark as free) the space in which it travels.

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/hydro/obstacles (last edited 2019-02-22 10:39:49 by MatthiasGruhler)