Gazebo | Ignition | Community
Ask Your Question
0

multiple visual/collision per link in URDF

asked 2021-06-22 03:26:34 -0500

this post is marked as community wiki

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

Hello everyone,

I was wondering whether there's a way to use more than one collision or visual per link in URDF? I want to merge two cylinder shaped links into one so I only have to use one inertial tag with two different visuals/collisions.

C:\fakepath\GazeboQuestion.png

In the Image I used two different Links but I only have data (inertial tag) of the whole rear axle(red part) that's why I tried to use only one Link

Thanks for your help, MeGusta

Edit: Thanks for your answers, I have to problem if i try to use 2 visual and 2 collision tags one link with only one inertia tag, one of them doesnt show up on my Model for ex here is how i tried it :

<link name='hintere_Achse'>
  <inertial>
    <mass>32.528</mass>
    <inertia>
      <ixx>0.074</ixx>
      <ixy>-0.003</ixy>
      <ixz>0.997</ixz>
      <iyy>0.023</iyy>
      <iyz>-0.073</iyz>
      <izz>0.004</izz>
    </inertia>
    <pose>0 0 0 0 -0 0</pose>
  </inertial>
  <pose>-0.3695 -0 0.145945 0 -0 0</pose>
  <gravity>1</gravity>
  <self_collide>0</self_collide>
  <kinematic>0</kinematic>
  <enable_wind>0</enable_wind>
  <visual name='visual'>
    <pose>0 0 0 -0.000572 1.5707 1.57013</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.302</length>
      </cylinder>
    </geometry>
    <material>
      <lighting>1</lighting>
      <script>
        <uri>file://media/materials/scripts/gazebo.material</uri>
        <name>Gazebo/White</name>
      </script>
      <shader type='pixel'>
        <normal_map>__default__</normal_map>
      </shader>
    </material>
    <transparency>0</transparency>
    <cast_shadows>1</cast_shadows>
  </visual>
  <collision name='collision'>
    <laser_retro>0</laser_retro>
    <max_contacts>10</max_contacts>
    <pose>0 0 0 -0 1.5707 1.5707</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.302</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>1</mu>
          <mu2>1</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>
  <visual name='visual2'>
    <pose>0 0 0 0 1.5707 0</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.3695</length>
      </cylinder>
    </geometry>
    <material>
      <lighting>1</lighting>
      <script>
        <uri>file://media/materials/scripts/gazebo.material</uri>
        <name>Gazebo/White</name>
      </script>
      <shader type='pixel2'>
        <normal_map>__default__</normal_map>
      </shader>
    </material>
    <transparency>0</transparency>
    <cast_shadows>1</cast_shadows>
  </visual>
  <collision name='collision2'>
    <laser_retro>0</laser_retro>
    <max_contacts>10</max_contacts>
    <pose>0 0 0 0 1.5707 0</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.3695</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>1</mu>
          <mu2>1</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2 ...
(more)
edit retag flag offensive close merge delete

Comments

You should try to do more unitary tests. try with an urdf with only inertial/collision/visual tags, and remove all tags related to bullet, contact, surface, ect. It will be more easy to see what is wrong. Here it is unreadable...

Clément Rolinat gravatar imageClément Rolinat ( 2021-06-29 09:25:02 -0500 )edit

You should try removing the "name" attribute in collision and visual tags. Maybe the multi collision/visual tag feature work only if you let the parser choose names automatically.

Clément Rolinat gravatar imageClément Rolinat ( 2021-07-08 07:29:33 -0500 )edit

3 Answers

Sort by » oldest newest most voted
0

answered 2021-06-28 02:10:41 -0500

MeGusta gravatar image

Thanks for your answers, I have to problem if i try to use 2 visual and 2 collision tags one link with only one inertia tag, one of them doesnt show up on my Model for ex here is how i tried it :

<link name='hintere_Achse'>
  <inertial>
    <mass>32.528</mass>
    <inertia>
      <ixx>0.074</ixx>
      <ixy>-0.003</ixy>
      <ixz>0.997</ixz>
      <iyy>0.023</iyy>
      <iyz>-0.073</iyz>
      <izz>0.004</izz>
    </inertia>
    <pose>0 0 0 0 -0 0</pose>
  </inertial>
  <pose>-0.3695 -0 0.145945 0 -0 0</pose>
  <gravity>1</gravity>
  <self_collide>0</self_collide>
  <kinematic>0</kinematic>
  <enable_wind>0</enable_wind>
  <visual name='visual'>
    <pose>0 0 0 -0.000572 1.5707 1.57013</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.302</length>
      </cylinder>
    </geometry>
    <material>
      <lighting>1</lighting>
      <script>
        <uri>file://media/materials/scripts/gazebo.material</uri>
        <name>Gazebo/White</name>
      </script>
      <shader type='pixel'>
        <normal_map>__default__</normal_map>
      </shader>
    </material>
    <transparency>0</transparency>
    <cast_shadows>1</cast_shadows>
  </visual>
  <collision name='collision'>
    <laser_retro>0</laser_retro>
    <max_contacts>10</max_contacts>
    <pose>0 0 0 -0 1.5707 1.5707</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.302</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>1</mu>
          <mu2>1</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>
  <visual name='visual2'>
    <pose>0 0 0 0 1.5707 0</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.3695</length>
      </cylinder>
    </geometry>
    <material>
      <lighting>1</lighting>
      <script>
        <uri>file://media/materials/scripts/gazebo.material</uri>
        <name>Gazebo/White</name>
      </script>
      <shader type='pixel2'>
        <normal_map>__default__</normal_map>
      </shader>
    </material>
    <transparency>0</transparency>
    <cast_shadows>1</cast_shadows>
  </visual>
  <collision name='collision2'>
    <laser_retro>0</laser_retro>
    <max_contacts>10</max_contacts>
    <pose>0 0 0 0 1.5707 0</pose>
    <geometry>
      <cylinder>
        <radius>0.025</radius>
        <length>0.3695</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>1</mu>
          <mu2>1</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 ...
