[Documentation] [TitleIndex] [WordIndex

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

Published Topics

~<name>/obstacles (nav_msgs/GridCells) ~<name>/inflated_obstacles (nav_msgs/GridCells) ~<name>/unknown_space (nav_msgs/GridCells) ~<name>/voxel_grid (costmap_2d/VoxelGrid)

Subscribed Topics

<point_cloud_topic> (sensor_msgs/PointCloud) <point_cloud2_topic> (sensor_msgs/PointCloud2) <laser_scan_topic> (sensor_msgs/LaserScan) "map" (nav_msgs/OccupancyGrid)

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

~<name>/robot_base_frame (string, default: "base_link") ~<name>/transform_tolerance (double, default: 0.2)

Rate parameters

~<name>/update_frequency (double, default: 5.0)

~<name>/publish_frequency (double, default: 0.0)

Global costmap parameters

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

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

Robot description parameters

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

~<name>/footprint (list, default: [])

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

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

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)

Map management parameters

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

~<name>/rolling_window (bool, default: false) ~<name>/unknown_cost_value (int, default: "0") ~<name>/publish_voxel_map (bool, default: false) ~<name>/lethal_cost_threshold (int, default: 100) ~<name>/map_topic (string, default: "map")

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.

Map type parameters

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

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

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

Required tf Transforms

(value of global_frame parameter)(value of robot_base_frame parameter)

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

Published Topics

raw_obstacles (nav_msgs/GridCells) inflated_obstacles (nav_msgs/GridCells) unknown_space (nav_msgs/GridCells)

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

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

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

C++ API

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


2019-08-17 12:38