Merge pull request #765 from YunfeiBai/master
Torsional and rolling friction for btMultiBody
This commit is contained in:
45
data/cube_gripper_left.urdf
Normal file
45
data/cube_gripper_left.urdf
Normal file
@@ -0,0 +1,45 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube_gripper_left.urdf">
|
||||
<link name="world">
|
||||
</link>
|
||||
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<rolling_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"/>
|
||||
<mass value=".1"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0.785398 0.785398" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="cube.obj" scale=".05 .05 .05"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0.785398 0.785398" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".05 .05 .05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="cube_joint" type="prismatic">
|
||||
<parent link="world"/>
|
||||
<child link="baseLink"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.0"/>
|
||||
</joint>
|
||||
</robot>
|
||||
|
||||
45
data/cube_gripper_right.urdf
Normal file
45
data/cube_gripper_right.urdf
Normal file
@@ -0,0 +1,45 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube_gripper_right.urdf">
|
||||
<link name="world">
|
||||
</link>
|
||||
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<rolling_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"/>
|
||||
<mass value=".1"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 -0.785398 -0.785398" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="cube.obj" scale=".05 .05 .05"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 -0.785398 -0.785398" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size=".05 .05 .05"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="cube_joint" type="prismatic">
|
||||
<parent link="world"/>
|
||||
<child link="baseLink"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="1 0 0"/>
|
||||
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
|
||||
<dynamics damping="0.0"/>
|
||||
</joint>
|
||||
</robot>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="1.0"/>
|
||||
<rolling_friction value="0.0"/>
|
||||
<rolling_friction value="0.3"/>
|
||||
<inertia_scaling value="3.0"/>
|
||||
<contact_cfm value="0.0"/>
|
||||
<contact_erp value="1.0"/>
|
||||
|
||||
@@ -1,6 +1,9 @@
|
||||
<?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"/>
|
||||
|
||||
29
data/sphere2_rolling_friction.urdf
Normal file
29
data/sphere2_rolling_friction.urdf
Normal file
@@ -0,0 +1,29 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="urdf_robot">
|
||||
<link name="base_link">
|
||||
<contact>
|
||||
<rolling_friction value="0.3"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="10.0"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.5"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
Reference in New Issue
Block a user