[ros-users] ROS navigation stack for Mulit-Robot-Szenario
Markus Bader
markus.bader at tuwien.ac.at
Fri Mar 28 09:02:16 UTC 2014
Hi
I am working with a multi robot scenario and I had a problem with the
navigation stack because I like to use only one set of configuration files
for all robots with separate name spaces for each robot.
Name spaces are working perfect to rename topics but some nodes have shared
parameter to name a tf frame
I solved the problem by forking the navigation stack and I added a checks
on these parameter like amcl: odom_frame_id, base_frame_id, global_frame_id
to get the name space right.
Finally everything worked.
It would be nice now to get some feedback and to get my work pulled back
into the original navigation stack.
https://github.com/ros-planning/navigation/pull/178
My solution works but I find it better to introduce a shared parameter type
for tf frames which solves the name space problem
The following launch file shows how I deal now with two robots :-)
Greetings
Markus
<launch>
<arg name="scan" value="front_laser/scan" />
<!-- Mapserver -->
<include file="$(find v4r_launch)/launch/map.launch">
<arg name="room" value="gh25" />
<arg name="env" value="sim" />
</include>
<!-- Robot r1 -->
<group ns="r1">
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<remap from="scan" to="$(arg scan)"/>
<remap from="map" to="/map"/>
<rosparam file="$(find
v4r_launch)/cfg/amcl/marry_real/amcl_filter.yaml" command="load"/>
<rosparam file="$(find
v4r_launch)/cfg/amcl/marry_real/amcl_laser_model.yaml" command="load"/>
<rosparam file="$(find
v4r_launch)/cfg/amcl/marry_real/amcl_motion_model.yaml" command="load"/>
</node>
<node pkg="move_base" type="move_base" name="move_base"
output="screen">
<remap from="scan" to="$(arg scan)"/>
<remap from="map" to="/map"/>
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/common_costmap.yaml" command="load"
ns="global_costmap" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/common_costmap.yaml" command="load"
ns="local_costmap" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/global_costmap.yaml" command="load" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/local_costmap.yaml" command="load" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/base_local_planner.yaml" command="load"
/>
</node>
</group>
<!-- Robot r2 -->
<group ns="r2">
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<remap from="scan" to="$(arg scan)"/>
<remap from="map" to="/map"/>
<rosparam file="$(find
v4r_launch)/cfg/amcl/marry_real/amcl_filter.yaml" command="load"/>
<rosparam file="$(find
v4r_launch)/cfg/amcl/marry_real/amcl_laser_model.yaml" command="load"/>
<rosparam file="$(find
v4r_launch)/cfg/amcl/marry_real/amcl_motion_model.yaml" command="load"/>
</node>
<node pkg="move_base" type="move_base" name="move_base"
output="screen">
<remap from="scan" to="$(arg scan)"/>
<remap from="map" to="/map"/>
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/common_costmap.yaml" command="load"
ns="global_costmap" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/common_costmap.yaml" command="load"
ns="local_costmap" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/global_costmap.yaml" command="load" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/local_costmap.yaml" command="load" />
<rosparam file="$(find
v4r_launch)/cfg/move_base/bader3dx/base_local_planner.yaml" command="load"
/>
</node>
</group>
</launch>
--
Dipl.-Ing. Dr.tech. Markus Bader
ACIN | AUTOMATION & CONTROL INSTITUTE
INSTITUT FÜR AUTOMATISIERUNGS- & REGELUNGSTECHNIK
TECHNISCHE UNIVERSITÄT WIEN
Gusshausstrasse 27-29 | 376. 1040 Wien
DVR-Nummer: 0005886
Tel. +43 (0)1 58801 - 376646
Skype: markus.bader.at.work
Fax. +43 (0)1 58801 - 37697
markus.bader at tuwien.ac.at | www.acin.tuwien.ac.at
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20140328/5f5a1124/attachment.html>
More information about the ros-users
mailing list