add pybullet.connect(pybullet.GUI_SERVER) option. This allows shared memory connections, acting as a physics server. You can connect using SHARED_MEMORY to this GUI_SERVER.

This commit is contained in:
Erwin Coumans
2017-08-14 17:02:20 -07:00
parent aafaa7e33e
commit 60b60ef9fd
7 changed files with 49 additions and 27 deletions

View File

@@ -316,11 +316,12 @@ struct btInProcessExampleBrowserInternalData
btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,char** argv2) btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,char** argv2, bool useInProcessMemory)
{ {
btInProcessExampleBrowserInternalData* data = new btInProcessExampleBrowserInternalData; btInProcessExampleBrowserInternalData* data = new btInProcessExampleBrowserInternalData;
data->m_sharedMem = new InProcessMemory;
data->m_sharedMem = useInProcessMemory ? new InProcessMemory : 0;
int numThreads = 1; int numThreads = 1;
int i; int i;
@@ -410,12 +411,12 @@ struct btInProcessExampleBrowserMainThreadInternalData
b3Clock m_clock; b3Clock m_clock;
}; };
btInProcessExampleBrowserMainThreadInternalData* btCreateInProcessExampleBrowserMainThread(int argc,char** argv) btInProcessExampleBrowserMainThreadInternalData* btCreateInProcessExampleBrowserMainThread(int argc,char** argv, bool useInProcessMemory)
{ {
btInProcessExampleBrowserMainThreadInternalData* data = new btInProcessExampleBrowserMainThreadInternalData; btInProcessExampleBrowserMainThreadInternalData* data = new btInProcessExampleBrowserMainThreadInternalData;
data->m_examples.initExampleEntries(); data->m_examples.initExampleEntries();
data->m_exampleBrowser = new DefaultBrowser(&data->m_examples); data->m_exampleBrowser = new DefaultBrowser(&data->m_examples);
data->m_sharedMem = new InProcessMemory; data->m_sharedMem = useInProcessMemory ? new InProcessMemory : 0;
data->m_exampleBrowser->setSharedMemoryInterface(data->m_sharedMem ); data->m_exampleBrowser->setSharedMemoryInterface(data->m_sharedMem );
bool init; bool init;
init = data->m_exampleBrowser->init(argc,argv); init = data->m_exampleBrowser->init(argc,argv);

View File

@@ -3,7 +3,7 @@
struct btInProcessExampleBrowserInternalData; struct btInProcessExampleBrowserInternalData;
btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,char** argv2); btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,char** argv2, bool useInProcessMemory);
bool btIsExampleBrowserTerminated(btInProcessExampleBrowserInternalData* data); bool btIsExampleBrowserTerminated(btInProcessExampleBrowserInternalData* data);
@@ -17,7 +17,7 @@ class SharedMemoryInterface* btGetSharedMemoryInterface(btInProcessExampleBrowse
struct btInProcessExampleBrowserMainThreadInternalData; struct btInProcessExampleBrowserMainThreadInternalData;
btInProcessExampleBrowserMainThreadInternalData* btCreateInProcessExampleBrowserMainThread(int argc,char** argv2); btInProcessExampleBrowserMainThreadInternalData* btCreateInProcessExampleBrowserMainThread(int argc,char** argv2, bool useInProcessMemory);
bool btIsExampleBrowserMainThreadTerminated(btInProcessExampleBrowserMainThreadInternalData* data); bool btIsExampleBrowserMainThreadTerminated(btInProcessExampleBrowserMainThreadInternalData* data);

View File

@@ -251,10 +251,15 @@ void PhysicsClientSharedMemory::resetData()
m_data->m_userConstraintInfoMap.clear(); m_data->m_userConstraintInfoMap.clear();
} }
void PhysicsClientSharedMemory::setSharedMemoryKey(int key) { m_data->m_sharedMemoryKey = key; } void PhysicsClientSharedMemory::setSharedMemoryKey(int key)
{
m_data->m_sharedMemoryKey = key;
}
void PhysicsClientSharedMemory::setSharedMemoryInterface(class SharedMemoryInterface* sharedMem) void PhysicsClientSharedMemory::setSharedMemoryInterface(class SharedMemoryInterface* sharedMem)
{
if (sharedMem)
{ {
if (m_data->m_sharedMemory && m_data->m_ownsSharedMemory) if (m_data->m_sharedMemory && m_data->m_ownsSharedMemory)
{ {
@@ -262,6 +267,7 @@ void PhysicsClientSharedMemory::setSharedMemoryInterface(class SharedMemoryInter
} }
m_data->m_ownsSharedMemory = false; m_data->m_ownsSharedMemory = false;
m_data->m_sharedMemory = sharedMem; m_data->m_sharedMemory = sharedMem;
};
} }
void PhysicsClientSharedMemory::disconnectSharedMemory() { void PhysicsClientSharedMemory::disconnectSharedMemory() {

View File

@@ -5,7 +5,7 @@
#include "PhysicsClientSharedMemory.h" #include "PhysicsClientSharedMemory.h"
#include"../ExampleBrowser/InProcessExampleBrowser.h" #include"../ExampleBrowser/InProcessExampleBrowser.h"
#include <stdio.h> #include <stdio.h>
#include <string.h>
#include "PhysicsServerExampleBullet2.h" #include "PhysicsServerExampleBullet2.h"
#include "../CommonInterfaces/CommonExampleInterface.h" #include "../CommonInterfaces/CommonExampleInterface.h"
@@ -19,7 +19,7 @@ class InProcessPhysicsClientSharedMemoryMainThread : public PhysicsClientSharedM
public: public:
InProcessPhysicsClientSharedMemoryMainThread(int argc, char* argv[]) InProcessPhysicsClientSharedMemoryMainThread(int argc, char* argv[], bool useInProcessMemory)
{ {
int newargc = argc+2; int newargc = argc+2;
char** newargv = (char**)malloc(sizeof(void*)*newargc); char** newargv = (char**)malloc(sizeof(void*)*newargc);
@@ -30,7 +30,7 @@ public:
char* t1 = (char*)"--start_demo_name=Physics Server"; char* t1 = (char*)"--start_demo_name=Physics Server";
newargv[argc] = t0; newargv[argc] = t0;
newargv[argc+1] = t1; newargv[argc+1] = t1;
m_data = btCreateInProcessExampleBrowserMainThread(newargc,newargv); m_data = btCreateInProcessExampleBrowserMainThread(newargc,newargv, useInProcessMemory);
SharedMemoryInterface* shMem = btGetSharedMemoryInterfaceMainThread(m_data); SharedMemoryInterface* shMem = btGetSharedMemoryInterfaceMainThread(m_data);
setSharedMemoryInterface(shMem); setSharedMemoryInterface(shMem);
@@ -83,9 +83,9 @@ public:
}; };
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]) b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[], int useInProcessMemory)
{ {
InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv); InProcessPhysicsClientSharedMemoryMainThread* cl = new InProcessPhysicsClientSharedMemoryMainThread(argc, argv, useInProcessMemory);
cl->setSharedMemoryKey(SHARED_MEMORY_KEY); cl->setSharedMemoryKey(SHARED_MEMORY_KEY);
cl->connect(); cl->connect();
return (b3PhysicsClientHandle ) cl; return (b3PhysicsClientHandle ) cl;
@@ -98,7 +98,7 @@ class InProcessPhysicsClientSharedMemory : public PhysicsClientSharedMemory
public: public:
InProcessPhysicsClientSharedMemory(int argc, char* argv[]) InProcessPhysicsClientSharedMemory(int argc, char* argv[], bool useInProcessMemory)
{ {
int newargc = argc+2; int newargc = argc+2;
m_newargv = (char**)malloc(sizeof(void*)*newargc); m_newargv = (char**)malloc(sizeof(void*)*newargc);
@@ -109,7 +109,7 @@ public:
char* t1 = (char*)"--start_demo_name=Physics Server"; char* t1 = (char*)"--start_demo_name=Physics Server";
m_newargv[argc] = t0; m_newargv[argc] = t0;
m_newargv[argc+1] = t1; m_newargv[argc+1] = t1;
m_data = btCreateInProcessExampleBrowser(newargc,m_newargv); m_data = btCreateInProcessExampleBrowser(newargc,m_newargv, useInProcessMemory);
SharedMemoryInterface* shMem = btGetSharedMemoryInterface(m_data); SharedMemoryInterface* shMem = btGetSharedMemoryInterface(m_data);
setSharedMemoryInterface(shMem); setSharedMemoryInterface(shMem);
} }
@@ -123,11 +123,11 @@ public:
}; };
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]) b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[], int useInProcessMemory)
{ {
InProcessPhysicsClientSharedMemory* cl = new InProcessPhysicsClientSharedMemory(argc, argv); InProcessPhysicsClientSharedMemory* cl = new InProcessPhysicsClientSharedMemory(argc, argv, useInProcessMemory);
cl->setSharedMemoryKey(SHARED_MEMORY_KEY); cl->setSharedMemoryKey(SHARED_MEMORY_KEY+1);
cl->connect(); cl->connect();
return (b3PhysicsClientHandle ) cl; return (b3PhysicsClientHandle ) cl;
} }

