[ros-users] ROS navigation stack for Mulit-Robot-Szenario

Markus Bader markus.bader at tuwien.ac.at
Fri Mar 28 15:29:14 UTC 2014


Hi

After some nice discussion with the navigation community we figured out a
way how to deal with the shared parameters using roslaunch variables:

Have a look at:


<launch>

  <arg name="robot_name" default="r1" />
  <arg name="room" default="gh25" />
  <arg name="env" default="sim" />
  <arg name="scan" default="front_laser/scan" />


   <!-- Mapserver -->
  <include file="$(find v4r_launch)/launch/map.launch">
     <arg name="room" value="$(arg room)" />
     <arg name="env" value="$(arg env)" />
   </include>

  <!-- Navigation -->
  <group ns="$(arg robot_name)">
    <include file="$(find v4r_launch)/launch/amcl.launch">
      <arg name="scan" value="$(arg scan)" />
      <arg name="robot_name" default="$(arg robot_name)" />
    </include>
    <include file="$(find v4r_launch)/launch/move_base.launch">
      <arg name="scan" value="$(arg scan)" />
      <arg name="robot_name" default="$(arg robot_name)" />
    </include>
  </group>

</launch>

---------------- File: $(find v4r_launch)/launch/amcl.launch
--------------------
<launch>

  <arg name="robot_name" default="r1" />
  <arg name="scan" default="front_laser/scan" />

  <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"/>
    <param name="odom_frame_id" value="$(arg robot_name)/odom"/>
    <param name="base_frame_id" value="$(arg robot_name)/base_link"/>
    <param name="global_frame_id" value="/map"/>
  </node>


</launch>



---------------- File: $(find v4r_launch)/launch/move_base.launch
--------------------
<launch>

  <arg name="robot_name" default="r1" />
  <arg name="scan" default="front_laser/scan" />

  <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"
/>
    <param name="TrajectoryPlannerROS/global_frame_id" value="$(arg
robot_name)/odom"/>
    <param name="global_costmap/global_frame" value="map"/>
    <param name="global_costmap/robot_base_frame" value="$(arg
robot_name)/base_link"/>
    <param
name="global_costmap/obstacle_layer/laser_scan_sensor/sensor_frame"
value="$(arg robot_name)/front_laser"/>
    <param name="local_costmap/global_frame" value="$(arg
robot_name)/odom"/>
    <param name="local_costmap/robot_base_frame" value="$(arg
robot_name)/base_link"/>
    <param
name="local_costmap/obstacle_layer/laser_scan_sensor/sensor_frame"
value="$(arg robot_name)/front_laser"/>
  </node>

</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/c32ee808/attachment.html>


More information about the ros-users mailing list