(more)
edit flag offensive delete link more

Comments

hello, can you provide a minimal example showing your issue (that is an urdf with only inertial/collision/visual tags that shows your issue)? Indeed there are a lot of unused/useless tags in your urdf, it is difficult to help... And maybe I think you should not post it as an answer, but edit your initial question instead. Also, can you provide more details on what is happening ? Which visual geometry is correctly displayed, and which one is not, and same for collision geometry.

Clément Rolinat gravatar imageClément Rolinat ( 2021-06-29 02:22:46 -0500 )edit

Hello, first of all thank you for your help I have a lot of more code but its only this part where the problem is. I try to do everything the same as i did when i only used 1 collision tag and 1 visual tag. Only difference is I used 2 of both. Now if i try to place the Robot in gazebo it shows at first but when i left click it to place it, it disappears. Also the part i changed (marked red in first pic) its not even there in the preview.

MeGusta gravatar imageMeGusta ( 2021-06-29 06:51:28 -0500 )edit
0

answered 2021-06-24 04:06:05 -0500

Clément Rolinat gravatar image

updated 2021-06-25 08:15:41 -0500

hello, actually you can specify several collision tags and visual tags inside the same link tag (at least I did it for collision tags and it work perfectly with Gazebo 9). This feature is described here: urdf doc

for example, a link defined like this works well:

<link name="link_name">
    <inertial>
        <origin
             xyz=<set origin>
             rpy=<set origin> />
        <mass
             value=<set mass> />
        <inertia <set inertia>
                ixx=
                ixy=
                ixz=
                iyy=
                iyz=
                izz= />
    </inertial>
    <visual>
            <origin
                    xyz="0 0 0"
                    rpy="0 0 0" />
            <geometry>
                <mesh
                        filename=<path to mesh> />
            </geometry>
    </visual>
    <collision>
            <origin
                    xyz=<set origin>
                    rpy=<set origin>
            <geometry>
                   <cylinder radius= length= />
            </geometry>
    </collision>
    <collision>
            <origin
                    xyz=<set origin>
                    rpy=<set origin> />
            <geometry>
                 <sphere radius= />
            </geometry>
    </collision>
</link>

I set a mesh for the visual tag because in my case, I have a mesh, so I use directly the mesh for the visual, and I use simplier geometry for the collision. But I think it shouldn't cause any problem to have several visual tags with simple geometry as well.

edit flag offensive delete link more

Comments

Well, I learned something today, so that's great! Cheers. I'm curious though, the link you included specifies that

"It was decided that URDFs should not support multiple groups of collision bodies, even though there are sometimes applications for this ..."

Does Gazebo still represent the multiple collision models correctly?

shonigmann gravatar imageshonigmann ( 2021-06-24 19:42:31 -0500 )edit

Yes, Gazebo represents the collision geometries correctly when you check the corresponding option in GUI to display collision bodies. The paragraph you refer to is about something else: for exemple, if you need a given collision geometry for the physics, and an other collision geometry for path planning. This is not possible in urdf, unless you add your own tag and parse it yourself.

Clément Rolinat gravatar imageClément Rolinat ( 2021-06-25 08:04:04 -0500 )edit

good to know, thanks again

shonigmann gravatar imageshonigmann ( 2021-06-27 11:30:28 -0500 )edit

Thanks for you answers I posted another answer because my code is too big for a comment due the useless lines of code ;) maybe you can see my question there :D

MeGusta gravatar imageMeGusta ( 2021-06-28 02:11:55 -0500 )edit
0

answered 2021-06-22 13:38:35 -0500

shonigmann gravatar image

updated 2021-06-24 19:44:32 -0500

̶U̶n̶f̶o̶r̶t̶u̶n̶a̶t̶e̶l̶y̶ ̶t̶h̶i̶s̶ ̶i̶s̶ ̶n̶o̶t̶ ̶p̶o̶s̶s̶i̶b̶l̶e̶ ̶t̶o̶ ̶m̶y̶ ̶k̶n̶o̶w̶l̶e̶d̶g̶e̶,̶ ̶a̶n̶d̶ ̶I̶ ̶a̶g̶r̶e̶e̶ ̶i̶t̶ ̶c̶a̶n̶ ̶f̶e̶e̶l̶ ̶t̶e̶d̶i̶o̶u̶s̶ ̶t̶o̶ ̶s̶p̶e̶c̶i̶f̶y̶ ̶t̶h̶e̶ ̶e̶x̶t̶r̶a̶ ̶f̶i̶x̶e̶d̶ ̶j̶o̶i̶n̶t̶.̶ Some alternatives are:

  • as you suggested, having multiple links and only defining the inertial tag in one link, or
  • using a basic CAD/Mesh editor (e.g. MeshLab or OnShape) to create a single mesh file with the two cylinders
edit flag offensive delete link more
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2021-06-22 03:26:34 -0500

Seen: 584 times

Last updated: Jun 29 '21