Add option GUI_MAIN_THREAD for running OpenGL in the main thread (Python thread). This already happens on Mac OSX by default.

Pass all argc/argc from options to InProcessPhysicsClientSharedMemoryMainThread
This commit is contained in:
erwincoumans
2018-02-14 16:49:44 -08:00
parent 5e08d6d334
commit d3fe21ef17
5 changed files with 20 additions and 12 deletions

View File

@@ -6,11 +6,12 @@ import pybullet
class BulletClient(object):
"""A wrapper for pybullet to manage different clients."""
def __init__(self, connection_mode=pybullet.DIRECT):
def __init__(self, connection_mode=pybullet.DIRECT, options=""):
"""Create a simulation and connect to it."""
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
if(self._client<0):
self._client = pybullet.connect(connection_mode)
print("options=",options)
self._client = pybullet.connect(connection_mode,options=options)
self._shapes = {}
def __del__(self):