tune kuka grasp gym env (make it a bit too easy)

This commit is contained in:
erwincoumans
2017-06-15 11:18:08 -07:00
parent 16f439d774
commit c903bd8a49
4 changed files with 129 additions and 58 deletions

View File

@@ -401,7 +401,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>
<mass>1.3</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
@@ -462,12 +462,6 @@
<child>base_link</child>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<damping>0.5</damping>
<friction>0</friction>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
</axis>
</joint>
@@ -477,7 +471,7 @@
<pose frame=''>0 0 1.305 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>1.2</mass>
<mass>0.2</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
@@ -501,6 +495,20 @@
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='base_link_collision'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.1 </size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</collision>
</link>
<joint name='base_left_finger_joint' type='revolute'>
@@ -526,7 +534,7 @@
<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>
<mass>0.2</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
@@ -550,12 +558,25 @@
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='left_finger_collision'>
<pose frame=''>0 0 0.04 0 0 0</pose>
<geometry>
<box>
<size>0.01 0.01 0.08</size>
</box>
</geometry>
</collision>
</link>
<joint name='left_finger_base_joint' type='fixed'>
<parent>left_finger</parent>
<child>left_finger_base</child>
</joint>
<link name='left_finger_base'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>.1</spinning_friction>
</contact>
<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>
@@ -616,7 +637,7 @@
<link name='left_finger_tip'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>1.0</spinning_friction>
<spinning_friction>.1</spinning_friction>
</contact>
<pose frame=''>-0.02 0.024 1.49 0 0.2 0</pose>
<inertial>
@@ -676,10 +697,14 @@
</axis>
</joint>
<link name='right_finger'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>.1</spinning_friction>
</contact>
<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>
<mass>0.2</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
@@ -703,12 +728,30 @@
<emissive>0 0 0 0</emissive>
</material>
</visual>
<collision name='right_finger_collision'>
<pose frame=''>0 0 0.04 0 0 0</pose>
<geometry>
<box>
<size>0.01 0.01 0.08</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</collision>
</link>
<joint name='right_finger_base_joint' type='fixed'>
<parent>right_finger</parent>
<child>right_finger_base</child>
</joint>
<link name='right_finger_base'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>.1</spinning_friction>
</contact>
<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>
@@ -769,7 +812,7 @@
<link name='right_finger_tip'>
<contact>
<lateral_friction>0.8</lateral_friction>
<spinning_friction>1.0</spinning_friction>
<spinning_friction>.1</spinning_friction>
</contact>
<pose frame=''>0.02 0.024 1.49 0 -0.2 0</pose>
<inertial>