<> === Costmap2DROS === The `costmap_2d::Costmap2DROS` object is a [[navigation/ROS_Wrappers | wrapper]] for a `costmap_2d::Costmap2D` object that exposes its functionality as a [[navigation/ROS_Wrappers | 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: {{{ #!cplusplus #include #include ... tf::TransformListener tf(ros::Duration(10)); 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. {{{ #!clearsilver CS/NodeAPI pub { 0.name= ~/costmap 0.type= nav_msgs/OccupancyGrid 0.desc= The values in the costmap 1.name=~/costmap_updates 1.type= map_msgs/OccupancyGridUpdate 1.desc= The value of the updated area of the costmap 3.name= ~/voxel_grid 3.type= costmap_2d/VoxelGrid 3.desc= Optionally advertised when the underlying occupancy grid uses voxels and the user requests the voxel grid be published. } sub { 0.name=~/footprint 0.type= geometry_msgs/Polygon 0.desc= Specification for the footprint of the robot. This replaces the previous parameter specification of the footprint. } }}} ==== 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 ===== {{{ #!clearsilver CS/NodeAPI param { no_header=True 0.name= ~/plugins 0.default= pre-Hydro behavior 0.type= sequence 0.desc= 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 [[costmap_2d/Tutorials/Configuring Layered Costmaps | tutorials]] for examples. } }}} ===== Coordinate frame and tf parameters ===== {{{ #!clearsilver CS/NodeAPI param { no_header=True 0.name= ~/global_frame 0.default= `"/map"` 0.type= string 0.desc= The global frame for the costmap to operate in. 1.name= ~/robot_base_frame 1.default= `"base_link"` 1.type= string 1.desc= The name of the frame for the base link of the robot. 2.name= ~/transform_tolerance 2.default= 0.2 2.type= double 2.desc= 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 | navigation stack]] will stop the robot. } }}} ===== Rate parameters ===== {{{ #!clearsilver CS/NodeAPI param { no_header=True 0.name= ~/update_frequency 0.default=5.0 0.type= double 0.desc= The frequency in Hz for the map to be updated. 1.name= ~/publish_frequency 1.default= 0.0 1.type= double 1.desc= The frequency in Hz for the map to be publish display information. } }}} ===== Map management parameters ===== {{{ #!clearsilver CS/NodeAPI param { no_header=True 1.name= ~/rolling_window 1.default= `false` 1.type= bool 1.desc= 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. 2.name= ~/always_send_full_costmap 2.default= `false` 2.type= bool 2.desc= If true the full costmap is published to "~/costmap" every update. If false only the part of the costmap that has changed is published on the "~/costmap_updates" topic. } }}} The following parameters can be overwritten by some layers, namely the static map layer. {{{ #!clearsilver CS/NodeAPI param { no_header=True 0.name= ~/width 0.default= 10 0.type= int 0.desc= The width of the map in meters. 1.name= ~/height 1.default= 10 1.type= int 1.desc= The height of the map in meters. 2.name= ~/resolution 2.default= 0.05 2.type= double 2.desc= The resolution of the map in meters/cell. 3.name= ~/origin_x 3.default= 0.0 3.type= double 3.desc= The x origin of the map in the global frame in meters. 4.name= ~/origin_y 4.default= 0.0 4.type= double 4.desc= The y origin of the map in the global frame in meters. }}} {{{ #!clearsilver CS/NodeAPI req_tf { 0.to= (value of robot_base_frame parameter) 0.from= (value of global_frame parameter) 0.desc= 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: [[http://ros.org/doc/api/costmap_2d/html/classcostmap__2d_1_1Costmap2DROS.html|Costmap2DROS C++ API]] === Layer Specifications === ==== Static Map Layer ==== The [[costmap_2d/hydro/staticmap | static map layer]] represents a largely unchanging portion of the costmap, like those generated by SLAM. ==== Obstacle Map Layer ==== The [[costmap_2d/hydro/obstacles | obstacle layer]] tracks the obstacles as read by the sensor data. The `ObstacleCostmapPlugin` marks and raytraces obstacles in two dimensions, while the [[costmap_2d/hydro/obstacles#VoxelCostmapPlugin | VoxelCostmapPlugin]] does so in three dimensions. ==== Inflation Layer ==== The [[costmap_2d/hydro/inflation | 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. * [[ social_navigation_layers | Social Costmap Layer ]] * [[ range_sensor_layer | Range Sensor Layer ]]