rolling friction -> combine using rolling*normal friction, add for both objects.

rolling friction -> only along the normal, until we have separate rolling friction coefficients on normal and non-normal directions
Don't teleport with grasping controller (VR)
Tune VR grasping a bit.
This commit is contained in:
erwincoumans
2016-09-12 19:10:20 +01:00
parent af7c44d360
commit e5a8eb2425
8 changed files with 36 additions and 20 deletions

View File

@@ -3,9 +3,8 @@
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.01"/>
<rolling_friction value="0.1"/>
<inertia_scaling value="3.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>

View File

@@ -31,6 +31,9 @@
</joint>
<link name="left_gripper">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
@@ -55,6 +58,9 @@
</joint>
<link name="left_tip">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual>
<origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/>
<geometry>
@@ -63,9 +69,9 @@
</visual>
<collision>
<geometry>
<mesh filename="l_finger_tip.stl"/>
<box size=".03 .03 .02"/>
</geometry>
<origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/>
<origin rpy="0.0 0 0" xyz="0.109137 0.00495 0"/>
</collision>
<inertial>
<mass value="0.05"/>
@@ -82,6 +88,9 @@
</joint>
<link name="right_gripper">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual>
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
<geometry>
@@ -106,6 +115,9 @@
</joint>
<link name="right_tip">
<contact>
<lateral_friction value="50.0"/>
</contact>
<visual>
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
<geometry>
@@ -114,9 +126,9 @@
</visual>
<collision>
<geometry>
<mesh filename="l_finger_tip.stl"/>
<box size=".03 .03 .02"/>
</geometry>
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
<origin rpy="-3.1415 0 0" xyz="0.109137 0.00495 0"/>
</collision>
<inertial>
<mass value="0.05"/>