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:
@@ -21,15 +21,15 @@ public:
|
||||
|
||||
InProcessPhysicsClientSharedMemoryMainThread(int argc, char* argv[], bool useInProcessMemory)
|
||||
{
|
||||
int newargc = argc+2;
|
||||
int newargc = argc+3;
|
||||
char** newargv = (char**)malloc(sizeof(void*)*newargc);
|
||||
char* t0 = (char*)"--unused";
|
||||
newargv[0] = t0;
|
||||
for (int i=0;i<argc;i++)
|
||||
newargv[i] = argv[i];
|
||||
newargv[i+1] = argv[i];
|
||||
newargv[argc+1]=(char*)"--logtostderr";
|
||||
newargv[argc+2]=(char*)"--start_demo_name=Physics Server";
|
||||
|
||||
char* t0 = (char*)"--logtostderr";
|
||||
char* t1 = (char*)"--start_demo_name=Physics Server";
|
||||
newargv[argc] = t0;
|
||||
newargv[argc+1] = t1;
|
||||
m_data = btCreateInProcessExampleBrowserMainThread(newargc,newargv, useInProcessMemory);
|
||||
SharedMemoryInterface* shMem = btGetSharedMemoryInterfaceMainThread(m_data);
|
||||
|
||||
|
||||
@@ -664,6 +664,7 @@ enum eCONNECT_METHOD {
|
||||
eCONNECT_TCP = 5,
|
||||
eCONNECT_EXISTING_EXAMPLE_BROWSER=6,
|
||||
eCONNECT_GUI_SERVER=7,
|
||||
eCONNECT_GUI_MAIN_THREAD=8,
|
||||
};
|
||||
|
||||
enum eURDF_Flags
|
||||
|
||||
@@ -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):
|
||||
|
||||
@@ -40,8 +40,8 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
render_sleep=False,
|
||||
debug_visualization=True,
|
||||
hard_reset = False,
|
||||
render_width=740,
|
||||
render_height=740,
|
||||
render_width=240,
|
||||
render_height=240,
|
||||
action_repeat=1,
|
||||
time_step = 1./240.,
|
||||
num_bullet_solver_iterations=50,
|
||||
@@ -190,7 +190,7 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
proj_matrix=[1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
|
||||
(_, _, px, _, _) = self._pybullet_client.getCameraImage(
|
||||
width=self._render_width, height=self._render_height, viewMatrix=view_matrix,
|
||||
projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||
projectionMatrix=proj_matrix, renderer=pybullet.ER_TINY_RENDERER)
|
||||
rgb_array = np.array(px, dtype=np.uint8)
|
||||
rgb_array = np.reshape(rgb_array, (self._render_height, self._render_width, 4))
|
||||
rgb_array = rgb_array[:, :, :3]
|
||||
|
||||
@@ -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