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:
@@ -382,6 +382,11 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case eCONNECT_GUI_MAIN_THREAD:
|
||||
{
|
||||
sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
|
||||
break;
|
||||
}
|
||||
case eCONNECT_GUI_SERVER:
|
||||
{
|
||||
|
||||
@@ -8776,6 +8781,7 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read
|
||||
PyModule_AddIntConstant(m, "TCP", eCONNECT_TCP); // user read
|
||||
PyModule_AddIntConstant(m, "GUI_SERVER", eCONNECT_GUI_SERVER); // user read
|
||||
PyModule_AddIntConstant(m, "GUI_MAIN_THREAD", eCONNECT_GUI_MAIN_THREAD); // user read
|
||||
|
||||
PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read
|
||||
PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read
|
||||
|
||||
Reference in New Issue
Block a user