Wiki

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) <point_cloud2_topic> (sensor_msgs/PointCloud2) <laser_scan_topic> (sensor_msgs/LaserScan) "map" (nav_msgs/OccupancyGrid)

Sensor management parameters

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

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

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

~<name>/<source_name>/sensor_frame (string, default: "") ~<name>/<source_name>/observation_persistence (double, default: 0.0) ~<name>/<source_name>/expected_update_rate (double, default: 0.0) ~<name>/<source_name>/data_type (string, default: "PointCloud") ~<name>/<source_name>/clearing (bool, default: false) ~<name>/<source_name>/marking (bool, default: true) ~<name>/<source_name>/max_obstacle_height (double, default: 2.0) ~<name>/<source_name>/min_obstacle_height (double, default: 0.0) ~<name>/<source_name>/obstacle_range (double, default: 2.5) ~<name>/<source_name>/raytrace_range (double, default: 3.0) ~<name>/<source_name>/inf_is_valid (bool, default: false)

Global Filtering Parameters

These parameters apply to all sensors.

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

~<name>/obstacle_range (double, default: 2.5) ~<name>/raytrace_range (double, default: 3.0)

ObstacleCostmapPlugin

These parameters are used by the ObstacleCostmapPlugin.

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

~<name>/footprint_clearing_enabled (bool, default: true) ~<name>/combination_method (enum, default: 1)

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)

~<name>/z_resolution (double, default: 0.2) ~<name>/z_voxels (int, default: 10) ~<name>/unknown_threshold (int, default: ~<name>/z_voxels) ~<name>/mark_threshold (int, default: 0) ~<name>/publish_voxel_map (bool, default: false) ~<name>/footprint_clearing_enabled (bool, default: true)

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

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)