graphicsServer to workaround OpenGL issues on some servers.
This commit is contained in:
@@ -5,7 +5,9 @@ from datetime import datetime
|
||||
|
||||
clid = p.connect(p.SHARED_MEMORY)
|
||||
if (clid < 0):
|
||||
p.connect(p.GUI)
|
||||
#p.connect(p.GUI)
|
||||
p.connect(p.SHARED_MEMORY_GUI)
|
||||
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
kukaId = p.loadURDF("kuka_iiwa/model.urdf", [0, 0, 0])
|
||||
p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1])
|
||||
@@ -46,7 +48,9 @@ p.setRealTimeSimulation(useRealTimeSimulation)
|
||||
#use 0 for no-removal
|
||||
trailDuration = 15
|
||||
|
||||
while 1:
|
||||
i=0
|
||||
while i<5:
|
||||
i+=1
|
||||
p.getCameraImage(320,
|
||||
200,
|
||||
flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX,
|
||||
@@ -115,3 +119,4 @@ while 1:
|
||||
prevPose = pos
|
||||
prevPose1 = ls[4]
|
||||
hasPrevPose = 1
|
||||
p.disconnect()
|
||||
@@ -463,6 +463,14 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
sm = b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect3(0, key);
|
||||
break;
|
||||
}
|
||||
|
||||
case eCONNECT_SHARED_MEMORY_GUI:
|
||||
{
|
||||
sm = b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect4(0, key);
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
case eCONNECT_DIRECT:
|
||||
{
|
||||
sm = b3ConnectPhysicsDirect();
|
||||
@@ -10933,6 +10941,9 @@ initpybullet(void)
|
||||
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, "SHARED_MEMORY_SERVER", eCONNECT_SHARED_MEMORY_SERVER); // user read
|
||||
PyModule_AddIntConstant(m, "SHARED_MEMORY_GUI", eCONNECT_SHARED_MEMORY_GUI); // user read
|
||||
|
||||
|
||||
#ifdef BT_ENABLE_DART
|
||||
PyModule_AddIntConstant(m, "DART", eCONNECT_DART); // user read
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user