ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Where does amcl_demo.launch load its plugins from?

asked 2014-04-03 10:33:31 -0500

oswinium gravatar image

updated 2014-04-03 10:36:29 -0500

When I run roslaunch turtlebot_navigation amcl_demo.launch map_file:=<path_of_my_map> I get, as part of the output:

[ INFO] [1396554684.603955092]: Using plugin "static_layer"
[ INFO] [1396554684.956445219]: Requesting the map...
[ INFO] [1396554685.162530181]: Resizing costmap to 480 X 288 at 0.050000 m/pix
[ INFO] [1396554685.262220473]: Received a 480 X 288 map at 0.050000 m/pix
[ INFO] [1396554685.288558669]: Using plugin "obstacle_layer"
[ INFO] [1396554685.355236864]:     Subscribed to Topics: scan bump
[ INFO] [1396554685.659024142]: Using plugin "inflation_layer"
[ INFO] [1396554686.518542435]: Loading from pre-hydro parameter style
[ INFO] [1396554686.738804760]: Using plugin "obstacle_layer"
[ INFO] [1396554687.077918589]:     Subscribed to Topics: scan bump
[ INFO] [1396554687.373924581]: Using plugin "inflation_layer"
[ INFO] [1396554687.994371819]: Created local_planner base_local_planner/TrajectoryPlannerROS
[ INFO] [1396554688.069237432]: Sim period is set to 0.20
[ INFO] [1396554690.131045226]: odom received!

Where does amcl_demo.launch its plugins from?

(ROS Distro is Hydro and Ubuntu is 13.04).

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2014-04-03 23:59:16 -0500

demmeln gravatar image

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.

edit flag offensive delete link more

Comments

Thanks a lot for the detailed response!

oswinium gravatar image oswinium  ( 2014-04-07 06:48:13 -0500 )edit

What I don't understand is why I would be making changes to the local costmap with static_map set to false and rolling_window set to true, considering that my aim is to load a (static?) layer with a lethal obstacle one meter ahead of the robot...

oswinium gravatar image oswinium  ( 2014-04-07 07:55:07 -0500 )edit
1

Since you want to place something relative to the robot, it for obstacle avoidance, it seems the local costmap is the right choice. I'm not sure how the rolling_window option will be interacting with you plugin. I suggest trying it or checking the source code on more details about rolloing_window.

demmeln gravatar image demmeln  ( 2014-04-07 09:21:44 -0500 )edit

Also, it depends a bit on what exactly you want to achieve with your custom layer. Maybe you can share a bit more on the actual goal of all this.

demmeln gravatar image demmeln  ( 2014-04-07 09:22:33 -0500 )edit

OK you were right; adding the plugins (the same stuff in the minimal.yaml file here: http://bit.ly/1qggQa7) to the local_costmap_params.yaml file does the trick. My main aim is to do this - http://bit.ly/1swomQj - and load it as a separate layer on my costmap for social navigation of my robot.

oswinium gravatar image oswinium  ( 2014-04-08 05:21:33 -0500 )edit

Good to know :)

demmeln gravatar image demmeln  ( 2014-04-08 06:16:30 -0500 )edit

So just another follow-up question: when this new layer is loaded, does the robot actually consider the 'fake' obstacle as a 'real' obstacle? I ask because it seems to have no problem 'walking through' it :S

oswinium gravatar image oswinium  ( 2014-04-08 09:40:40 -0500 )edit
1

I believe the local costmap is used for the local planner for doing obstacle avoidance. The global path planner is using only the global costmap I believe, so this will not consider your obstacle unless you also add something to the global costmap.

demmeln gravatar image demmeln  ( 2014-04-08 10:41:44 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-04-03 10:33:31 -0500

Seen: 901 times

Last updated: Apr 03 '14