Merge pull request #1143 from YunfeiBai/master

Add kuka grasping block playback.
This commit is contained in:
erwincoumans 2017-05-23 10:05:15 -07:00 committed by GitHub
commit f63ca87049
12 changed files with 1185 additions and 3 deletions

32
data/block.urdf Normal file
View File

@ -0,0 +1,32 @@
<?xml version="1.0"?>
<robot name="block_2">
<link name="block_2_base_link">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<inertia_scaling value="3.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.02"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<box size="0.10 0.018 0.018"/>
</geometry>
<material name="blockmat">
<color rgba="0.1 0.7 0.1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
<geometry>
<box size="0.10 0.018 0.018"/>
</geometry>
</collision>
</link>
</robot>

BIN
data/block_grasp_log.bin Normal file

Binary file not shown.

View File

@ -0,0 +1,760 @@
<?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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.5 0.5 0.5 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.5 0.5 0.5 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1.0 0.42 0.04 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1.0 0.42 0.04 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<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>
</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>-0.4</lower>
<upper>0.01</upper>
<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>
</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>
</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>-0.1</lower>
<upper>0.3</upper>
<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>
</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>-0.01</lower>
<upper>0.4</upper>
<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>
</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>
</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>-0.3</lower>
<upper>0.1</upper>
<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>
</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>

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

30
data/tray/tray.urdf Executable file
View File

@ -0,0 +1,30 @@
<robot name="tray">
<link name="tray_base_link">
<contact>
<lateral_friction value="0.5"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="tray_textured4.obj" scale="0.5 0.5 0.5"/>
</geometry>
<material name="tray_material">
<color rgba="0.7 0.7 0.7 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="tray_textured4.obj" scale="0.5 0.5 0.5"/>
</geometry>
</collision>
</link>
</robot>

13
data/tray/tray_textured4.mtl Executable file
View File

@ -0,0 +1,13 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0.000000
Ka 0.000000 0.000000 0.000000
Kd 0.800000 0.800000 0.800000
Ks 0.800000 0.800000 0.800000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
#map_Kd tray.jpg

256
data/tray/tray_textured4.obj Executable file
View File

