From 2d91e1388618c3ccb18723737cb77435cc13bd89 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sun, 24 Sep 2017 21:37:31 -0700 Subject: [PATCH] tweak pybullet examples a bit (mac OSX OpenGL runs in mainloop, with python interpreter, so it needs some 'ping' command bump up pybullet to version 1.4.6 --- examples/pybullet/examples/mimicJointConstraint.py | 3 ++- examples/pybullet/examples/quadruped.py | 1 + examples/pybullet/examples/vr_kuka_setup.py | 10 +++++++++- setup.py | 2 +- 4 files changed, 13 insertions(+), 3 deletions(-) diff --git a/examples/pybullet/examples/mimicJointConstraint.py b/examples/pybullet/examples/mimicJointConstraint.py index 60a0625d9..968a24354 100644 --- a/examples/pybullet/examples/mimicJointConstraint.py +++ b/examples/pybullet/examples/mimicJointConstraint.py @@ -23,6 +23,7 @@ p.changeConstraint(c,gearRatio=-1, maxForce=10000) p.setRealTimeSimulation(1) while(1): + p.setGravity(0,0,-10) time.sleep(0.01) #p.removeConstraint(c) - \ No newline at end of file + diff --git a/examples/pybullet/examples/quadruped.py b/examples/pybullet/examples/quadruped.py index 19527fa47..7e3ee1262 100644 --- a/examples/pybullet/examples/quadruped.py +++ b/examples/pybullet/examples/quadruped.py @@ -187,6 +187,7 @@ t = 0.0 t_end = t + 15 ref_time = time.time() while (t