tune gripper parameters for VR demo
This commit is contained in:
@@ -17,7 +17,7 @@
|
||||
<origin rpy="0 1.57075 0 " xyz="0.1 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="100"/>
|
||||
<mass value="0.5"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -32,7 +32,7 @@
|
||||
|
||||
<link name="left_gripper">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
</contact>
|
||||
<visual>
|
||||
@@ -41,8 +41,14 @@
|
||||
<mesh filename="l_finger.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="l_finger_collision.stl" scale=".9 .9 .9"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
<mass value="0.5"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -54,7 +60,7 @@
|
||||
|
||||
<link name="left_tip">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
</contact>
|
||||
<visual>
|
||||
@@ -65,12 +71,12 @@
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size=".13 .03 .02"/>
|
||||
<box size=".03 .03 .02"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 0 0" xyz="0.055 0.00495 0"/>
|
||||
<origin rpy="0.0 0 0" xyz="0.105 0.00495 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
<mass value="0.1"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
@@ -85,8 +91,8 @@
|
||||
|
||||
<link name="right_gripper">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
|
||||
@@ -94,6 +100,12 @@
|
||||
<mesh filename="l_finger.stl"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="l_finger_collision.stl" scale=".9 .9 .9"/>
|
||||
</geometry>
|
||||
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
@@ -107,8 +119,8 @@
|
||||
|
||||
<link name="right_tip">
|
||||
<contact>
|
||||
<lateral_friction value="50.0"/>
|
||||
<spinning_friction value="0.1"/>
|
||||
<lateral_friction value="5.0"/>
|
||||
<spinning_friction value=".2"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
|
||||
@@ -118,9 +130,9 @@
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size=".13 .03 .02"/>
|
||||
<box size=".03 .03 .02"/>
|
||||
</geometry>
|
||||
<origin rpy="-3.1415 0 0" xyz="0.055 0.00495 0"/>
|
||||
<origin rpy="-3.1415 0 0" xyz="0.105 0.00495 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.05"/>
|
||||
|
||||
Reference in New Issue
Block a user