separate spinning and rolling friction coefficients, exposed in URDF as spinning_friction / m_rolling_friction

improvements in VR demo, add grasper etc.
This commit is contained in:
Erwin Coumans
2016-09-16 00:57:00 +01:00
parent 1d88cf71e4
commit 567b003654
14 changed files with 92 additions and 74 deletions

View File

@@ -6,10 +6,8 @@
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.3"/>
<spinning_friction value="0.3"/>
<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"/>

View File

@@ -6,10 +6,8 @@
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.3"/>
<spinning_friction value="0.3"/>
<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"/>

View File

@@ -3,7 +3,7 @@
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.1"/>
<spinning_friction value="0.1"/>
<inertia_scaling value="3.0"/>
</contact>
<inertial>

View File

@@ -1,9 +1,6 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<contact>
<rolling_friction value="0.3"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>

View File

@@ -33,6 +33,7 @@
<link name="left_gripper">
<contact>
<lateral_friction value="50.0"/>
<spinning_friction value="0.1"/>
</contact>
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>