URDF to SDF: Duplicate Physics Tags

asked 2020-06-12 22:58:00 -0500

adcurry gravatar image

updated 2020-06-12 23:17:30 -0500

Hi all,

I am trying to convert the following URDF into SDF using gz sdf -p model.urdf > model.sdf. I am trying to make sure the implicit spring damper is set to 1 through a gazebo reference. But in the output i get a duplicate.

INPUT URDF

<?xml version="1.0" ?>
<robot name="iris">
  <origin rpy="0 0 0" xyz="0    0     0.194923"/>

  <link name="base_link">
    <inertial>
      <mass value="1.5"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.008" ixy="0" ixz="0" iyy="0.015" iyz="0" izz="0.017"/>
    </inertial>
    <collision name="base_link">
      <origin rpy="0 0 0" xyz="0      0      -0.08"/>
      <geometry>
        <box size="0.47 0.47 0.23"/>
      </geometry>
    </collision>
    <visual name="base_link">
      <geometry>
        <mesh filename="package://pysdf/scripts/meshes/iris.dae" scale="1.0 1.0 1.0"/>
      </geometry>
    </visual>
  </link>

  <link name="rotor_0">
    <inertial>
      <mass value="0.025"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="9.75e-06" ixy="0" ixz="0" iyy="0.000166704" iyz="0" izz="0.000167604"/>
    </inertial>
    <collision name="rotor_0">
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.005" radius="0.1"/>
      </geometry>
    </collision>
    <visual name="rotor_0">
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://pysdf/scripts/meshes/iris_prop_ccw.dae" scale="1 1 1"/>
      </geometry>
    </visual>
  </link>

  <joint name="rotor_0_joint" type="revolute">
    <parent link="base_link"/>
    <child link="rotor_0"/>
    <origin rpy="0 0 0" xyz="0.13    -0.22     0.023"/>
    <axis xyz="0 0 1"/>
    <dynamics damping="0.004"/>
    <limit effort="-1" lower="-1e+16" upper="1e+16" velocity="-1"/>
  </joint>

  <gazebo reference="rotor_0">
    <collision name='rotor_0_collision'>
      <surface>
        <contact>
          <ode/>
        </contact>
        <friction>
          <ode/>
        </friction>
      </surface>
    </collision>
    <visual name='rotor_0_visual'>
      <material>
        <script>
          <name>Gazebo/Blue</name>
          <uri>__default__</uri>
        </script>
      </material>
    </visual>
    <self_collide>0</self_collide>
  </gazebo>

  <gazebo reference="rotor_0_joint">
    <physics>
      <ode>
         <implicit_spring_damper>1</implicit_spring_damper>
      </ode>
    </physics>
  </gazebo>

</robot>

The generated SDF returns multiple physics tags. Is it possible to combine them into the one tag upon upon conversion from URDF to SDF?

OUTPUT SDF (partial)

<joint name='rotor_0_joint' type='revolute'>
  <child>rotor_0</child>
  <parent>base_link</parent>
  <axis>
    <xyz>0 0 1</xyz>
    <limit>
      <lower>-1e+16</lower>
      <upper>1e+16</upper>
      <effort>-1</effort>
      <velocity>-1</velocity>
    </limit>
    <dynamics>
      <damping>0.004</damping>
      <friction>0</friction>
      <spring_reference>0</spring_reference>
      <spring_stiffness>0</spring_stiffness>
    </dynamics>
    <use_parent_model_frame>1</use_parent_model_frame>
  </axis>
  <physics>
    <ode>
      <limit>
        <cfm>0</cfm>
        <erp>0.2</erp>
      </limit>
    </ode>
  </physics>
  <physics>
    <ode>
      <implicit_spring_damper>1</implicit_spring_damper>
    </ode>
  </physics>
</joint>

Notice there are TWO physics tags! Does Gazebo9 automatically merge the two Physics tags and their contents together or does it only read one of them?

Thanks

edit retag flag offensive close merge delete

Comments

I would assume that it works but i haven't tested it. I would follow the SDF docs: link text and write it into one Element.

stephanr gravatar imagestephanr ( 2020-06-13 02:49:17 -0500 )edit