exit gracefully and call destructor of the current active example
fflush after printf implemented stepForward and Shutdown for the SharedMemory client/server
This commit is contained in:
@@ -79,7 +79,7 @@
|
|||||||
defines {"_DEBUG=1"}
|
defines {"_DEBUG=1"}
|
||||||
flags { "Symbols", "StaticRuntime" , "NoMinimalRebuild", "NoEditAndContinue" ,"FloatFast"}
|
flags { "Symbols", "StaticRuntime" , "NoMinimalRebuild", "NoEditAndContinue" ,"FloatFast"}
|
||||||
|
|
||||||
if os.is("Linux") then
|
if os.is("Linux") or os.is("macosx") then
|
||||||
if os.is64bit() then
|
if os.is64bit() then
|
||||||
platforms {"x64"}
|
platforms {"x64"}
|
||||||
else
|
else
|
||||||
|
|||||||
@@ -42,13 +42,17 @@ class MyMenuItems : public Gwen::Controls::Base
|
|||||||
public:
|
public:
|
||||||
|
|
||||||
b3FileOpenCallback m_fileOpenCallback;
|
b3FileOpenCallback m_fileOpenCallback;
|
||||||
|
b3QuitCallback m_quitCallback;
|
||||||
|
|
||||||
MyMenuItems() :Gwen::Controls::Base(0),m_fileOpenCallback(0)
|
MyMenuItems() :Gwen::Controls::Base(0),m_fileOpenCallback(0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
void myQuitApp( Gwen::Controls::Base* pControl )
|
void myQuitApp( Gwen::Controls::Base* pControl )
|
||||||
{
|
{
|
||||||
exit(0);
|
if (m_quitCallback)
|
||||||
|
{
|
||||||
|
(*m_quitCallback)();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
void fileOpen( Gwen::Controls::Base* pControl )
|
void fileOpen( Gwen::Controls::Base* pControl )
|
||||||
{
|
{
|
||||||
@@ -74,6 +78,7 @@ struct MyTestMenuBar : public Gwen::Controls::MenuStrip
|
|||||||
{
|
{
|
||||||
m_menuItems = new MyMenuItems();
|
m_menuItems = new MyMenuItems();
|
||||||
m_menuItems->m_fileOpenCallback = 0;
|
m_menuItems->m_fileOpenCallback = 0;
|
||||||
|
m_menuItems->m_quitCallback = 0;
|
||||||
|
|
||||||
m_fileMenu = AddItem( L"File" );
|
m_fileMenu = AddItem( L"File" );
|
||||||
|
|
||||||
@@ -230,6 +235,11 @@ void GwenUserInterface::registerFileOpenCallback(b3FileOpenCallback callback)
|
|||||||
m_data->m_menuItems->m_fileOpenCallback = callback;
|
m_data->m_menuItems->m_fileOpenCallback = callback;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GwenUserInterface::registerQuitCallback(b3QuitCallback callback)
|
||||||
|
{
|
||||||
|
m_data->m_menuItems->m_quitCallback = callback;
|
||||||
|
}
|
||||||
|
|
||||||
void GwenUserInterface::init(int width, int height,Gwen::Renderer::Base* renderer,float retinaScale)
|
void GwenUserInterface::init(int width, int height,Gwen::Renderer::Base* renderer,float retinaScale)
|
||||||
{
|
{
|
||||||
m_data->m_curYposition = 20;
|
m_data->m_curYposition = 20;
|
||||||
|
|||||||
@@ -6,6 +6,7 @@ struct GwenInternalData;
|
|||||||
typedef void (*b3ComboBoxCallback) (int combobox, const char* item);
|
typedef void (*b3ComboBoxCallback) (int combobox, const char* item);
|
||||||
typedef void (*b3ToggleButtonCallback)(int button, int state);
|
typedef void (*b3ToggleButtonCallback)(int button, int state);
|
||||||
typedef void (*b3FileOpenCallback)();
|
typedef void (*b3FileOpenCallback)();
|
||||||
|
typedef void (*b3QuitCallback)();
|
||||||
|
|
||||||
namespace Gwen
|
namespace Gwen
|
||||||
{
|
{
|
||||||
@@ -53,6 +54,7 @@ class GwenUserInterface
|
|||||||
|
|
||||||
|
|
||||||
void registerFileOpenCallback(b3FileOpenCallback callback);
|
void registerFileOpenCallback(b3FileOpenCallback callback);
|
||||||
|
void registerQuitCallback(b3QuitCallback callback);
|
||||||
|
|
||||||
GwenInternalData* getInternalData()
|
GwenInternalData* getInternalData()
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -88,7 +88,18 @@ int gGpuArraySizeZ=15;
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void deleteDemo()
|
||||||
|
{
|
||||||
|
if (sCurrentDemo)
|
||||||
|
{
|
||||||
|
sCurrentDemo->exitPhysics();
|
||||||
|
s_instancingRenderer->removeAllInstances();
|
||||||
|
delete sCurrentDemo;
|
||||||
|
sCurrentDemo=0;
|
||||||
|
delete s_guiHelper;
|
||||||
|
s_guiHelper = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
b3KeyboardCallback prevKeyboardCallback = 0;
|
b3KeyboardCallback prevKeyboardCallback = 0;
|
||||||
@@ -163,6 +174,7 @@ void MyKeyboardCallback(int key, int state)
|
|||||||
#endif
|
#endif
|
||||||
if (key==B3G_ESCAPE && s_window)
|
if (key==B3G_ESCAPE && s_window)
|
||||||
{
|
{
|
||||||
|
|
||||||
s_window->setRequestExit();
|
s_window->setRequestExit();
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -270,15 +282,8 @@ void selectDemo(int demoIndex)
|
|||||||
{
|
{
|
||||||
demoIndex = 0;
|
demoIndex = 0;
|
||||||
}
|
}
|
||||||
if (sCurrentDemo)
|
deleteDemo();
|
||||||
{
|
|
||||||
sCurrentDemo->exitPhysics();
|
|
||||||
s_instancingRenderer->removeAllInstances();
|
|
||||||
delete sCurrentDemo;
|
|
||||||
sCurrentDemo=0;
|
|
||||||
delete s_guiHelper;
|
|
||||||
s_guiHelper = 0;
|
|
||||||
}
|
|
||||||
CommonExampleInterface::CreateFunc* func = gAllExamples->getExampleCreateFunc(demoIndex);
|
CommonExampleInterface::CreateFunc* func = gAllExamples->getExampleCreateFunc(demoIndex);
|
||||||
if (func)
|
if (func)
|
||||||
{
|
{
|
||||||
@@ -495,6 +500,12 @@ struct GL3TexLoader : public MyTextureLoader
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
void quitCallback()
|
||||||
|
{
|
||||||
|
|
||||||
|
s_window->setRequestExit();
|
||||||
|
}
|
||||||
|
|
||||||
void fileOpenCallback()
|
void fileOpenCallback()
|
||||||
{
|
{
|
||||||
|
|
||||||
@@ -581,6 +592,7 @@ OpenGLExampleBrowser::OpenGLExampleBrowser(class ExampleEntries* examples)
|
|||||||
|
|
||||||
OpenGLExampleBrowser::~OpenGLExampleBrowser()
|
OpenGLExampleBrowser::~OpenGLExampleBrowser()
|
||||||
{
|
{
|
||||||
|
deleteDemo();
|
||||||
gAllExamples = 0;
|
gAllExamples = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -790,7 +802,7 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
|
|||||||
}
|
}
|
||||||
|
|
||||||
gui->registerFileOpenCallback(fileOpenCallback);
|
gui->registerFileOpenCallback(fileOpenCallback);
|
||||||
|
gui->registerQuitCallback(quitCallback);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -48,6 +48,7 @@ void dumpInfo(void)
|
|||||||
NSOpenGLContext* m_context;
|
NSOpenGLContext* m_context;
|
||||||
int m_lastWidth;
|
int m_lastWidth;
|
||||||
int m_lastHeight;
|
int m_lastHeight;
|
||||||
|
bool m_requestClose;
|
||||||
b3ResizeCallback m_resizeCallback;
|
b3ResizeCallback m_resizeCallback;
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -56,6 +57,8 @@ void dumpInfo(void)
|
|||||||
-(void) MakeCurrent;
|
-(void) MakeCurrent;
|
||||||
-(float) GetWindowWidth;
|
-(float) GetWindowWidth;
|
||||||
-(float) GetWindowHeight;
|
-(float) GetWindowHeight;
|
||||||
|
-(BOOL) GetRequestClose;
|
||||||
|
- (BOOL)windowShouldClose:(id)sender;
|
||||||
-(void) setResizeCallback:(b3ResizeCallback) callback;
|
-(void) setResizeCallback:(b3ResizeCallback) callback;
|
||||||
-(b3ResizeCallback) getResizeCallback;
|
-(b3ResizeCallback) getResizeCallback;
|
||||||
-(NSOpenGLContext*) getContext;
|
-(NSOpenGLContext*) getContext;
|
||||||
@@ -67,6 +70,15 @@ float loop;
|
|||||||
|
|
||||||
@implementation TestView
|
@implementation TestView
|
||||||
|
|
||||||
|
- (BOOL)windowShouldClose:(id)sender
|
||||||
|
{
|
||||||
|
m_requestClose = true;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
-(BOOL) GetRequestClose
|
||||||
|
{
|
||||||
|
return m_requestClose;
|
||||||
|
}
|
||||||
-(float) GetWindowWidth
|
-(float) GetWindowWidth
|
||||||
{
|
{
|
||||||
return m_lastWidth;
|
return m_lastWidth;
|
||||||
@@ -140,7 +152,7 @@ float loop;
|
|||||||
// NSWindow *w;
|
// NSWindow *w;
|
||||||
NSOpenGLPixelFormat *fmt;
|
NSOpenGLPixelFormat *fmt;
|
||||||
|
|
||||||
|
m_requestClose = false;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@@ -776,7 +788,6 @@ void MacOpenGLWindow::startRendering()
|
|||||||
//NSShiftKeyMask = 1 << 17,
|
//NSShiftKeyMask = 1 << 17,
|
||||||
//NSControlKeyMask
|
//NSControlKeyMask
|
||||||
|
|
||||||
|
|
||||||
if ([event type] == NSFlagsChanged)
|
if ([event type] == NSFlagsChanged)
|
||||||
{
|
{
|
||||||
int modifiers = [event modifierFlags];
|
int modifiers = [event modifierFlags];
|
||||||
@@ -1050,7 +1061,8 @@ void MacOpenGLWindow::endRendering()
|
|||||||
|
|
||||||
bool MacOpenGLWindow::requestedExit() const
|
bool MacOpenGLWindow::requestedExit() const
|
||||||
{
|
{
|
||||||
return m_internalData->m_exitRequested;
|
bool closeme = m_internalData->m_myview.GetRequestClose;
|
||||||
|
return m_internalData->m_exitRequested || closeme;
|
||||||
}
|
}
|
||||||
|
|
||||||
void MacOpenGLWindow::setRequestExit()
|
void MacOpenGLWindow::setRequestExit()
|
||||||
|
|||||||
@@ -3,11 +3,14 @@
|
|||||||
|
|
||||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||||
#include "PosixSharedMemory.h"
|
#include "PosixSharedMemory.h"
|
||||||
|
#include "SharedMemoryCommon.h"
|
||||||
|
|
||||||
class PhysicsClient : public CommonMultiBodyBase
|
class PhysicsClient : public SharedMemoryCommon
|
||||||
{
|
{
|
||||||
SharedMemoryInterface* m_sharedMemory;
|
SharedMemoryInterface* m_sharedMemory;
|
||||||
SharedMemoryExampleData* m_testBlock1;
|
SharedMemoryExampleData* m_testBlock1;
|
||||||
|
int m_counter;
|
||||||
|
bool m_wantsTermination;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
@@ -27,11 +30,17 @@ public:
|
|||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual bool wantsTermination()
|
||||||
|
{
|
||||||
|
return m_wantsTermination;
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
PhysicsClient::PhysicsClient(GUIHelperInterface* helper)
|
PhysicsClient::PhysicsClient(GUIHelperInterface* helper)
|
||||||
:CommonMultiBodyBase(helper),
|
:SharedMemoryCommon(helper),
|
||||||
m_testBlock1(0)
|
m_testBlock1(0),
|
||||||
|
m_counter(0),
|
||||||
|
m_wantsTermination(false)
|
||||||
{
|
{
|
||||||
b3Printf("Started PhysicsClient");
|
b3Printf("Started PhysicsClient");
|
||||||
m_sharedMemory = new PosixSharedMemory();
|
m_sharedMemory = new PosixSharedMemory();
|
||||||
@@ -55,21 +64,10 @@ void PhysicsClient::initPhysics()
|
|||||||
b3Error("Error: please start server before client");
|
b3Error("Error: please start server before client");
|
||||||
m_sharedMemory->releaseSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE);
|
m_sharedMemory->releaseSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE);
|
||||||
m_testBlock1 = 0;
|
m_testBlock1 = 0;
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
} else
|
||||||
|
|
||||||
void PhysicsClient::stepSimulation(float deltaTime)
|
|
||||||
{
|
{
|
||||||
|
//submit a 'load urdf' command to get things started
|
||||||
static int once = true;
|
|
||||||
|
|
||||||
if (m_testBlock1)
|
|
||||||
{
|
|
||||||
if (once)
|
|
||||||
{
|
|
||||||
once=false;
|
|
||||||
|
|
||||||
b3Printf("Client created CMD_LOAD_URDF");
|
b3Printf("Client created CMD_LOAD_URDF");
|
||||||
m_testBlock1->m_clientCommands[0].m_type =CMD_LOAD_URDF;
|
m_testBlock1->m_clientCommands[0].m_type =CMD_LOAD_URDF;
|
||||||
@@ -78,6 +76,66 @@ void PhysicsClient::stepSimulation(float deltaTime)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void PhysicsClient::stepSimulation(float deltaTime)
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
if (m_testBlock1)
|
||||||
|
{
|
||||||
|
//check progress and submit further commands
|
||||||
|
//we ignore overflow right now
|
||||||
|
|
||||||
|
if (m_testBlock1->m_numServerCommands> m_testBlock1->m_numProcessedServerCommands)
|
||||||
|
{
|
||||||
|
btAssert(m_testBlock1->m_numServerCommands==m_testBlock1->m_numProcessedServerCommands+1);
|
||||||
|
|
||||||
|
const SharedMemoryCommand& serverCmd =m_testBlock1->m_serverCommands[0];
|
||||||
|
|
||||||
|
//consume the command
|
||||||
|
switch (serverCmd.m_type)
|
||||||
|
{
|
||||||
|
|
||||||
|
case CMD_STEP_FORWARD_SIMULATION_COMPLETED:
|
||||||
|
case CMD_URDF_LOADING_COMPLETED:
|
||||||
|
{
|
||||||
|
//submit a 'step simulation' request
|
||||||
|
|
||||||
|
if (m_counter<10)
|
||||||
|
{
|
||||||
|
m_testBlock1->m_clientCommands[0].m_type =CMD_STEP_FORWARD_SIMULATION;
|
||||||
|
m_testBlock1->m_clientCommands[0].m_stepSimulationArguments.m_deltaTimeInSeconds = 1./60.;
|
||||||
|
m_testBlock1->m_numClientCommands++;
|
||||||
|
m_counter++;
|
||||||
|
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
m_wantsTermination = true;
|
||||||
|
m_testBlock1->m_clientCommands[0].m_type =CMD_SHUTDOWN;
|
||||||
|
m_testBlock1->m_numClientCommands++;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case CMD_URDF_LOADING_FAILED:
|
||||||
|
{
|
||||||
|
b3Printf("Server failed loading the URDF...");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
b3Error("Unknown server command");
|
||||||
|
btAssert(0);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
m_testBlock1->m_numProcessedServerCommands++;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -1,19 +1,19 @@
|
|||||||
|
|
||||||
#include "PhysicsServer.h"
|
#include "PhysicsServer.h"
|
||||||
|
|
||||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
|
||||||
#include "PosixSharedMemory.h"
|
#include "PosixSharedMemory.h"
|
||||||
#include "../Importers/ImportURDFDemo/MyURDFImporter.h"
|
#include "../Importers/ImportURDFDemo/MyURDFImporter.h"
|
||||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||||
|
|
||||||
|
#include "SharedMemoryCommon.h"
|
||||||
|
|
||||||
|
|
||||||
|
class PhysicsServer : public SharedMemoryCommon
|
||||||
class PhysicsServer : public CommonMultiBodyBase
|
|
||||||
{
|
{
|
||||||
SharedMemoryInterface* m_sharedMemory;
|
SharedMemoryInterface* m_sharedMemory;
|
||||||
SharedMemoryExampleData* m_testBlock1;
|
SharedMemoryExampleData* m_testBlock1;
|
||||||
|
bool m_wantsShutdown;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
@@ -25,6 +25,8 @@ public:
|
|||||||
|
|
||||||
virtual void stepSimulation(float deltaTime);
|
virtual void stepSimulation(float deltaTime);
|
||||||
|
|
||||||
|
void releaseSharedMemory();
|
||||||
|
|
||||||
bool loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
|
bool loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
|
||||||
bool useMultiBody, bool useFixedBase);
|
bool useMultiBody, bool useFixedBase);
|
||||||
|
|
||||||
@@ -37,25 +39,39 @@ public:
|
|||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual bool wantsTermination();
|
||||||
};
|
};
|
||||||
|
|
||||||
PhysicsServer::PhysicsServer(GUIHelperInterface* helper)
|
PhysicsServer::PhysicsServer(GUIHelperInterface* helper)
|
||||||
:CommonMultiBodyBase(helper),
|
:SharedMemoryCommon(helper),
|
||||||
m_testBlock1(0)
|
m_testBlock1(0),
|
||||||
|
m_wantsShutdown(false)
|
||||||
{
|
{
|
||||||
b3Printf("Started PhysicsServer\n");
|
b3Printf("Started PhysicsServer\n");
|
||||||
m_sharedMemory = new PosixSharedMemory();
|
m_sharedMemory = new PosixSharedMemory();
|
||||||
}
|
}
|
||||||
|
|
||||||
PhysicsServer::~PhysicsServer()
|
void PhysicsServer::releaseSharedMemory()
|
||||||
{
|
{
|
||||||
if (m_testBlock1)
|
if (m_testBlock1)
|
||||||
{
|
{
|
||||||
m_testBlock1->m_magicId = 0;
|
m_testBlock1->m_magicId = 0;
|
||||||
b3Printf("magic id = %d\n",m_testBlock1->m_magicId);
|
b3Printf("magic id = %d\n",m_testBlock1->m_magicId);
|
||||||
}
|
btAssert(m_sharedMemory);
|
||||||
m_sharedMemory->releaseSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE);
|
m_sharedMemory->releaseSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE);
|
||||||
|
}
|
||||||
|
if (m_sharedMemory)
|
||||||
|
{
|
||||||
|
|
||||||
delete m_sharedMemory;
|
delete m_sharedMemory;
|
||||||
|
m_sharedMemory = 0;
|
||||||
|
m_testBlock1 = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
PhysicsServer::~PhysicsServer()
|
||||||
|
{
|
||||||
|
releaseSharedMemory();
|
||||||
}
|
}
|
||||||
|
|
||||||
void PhysicsServer::initPhysics()
|
void PhysicsServer::initPhysics()
|
||||||
@@ -86,6 +102,12 @@ void PhysicsServer::initPhysics()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
bool PhysicsServer::wantsTermination()
|
||||||
|
{
|
||||||
|
return m_wantsShutdown;
|
||||||
|
}
|
||||||
|
|
||||||
bool PhysicsServer::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
|
bool PhysicsServer::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
|
||||||
bool useMultiBody, bool useFixedBase)
|
bool useMultiBody, bool useFixedBase)
|
||||||
{
|
{
|
||||||
@@ -103,17 +125,21 @@ bool PhysicsServer::loadUrdf(const char* fileName, const btVector3& pos, const b
|
|||||||
int rootLinkIndex = u2b.getRootLinkIndex();
|
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||||
// printf("urdf root link index = %d\n",rootLinkIndex);
|
// printf("urdf root link index = %d\n",rootLinkIndex);
|
||||||
MyMultiBodyCreator creation(m_guiHelper);
|
MyMultiBodyCreator creation(m_guiHelper);
|
||||||
bool m_useMultiBody = true;
|
|
||||||
ConvertURDF2Bullet(u2b,creation, tr,m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
|
ConvertURDF2Bullet(u2b,creation, tr,m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
|
||||||
btMultiBody* mb = creation.getBulletMultiBody();
|
btMultiBody* mb = creation.getBulletMultiBody();
|
||||||
|
|
||||||
return false;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PhysicsServer::stepSimulation(float deltaTime)
|
void PhysicsServer::stepSimulation(float deltaTime)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
bool wantsShutdown = false;
|
||||||
|
|
||||||
if (m_testBlock1)
|
if (m_testBlock1)
|
||||||
{
|
{
|
||||||
///we ignore overflow of integer for now
|
///we ignore overflow of integer for now
|
||||||
@@ -124,6 +150,7 @@ void PhysicsServer::stepSimulation(float deltaTime)
|
|||||||
btAssert(m_testBlock1->m_numClientCommands==m_testBlock1->m_numProcessedClientCommands+1);
|
btAssert(m_testBlock1->m_numClientCommands==m_testBlock1->m_numProcessedClientCommands+1);
|
||||||
|
|
||||||
const SharedMemoryCommand& clientCmd =m_testBlock1->m_clientCommands[0];
|
const SharedMemoryCommand& clientCmd =m_testBlock1->m_clientCommands[0];
|
||||||
|
m_testBlock1->m_numProcessedClientCommands++;
|
||||||
|
|
||||||
//consume the command
|
//consume the command
|
||||||
switch (clientCmd.m_type)
|
switch (clientCmd.m_type)
|
||||||
@@ -148,19 +175,45 @@ void PhysicsServer::stepSimulation(float deltaTime)
|
|||||||
|
|
||||||
}
|
}
|
||||||
m_testBlock1->m_numServerCommands++;
|
m_testBlock1->m_numServerCommands++;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case CMD_STEP_FORWARD_SIMULATION:
|
||||||
|
{
|
||||||
|
|
||||||
|
b3Printf("Step simulation request");
|
||||||
|
double timeStep = clientCmd.m_stepSimulationArguments.m_deltaTimeInSeconds;
|
||||||
|
m_dynamicsWorld->stepSimulation(timeStep);
|
||||||
|
|
||||||
|
SharedMemoryCommand& serverCmd =m_testBlock1->m_serverCommands[0];
|
||||||
|
|
||||||
|
serverCmd.m_type =CMD_STEP_FORWARD_SIMULATION_COMPLETED;
|
||||||
|
m_testBlock1->m_numServerCommands++;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case CMD_SHUTDOWN:
|
||||||
|
{
|
||||||
|
wantsShutdown = true;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
|
b3Error("Unsupported command encountered");
|
||||||
|
btAssert(0);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
m_testBlock1->m_numProcessedClientCommands++;
|
|
||||||
|
|
||||||
//process the command right now
|
//process the command right now
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (wantsShutdown)
|
||||||
|
{
|
||||||
|
m_wantsShutdown = true;
|
||||||
|
releaseSharedMemory();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -18,6 +18,7 @@ enum SharedMemoryClientCommand{
|
|||||||
CMD_LOAD_URDF,
|
CMD_LOAD_URDF,
|
||||||
CMD_STATE_UPDATED,
|
CMD_STATE_UPDATED,
|
||||||
CMD_STEP_FORWARD_SIMULATION, //includes CMD_REQUEST_STATE
|
CMD_STEP_FORWARD_SIMULATION, //includes CMD_REQUEST_STATE
|
||||||
|
CMD_SHUTDOWN,
|
||||||
CMD_MAX_CLIENT_COMMANDS
|
CMD_MAX_CLIENT_COMMANDS
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -20,8 +20,7 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
#include "../CommonInterfaces/CommonExampleInterface.h"
|
#include "../CommonInterfaces/CommonExampleInterface.h"
|
||||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
|
#include "SharedMemoryCommon.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
int main(int argc, char* argv[])
|
int main(int argc, char* argv[])
|
||||||
@@ -33,18 +32,22 @@ int main(int argc, char* argv[])
|
|||||||
DummyGUIHelper noGfx;
|
DummyGUIHelper noGfx;
|
||||||
|
|
||||||
CommonExampleOptions options(&noGfx);
|
CommonExampleOptions options(&noGfx);
|
||||||
CommonExampleInterface* example = 0;
|
SharedMemoryCommon* example = 0;
|
||||||
|
|
||||||
if (args.CheckCmdLineFlag("client"))
|
if (args.CheckCmdLineFlag("client"))
|
||||||
{
|
{
|
||||||
example = PhysicsClientCreateFunc(options);
|
example = (SharedMemoryCommon*)PhysicsClientCreateFunc(options);
|
||||||
}else
|
}else
|
||||||
{
|
{
|
||||||
example = PhysicsServerCreateFunc(options);
|
example = (SharedMemoryCommon*)PhysicsServerCreateFunc(options);
|
||||||
}
|
}
|
||||||
|
|
||||||
example->initPhysics();
|
example->initPhysics();
|
||||||
|
while (!example->wantsTermination())
|
||||||
|
{
|
||||||
example->stepSimulation(1.f/60.f);
|
example->stepSimulation(1.f/60.f);
|
||||||
|
}
|
||||||
|
|
||||||
example->exitPhysics();
|
example->exitPhysics();
|
||||||
|
|
||||||
delete example;
|
delete example;
|
||||||
|
|||||||
@@ -29,7 +29,8 @@ void b3PrintfFuncDefault(const char* msg)
|
|||||||
OutputDebugStringA(msg);
|
OutputDebugStringA(msg);
|
||||||
#endif
|
#endif
|
||||||
printf("%s",msg);
|
printf("%s",msg);
|
||||||
|
//is this portable?
|
||||||
|
fflush(stdout);
|
||||||
}
|
}
|
||||||
|
|
||||||
void b3WarningMessageFuncDefault(const char* msg)
|
void b3WarningMessageFuncDefault(const char* msg)
|
||||||
@@ -38,7 +39,8 @@ void b3WarningMessageFuncDefault(const char* msg)
|
|||||||
OutputDebugStringA(msg);
|
OutputDebugStringA(msg);
|
||||||
#endif
|
#endif
|
||||||
printf("%s",msg);
|
printf("%s",msg);
|
||||||
|
//is this portable?
|
||||||
|
fflush(stdout);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -50,6 +52,9 @@ void b3ErrorMessageFuncDefault(const char* msg)
|
|||||||
#endif
|
#endif
|
||||||
printf("%s",msg);
|
printf("%s",msg);
|
||||||
|
|
||||||
|
//is this portable?
|
||||||
|
fflush(stdout);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user