Add python binding and a pybullet example for loading softbody from obj.
This commit is contained in:
20
examples/pybullet/examples/load_soft_body.py
Normal file
20
examples/pybullet/examples/load_soft_body.py
Normal 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()
|
||||
Reference in New Issue
Block a user