From 6268911a433ea6f1af17513921ef2f9c6c07effd Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Fri, 15 Nov 2019 22:38:47 -0800 Subject: [PATCH] enable real time simulation --- examples/pybullet/examples/deformable_torus.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/examples/deformable_torus.py b/examples/pybullet/examples/deformable_torus.py index 8bebe38ab..ee5c78772 100644 --- a/examples/pybullet/examples/deformable_torus.py +++ b/examples/pybullet/examples/deformable_torus.py @@ -12,6 +12,8 @@ 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) +p.setRealTimeSimulation(1) + while p.isConnected(): - p.stepSimulation() + p.setGravity(0,0,-10) + sleep(1./240.)