@ -0,0 +1,256 @@
# Blender v2.77 (sub 0) OBJ File: ''
# www.blender.org
mtllib tray_textured5.mtl
o edge_2_Cube
v 0.593683 0.625721 0.255175
v 0.406317 0.459389 0.004580
v 0.576239 0.625721 0.266503
v 0.593683 -0.580640 0.255175
v 0.423761 0.459389 -0.006748
v 0.576239 -0.580640 0.266503
v 0.423761 -0.413369 -0.007320
v 0.406317 -0.413369 0.004008
vt 0.9410 0.8520
vt 0.7523 0.8566
vt 0.9234 0.8524
vt 0.8896 0.1426
vt 0.7698 0.8562
vt 0.8721 0.1430
vt 0.7185 0.1468
vt 0.7009 0.1472
vn -0.2561 0.8826 -0.3943
vn 0.8394 0.0003 -0.5435
vn 0.8390 0.0001 -0.5441
vn 0.8389 0.0000 -0.5443
vn -0.2569 -0.8818 -0.3956
vn -0.8390 -0.0003 0.5441
vn -0.8394 -0.0001 0.5436
vn -0.8395 -0.0000 0.5434
vn -0.5446 0.0005 -0.8387
vn 0.5446 -0.0000 0.8387
vn 0.8396 0.0004 -0.5433
vn -0.8388 -0.0004 0.5444
usemtl None
s 1
f 1/1/1 2/2/1 3/3/1
f 4/4/2 5/5/3 1/1/4
f 6/6/5 7/7/5 4/4/5
f 3/3/6 8/8/7 6/6/8
f 5/5/9 8/8/9 2/2/9
f 4/4/10 3/3/10 6/6/10
f 1/1/1 5/5/1 2/2/1
f 4/4/2 7/7/11 5/5/3
f 6/6/5 8/8/5 7/7/5
f 3/3/6 2/2/12 8/8/7
f 5/5/9 7/7/9 8/8/9
f 4/4/10 1/1/10 3/3/10
o edge_3_Cube.002
v 0.580000 -0.573309 0.261247
v -0.419400 -0.409917 0.008678
v -0.580000 -0.573309 0.261247
v 0.580000 -0.590083 0.250354
v 0.419883 -0.409917 0.009162
v -0.580000 -0.590083 0.250354
v 0.419883 -0.426691 -0.001731
v -0.419400 -0.426691 -0.002215
vt 0.8690 0.1040
vt 0.1365 0.1739
vt 0.0188 0.1040
vt 0.8690 0.0968
vt 0.7517 0.1739
vt 0.0188 0.0968
vt 0.7517 0.1668
vt 0.1365 0.1668
vn -0.0002 0.8392 0.5438
vn -0.0000 0.8395 0.5433
vn 0.0000 0.8396 0.5432
vn 0.8825 0.2562 -0.3945
vn 0.0002 -0.8396 -0.5433
vn 0.0000 -0.8392 -0.5438
vn 0.0000 -0.8391 -0.5439
vn -0.8821 0.2565 -0.3950
vn -0.8822 0.2565 -0.3950
vn 0.0005 0.5446 -0.8387
vn 0.0000 -0.5446 0.8387
vn -0.0003 0.8391 0.5440
vn 0.0003 -0.8397 -0.5430
usemtl None
s 1
f 9/9/13 10/10/14 11/11/15
f 12/12/16 13/13/16 9/9/16
f 14/14/17 15/15/18 12/12/19
f 11/11/20 16/16/21 14/14/21
f 13/13/22 16/16/22 10/10/22
f 12/12/23 11/11/23 14/14/23
f 9/9/13 13/13/24 10/10/14
f 12/12/16 15/15/16 13/13/16
f 14/14/17 16/16/25 15/15/18
f 11/11/20 10/10/21 16/16/21
f 13/13/22 15/15/22 16/16/22
f 12/12/23 9/9/23 11/11/23
o base_Cube.004
v 0.417551 0.466622 0.009942
v -0.417551 0.466622 -0.009942
v -0.417551 0.466622 0.009942
v 0.417551 -0.415378 0.009942
v 0.417551 0.466622 -0.009942
v -0.417551 -0.415378 0.009942
v 0.417551 -0.415378 -0.009942
v -0.417551 -0.415378 -0.009942
vt 0.7524 0.8072
vt -0.3038 0.8371
vt -0.3038 0.8371
vt 0.7012 0.1905
vt 0.7524 0.8072
vt -0.3550 0.2204
vt 0.7012 0.1905
vt -0.3550 0.2204
vn 0.0000 1.0000 0.0000
vn 1.0000 -0.0000 0.0000
vn 0.0000 -1.0000 0.0000
vn -1.0000 -0.0000 0.0000
vn 0.0000 0.0000 -1.0000
vn 0.0000 -0.0000 1.0000
usemtl None
s 1
f 17/17/26 18/18/26 19/19/26
f 20/20/27 21/21/27 17/17/27
f 22/22/28 23/23/28 20/20/28
f 19/19/29 24/24/29 22/22/29
f 21/21/30 24/24/30 18/18/30
f 20/20/31 19/19/31 22/22/31
f 17/17/26 21/21/26 18/18/26
f 20/20/27 23/23/27 21/21/27
f 22/22/28 24/24/28 23/23/28
f 19/19/29 18/18/29 24/24/29
f 21/21/30 23/23/30 24/24/30
f 20/20/31 17/17/31 19/19/31
o edge_4_Cube.001
v -0.576397 0.631608 0.266791
v -0.423603 0.464243 -0.007768
v -0.593877 0.631608 0.255439
v -0.576397 -0.577253 0.266791
v -0.406123 0.464243 0.003584
v -0.593877 -0.577253 0.255439
v -0.406123 -0.409889 0.004087
v -0.423603 -0.409889 -0.007265
vt 0.9046 0.2397
vt 0.7929 0.2434
vt 0.9174 0.2393
vt 0.9537 0.7559
vt 0.7801 0.2438
vt 0.9664 0.7554
vt 0.8291 0.7599
vt 0.8419 0.7595
vn 0.2565 0.8821 -0.3950
vn 0.8392 0.0002 0.5438
vn 0.8395 0.0000 0.5433
vn 0.8396 -0.0000 0.5432
vn 0.2568 -0.8819 -0.3954
vn -0.8396 -0.0002 -0.5433
vn -0.8392 -0.0000 -0.5438
vn -0.8391 0.0000 -0.5439
vn 0.5446 -0.0005 -0.8387
vn -0.5446 -0.0000 0.8387
vn 0.8391 0.0003 0.5440
vn -0.8397 -0.0003 -0.5430
usemtl None
s 1
f 25/25/32 26/26/32 27/27/32
f 28/28/33 29/29/34 25/25/35
f 30/30/36 31/31/36 28/28/36
f 27/27/37 32/32/38 30/30/39
f 29/29/40 32/32/40 26/26/40
f 28/28/41 27/27/41 30/30/41
f 25/25/32 29/29/32 26/26/32
f 28/28/33 31/31/42 29/29/34
f 30/30/36 32/32/36 31/31/36
f 27/27/37 26/26/43 32/32/38
f 29/29/40 31/31/40 32/32/40
f 28/28/41 25/25/41 27/27/41
o edge_5_Cube.005
v -0.326052 0.623641 0.266072
v -0.174054 0.457147 -0.007058
v -0.343442 0.623641 0.254779
v -0.326052 -0.578931 0.266072
v -0.156664 0.457147 0.004235
v -0.343442 -0.578931 0.254779
v -0.156664 -0.412938 0.005326
v -0.174054 -0.412938 -0.005967
vt 0.0506 0.8517
vt 0.1935 0.8492
vt 0.0342 0.8520
vt 0.0164 0.1914
vt 0.2099 0.8489
vt 0.0001 0.1917
vt 0.1757 0.1886
vt 0.1594 0.1889
vn 0.2565 0.8821 -0.3950
vn 0.8387 0.0005 0.5446
vn 0.8394 0.0001 0.5434
vn 0.8396 -0.0000 0.5432
vn 0.2565 -0.8822 -0.3950
vn -0.8395 -0.0005 -0.5434
vn -0.8388 -0.0001 -0.5445
vn -0.8386 0.0000 -0.5448
vn 0.5446 -0.0011 -0.8387
vn -0.5446 -0.0000 0.8387
vn 0.8384 0.0007 0.5451
vn -0.8398 -0.0007 -0.5429
usemtl None
s 1
f 33/33/44 34/34/44 35/35/44
f 36/36/45 37/37/46 33/33/47
f 38/38/48 39/39/48 36/36/48
f 35/35/49 40/40/50 38/38/51
f 37/37/52 40/40/52 34/34/52
f 36/36/53 35/35/53 38/38/53
f 33/33/44 37/37/44 34/34/44
f 36/36/45 39/39/54 37/37/46
f 38/38/48 40/40/48 39/39/48
f 35/35/49 34/34/55 40/40/50
f 37/37/52 39/39/52 40/40/52
f 36/36/53 33/33/53 35/35/53
o edge_1_Cube.003
v 0.580000 0.640851 0.250354
v -0.419960 0.477459 -0.001860
v -0.580000 0.640851 0.250354
v 0.580000 0.624077 0.261247
v 0.420014 0.477459 -0.001059
v -0.580000 0.624077 0.261247
v 0.420014 0.460685 0.009834
v -0.419960 0.460685 0.009033
vt 0.8346 0.9187
vt 0.2203 0.8574
vt 0.1480 0.9187
vt 0.8346 0.9129
vt 0.7623 0.8574
vt 0.1480 0.9129
vt 0.7623 0.8511
vt 0.2203 0.8511
vn 0.0004 0.8386 -0.5448
vn 0.0001 0.8391 -0.5439
vn 0.0000 0.8393 -0.5437
vn 0.8823 -0.2564 -0.3948
vn -0.0004 -0.8392 0.5439
vn -0.0001 -0.8386 0.5447
vn 0.0000 -0.8385 0.5449
vn -0.8826 -0.2560 -0.3942
vn 0.0008 -0.5446 -0.8387
vn 0.0000 0.5446 0.8387
vn 0.0005 0.8383 -0.5452
vn -0.0005 -0.8394 0.5435
usemtl None
s 1
f 41/41/56 42/42/57 43/43/58
f 44/44/59 45/45/59 41/41/59
f 46/46/60 47/47/61 44/44/62
f 43/43/63 48/48/63 46/46/63
f 45/45/64 48/48/64 42/42/64
f 44/44/65 43/43/65 46/46/65
f 41/41/56 45/45/66 42/42/57
f 44/44/59 47/47/59 45/45/59
f 46/46/60 48/48/67 47/47/61
f 43/43/63 42/42/63 48/48/63
f 45/45/64 47/47/64 48/48/64
f 44/44/65 41/41/65 43/43/65

