add more URDF files to pybullet_data
This commit is contained in:
Binary file not shown.
BIN
examples/pybullet/gym/pybullet_data/gripper/meshes/WSG-FMF.stl
Normal file
BIN
examples/pybullet/gym/pybullet_data/gripper/meshes/WSG-FMF.stl
Normal file
Binary file not shown.
BIN
examples/pybullet/gym/pybullet_data/gripper/meshes/WSG50_110.stl
Normal file
BIN
examples/pybullet/gym/pybullet_data/gripper/meshes/WSG50_110.stl
Normal file
Binary file not shown.
Binary file not shown.
@@ -0,0 +1,388 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
<pose frame=''>0 0 0.26 3.14 0 0</pose>
|
||||
|
||||
<link name='world'>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='prismatic'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.5</lower>
|
||||
<upper>10</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<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.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>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<link name='motor'>
|
||||
<pose frame=''>0 0 0.03 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 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='motor_visual'>
|
||||
<pose frame=''>0 0 0.01 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.02 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_motor' type='prismatic'>
|
||||
<child>motor</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.047</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>10.0</effort>
|
||||
<velocity>10.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_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>-0.03 0 0.01 0 -1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_left_hinge_joint' type='revolute'>
|
||||
<child>left_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='right_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>0.03 0 0.01 0 1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_right_hinge_joint' type='revolute'>
|
||||
<child>right_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0.06 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_left_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name='gripper_left_hinge_joint' type='revolute'>
|
||||
<child>gripper_left</child>
|
||||
<parent>left_hinge</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1.0</lower>
|
||||
<upper>1.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.01</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='gripper_right'>
|
||||
<pose frame=''>0.055 0 0.06 0 0 3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_right_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_right_hinge_joint' type='revolute'>
|
||||
<child>gripper_right</child>
|
||||
<parent>right_hinge</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-1.0</lower>
|
||||
<upper>1.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.01</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='finger_right'>
|
||||
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_right_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_right_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_right' type='fixed'>
|
||||
<parent>gripper_right</parent>
|
||||
<child>finger_right</child>
|
||||
</joint>
|
||||
|
||||
<link name='finger_left'>
|
||||
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_left_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_left_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_left' type='fixed'>
|
||||
<parent>gripper_left</parent>
|
||||
<child>finger_left</child>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,394 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
|
||||
<pose frame=''>0 -2.3 2.1 0 0 0</pose>
|
||||
<link name='world'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='fixed'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
</joint>
|
||||
|
||||
<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.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>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<link name='motor'>
|
||||
<pose frame=''>0 0 0.03 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 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='motor_visual'>
|
||||
<pose frame=''>0 0 0.01 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.02 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_motor' type='prismatic'>
|
||||
<child>motor</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.047</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>10.0</effort>
|
||||
<velocity>10.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_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>-0.03 0 0.01 0 -1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_left_hinge_joint' type='revolute'>
|
||||
<child>left_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='right_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>0.03 0 0.01 0 1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_right_hinge_joint' type='revolute'>
|
||||
<child>right_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0.06 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_left_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name='gripper_left_hinge_joint' type='revolute'>
|
||||
<child>gripper_left</child>
|
||||
<parent>left_hinge</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-4.0</lower>
|
||||
<upper>4.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.01</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='gripper_right'>
|
||||
<pose frame=''>0.055 0 0.06 0 0 3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_right_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_right_hinge_joint' type='revolute'>
|
||||
<child>gripper_right</child>
|
||||
<parent>right_hinge</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-4.0</lower>
|
||||
<upper>4.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0.01</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='finger_right'>
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<spinning_friction value="1.5"/>
|
||||
</contact>
|
||||
<pose frame=''>0.042 0 0.145 0 0 1.5708</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_right_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_right_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_right' type='fixed'>
|
||||
<parent>gripper_right</parent>
|
||||
<child>finger_right</child>
|
||||
</joint>
|
||||
|
||||
<link name='finger_left'>
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<spinning_friction value="1.5"/>
|
||||
</contact>
|
||||
<pose frame=''>-0.042 0 0.145 0 0 4.71239</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_left_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_left_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_left' type='fixed'>
|
||||
<parent>gripper_left</parent>
|
||||
<child>finger_left</child>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,27 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="left_finger.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<inertia_scaling value="3.0"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.05"/>
|
||||
<mass value=".2"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 4.71239" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/l_gripper_tip_scaled.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.042"/>
|
||||
<geometry>
|
||||
<box size="0.02 0.02 0.15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
@@ -0,0 +1,394 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
<pose frame=''>0 0 0.7 3.14 0 0</pose>
|
||||
|
||||
<link name='world'>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='prismatic'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.5</lower>
|
||||
<upper>10</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<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.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>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<link name='motor'>
|
||||
<pose frame=''>0 0 0.03 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 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='motor_visual'>
|
||||
<pose frame=''>0 0 0.01 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.02 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_motor' type='prismatic'>
|
||||
<child>motor</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.055</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>10.0</effort>
|
||||
<velocity>10.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_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>-0.03 0 0.01 0 -1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_left_hinge_joint' type='revolute'>
|
||||
<child>left_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='right_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>0.03 0 0.01 0 1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_right_hinge_joint' type='revolute'>
|
||||
<child>right_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0.06 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_left_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name='gripper_left_hinge_joint' type='prismatic'>
|
||||
<child>gripper_left</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.01</lower>
|
||||
<upper>0.05</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='gripper_right'>
|
||||
<pose frame=''>0.055 0 0.06 0 0 3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_right_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_right_hinge_joint' type='prismatic'>
|
||||
<child>gripper_right</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.01</lower>
|
||||
<upper>0.05</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='finger_right'>
|
||||
<contact>
|
||||
<spinning_friction>.3</spinning_friction>
|
||||
<rolling_friction>0.04</rolling_friction>
|
||||
</contact>
|
||||
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_right_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_right_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_right' type='fixed'>
|
||||
<parent>gripper_right</parent>
|
||||
<child>finger_right</child>
|
||||
</joint>
|
||||
|
||||
<link name='finger_left'>
|
||||
<contact>
|
||||
<spinning_friction>.3</spinning_friction>
|
||||
<rolling_friction>0.04</rolling_friction>
|
||||
</contact>
|
||||
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_left_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_left_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_left' type='fixed'>
|
||||
<parent>gripper_left</parent>
|
||||
<child>finger_left</child>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,391 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
<pose frame=''>1.4 -0.2 2.1 0 0 0</pose>
|
||||
<link name='world'>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='fixed'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
</joint>
|
||||
|
||||
<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.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>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<link name='motor'>
|
||||
<pose frame=''>0 0 0.03 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 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='motor_visual'>
|
||||
<pose frame=''>0 0 0.01 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.02 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_motor' type='prismatic'>
|
||||
<child>motor</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.055</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>10.0</effort>
|
||||
<velocity>10.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_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>-0.03 0 0.01 0 -1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_left_hinge_joint' type='revolute'>
|
||||
<child>left_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='right_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>0.03 0 0.01 0 1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_right_hinge_joint' type='revolute'>
|
||||
<child>right_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0.06 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_left_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name='gripper_left_hinge_joint' type='prismatic'>
|
||||
<child>gripper_left</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.01</lower>
|
||||
<upper>0.05</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='gripper_right'>
|
||||
<pose frame=''>0.055 0 0.06 0 0 3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_right_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_right_hinge_joint' type='prismatic'>
|
||||
<child>gripper_right</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.01</lower>
|
||||
<upper>0.05</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='finger_right'>
|
||||
<contact>
|
||||
<lateral_friction>1.0</lateral_friction>
|
||||
<spinning_friction>1.5</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_right_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_right_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_right' type='fixed'>
|
||||
<parent>gripper_right</parent>
|
||||
<child>finger_right</child>
|
||||
</joint>
|
||||
|
||||
<link name='finger_left'>
|
||||
<contact>
|
||||
<lateral_friction>1.0</lateral_friction>
|
||||
<spinning_friction>1.5</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_left_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_left_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_left' type='fixed'>
|
||||
<parent>gripper_left</parent>
|
||||
<child>finger_left</child>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,307 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
<pose frame=''>0 0 0.4 3.14 0 0</pose>
|
||||
|
||||
<link name='world'>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='prismatic'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-10</lower>
|
||||
<upper>10</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<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.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>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<link name='motor'>
|
||||
<pose frame=''>0 0 0.03 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0 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='motor_visual'>
|
||||
<pose frame=''>0 0 0.01 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.02 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_motor' type='prismatic'>
|
||||
<child>motor</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.055</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>10.0</effort>
|
||||
<velocity>10.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_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>-0.03 0 0.01 0 -1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_left_hinge_joint' type='revolute'>
|
||||
<child>left_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='right_hinge'>
|
||||
<pose frame=''>0 0 0.04 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.035 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='motor_visual'>
|
||||
<pose frame=''>0.03 0 0.01 0 1.2 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.07 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='motor_right_hinge_joint' type='revolute'>
|
||||
<child>right_hinge</child>
|
||||
<parent>motor</parent>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<lower>-20.0</lower>
|
||||
<upper>20.0</upper>
|
||||
<effort>10</effort>
|
||||
<velocity>10</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</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='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0.06 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_left_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name='gripper_left_hinge_joint' type='prismatic'>
|
||||
<child>gripper_left</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.01</lower>
|
||||
<upper>0.04</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='gripper_right'>
|
||||
<pose frame=''>0.055 0 0.06 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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='gripper_right_visual'>
|
||||
<pose frame=''>0 0 -0.06 0 0 3.14159</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 -0.037 0 0 3.14159</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_right_hinge_joint' type='prismatic'>
|
||||
<child>gripper_right</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.04</lower>
|
||||
<upper>0.01</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>0</damping>
|
||||
<friction>0</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -0,0 +1,27 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="right_finger.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<inertia_scaling value="3.0"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.05"/>
|
||||
<mass value=".2"/>
|
||||
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 1.5708" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="meshes/l_gripper_tip_scaled.stl" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.042"/>
|
||||
<geometry>
|
||||
<box size="0.02 0.02 0.15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
@@ -0,0 +1,306 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<model name='wsg50_with_gripper'>
|
||||
<pose frame=''>0 0 0.27 3.14 0 0</pose>
|
||||
|
||||
<link name='world'>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint' type='prismatic'>
|
||||
<parent>world</parent>
|
||||
<child>base_link</child>
|
||||
<axis>
|
||||
<xyz>0 0 1</xyz>
|
||||
<limit>
|
||||
<lower>-0.5</lower>
|
||||
<upper>10</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<friction>100</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<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.2</mass>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='base_link_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.2 0.05 0.05 </size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='base_link_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
|
||||
</material>
|
||||
</visual>
|
||||
<gravity>1</gravity>
|
||||
<velocity_decay/>
|
||||
<self_collide>0</self_collide>
|
||||
</link>
|
||||
|
||||
<link name='gripper_left'>
|
||||
<pose frame=''>-0.055 0 0 0 -0 0</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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>
|
||||
|
||||
<collision name='gripper_left_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision name='gripper_left_fixed_joint_lump__finger_left_collision_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='gripper_left_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_left_fixed_joint_lump__finger_left_visual_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
<joint name='base_joint_gripper_left' type='prismatic'>
|
||||
<child>gripper_left</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.001</lower>
|
||||
<upper>0.055</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<friction>100</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='gripper_right'>
|
||||
<pose frame=''>0.055 0 0 0 -0 3.14159</pose>
|
||||
<inertial>
|
||||
<pose frame=''>0 0 0.0115 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>
|
||||
|
||||
<collision name='gripper_right_collision'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<collision name='gripper_right_fixed_joint_lump__finger_right_collision_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='gripper_right_visual'>
|
||||
<pose frame=''>0 0 0 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/GUIDE_WSG50_110.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<visual name='gripper_right_fixed_joint_lump__finger_right_visual_1'>
|
||||
<pose frame=''>0 0 0.023 0 -0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.001 0.001 0.001</scale>
|
||||
<uri>meshes/WSG-FMF.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='base_joint_gripper_right' type='prismatic'>
|
||||
<child>gripper_right</child>
|
||||
<parent>base_link</parent>
|
||||
<axis>
|
||||
<xyz>-1 0 0</xyz>
|
||||
<limit>
|
||||
<lower>-0.055</lower>
|
||||
<upper>0.001</upper>
|
||||
<effort>1</effort>
|
||||
<velocity>1</velocity>
|
||||
</limit>
|
||||
<dynamics>
|
||||
<damping>100</damping>
|
||||
<friction>100</friction>
|
||||
<spring_reference>0</spring_reference>
|
||||
<spring_stiffness>0</spring_stiffness>
|
||||
</dynamics>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
<link name='finger_right'>
|
||||
<contact>
|
||||
<lateral_friction>1.0</lateral_friction>
|
||||
<spinning_friction>1.5</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_right_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_right_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_right' type='fixed'>
|
||||
<parent>gripper_right</parent>
|
||||
<child>finger_right</child>
|
||||
</joint>
|
||||
|
||||
<link name='finger_left'>
|
||||
<contact>
|
||||
<lateral_friction>1.0</lateral_friction>
|
||||
<spinning_friction>1.5</spinning_friction>
|
||||
</contact>
|
||||
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
|
||||
<inertial>
|
||||
<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>
|
||||
|
||||
<collision name='finger_left_collision'>
|
||||
<pose frame=''>0 0 0.042 0 0 0 </pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.02 0.02 0.15 </size>
|
||||
</box>
|
||||
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name='finger_left_visual'>
|
||||
<pose frame=''>0 0 0 0 0 0 </pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1 </scale>
|
||||
<uri>meshes/l_gripper_tip_scaled.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<joint name='gripper_finger_left' type='fixed'>
|
||||
<parent>gripper_left</parent>
|
||||
<child>finger_left</child>
|
||||
</joint>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
Reference in New Issue
Block a user