Gazebo | Ignition | Community
Ask Your Question
2

How to support additional sdf elements (<ode>, <bullet>, <bounce>, etc) in urdf file using the <gazebo> tag

asked 2017-11-14 01:41:52 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

Hey there,

I would like to use ROS and urdf to simulate my robot. (I do not want to use any sdf files). However I have a given sdf file and now try to convert it to urdf. Now my problem is that in the sdf file there are multiple physics engines used ( ode and bullet). Does anyone know how to convert that to urdf? Cause according to this http://gazebosim.org/tutorials/?tut=r... Tutorial (under <gazebo> Elements For Links) There is only a very limited table of what is possible to add in gazebo references.</gazebo>

This is a snippet of my sdf file I would like to convert to urdf:

 <collision name='body_collision'>
    <laser_retro>0</laser_retro>
    <max_contacts>10</max_contacts>
    <pose frame=''>0 0 0 0 -0 0</pose>
    <geometry>
      <mesh>
        <uri>model://ballbot/meshs/body.stl</uri>
        <scale>0.001 0.001 0.001</scale>
      </mesh>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>0</mu>
          <mu2>0</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
        <torsional>
          <coefficient>1</coefficient>
          <patch_radius>0</patch_radius>
          <surface_radius>0</surface_radius>
          <use_patch_radius>1</use_patch_radius>
          <ode>
            <slip>0</slip>
          </ode>
        </torsional>
      </friction>
      <bounce>
        <restitution_coefficient>0</restitution_coefficient>
        <threshold>1e+06</threshold>
      </bounce>
      <contact>
        <collide_without_contact>0</collide_without_contact>
        <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
        <collide_bitmask>1</collide_bitmask>
        <ode>
          <soft_cfm>0</soft_cfm>
          <soft_erp>0.2</soft_erp>
          <kp>1e+13</kp>
          <kd>1</kd>
          <max_vel>0.01</max_vel>
          <min_depth>0</min_depth>
        </ode>
        <bullet>
          <split_impulse>1</split_impulse>
          <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
          <soft_cfm>0</soft_cfm>
          <soft_erp>0.2</soft_erp>
          <kp>1e+13</kp>
          <kd>1</kd>
        </bullet>
      </contact>
    </surface>
  </collision>

I currently did it like this:

  <gazebo reference="base_link">
<material>Gazebo/DarkGrey</material>
<gravity>1</gravity>
<maxVel>0.01</maxVel>
<minDepth>0</minDepth>
<mu1>0.0</mu1>
<mu2>0.0</mu2>
<fdir1>0 0 0</fdir1>
<kp>1e+13</kp>
<kd>1.0</kd>
<selfCollide>0</selfCollide>
<maxContacts>10</maxContacts>
<laserRetro>0</laserRetro>
</gazebo>

With josephcoombe hint I now did the following:test.urdf:

<?xml version="1.0"?>
<robot name ="myrobot" xmlns:xacro="http://ros.org/wiki/xacro">

      <link name="wheel2_link">
         <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
               <mesh filename="package://....stl" scale="0.001 0.001 0.001" />
            </geometry>
            <cast_shadows>1</cast_shadows>
            <transparency>0</transparency>
            <material name="light_black" />
         </visual>
         <inertial>
            <origin xyz="0.0 0.0 0.0" />
            <mass value="0.275" />
            <inertia ixx="0.00026602" ixy="0" ixz="0" iyy="0.00019582" iyz="0" izz="0.00029553" />
         </inertial>
         <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
               <mesh filename="package://....stl" scale="0.001 0.001 0.001" />
            </geometry>
         </collision>
      </link>


 <gazebo reference="wheel2_link">
    <maxVel>0.01</maxVel>
    <minDepth>0</minDepth>
    <mu1>0.2</mu1>
    <mu2>0.0</mu2>
    <fdir1>0 0 0</fdir1>
    <kp>1e+13</kp>
    <kd>1.0</kd>
    <selfCollide>0</selfCollide>
    <maxContacts>10</maxContacts>
    <laserRetro>0</laserRetro>
  </gazebo>
</robot>

My result test.sdf file:

<sdf version='1.6'>
  <model name='myrobot'>
    <link name='wheel2_link'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 ...
(more)
edit retag flag offensive close merge delete

Comments

Edited question title to better reflect content

