VR video recording, use command-line --mp4=videoname.mp4

tune gripper grasp example with tefal pan, 800Newton force.
URDF importer: if using single transform 1 child shape, don't use compound shape.
if renderGUI is false, don't intercept mouse clicks
add manyspheres.py example (performance is pretty bad, will look into it)
[pybullet] expose contactBreakingThreshold
This commit is contained in:
Erwin Coumans
2017-02-16 14:19:09 -08:00
parent 08b83c3cd8
commit 63486a712c
18 changed files with 140 additions and 82 deletions

View File

@@ -303,6 +303,10 @@
</joint>
<link name='finger_right'>
<contact>
<spinning_friction>.3</spinning_friction>
<rolling_friction>0.04</rolling_friction>
</contact>
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
<inertial>
<mass>0.2</mass>
@@ -343,6 +347,10 @@
</joint>
<link name='finger_left'>
<contact>
<spinning_friction>.3</spinning_friction>
<rolling_friction>0.04</rolling_friction>
</contact>
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
<inertial>
<mass>0.2</mass>

View File

@@ -2,23 +2,15 @@
<robot name="urdf_robot">
<link name="base_link">
<contact>
<rolling_friction value="0.0001"/>
<spinning_friction value="0.0001"/>
<rolling_friction value="0.001"/>
<spinning_friction value="0.001"/>
</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 0" xyz="0 0 0"/>
<geometry>
<mesh filename="textured_sphere_smooth.obj" scale="0.005 0.005 0.005"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>