mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-05 15:21:06 +00:00
63486a712c
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
26 lines
874 B
Python
26 lines
874 B
Python
import pybullet as p
|
|
import time
|
|
|
|
p.connect(p.GUI)
|
|
p.loadURDF("plane.urdf",useMaximalCoordinates=True)
|
|
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,-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):
|
|
ob = p.loadURDF("sphere_1cm.urdf",[0.02*i,0.02*j,0.2+0.02*k],useMaximalCoordinates=True)
|
|
p.setGravity(0,0,-10)
|
|
p.setRealTimeSimulation(1)
|
|
while True:
|
|
gravX = p.readUserDebugParameter(gravXid)
|
|
gravY = p.readUserDebugParameter(gravYid)
|
|
gravZ = p.readUserDebugParameter(gravZid)
|
|
p.setGravity(gravX,gravY,gravZ)
|
|
time.sleep(0.01)
|
|
|