From f237a40621d4d03cf169a055f4ddd913ac7b2471 Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Thu, 21 Nov 2019 00:09:32 -0800 Subject: [PATCH] add a pybullet example to compare the result of soft body and deformable body --- examples/pybullet/examples/test_inertia.py | 28 ++++++++++++++++++++++ 1 file changed, 28 insertions(+) create mode 100644 examples/pybullet/examples/test_inertia.py diff --git a/examples/pybullet/examples/test_inertia.py b/examples/pybullet/examples/test_inertia.py new file mode 100644 index 000000000..a290f3bac --- /dev/null +++ b/examples/pybullet/examples/test_inertia.py @@ -0,0 +1,28 @@ +import pybullet as p +from time import sleep + +physicsClient = p.connect(p.GUI) + +useDeformable = True +if useDeformable: + p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) + +gravZ=-10 +p.setGravity(0, 0, gravZ) + +planeOrn = [0,0,0,1]#p.getQuaternionFromEuler([0.3,0,0]) +planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn) + +boxId = p.loadURDF("cube.urdf", [0,1,2],useMaximalCoordinates = True) + +clothId = p.loadSoftBody("bunny.obj", basePosition = [0,0,2], scale = 0.5, mass = 1., useNeoHookean = 0, useBendingSprings=1, useMassSpring=1, springElasticStiffness=100, springDampingStiffness=.001, useSelfCollision = 0, frictionCoeff = .5, useFaceContact=1) + +p.setTimeStep(0.0005) + +p.setRealTimeSimulation(1) + + +while p.isConnected(): + p.setGravity(0,0,gravZ) + sleep(1./240.) +