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

Multi-robot navigation

asked 2011-04-28 09:18:11 -0600

Jack Sparrow gravatar image

updated 2011-04-28 09:41:06 -0600

Hi,

I have problem with implementing navigation to work with multiple robots. Errors:

Waiting on transform from /robot_1/base to /map to become available before running costmap, tf error: Frame id /robot_1/base does not exist!
Waiting on transform from /robot_2/base to /map to become available before running costmap, tf error: Frame id /robot_2/base does not exist!

Probably, the problem is in transformations that transform /map to /base and not from /map to /robot_1/base. I use groups/namespaces in launch file to separate each robot node with correspondiong move_base node from other nodes. To run navigation stack I launch robot_configuaration.launch and move_base.launch. I have found the following solution:

<launch>
  <group ns="robot_1">
    <param name="tf_prefix" value="robot_1"/>
    <node pkg="usarsim" type="usarsim.py" respawn="false" name="usarsim_1" output="screen">
  </group>
  <group ns="robot_2">
    <param name="tf_prefix" value="robot_2"/>
    <node pkg="usarsim" type="usarsim2.py" respawn="false" name="usarsim_2" output="screen">
  </group>

and

<launch>
  <node name="map_server" pkg="map_server" type="map_server" args="/home/user/Desktop/ROS/map.pgm 0.05" respawn="false">
  </node>

  <group ns="robot_1"><br>
    <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
      <rosparam file="$(find robot_2dnav)/costmap_common_params.yaml" command="load" ns="global_costmap" />
      <rosparam file="$(find robot_2dnav)/costmap_common_params.yaml" command="load" ns="local_costmap" />
      <rosparam file="$(find robot_2dnav)/local_costmap_params.yaml" command="load" />
      <rosparam file="$(find robot_2dnav)/global_costmap_params.yaml" command="load" />
      <rosparam file="$(find robot_2dnav)/base_local_planner_params.yaml" command="load" /><br>
    </node><br>
  </group>

  <group ns="robot_2">
    <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
    ...same as for group_1

but this doesn't work. Is there some solution to automatically map all topics and tf's directly from .launch file?

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
3

answered 2011-05-03 07:15:16 -0600

eitan gravatar image

Well, it turns out that the python version of transformBroadcaster has a bug in that it doesn't read the tf_prefix parameter. I've filed a ticket to have this fixed here: https://code.ros.org/trac/ros-pkg/ticket/4943.

In the meantime, you have a couple of options:

1) Write the search param logic yourself for the transformBroadcaster, submit a patch to the above ticket, get mad props from the ROS community for fixing a bug :)

2) Have a parameter on your node that allows you to change the frame name before you pass it to the transformBroadcaster.

3) Switch to the C++ API which works as expected.

Hope this helps.

edit flag offensive delete link more
1

answered 2011-05-02 05:22:51 -0600

eitan gravatar image

From the frames you posted, it looks like the driver for your robot is not remapping the frames it is broadcasting when "tf_prefix" is set. Details on the "tf_prefix" parameter and what it does can be found here. How are you publishing the frames for your robot? With a transformBroadcaster? Or some other way?

edit flag offensive delete link more

Comments

Yes, with transformBroadcaster. The following code is the same for robot_1 and robot_2: broadcaster.sendTransform(position, orientation, rospy.Time.now(), "odom", "map"). Do I need to change odom for every robot_x to /robot_x/odom manually or this is done automatically with tf_prefix?
Jack Sparrow gravatar image Jack Sparrow  ( 2011-05-03 03:43:13 -0600 )edit
1

answered 2011-04-28 11:34:58 -0600

eitan gravatar image

The navigation_stage package in the navigation_tutorials stack has an example launch file for how to bring the navigation stack up with multiple robots called move_base_multi_robot.launch. Examining that launch file should help you out a bit.

edit flag offensive delete link more

Comments

1
Yes, I tried to setup my launch file similar to this navigation_stage .launch, but I don't use fake localization, and stageros node.
Jack Sparrow gravatar image Jack Sparrow  ( 2011-04-29 00:37:58 -0600 )edit
1
Does the navigation_stage launch file work correctly on your system when you try to run it?
eitan gravatar image eitan  ( 2011-04-29 05:24:11 -0600 )edit
1
Yes, in rviz everything looks ok!
Jack Sparrow gravatar image Jack Sparrow  ( 2011-04-29 08:55:19 -0600 )edit
1

answered 2011-04-28 09:40:38 -0600

ben gravatar image

updated 2011-04-28 09:42:01 -0600

I think you are missing a couple of remappings and some custom parameter changes... that need to be done. This may not be the complete solution but it should get you a bit closer. Let me know how it goes.

<group ns="robot_0">
 <param name="~tf_prefix" value="robot_0" />

 <node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen">
    <remap from="odom" to="odom" />
    <remap from="cmd_vel" to="cmd_vel" />
    <remap from="map" to="/map" />

    <rosparam file="$(find robot_2dnav)/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find robot_2dnav)/costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find robot_2dnav)/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find robot_2dnav)/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find robot_2dnav)/base_local_planner_params.yaml" command="load" /><br>

    <param name="~/global_costmap/robot_base_frame" value="robot_0/base_link" />
    <param name="~/local_costmap/robot_base_frame" value="robot_0/base_link" />
    <param name="~/local_costmap/global_frame" value="robot_0/odom" />
 </node>
</group>
edit flag offensive delete link more

Comments

1
I get the same warning as above, nothing happens with changing the code with this 3 remappings and this 3 params. Is it needed to remap from odom to odom?
Jack Sparrow gravatar image Jack Sparrow  ( 2011-04-28 21:53:58 -0600 )edit
1
I figured how to solve this errors - rosmake :) but I had to remove this 3 params change because there weren't any subscriptions for odom and scan in move_base. Still there is one proble left..move_base nodes subscribe to /scan, not on /robot_x/scan? odom si fine.
Jack Sparrow gravatar image Jack Sparrow  ( 2011-04-28 22:18:28 -0600 )edit
1
This problem with /scan was in costmap_common_params.yaml. Now i get no errors, changed ~tf_prefix to tf_prefix, but navigation doesn't give any sign of life, no footprint, no obstacles, no path.. edit: without ~ navigation doesn't subscribe to most of topics, including scan and odom
Jack Sparrow gravatar image Jack Sparrow  ( 2011-04-28 23:46:50 -0600 )edit
1
Any chance you can generate a pdf of your TF tree "rosrun tf view_frames" and post the output. Its possible that something could be wrong there.
eitan gravatar image eitan  ( 2011-04-29 10:12:17 -0600 )edit
1
http://www.megaupload.com/?d=DCTZSB2Q I guess something is wrong here... Can you tell me what does tf_prefix do? Isn't that for remapping tf frames (odom->robot_x/odom)?
Jack Sparrow gravatar image Jack Sparrow  ( 2011-04-30 08:08:03 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-04-28 09:18:11 -0600

Seen: 3,713 times

Last updated: May 03 '11