ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
This is actually a really good question, and given the state of the documentation not trivial to find out. I haven't used costmaps heavily myself, only move_base
without changing the default config much, so I had to some digging in the code to see whats going on. The output Loading from pre-hydro parameter style
gives some hint.
So in the amcl_demo.launch
file through includes eventually the move_base
node is started. This node includes two cost maps (local and global), which are run inside the node (not as seperate nodes). This could be the first confusion. The corresponding objects are created here (move_base.cpp#L111) and here (move_base.cpp#L139). You can see that the costmaps are invoked with the names global_costmap
and local_costmap
. This is important for specifying the parameters correctly.
In the launch include file where move base is specified, you can see that there are 4 lines to load parameters for the 2 costmaps (move_base.launch.xml#L11-L14). Notice the extra ns="global_costmap"
and ns="local_costmap"
tags when loading costmap_common_params.yaml
. The two other parameter files specifying parameters specific to local and global costmap have this namespace inside the .yaml
file. So now we know where the parameters for the two costmaps are specified. But why is there nothing about plugins
?
We have to dig further and have a look inside the Costmap2DROS node. During initialization of the costmap, it checks (costmap_2d_ros.cpp#L107-L110) if the parameter plugins
is set (in the private namespace). If not, it calls function resetOldParameters
, which sets up the plugin parameters from within the node to mimick some default behaviour.
So in order to change the plugins for example for the local costmap, first check in the resetOldParameters
code to see how the parameters are set up (or use rosparam
to inspect the parameters after the node was started). Then modify the yaml file for the local costmap (local_costmap_params.yaml
in the turtlebot amcl demo) to specify the default plugins to get back to the default behaviour. If that works as expected, you can now add your additional custom plugins to this file.
@David Lu, @tfoote: As maintainers of the the navigation stack / turtlebot_navigation package, it would probably be very helpful if the example launch files in move_base
and/or turtlebot_navigation
and/or costmap_2d
would actually use the post-electric style parameterization of costmaps explicitely listing the layers in the plugins
parameter. Otherwise there is a discrepancy between the costmap tutorial and the examples.