josephcoombe gravatar imagejosephcoombe ( 2017-11-16 11:03:04 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2017-11-15 10:03:17 -0500

updated 2017-11-16 10:10:10 -0500

You can add additional SDF-specific tags under your <gazebo reference="name_link"> tag.

How to check if this works:

  1. Make a *.urdf using this strategy.
  2. Use gz sdf -p my_urdf.urdf > my_sdf.sdf to convert your *.urdf into *.sdf.
  3. Check that the generated *.sdf matches your original *.sdf.

Example:

1.

<?xml version="1.0"?>
<robot name="testrobot">
  <link name="base_link">
    <visual>
      <geometry>
        <box size="0.3048 0.3048 0.1524"/>
      </geometry>
      <material name="silver">
        <color rgba="0.75 0.75 0.75 1"/>
      </material>
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </visual>
    <collision>
      <geometry>
        <box size="0.3048 0.3048 0.1524"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </collision>
    <inertial>
      <mass value="1.0"/>
      <inertia ixx="0.009677" iyy="0.01548" izz="0.009677"
               ixy="0.0" ixz="0.0" iyz="0.0"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
    </inertial>
  </link>

  <gazebo reference="base_link">
    <collision>
      <surface>
        <bounce>
          <restitution_coefficient>0</restitution_coefficient>
          <threshold>1e+06</threshold>
        </bounce>
        <contact>
          <collide_without_contact>0</collide_without_contact>
          <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
          <collide_bitmask>1</collide_bitmask>
          <ode>
            <soft_cfm>0</soft_cfm>
            <soft_erp>0.2</soft_erp>
            <kp>1e+13</kp>
            <kd>1</kd>
            <max_vel>0.01</max_vel>
            <min_depth>0</min_depth>
          </ode>
          <bullet>
            <split_impulse>1</split_impulse>
            <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
            <soft_cfm>0</soft_cfm>
            <soft_erp>0.2</soft_erp>
            <kp>1e+13</kp>
            <kd>1</kd>
          </bullet>
        </contact>
      </surface>
    </collision>
  </gazebo>
</robot>

2.

gz sdf -p test.urdf > test.sdf

3.

<sdf version='1.6'>
  <model name='testrobot'>
    <link name='base_link'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>1</mass>
        <inertia>
          <ixx>0.009677</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.01548</iyy>
          <iyz>0</iyz>
          <izz>0.009677</izz>
        </inertia>
      </inertial>
      <collision name='base_link_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.3048 0.3048 0.1524</size>
          </box>
        </geometry>
        <surface>
          <bounce>
            <restitution_coefficient>0</restitution_coefficient>
            <threshold>1e+06</threshold>
          </bounce>
          <contact>
            <collide_without_contact>0</collide_without_contact>
            <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
            <collide_bitmask>1</collide_bitmask>
            <ode>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
              <max_vel>0.01</max_vel>
              <min_depth>0</min_depth>
            </ode>
            <bullet>
              <split_impulse>1</split_impulse>
              <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
              <soft_cfm>0</soft_cfm>
              <soft_erp>0.2</soft_erp>
              <kp>1e+13</kp>
              <kd>1</kd>
            </bullet>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='base_link_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.3048 0.3048 0.1524</size>
          </box>
        </geometry>
        <material>
          <script>
            <uri>__default__</uri>
            <name>__default__</name>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>
  </model>
</sdf>
edit flag offensive delete link more

Comments

Thats a nice check thanks! I tried it as you can see above ... However I do not know how to convert tags like <collide_bitmask>1</collide_bitmask> or bounce tags so that they are correctly parsed from urdf to sdf.....

markus gravatar imagemarkus ( 2017-11-16 03:59:40 -0500 )edit

@markus I've updated my answer. For some of the tags, you'll have to provide the full xml hierarchy using proper sdf (http://sdformat.org/spec?ver=1.6&elem=collision) within your gazebo tag.

josephcoombe gravatar imagejosephcoombe ( 2017-11-16 10:04:58 -0500 )edit

I guess the tags in the http://gazebosim.org/tutorials/?tut=ros_urdf table are commonly used, so the urdf to sdf parser lets you use them without an explicit hierarchy as a "shortcut."

josephcoombe gravatar imagejosephcoombe ( 2017-11-16 10:07:18 -0500 )edit
1

All right :) Thanks a lot! Thats great I just use all the values from the table as a shortcut and the rest I just implement in a gazebo reference as full sdf.

markus gravatar imagemarkus ( 2017-11-16 13:57:04 -0500 )edit
Login/Signup to Answer

Question Tools

2 followers

Stats

Asked: 2017-11-14 01:41:52 -0500

Seen: 4,302 times

Last updated: Nov 16 '17