quick draft implementation for SharedMemoryInProcessPhysicsC_API

This commit is contained in:
erwincoumans
2016-03-07 14:56:16 -08:00
parent b130be46f7
commit 9be978337f
8 changed files with 187 additions and 24 deletions

View File

@@ -29,6 +29,7 @@ SET(App_ExampleBrowser_SRCS
../SharedMemory/PhysicsDirect.h
../SharedMemory/PhysicsDirectC_API.cpp
../SharedMemory/PhysicsDirectC_API.h
../SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
../SharedMemory/PhysicsLoopBack.cpp
../SharedMemory/PhysicsLoopBack.h
../SharedMemory/PhysicsLoopBackC_API.cpp

View File

@@ -71,6 +71,9 @@ struct ExampleBrowserThreadLocalStorage
enum TestExampleBrowserCommunicationEnums
{
eRequestTerminateExampleBrowser = 13,
eExampleBrowserIsUnInitialized,
eExampleBrowserIsInitialized,
eExampleBrowserInitializationFailed,
eExampleBrowserHasTerminated
};
@@ -94,6 +97,11 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
clock.reset();
if (init)
{
args->m_cs->lock();
args->m_cs->setSharedParam(0,eExampleBrowserIsInitialized);
args->m_cs->unlock();
do
{
float deltaTimeInSeconds = clock.getTimeMicroseconds()/1000000.f;
@@ -101,7 +109,13 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
exampleBrowser->update(deltaTimeInSeconds);
} while (!exampleBrowser->requestedExit() && (args->m_cs->getSharedParam(0)!=eRequestTerminateExampleBrowser));
} else
{
args->m_cs->lock();
args->m_cs->setSharedParam(0,eExampleBrowserInitializationFailed);
args->m_cs->unlock();
}
delete exampleBrowser;
args->m_cs->lock();
args->m_cs->setSharedParam(0,eExampleBrowserHasTerminated);
@@ -153,7 +167,7 @@ btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,
data->m_args.m_cs = data->m_threadSupport->createCriticalSection();
data->m_args.m_cs->setSharedParam(0,100);
data->m_args.m_cs->setSharedParam(0,eExampleBrowserIsUnInitialized);
data->m_args.m_argc = argc;
data->m_args.m_argv = argv2;
@@ -163,6 +177,10 @@ btInProcessExampleBrowserInternalData* btCreateInProcessExampleBrowser(int argc,
data->m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*) &data->m_args, i);
}
while (data->m_args.m_cs->getSharedParam(0)==eExampleBrowserIsUnInitialized)
{
}
return data;
}

View File

