Links and joints don't appear in generated SDF

asked 2017-09-27 18:04:07 -0600

clydemcqueen gravatar image

updated 2017-09-29 14:43:33 -0600

I'm using ROS and Gazebo and I'm a bit mystified by the URDF to SDF conversion process. It appears that all links except the base_link, and all joints, are not added to the generated SDF file. What I get is a single link with 1 combined inertial section and multiple collision and visual sections. Most of the names are mangled.

I'm writing a plugin that applies force to some joints, and I need to get the joint poses. I see plugin code that enumerates links and joints looking at name matches, but I suppose that this is only possible if I hand-build an SDF file? Is there a preferred way to manage this?

For reference, here's a snippet of my roslaunch file showing how I'm injecting URDF files into Gazebo:

<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -z 1 -model test"/>

Updated: here's a stripped down URDF file that I used for testing:

<?xml version="1.0"?>
<robot name="test">
  <link name="base_link">
    <inertial>
      <origin xyz="0 0 0"/>
      <mass value="1"/>
      <inertia
        ixx="1.0" ixy="0.0" ixz="0.0"
        iyy="1.0" iyz="0.0"
        izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </collision>
  </link>
  <link name="two">
    <inertial>
      <origin xyz="0 0 0"/>
      <mass value="2"/>
      <inertia
        ixx="1.0" ixy="0.0" ixz="0.0"
        iyy="1.0" iyz="0.0"
        izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <box size="1 1 1"/>
      </geometry>
    </collision>
  </link>
  <joint name="base_link_to_two" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="base_link"/>
    <child link="two"/>
  </joint>
</robot>

Here's the resulting SDF:

<sdf version='1.6'>
  <model name='test'>
    <link name='base_link'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>3</mass>
        <inertia>
          <ixx>2</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>2</iyy>
          <iyz>0</iyz>
          <izz>2</izz>
        </inertia>
      </inertial>
      <collision name='base_link_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>1 1 1</size>
          </box>
        </geometry>
      </collision>
      <collision name='base_link_fixed_joint_lump__two_collision_1'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>1 1 1</size>
          </box>
        </geometry>
      </collision>
      <visual name='base_link_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>1 1 1</size>
          </box>
        </geometry>
      </visual>
      <visual name='base_link_fixed_joint_lump__two_visual_1'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>1 1 1</size>
          </box>
        </geometry>
      </visual>
    </link>
  </model>
</sdf>
edit retag flag offensive close merge delete

Comments

Seeing your URDF or a simplified version of it which reproduces the problem would help. I assume your links and joints are missing from the Gazebo UI, or are you checking it some other way?

chapulina gravatar imagechapulina ( 2017-09-27 18:12:57 -0600 )edit

do you have fixed joints in your URDF model? If so, all the links connected by fixed joints could be lumped together into one link with multiple collisions. The <disablefixedjointlumping> tag could help here

iche033 gravatar imageiche033 ( 2017-09-27 21:05:56 -0600 )edit

Ah, thanks for the comment iche033 -- I wasn't aware of the <disablefixedjointlumping> tag.

clydemcqueen gravatar imageclydemcqueen ( 2017-09-29 14:45:50 -0600 )edit