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

How to spawn urdf.xacro-file into Gazebo

asked 2013-08-01 04:31:28 -0500

platzhirsch gravatar image

updated 2013-08-04 23:24:58 -0500

Hi all,

I've build a robot model with urdf. Additional I've used some macros to reduce my code. The model is working in rviz too. But if I want to spawn my robot into Gazebo, it doesn't work. After removing each macro, I can spawn my model into Gazebo. Is there a way to use my first robot model directly in Gazebo? How can I design my own color in Gazebo. Something like this

  <gazebo reference="name_of_link">
    <material name="Green">
      <color rgba="0.0 0.8 0.0 1.0"/>
    </material>
  </gazebo>

doesn't work. Many thanks for your help!!!

Now I have a new problem:-( Since the usage of macros still doesn't work, I removed the macros and buil my new robot model bit by bit. But from a certain number of model parts the process of spawning a model is successful but you can't see a model in Gazebo although the robot is listed in the model list. Any ideas?

While spawning I get no errors on the terminal. Here is a part of my code.

<!-- Motorhalterung -->
<link name="motor_holder">
        <inertial>
                    <mass value="1.0" />
                <inertia ixx="1" ixy="0"  ixz="0"
                     iyy="1" iyz="0"
                         izz="1" />
        </inertial> 
    <visual>
        <geometry>
            <box size="0.03 0.09 0.07"/>
        </geometry>
        <material name="Dark_Grey">
            <color rgba="0.3 0.3 0.3 1"/>
        </material>
    </visual>
    <collision>
        <geometry>
            <box size="0.03 0.09 0.07"/>
        </geometry>
    </collision>
</link>

<joint name="chassis_to_motor_holder" type="fixed">
  <parent link="base_link"/>
  <child link="motor_holder"/>
  <origin xyz="0.09 0 ${chassis_height/2 + 0.07/2}"/>
    </joint>

    <gazebo reference="motor_holder">
        <material>ETABot/Dark_Grey</material>
    </gazebo>

    <!-- Motor -->
<link name="motor">
        <inertial>
                    <mass value="1.0" />
                <inertia ixx="1" ixy="0"  ixz="0"
                     iyy="1" iyz="0"
                         izz="1" />
        </inertial> 
    <visual>
        <geometry>
            <cylinder length="0.09" radius="0.03"/>
        </geometry>
        <origin rpy="0 ${pi/2} 0" xyz="0 0 0"/>
        <material name="Blue" />
    </visual>
    <collision>
        <geometry>
            <cylinder length="0.06" radius="0.03"/>
        </geometry>
        <origin rpy="0 ${pi/2} 0" xyz="0 0 0"/>
    </collision>
</link>

<joint name="motor_holder_to_motor" type="fixed">
  <parent link="motor_holder"/>
  <child link="motor"/>
  <origin xyz="-0.06 0 0"/>
    </joint>

    <gazebo reference="motor">
        <material>ETABot/Blue</material>
    </gazebo>

<!-- Motor -->
<link name="motor_controller">
        <inertial>
                    <mass value="1.0" />
                <inertia ixx="1" ixy="0"  ixz="0"
                     iyy="1" iyz="0"
                         izz="1" />
        </inertial> 
    <visual>
        <geometry>
            <box size="0.05 0.05 0.03"/>
        </geometry>
        <material name="Blue" />
    </visual>
    <collision>
        <geometry>
            <box size="0.05 0.05 0.03"/>
        </geometry>
    </collision>
</link>

<joint name="chassis_to_motor_controller" type="fixed">
  <parent link="base_link"/>
  <child link="motor_controller"/>
  <origin xyz="-0.11 0 ${chassis_height/2 + 0.03/2}"/>
    </joint>

    <gazebo reference="motor_controller">
        <material>ETABot/Blue</material>
    </gazebo>

From the point where the link "motor_controller" will be added, the model will be spawn in Gazebo without any errors but you can't see the robot in the simulator. If I remove the link "motor", the model will be spawn in Gazebo and you can see the robot with ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
6

answered 2013-08-01 16:56:07 -0500

Zee-Q gravatar image

updated 2013-08-01 16:59:55 -0500

Hi,

To spawn a urdf.xacro file in gazebo you have to first convert xacro file using xacro.py script. For example if you have robot.xacro.urdf file in a package called robot_package then following launch file will spawn your robot in Gazebo.

<launch>
<!-- Convert xacro and put on parameter server -->
<param name="robot_description" command="$(find xacro)/xacro.py $(find robot_package)/urdf/robot.urdf.xacro" />

<!-- Spawn a robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model robot" />
</launch>

Note: Replace the node and package if you are using simulator_gazebo and not stand alone gazebo accordingly. Additionally, you can find more details in this tutorial and its better to ask gazebo related questions on Gazebo sim forum.

To add color in gazebo navigate to the file gazebo.material in materials/scripts folder of your gazebo and include your own color definition. Other colors are defined there you can follow the pattern. To assign this color to a model use following code in your file.

<material>
     <script>Gazebo/yourcolor</script>
</material>

Note: This code is for SDF 1.4 change accordingly for your version see documentation hereSDF.

edit flag offensive delete link more

Comments

Hi Zee-Q, many thanks for your help. This was the way I tried to spawn my robot into Gazebo, but if I use macros it doesn't work. Apart form that I'm yousing a xacros-file. Other functions from xacros like constants or math work without any problems. I'm using ROS-Fuerte with Gazebo 1.2.

platzhirsch gravatar image platzhirsch  ( 2013-08-01 21:26:04 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2013-08-01 04:31:28 -0500

Seen: 10,717 times

Last updated: Aug 04 '13