View File

@@ -10,9 +10,9 @@ extern "C" {
///think more about naming. The b3ConnectPhysicsLoopback ///think more about naming. The b3ConnectPhysicsLoopback
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]); b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[], int useInProcessMemory);
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]); b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[], int useInProcessMemory);
b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr); b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(void* guiHelperPtr);

View File

@@ -577,6 +577,7 @@ enum eCONNECT_METHOD {
eCONNECT_UDP = 4, eCONNECT_UDP = 4,
eCONNECT_TCP = 5, eCONNECT_TCP = 5,
eCONNECT_EXISTING_EXAMPLE_BROWSER=6, eCONNECT_EXISTING_EXAMPLE_BROWSER=6,
eCONNECT_GUI_SERVER=7,
}; };
enum eURDF_Flags enum eURDF_Flags

View File

@@ -294,6 +294,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
int method = eCONNECT_GUI; int method = eCONNECT_GUI;
int i; int i;
char* options=""; char* options="";
b3PhysicsClientHandle sm = 0; b3PhysicsClientHandle sm = 0;
if (sNumPhysicsClients >= MAX_PHYSICS_CLIENTS) if (sNumPhysicsClients >= MAX_PHYSICS_CLIENTS)
@@ -354,9 +355,21 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
char* argv[2] = {"unused",options}; char* argv[2] = {"unused",options};
#ifdef __APPLE__ #ifdef __APPLE__
sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv,1);
#else #else
sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv); sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv,1);
#endif
break;
}
case eCONNECT_GUI_SERVER:
{
int argc = 2;
char* argv[2] = {"unused",options};
#ifdef __APPLE__
sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv,0);
#else
sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv,0);
#endif #endif
break; break;
} }
@@ -7261,6 +7274,7 @@ initpybullet(void)
PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read
PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read
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, "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