Add python binding and a pybullet example for loading softbody from obj.

This commit is contained in:
yunfeibai
2018-01-08 18:10:28 -08:00
parent d3bc98e245
commit 0e0d3da2b5
3 changed files with 88 additions and 4 deletions

View File

@@ -0,0 +1,20 @@
import pybullet as p
from time import sleep
physicsClient = p.connect(p.GUI)
p.setGravity(0,0,-10)
planeId = p.loadURDF("plane.urdf")
bunnyId = p.loadSoftBody("bunny.obj")
useRealTimeSimulation = 1
if (useRealTimeSimulation):
p.setRealTimeSimulation(1)
while 1:
if (useRealTimeSimulation):
p.setGravity(0,0,-10)
sleep(0.01) # Time in seconds.
else:
p.stepSimulation()