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:
@@ -7,9 +7,9 @@ p.loadURDF("tray/traybox.urdf",useMaximalCoordinates=True)
|
||||
|
||||
gravXid = p.addUserDebugParameter("gravityX",-10,10,0)
|
||||
gravYid = p.addUserDebugParameter("gravityY",-10,10,0)
|
||||
gravZid = p.addUserDebugParameter("gravityZ",-10,10,0)
|
||||
gravZid = p.addUserDebugParameter("gravityZ",-10,10,-10)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
|
||||
p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
|
||||
for i in range (10):
|
||||
for j in range (10):
|
||||
for k in range (5):
|
||||
@@ -21,5 +21,5 @@ while True:
|
||||
gravY = p.readUserDebugParameter(gravYid)
|
||||
gravZ = p.readUserDebugParameter(gravZid)
|
||||
p.setGravity(gravX,gravY,gravZ)
|
||||
time.sleep(1)
|
||||
time.sleep(0.01)
|
||||
|
||||
|
||||
Reference in New Issue
Block a user