expose PyBullet.SHARED_MEMORY_SERVER
connect from 1 different PyBullet client using PyBullet.SHARED_MEMORY) (don't use more than 1 other client to submit commands in parallel)
This commit is contained in:
@@ -19,13 +19,15 @@ struct CommonExampleOptions
|
|||||||
const char* m_fileName;
|
const char* m_fileName;
|
||||||
class SharedMemoryInterface* m_sharedMem;
|
class SharedMemoryInterface* m_sharedMem;
|
||||||
CommandProcessorCreationInterface* m_commandProcessorCreation;
|
CommandProcessorCreationInterface* m_commandProcessorCreation;
|
||||||
|
bool m_skipGraphicsUpdate;
|
||||||
|
|
||||||
CommonExampleOptions(struct GUIHelperInterface* helper, int option=0)
|
CommonExampleOptions(struct GUIHelperInterface* helper, int option=0)
|
||||||
:m_guiHelper(helper),
|
:m_guiHelper(helper),
|
||||||
m_option(option),
|
m_option(option),
|
||||||
m_fileName(0),
|
m_fileName(0),
|
||||||
m_sharedMem(0),
|
m_sharedMem(0),
|
||||||
m_commandProcessorCreation(0)
|
m_commandProcessorCreation(0),
|
||||||
|
m_skipGraphicsUpdate(false)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -708,7 +708,8 @@ public:
|
|||||||
int m_primitiveType;
|
int m_primitiveType;
|
||||||
int m_textureId;
|
int m_textureId;
|
||||||
int m_instanceId;
|
int m_instanceId;
|
||||||
|
bool m_skipGraphicsUpdate;
|
||||||
|
|
||||||
void mainThreadRelease()
|
void mainThreadRelease()
|
||||||
{
|
{
|
||||||
BT_PROFILE("mainThreadRelease");
|
BT_PROFILE("mainThreadRelease");
|
||||||
@@ -725,7 +726,14 @@ public:
|
|||||||
|
|
||||||
void workerThreadWait()
|
void workerThreadWait()
|
||||||
{
|
{
|
||||||
BT_PROFILE("workerThreadWait");
|
BT_PROFILE("workerThreadWait");
|
||||||
|
|
||||||
|
if (m_skipGraphicsUpdate)
|
||||||
|
{
|
||||||
|
getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
|
||||||
|
m_cs->unlock();
|
||||||
|
return;
|
||||||
|
}
|
||||||
m_cs2->lock();
|
m_cs2->lock();
|
||||||
m_cs->unlock();
|
m_cs->unlock();
|
||||||
m_cs2->unlock();
|
m_cs2->unlock();
|
||||||
@@ -740,7 +748,7 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
|
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper, int skipGraphicsUpdate)
|
||||||
:
|
:
|
||||||
//m_app(app),
|
//m_app(app),
|
||||||
m_cs(0),
|
m_cs(0),
|
||||||
@@ -750,7 +758,10 @@ public:
|
|||||||
m_debugDraw(0),
|
m_debugDraw(0),
|
||||||
m_uidGenerator(0),
|
m_uidGenerator(0),
|
||||||
m_texels(0),
|
m_texels(0),
|
||||||
m_textureId(-1)
|
m_shapeIndex(-1),
|
||||||
|
m_textureId(-1),
|
||||||
|
m_instanceId(-1),
|
||||||
|
m_skipGraphicsUpdate(skipGraphicsUpdate)
|
||||||
{
|
{
|
||||||
m_childGuiHelper = guiHelper;
|
m_childGuiHelper = guiHelper;
|
||||||
|
|
||||||
@@ -971,6 +982,7 @@ public:
|
|||||||
m_getShapeIndex_instance = instance;
|
m_getShapeIndex_instance = instance;
|
||||||
m_cs->lock();
|
m_cs->lock();
|
||||||
m_cs->setSharedParam(1,eGUIHelperGetShapeIndexFromInstance);
|
m_cs->setSharedParam(1,eGUIHelperGetShapeIndexFromInstance);
|
||||||
|
getShapeIndex_shapeIndex=-1;
|
||||||
workerThreadWait();
|
workerThreadWait();
|
||||||
return getShapeIndex_shapeIndex;
|
return getShapeIndex_shapeIndex;
|
||||||
}
|
}
|
||||||
@@ -1205,6 +1217,7 @@ public:
|
|||||||
|
|
||||||
m_cs->lock();
|
m_cs->lock();
|
||||||
m_cs->setSharedParam(1, eGUIUserDebugAddText);
|
m_cs->setSharedParam(1, eGUIUserDebugAddText);
|
||||||
|
m_resultUserDebugTextUid=-1;
|
||||||
workerThreadWait();
|
workerThreadWait();
|
||||||
|
|
||||||
return m_resultUserDebugTextUid;
|
return m_resultUserDebugTextUid;
|
||||||
@@ -1237,6 +1250,7 @@ public:
|
|||||||
|
|
||||||
m_cs->lock();
|
m_cs->lock();
|
||||||
m_cs->setSharedParam(1, eGUIUserDebugAddParameter);
|
m_cs->setSharedParam(1, eGUIUserDebugAddParameter);
|
||||||
|
m_userDebugParamUid=-1;
|
||||||
workerThreadWait();
|
workerThreadWait();
|
||||||
|
|
||||||
return m_userDebugParamUid;
|
return m_userDebugParamUid;
|
||||||
@@ -1265,6 +1279,7 @@ public:
|
|||||||
m_tmpLine.m_trackingVisualShapeIndex = trackingVisualShapeIndex;
|
m_tmpLine.m_trackingVisualShapeIndex = trackingVisualShapeIndex;
|
||||||
m_cs->lock();
|
m_cs->lock();
|
||||||
m_cs->setSharedParam(1, eGUIUserDebugAddLine);
|
m_cs->setSharedParam(1, eGUIUserDebugAddLine);
|
||||||
|
m_resultDebugLineUid=-1;
|
||||||
workerThreadWait();
|
workerThreadWait();
|
||||||
return m_resultDebugLineUid;
|
return m_resultDebugLineUid;
|
||||||
}
|
}
|
||||||
@@ -1729,9 +1744,6 @@ void PhysicsServerExample::initPhysics()
|
|||||||
m_guiHelper->setUpAxis(upAxis);
|
m_guiHelper->setUpAxis(upAxis);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
m_threadSupport = createMotionThreadSupport(MAX_MOTION_NUM_THREADS);
|
m_threadSupport = createMotionThreadSupport(MAX_MOTION_NUM_THREADS);
|
||||||
|
|
||||||
|
|
||||||
@@ -3226,7 +3238,7 @@ extern int gSharedMemoryKey;
|
|||||||
class CommonExampleInterface* PhysicsServerCreateFuncInternal(struct CommonExampleOptions& options)
|
class CommonExampleInterface* PhysicsServerCreateFuncInternal(struct CommonExampleOptions& options)
|
||||||
{
|
{
|
||||||
|
|
||||||
MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(),options.m_guiHelper);
|
MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(),options.m_guiHelper, options.m_skipGraphicsUpdate);
|
||||||
|
|
||||||
|
|
||||||
PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
|
PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
|
||||||
|
|||||||
@@ -7,7 +7,7 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include "PhysicsServerExampleBullet2.h"
|
#include "PhysicsServerExampleBullet2.h"
|
||||||
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
#include "../CommonInterfaces/CommonExampleInterface.h"
|
#include "../CommonInterfaces/CommonExampleInterface.h"
|
||||||
#include "InProcessMemory.h"
|
#include "InProcessMemory.h"
|
||||||
|
|
||||||
@@ -158,15 +158,19 @@ class InProcessPhysicsClientExistingExampleBrowser : public PhysicsClientSharedM
|
|||||||
b3Clock m_clock;
|
b3Clock m_clock;
|
||||||
unsigned long long int m_prevTime;
|
unsigned long long int m_prevTime;
|
||||||
public:
|
public:
|
||||||
InProcessPhysicsClientExistingExampleBrowser (struct GUIHelperInterface* guiHelper)
|
InProcessPhysicsClientExistingExampleBrowser (struct GUIHelperInterface* guiHelper, bool useInProcessMemory, bool skipGraphicsUpdate)
|
||||||
{
|
{
|
||||||
|
m_sharedMem=0;
|
||||||
|
|
||||||
m_sharedMem = new InProcessMemory;
|
|
||||||
CommonExampleOptions options(guiHelper);
|
CommonExampleOptions options(guiHelper);
|
||||||
options.m_sharedMem = m_sharedMem;
|
|
||||||
|
if (useInProcessMemory)
|
||||||
m_physicsServerExample = PhysicsServerCreateFuncBullet2(options);
|
{
|
||||||
|
m_sharedMem = new InProcessMemory;
|
||||||
|
options.m_sharedMem = m_sharedMem;
|
||||||
|
}
|
||||||
|
|
||||||
|
options.m_skipGraphicsUpdate = skipGraphicsUpdate;
|
||||||
|
m_physicsServerExample = PhysicsServerCreateFuncBullet2(options);
|
||||||
m_physicsServerExample ->initPhysics();
|
m_physicsServerExample ->initPhysics();
|
||||||
m_physicsServerExample ->resetCamera();
|
m_physicsServerExample ->resetCamera();
|
||||||
setSharedMemoryInterface(m_sharedMem);
|
setSharedMemoryInterface(m_sharedMem);
|
||||||
@@ -251,9 +255,36 @@ int b3InProcessMouseButtonCallback(b3PhysicsClientHandle clientHandle, int butto
|
|||||||
|
|
||||||
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr)
|
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr)
|
||||||
{
|
{
|
||||||
|
static DummyGUIHelper noGfx;
|
||||||
|
|
||||||
GUIHelperInterface* guiHelper = (GUIHelperInterface*) guiHelperPtr;
|
GUIHelperInterface* guiHelper = (GUIHelperInterface*) guiHelperPtr;
|
||||||
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper);
|
if (!guiHelper)
|
||||||
//InProcessPhysicsClientFromGuiHelper* cl = new InProcessPhysicsClientFromGuiHelper(guiHelper);
|
{
|
||||||
|
guiHelper = &noGfx;
|
||||||
|
}
|
||||||
|
bool useInprocessMemory = true;
|
||||||
|
bool skipGraphicsUpdate = false;
|
||||||
|
|
||||||
|
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper,useInprocessMemory,skipGraphicsUpdate);
|
||||||
|
|
||||||
cl->connect();
|
cl->connect();
|
||||||
return (b3PhysicsClientHandle ) cl;
|
return (b3PhysicsClientHandle ) cl;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect2(void* guiHelperPtr)
|
||||||
|
{
|
||||||
|
static DummyGUIHelper noGfx;
|
||||||
|
|
||||||
|
GUIHelperInterface* guiHelper = (GUIHelperInterface*) guiHelperPtr;
|
||||||
|
if (!guiHelper)
|
||||||
|
{
|
||||||
|
guiHelper = &noGfx;
|
||||||
|
}
|
||||||
|
bool useInprocessMemory = false;
|
||||||
|
bool skipGraphicsUpdate = true;
|
||||||
|
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper, useInprocessMemory, skipGraphicsUpdate);
|
||||||
|
|
||||||
|
cl->connect();
|
||||||
|
return (b3PhysicsClientHandle ) cl;
|
||||||
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -16,7 +16,9 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectShar
|
|||||||
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]);
|
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]);
|
||||||
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]);
|
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(int argc, char* argv[]);
|
||||||
|
|
||||||
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr);
|
//B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr);
|
||||||
|
//create a shared memory physics server, with a DummyGUIHelper (no graphics)
|
||||||
|
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect2(void* guiHelperPtr);
|
||||||
|
|
||||||
///ignore the following APIs, they are for internal use for example browser
|
///ignore the following APIs, they are for internal use for example browser
|
||||||
void b3InProcessRenderSceneInternal(b3PhysicsClientHandle clientHandle);
|
void b3InProcessRenderSceneInternal(b3PhysicsClientHandle clientHandle);
|
||||||
|
|||||||
@@ -668,6 +668,7 @@ enum eCONNECT_METHOD {
|
|||||||
eCONNECT_EXISTING_EXAMPLE_BROWSER=6,
|
eCONNECT_EXISTING_EXAMPLE_BROWSER=6,
|
||||||
eCONNECT_GUI_SERVER=7,
|
eCONNECT_GUI_SERVER=7,
|
||||||
eCONNECT_GUI_MAIN_THREAD=8,
|
eCONNECT_GUI_MAIN_THREAD=8,
|
||||||
|
eCONNECT_SHARED_MEMORY_SERVER=9,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum eURDF_Flags
|
enum eURDF_Flags
|
||||||
|
|||||||
@@ -397,6 +397,11 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
|||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case eCONNECT_SHARED_MEMORY_SERVER:
|
||||||
|
{
|
||||||
|
sm = b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect2(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
case eCONNECT_DIRECT:
|
case eCONNECT_DIRECT:
|
||||||
{
|
{
|
||||||
sm = b3ConnectPhysicsDirect();
|
sm = b3ConnectPhysicsDirect();
|
||||||
@@ -594,6 +599,42 @@ static PyObject* pybullet_getConnectionInfo(PyObject* self, PyObject* args, PyOb
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static PyObject* pybullet_syncBodyInfo(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
|
{
|
||||||
|
|
||||||
|
b3PhysicsClientHandle sm = 0;
|
||||||
|
int physicsClientId = 0;
|
||||||
|
static char* kwlist[] = {"physicsClientId", NULL};
|
||||||
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
|
||||||
|
{
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
sm = getPhysicsClient(physicsClientId);
|
||||||
|
if (sm == 0)
|
||||||
|
{
|
||||||
|
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle command;
|
||||||
|
b3SharedMemoryStatusHandle statusHandle;
|
||||||
|
int statusType;
|
||||||
|
|
||||||
|
command = b3InitSyncBodyInfoCommand(sm);
|
||||||
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||||
|
statusType = b3GetStatusType(statusHandle);
|
||||||
|
|
||||||
|
if (statusType != CMD_SYNC_BODY_INFO_COMPLETED)
|
||||||
|
{
|
||||||
|
PyErr_SetString(SpamError, "Error in syncBodyzInfo command.");
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
Py_INCREF(Py_None);
|
||||||
|
return Py_None;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds)
|
static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
{
|
{
|
||||||
const char* worldFileName = "";
|
const char* worldFileName = "";
|
||||||
@@ -8611,6 +8652,8 @@ static PyMethodDef SpamMethods[] = {
|
|||||||
"disconnect(physicsClientId=0)\n"
|
"disconnect(physicsClientId=0)\n"
|
||||||
"Disconnect from the physics server."},
|
"Disconnect from the physics server."},
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
{"getConnectionInfo", (PyCFunction)pybullet_getConnectionInfo, METH_VARARGS | METH_KEYWORDS,
|
{"getConnectionInfo", (PyCFunction)pybullet_getConnectionInfo, METH_VARARGS | METH_KEYWORDS,
|
||||||
"getConnectionInfo(physicsClientId=0)\n"
|
"getConnectionInfo(physicsClientId=0)\n"
|
||||||
"Return if a given client id is connected, and using what method."},
|
"Return if a given client id is connected, and using what method."},
|
||||||
@@ -8725,6 +8768,10 @@ static PyMethodDef SpamMethods[] = {
|
|||||||
{"getBodyInfo", (PyCFunction)pybullet_getBodyInfo, METH_VARARGS | METH_KEYWORDS,
|
{"getBodyInfo", (PyCFunction)pybullet_getBodyInfo, METH_VARARGS | METH_KEYWORDS,
|
||||||
"Get the body info, given a body unique id."},
|
"Get the body info, given a body unique id."},
|
||||||
|
|
||||||
|
{"syncBodyInfo", (PyCFunction)pybullet_syncBodyInfo, METH_VARARGS | METH_KEYWORDS,
|
||||||
|
"syncBodyInfo(physicsClientId=0)\n"
|
||||||
|
"Update body and constraint/joint information, in case other clients made changes."},
|
||||||
|
|
||||||
{"removeBody", (PyCFunction)pybullet_removeBody, METH_VARARGS | METH_KEYWORDS,
|
{"removeBody", (PyCFunction)pybullet_removeBody, METH_VARARGS | METH_KEYWORDS,
|
||||||
"Remove a body by its body unique id."},
|
"Remove a body by its body unique id."},
|
||||||
|
|
||||||
@@ -9113,7 +9160,11 @@ initpybullet(void)
|
|||||||
PyModule_AddIntConstant(m, "TCP", eCONNECT_TCP); // user read
|
PyModule_AddIntConstant(m, "TCP", eCONNECT_TCP); // user read
|
||||||
PyModule_AddIntConstant(m, "GUI_SERVER", eCONNECT_GUI_SERVER); // 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, "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_KEY", SHARED_MEMORY_KEY);
|
||||||
|
PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY2", SHARED_MEMORY_KEY+1);
|
||||||
|
|
||||||
PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read
|
PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read
|
||||||
PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read
|
PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read
|
||||||
PyModule_AddIntConstant(m, "JOINT_SPHERICAL", eSphericalType); // user read
|
PyModule_AddIntConstant(m, "JOINT_SPHERICAL", eSphericalType); // user read
|
||||||
|
|||||||
Reference in New Issue
Block a user