View File

@ -0,0 +1,91 @@
import pybullet as p
import time
import math
from datetime import datetime
from numpy import *
from pylab import *
import struct
import sys
import os, fnmatch
import argparse
from time import sleep
def readLogFile(filename, verbose = True):
f = open(filename, 'rb')
print('Opened'),
print(filename)
keys = f.readline().decode('utf8').rstrip('\n').split(',')
fmt = f.readline().decode('utf8').rstrip('\n')
# The byte number of one record
sz = struct.calcsize(fmt)
# The type number of one record
ncols = len(fmt)
if verbose:
print('Keys:'),
print(keys)
print('Format:'),
print(fmt)
print('Size:'),
print(sz)
print('Columns:'),
print(ncols)
# Read data
wholeFile = f.read()
# split by alignment word
chunks = wholeFile.split(b'\xaa\xbb')
log = list()
for chunk in chunks:
if len(chunk) == sz:
values = struct.unpack(fmt, chunk)
record = list()
for i in range(ncols):
record.append(values[i])
log.append(record)
return log
#clid = p.connect(p.SHARED_MEMORY)
p.connect(p.GUI)
p.loadSDF("kuka_iiwa/kuka_with_gripper.sdf")
p.loadURDF("tray/tray.urdf",[0,0,0])
p.loadURDF("block.urdf",[0,0,2])
log = readLogFile("data/block_grasp_log.bin")
recordNum = len(log)
itemNum = len(log[0])
objectNum = p.getNumBodies()
print('record num:'),
print(recordNum)
print('item num:'),
print(itemNum)
def Step(stepIndex):
for objectId in range(objectNum):
record = log[stepIndex*objectNum+objectId]
Id = record[2]
pos = [record[3],record[4],record[5]]
orn = [record[6],record[7],record[8],record[9]]
p.resetBasePositionAndOrientation(Id,pos,orn)
numJoints = p.getNumJoints(Id)
for i in range (numJoints):
jointInfo = p.getJointInfo(Id,i)
qIndex = jointInfo[3]
if qIndex > -1:
p.resetJointState(Id,i,record[qIndex-7+17])
stepIndexId = p.addUserDebugParameter("stepIndex",0,recordNum/objectNum-1,0)
while True:
stepIndex = int(p.readUserDebugParameter(stepIndexId))
Step(stepIndex)
p.stepSimulation()
Step(stepIndex)

View File

@ -6,15 +6,15 @@ p.connect(p.GUI)
planeId = p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593])
p.loadURDF(fileName="cube.urdf",baseOrientation=[0.25882,0,0,0.96593],basePosition=[0,0,2])
cubeId = p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4])
p.changeDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
#p.changeDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
#p.changeDynamics(bodyUniqueId=2,linkIndex=-1,mass=0.1)
p.changeDynamics(bodyUniqueId=2,linkIndex=-1,mass=100.0)
p.setGravity(0,0,-10)
p.setRealTimeSimulation(0)
t=0
while 1:
t=t+1
if t > 400:
p.changeDynamicsInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
p.changeDynamics(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
mass1,frictionCoeff1=p.getDynamicsInfo(bodyUniqueId=planeId,linkIndex=-1)
mass2,frictionCoeff2=p.getDynamicsInfo(bodyUniqueId=cubeId,linkIndex=-1)
print mass1,frictionCoeff1