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

Revision history [back]

click to hide/show revision 1
initial version

I assume that you use the spawn_model node from gazebo_ros. The reason why your solution does not work is that each URDF is loaded in the same parameter robot_description. If you do that in two separate launch files, the flow is more or less the following:

  1. Load the first URDF
  2. Spawn the first robot
  3. Load the second URDF
  4. Spawn the second robot

Note that at the end the first URDF is not available anymore. This is in general something you want to avoid (you might need it later for other components). If you launch everything at the same time, you need to keep in mind that parameters are all loaded before starting the nodes. Therefore, the launch sequence will be similar to:

  1. Load the first URDF
  2. Load the second URDF, the first is now "lost"
  3. Spawn the second robot
  4. Span another robot, it will again be the second one!

I can suggest you few solutions. The first one is to load the URDFs and to start the spawners into namespaces. This allows to have all URDFs at the same time. This can be accomplished like in the following:

<group ns="first_robot">
  <param name="robot_description" command="$(find xacro)/xacro.py '$(find mybot_description)/urdf/mybot.xacro' />
  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args="-urdf -model mybot -param robot_description"/>
</group>

A similar alternative is to change the name of the two parameters containing the descriptions:

<param name="first_robot_description" command="$(find xacro)/xacro.py '$(find mybot_description)/urdf/my_first_bot.xacro' />
<param name="second_robot_description" command="$(find xacro)/xacro.py '$(find mybot_description)/urdf/my_second_bot.xacro' />
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args="-urdf -model mybot -param first_robot_description"/>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args="-urdf -model mybot -param second_robot_description"/>

However, I would personally not use this solution since many ROS components use robot_description as the default name for the URDF parameter. Having a non-standard name will require to do more remapping, whereas the first solution simply requires to launch everything in a namespace - which I find easier and clearer - but I guess it is really up to you.

Finally, from the name fusion_13_structure I guess that the second URDF is used to represent an environment (I might be wrong, so you will tell me in the comments). In this case, you probably do not care much about the second URDF. You can thus load the robot into robot_description "as usual", and use one of these solutions for the environment:

  1. Spawn the environment using the -file argument rather than -param (see here). I believe that in this case the URDF must have already been processed "manually" by xacro.
  2. Load the environment into any parameter, like robot_environment_description, and spawn the URDF from this parameter (this is basically the second solution above).