bullet3/data/kuka_iiwa/kuka_world.sdf

414 lines
12 KiB
Plaintext
Raw Normal View History

2016-05-11 20:43:50 +00:00
<sdf version='1.6'>
<world name='default'>
<model name='lbr_iiwa'>
<joint name='fix_to_world' type='fixed'>
<parent>world</parent>
<child>lbr_iiwa_link_0</child>
</joint>
<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.01</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/coarse/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.stl</uri>
</mesh>
</geometry>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_1' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_2' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_3' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_4' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_5' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_6' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</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/coarse/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.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<joint name='lbr_iiwa_joint_7' 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>
<use_parent_model_frame>0</use_parent_model_frame>
</axis>
</joint>
</model>
</world>
</sdf>