@@ -1,5 +1,5 @@
project "App_ExampleBrowser"
project "BulletExampleBrowserLib"
hasCL = findOpenCL("clew")
@@ -13,7 +13,7 @@
language "C++"
kind "ConsoleApp"
kind "StaticLib"
includedirs {
".",
@@ -30,26 +30,20 @@
end
links{"gwen", "OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","Bullet3Common"}
initOpenGL()
initGlew()
if (hasCL) then
links {
"Bullet3OpenCL_clew",
"Bullet3Dynamics",
"Bullet3Collision",
"Bullet3Geometry",
"Bullet3Common",
}
end
defines {"INCLUDE_CLOTH_DEMOS"}
files {
"*.cpp",
"OpenGLExampleBrowser.cpp",
"OpenGLGuiHelper.cpp",
"InProcessExampleBrowser.cpp",
"GL_ShapeDrawer.cpp",
"OpenGLExampleBrowser.cpp",
"../Utils/b3Clock.cpp",
"*.h",
"GwenGUISupport/*.cpp",
"GwenGUISupport/*.h",
@@ -60,6 +54,7 @@
"../SharedMemory/PhysicsServer.cpp",
"../SharedMemory/PhysicsServerSharedMemory.cpp",
"../SharedMemory/PhysicsClientSharedMemory.cpp",
"../SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp",
"../SharedMemory/PhysicsClient.cpp",
"../SharedMemory/PosixSharedMemory.cpp",
"../SharedMemory/Win32SharedMemory.cpp",
@@ -109,7 +104,6 @@
"../ThirdPartyLibs/stb_image/*",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.*",
"../ThirdPartyLibs/tinyxml/*",
"../Utils/b3Clock.*",
"../Utils/b3ResourcePath.*",
"../GyroscopicDemo/GyroscopicSetup.cpp",
"../GyroscopicDemo/GyroscopicSetup.h",
@@ -149,8 +143,41 @@ if os.is("Linux") then
initX11()
end
if os.is("MacOSX") then
links{"Cocoa.framework"}
end
project "App_BulletExampleBrowser"
language "C++"
kind "ConsoleApp"
hasCL = findOpenCL("clew")
links{"BulletExampleBrowserLib","gwen", "OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","Bullet3Common"}
initOpenGL()
initGlew()
includedirs {
".",
"../../src",
"../ThirdPartyLibs",
}
if os.is("MacOSX") then
links{"Cocoa.framework"}
end
if (hasCL) then
links {
"Bullet3OpenCL_clew",
"Bullet3Dynamics",
"Bullet3Collision",
"Bullet3Geometry",
"Bullet3Common",
}
end
files {
"main.cpp",
"ExampleEntries.cpp",
}

View File

@@ -0,0 +1,41 @@
#include "SharedMemoryInProcessPhysicsC_API.h"
#include "PhysicsClientSharedMemory.h"
#include"ExampleBrowser/InProcessExampleBrowser.h"
class InProcessPhysicsClientSharedMemory : public PhysicsClientSharedMemory
{
btInProcessExampleBrowserInternalData* m_data;
public:
InProcessPhysicsClientSharedMemory(int argc, char* argv[])
{
int newargc = argc+2;
char** newargv = (char**)malloc(sizeof(void*)*newargc);
for (int i=0;i<argc;i++)
newargv[i] = argv[i];
char* t0 = (char*)"--logtostderr";
char* t1 = (char*)"--start_demo_name=Physics Server";
newargv[argc] = t0;
newargv[argc+1] = t1;
m_data = btCreateInProcessExampleBrowser(newargc,newargv);
}
virtual ~InProcessPhysicsClientSharedMemory()
{
btShutDownExampleBrowser(m_data);
}
};
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[])
{
InProcessPhysicsClientSharedMemory* cl = new InProcessPhysicsClientSharedMemory(argc, argv);
cl->setSharedMemoryKey(SHARED_MEMORY_KEY);
cl->connect();
return (b3PhysicsClientHandle ) cl;
}

View File

@@ -0,0 +1,19 @@
#ifndef IN_PROCESS_PHYSICS_C_API_H
#define IN_PROCESS_PHYSICS_C_API_H
#include "PhysicsClientC_API.h"
#ifdef __cplusplus
extern "C" {
#endif
///think more about naming. The b3ConnectPhysicsLoopback
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* argv[]);
#ifdef __cplusplus
}
#endif
#endif //IN_PROCESS_PHYSICS_C_API_H

View File

@@ -68,6 +68,7 @@ b3Clock::b3Clock()
reset();
}
b3Clock::~b3Clock()
{
delete m_data;

View File

@@ -141,4 +141,52 @@ project ("Test_PhysicsServerLoopBack")
}
project ("Test_PhysicsServerInProcessExampleBrowser")
language "C++"
kind "ConsoleApp"
includedirs {"../../src", "../../examples",
"../../examples/ThirdPartyLibs"}
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
-- links {
-- "BulletExampleBrowserLib",
-- "BulletFileLoader",
-- "BulletWorldImporter",
-- "Bullet3Common",
-- "BulletDynamics",
-- "BulletCollision",
-- "LinearMath"
-- }
hasCL = findOpenCL("clew")
links{"BulletExampleBrowserLib","gwen", "OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","Bullet3Common"}
initOpenGL()
initGlew()
includedirs {
".",
"../../src",
"../ThirdPartyLibs",
}
if os.is("MacOSX") then
links{"Cocoa.framework"}
end
if (hasCL) then
links {
"Bullet3OpenCL_clew",
"Bullet3Dynamics",
"Bullet3Collision",
"Bullet3Geometry",
"Bullet3Common",
}
end
files {
"test.c",
"../../examples/ExampleBrowser/ExampleEntries.cpp",
}

View File

@@ -9,6 +9,9 @@
#include "SharedMemory/PhysicsDirectC_API.h"
#endif //PHYSICS_SERVER_DIRECT
#ifdef PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
#include "SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
#endif//PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
#include "SharedMemory/SharedMemoryPublic.h"
#include "Bullet3Common/b3Logging.h"
@@ -17,6 +20,7 @@
#include <stdio.h>
int main(int argc, char* argv[])
{
int i, dofCount , posVarCount, ret ,numJoints ;
@@ -40,7 +44,11 @@ int main(int argc, char* argv[])
#ifdef PHYSICS_SERVER_DIRECT
sm = b3ConnectPhysicsDirect();
#else//PHYSICS_SERVER_DIRECT
#endif
#ifdef PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
sm = b3CreateInProcessPhysicsServerAndConnect(argc,argv);
#else
sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
#endif //PHYSICS_SERVER_DIRECT
@@ -61,8 +69,8 @@ int main(int argc, char* argv[])
b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName);
//setting the initial position, orientation and other arguments are optional
startPosX =2;
startPosY =3;
startPosX =0;
startPosY =0;
startPosZ = 1;
ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);