add nicer meshes to kuka_with_gripper.sdf and add kuka_with_gripper2.sdf that can rotate without messing up IK

fix tray/tray_textured4.obj and tray/tray.urdf
fix kuka_with_cube.py
allow both IK /end-effector control and joint-space control in kuka environment, use 1./240. sec. step and 150 solver iter
bump up pybullet to 1.1.7
This commit is contained in:
erwincoumans
2017-06-14 19:34:33 -07:00
parent cc34ebab25
commit d2888f0884
10 changed files with 1004 additions and 57 deletions

View File

@@ -38,13 +38,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_0.stl</uri>
<uri>meshes/link_0.obj</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>
<diffuse>0.2 0.2 0.2 1.0</diffuse>
<specular>0.4 0.4 0.4 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -77,13 +77,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_1.stl</uri>
<uri>meshes/link_1.obj</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>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -135,13 +135,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_2.stl</uri>
<uri>meshes/link_2.obj</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>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -193,13 +193,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_3.stl</uri>
<uri>meshes/link_3.obj</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>
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -251,13 +251,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_4.stl</uri>
<uri>meshes/link_4.obj</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>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -309,13 +309,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_5.stl</uri>
<uri>meshes/link_5.obj</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>
<diffuse>0.5 0.7 1.0 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -367,13 +367,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_6.stl</uri>
<uri>meshes/link_6.obj</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>
<diffuse>1.0 0.423529411765 0.0392156862745 1.0</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -425,13 +425,13 @@
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>meshes/link_7.stl</uri>
<uri>meshes/link_7.obj</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>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
@@ -482,6 +482,12 @@
<size>0.05 0.05 0.1 </size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
@@ -491,8 +497,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.4</lower>
<upper>0.01</upper>
<lower>-10.4</lower>
<upper>10.01</upper>
<effort>100</effort>
<velocity>0</velocity>
</limit>
@@ -525,6 +531,12 @@
<size>0.01 0.01 0.08</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='left_finger_base_joint' type='fixed'>
@@ -553,6 +565,12 @@
<uri>meshes/finger_base_left.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='left_finger_base_collision'>
<pose frame=''>0 0 0 0 0 0 </pose>
@@ -570,8 +588,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.1</lower>
<upper>0.3</upper>
<lower>-10.1</lower>
<upper>10.3</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
@@ -609,6 +627,12 @@
<uri>meshes/finger_tip_left.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='left_finger_tip_collision'>
<pose frame=''>0 0 0 0 0 0</pose>
@@ -626,8 +650,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.01</lower>
<upper>0.4</upper>
<lower>-10.01</lower>
<upper>10.4</upper>
<effort>100</effort>
<velocity>0</velocity>
</limit>
@@ -660,6 +684,12 @@
<size>0.01 0.01 0.08</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
<joint name='right_finger_base_joint' type='fixed'>
@@ -688,6 +718,12 @@
<uri>meshes/finger_base_right.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='right_finger_base_collision'>
<pose frame=''>0 0 0 0 0 0 </pose>
@@ -705,8 +741,8 @@
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-0.3</lower>
<upper>0.1</upper>
<lower>-10.3</lower>
<upper>10.1</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
@@ -744,6 +780,12 @@
<uri>meshes/finger_tip_right.stl</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='right_finger_tip_collision'>
<pose frame=''>0 0 0 0 0 0</pose>