bullet3/data/kuka_iiwa/kuka_with_gripper.sdf

803 lines
23 KiB
Plaintext
Raw Normal View History

2017-05-23 05:23:01 +00:00
<?xml version="1.0" ?>
<!--This file contains the SDF model of a KUKA iiwa robot with a wsg50 gripper.
It has been produced from the varients in //third_party/robotics/models.
Note: This file is temporary, and should be deleted once Bullet supports
importing models in SDF. Also, this file has been specialized for Bullet,
because the mass of the base link has been set to 0, as needed by Bullet.
Note: All of the gripper link poses have been adjusted in the z direction
to achieve a reasonable position of the gripper relative to the arm.
Note: The joint names for the KUKA have been changed to J0, J1, etc. -->
<sdf version='1.6'>
<world name='default'>
<model name='lbr_iiwa_with_wsg50'>
<link name='lbr_iiwa_link_0'>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertial>
<pose frame=''>-0.1 0 0.07 0 -0 0</pose>
<mass>0</mass>
<inertia>
<ixx>0.05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.06</iyy>
<iyz>0</iyz>
<izz>0.03</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_0_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>/meshes/link_0.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_0_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_0.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.2 0.2 0.2 1.0</diffuse>
<specular>0.4 0.4 0.4 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<link name='lbr_iiwa_link_1'>
<pose frame=''>0 0 0.1575 0 -0 0</pose>
<inertial>
<pose frame=''>0 -0.03 0.12 0 -0 0</pose>
<mass>4</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.09</iyy>
<iyz>0</iyz>
<izz>0.02</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_1_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_1.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_1_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_1.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J0' type='revolute'>
<child>lbr_iiwa_link_1</child>
<parent>lbr_iiwa_link_0</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-2.96706</lower>
<upper>2.96706</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='lbr_iiwa_link_2'>
<pose frame=''>0 0 0.36 1.5708 -0 -3.14159</pose>
<inertial>
<pose frame=''>0.0003 0.059 0.042 0 -0 0</pose>
<mass>4</mass>
<inertia>
<ixx>0.05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.018</iyy>
<iyz>0</iyz>
<izz>0.044</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_2_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_2.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_2_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_2.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J1' type='revolute'>
<child>lbr_iiwa_link_2</child>
<parent>lbr_iiwa_link_1</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-2.0944</lower>
<upper>2.0944</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='lbr_iiwa_link_3'>
<pose frame=''>0 -0 0.5645 0 0 0</pose>
<inertial>
<pose frame=''>0 0.03 0.13 0 -0 0</pose>
<mass>3</mass>
<inertia>
<ixx>0.08</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.075</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_3_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_3.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_3_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_3.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J2' type='revolute'>
<child>lbr_iiwa_link_3</child>
<parent>lbr_iiwa_link_2</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-2.96706</lower>
<upper>2.96706</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='lbr_iiwa_link_4'>
<pose frame=''>0 -0 0.78 1.5708 0 0</pose>
<inertial>
<pose frame=''>0 0.067 0.034 0 -0 0</pose>
<mass>2.7</mass>
<inertia>
<ixx>0.03</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.029</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_4_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_4.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_4_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_4.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J3' type='revolute'>
<child>lbr_iiwa_link_4</child>
<parent>lbr_iiwa_link_3</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-2.0944</lower>
<upper>2.0944</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='lbr_iiwa_link_5'>
<pose frame=''>0 -0 0.9645 0 -0 -3.14159</pose>
<inertial>
<pose frame=''>0.0001 0.021 0.076 0 -0 0</pose>
<mass>1.7</mass>
<inertia>
<ixx>0.02</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.018</iyy>
<iyz>0</iyz>
<izz>0.005</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_5_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_5.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_5_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_5.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J4' type='revolute'>
<child>lbr_iiwa_link_5</child>
<parent>lbr_iiwa_link_4</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-2.96706</lower>
<upper>2.96706</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='lbr_iiwa_link_6'>
<pose frame=''>0 0 1.18 1.5708 -0 -3.14159</pose>
<inertial>
<pose frame=''>0 0.0006 0.0004 0 -0 0</pose>
<mass>1.8</mass>
<inertia>
<ixx>0.005</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0036</iyy>
<iyz>0</iyz>
<izz>0.0047</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_6_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_6.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_6_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_6.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J5' type='revolute'>
<child>lbr_iiwa_link_6</child>
<parent>lbr_iiwa_link_5</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-2.0944</lower>
<upper>2.0944</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='lbr_iiwa_link_7'>
<pose frame=''>0 0 1.261 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0.02 0 -0 0</pose>
<mass>0.3</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name='lbr_iiwa_link_7_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_7.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='lbr_iiwa_link_7_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_7.obj</uri>
2017-05-23 05:23:01 +00:00
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
2017-05-23 05:23:01 +00:00
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='J6' type='revolute'>
<child>lbr_iiwa_link_7</child>
<parent>lbr_iiwa_link_6</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-3.05433</lower>
<upper>3.05433</upper>
<effort>300</effort>
<velocity>10</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<!-- Attach the base of the gripper to the end of the arm -->
<joint name='gripper_to_arm' type='fixed'>
<parent>lbr_iiwa_link_7</parent>
<child>base_link</child>
</joint>
<link name='base_link'>
<pose frame=''>0 0 1.305 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>1.2</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<visual name='base_link_visual'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.1 </size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
</link>
<joint name='base_left_finger_joint' type='revolute'>
<parent>base_link</parent>
<child>left_finger</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-10.4</lower>
<upper>10.01</upper>
2017-05-23 05:23:01 +00:00
<effort>100</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='left_finger'>
<pose frame=''>0 0.024 1.35 0 -0.05 0</pose>
<inertial>
<pose frame=''>0 0 0.04 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='left_finger_visual'>
<pose frame=''>0 0 0.04 0 0 0</pose>
<geometry>
<box>
<size>0.01 0.01 0.08</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
</link>
<joint name='left_finger_base_joint' type='fixed'>
<parent>left_finger</parent>
<child>left_finger_base</child>
</joint>
<link name='left_finger_base'>
<pose frame=''>-0.005 0.024 1.43 0 -0.3 0</pose>
<inertial>
<pose frame=''>-0.003 0 0.04 0 0 0 </pose>
<mass>0.2</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='left_finger_base_visual'>
<pose frame=''>0 0 0 0 0 0 </pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_base_left.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
<collision name='left_finger_base_collision'>
<pose frame=''>0 0 0 0 0 0 </pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_base_left.stl</uri>
</mesh>
</geometry>
</collision>
</link>
<joint name='left_base_tip_joint' type='revolute'>
<parent>left_finger_base</parent>
<child>left_finger_tip</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-10.1</lower>
<upper>10.3</upper>
2017-05-23 05:23:01 +00:00
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='left_finger_tip'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>1.0</spinning_friction>
</contact>
<pose frame=''>-0.02 0.024 1.49 0 0.2 0</pose>
<inertial>
<pose frame=''>-0.005 0 0.026 0 0 0 </pose>
<mass>0.2</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='left_finger_tip_visual'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_tip_left.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
<collision name='left_finger_tip_collision'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_tip_left.stl</uri>
</mesh>
</geometry>
</collision>
</link>
<joint name='base_right_finger_joint' type='revolute'>
<parent>base_link</parent>
<child>right_finger</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-10.01</lower>
<upper>10.4</upper>
2017-05-23 05:23:01 +00:00
<effort>100</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='right_finger'>
<pose frame=''>0 0.024 1.35 0 0.05 0</pose>
<inertial>
<pose frame=''>0 0 0.04 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='right_finger_visual'>
<pose frame=''>0 0 0.04 0 0 0</pose>
<geometry>
<box>
<size>0.01 0.01 0.08</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
</link>
<joint name='right_finger_base_joint' type='fixed'>
<parent>right_finger</parent>
<child>right_finger_base</child>
</joint>
<link name='right_finger_base'>
<pose frame=''>0.005 0.024 1.43 0 0.3 0</pose>
<inertial>
<pose frame=''>0.003 0 0.04 0 0 0 </pose>
<mass>0.2</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='right_finger_base_visual'>
<pose frame=''>0 0 0 0 0 0 </pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_base_right.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
<collision name='right_finger_base_collision'>
<pose frame=''>0 0 0 0 0 0 </pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_base_right.stl</uri>
</mesh>
</geometry>
</collision>
</link>
<joint name='right_base_tip_joint' type='revolute'>
<parent>right_finger_base</parent>
<child>right_finger_tip</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-10.3</lower>
<upper>10.1</upper>
2017-05-23 05:23:01 +00:00
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<damping>0</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
<link name='right_finger_tip'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>1.0</spinning_friction>
</contact>
<pose frame=''>0.02 0.024 1.49 0 -0.2 0</pose>
<inertial>
<pose frame=''>0.005 0 0.026 0 0 0 </pose>
<mass>0.2</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='right_finger_visual'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_tip_right.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
2017-05-23 05:23:01 +00:00
</visual>
<collision name='right_finger_tip_collision'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>1 1 1 </scale>
<uri>meshes/finger_tip_right.stl</uri>
</mesh>
</geometry>
</collision>
</link>
</model>
</world>
</sdf>