multiple visual/collision per link in URDF
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 ...
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...
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.