add python binding to allow loading deformable objects

This commit is contained in:
Xuchen Han
2019-11-15 21:25:11 -08:00
parent 28039903b1
commit a86710c5b6
6 changed files with 59 additions and 9 deletions

View File

@@ -0,0 +1,17 @@
import pybullet as p
from time import sleep
physicsClient = p.connect(p.GUI)
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
p.setGravity(0, 0, -10)
planeId = p.loadURDF("plane.urdf", [0,0,-2])
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
bunnyId = p.loadSoftBody("torus.vtk", useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, useSelfCollision = 1, frictionCoeff = 0.5)
p.setGravity(0, 0, -10)
while p.isConnected():
p.stepSimulation()