Merge pull request #509 from erwincoumans/master

fix case sensitive issue
This commit is contained in:
erwincoumans
2015-10-30 11:00:27 -07:00
11 changed files with 304 additions and 74 deletions

View File

@@ -215,6 +215,11 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Physics Server", "Create a physics server that communicates with a physics client over shared memory", ExampleEntry(1,"Physics Server", "Create a physics server that communicates with a physics client over shared memory",
PhysicsServerCreateFunc), PhysicsServerCreateFunc),
ExampleEntry(1,"Physics Server (Logging)", "Create a physics server that communicates with a physics client over shared memory. It will log all commands to a file.",
PhysicsServerCreateFunc,PHYSICS_SERVER_ENABLE_COMMAND_LOGGING),
ExampleEntry(1,"Physics Server (Replay Log)", "Create a physics server that replay a command log from disk.",
PhysicsServerCreateFunc,PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG),
ExampleEntry(1, "Physics Client", "Create a physics client that can communicate with a physics server over shared memory", PhysicsClientCreateFunc), ExampleEntry(1, "Physics Client", "Create a physics client that can communicate with a physics server over shared memory", PhysicsClientCreateFunc),
#ifdef ENABLE_LUA #ifdef ENABLE_LUA
ExampleEntry(1,"Lua Script", "Create the dynamics world, collision shapes and rigid bodies using Lua scripting", ExampleEntry(1,"Lua Script", "Create the dynamics world, collision shapes and rigid bodies using Lua scripting",

View File

@@ -71,6 +71,7 @@ extern bool useShadowMap;
static bool visualWireframe=false; static bool visualWireframe=false;
static bool renderVisualGeometry=true; static bool renderVisualGeometry=true;
static bool renderGrid = true; static bool renderGrid = true;
static bool renderGui = true;
static bool enable_experimental_opencl = false; static bool enable_experimental_opencl = false;
int gDebugDrawFlags = 0; int gDebugDrawFlags = 0;
@@ -170,6 +171,7 @@ void MyKeyboardCallback(int key, int state)
if (key=='g' && state) if (key=='g' && state)
{ {
renderGrid = !renderGrid; renderGrid = !renderGrid;
renderGui = !renderGui;
} }
@@ -1041,7 +1043,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
} }
static int toggle = 1; static int toggle = 1;
if (1) if (renderGui)
{ {
if (!pauseSimulation) if (!pauseSimulation)
processProfileData(s_profWindow,false); processProfileData(s_profWindow,false);

View File

@@ -367,7 +367,7 @@ void ImportUrdfSetup::initPhysics()
m_guiHelper->createCollisionShapeGraphicsObject(box); m_guiHelper->createCollisionShapeGraphicsObject(box);
btTransform start; start.setIdentity(); btTransform start; start.setIdentity();
btVector3 groundOrigin(0,0,0); btVector3 groundOrigin(0,0,0);
groundOrigin[upAxis]=-2;//.5; groundOrigin[upAxis]=-2.5;
start.setOrigin(groundOrigin); start.setOrigin(groundOrigin);
btRigidBody* body = createRigidBody(0,start,box); btRigidBody* body = createRigidBody(0,start,box);
//m_dynamicsWorld->removeRigidBody(body); //m_dynamicsWorld->removeRigidBody(body);

View File

@@ -109,6 +109,123 @@ struct InternalBodyHandle : public InteralBodyData
} }
}; };
class btCommandChunk
{
public:
int m_chunkCode;
int m_length;
void *m_oldPtr;
int m_dna_nr;
int m_number;
};
struct CommandLogger
{
FILE* m_file;
void writeHeader(unsigned char* buffer) const
{
#ifdef BT_USE_DOUBLE_PRECISION
memcpy(buffer, "BT3CMDd", 7);
#else
memcpy(buffer, "BT3CMDf", 7);
#endif //BT_USE_DOUBLE_PRECISION
int littleEndian= 1;
littleEndian= ((char*)&littleEndian)[0];
if (sizeof(void*)==8)
{
buffer[7] = '-';
} else
{
buffer[7] = '_';
}
if (littleEndian)
{
buffer[8]='v';
} else
{
buffer[8]='V';
}
buffer[9] = 0;
buffer[10] = 0;
buffer[11] = 0;
int ver = btGetVersion();
if (ver>=0 && ver<999)
{
sprintf((char*)&buffer[9],"%d",ver);
}
}
void logCommand(SharedMemoryBlock* testBlock1)
{
btCommandChunk chunk;
chunk.m_chunkCode = testBlock1->m_clientCommands[0].m_type;
chunk.m_oldPtr = 0;
chunk.m_dna_nr = 0;
chunk.m_length = sizeof(SharedMemoryCommand);
chunk.m_number = 1;
fwrite((const char*)&chunk,sizeof(btCommandChunk), 1,m_file);
fwrite((const char*)&testBlock1->m_clientCommands[0],sizeof(SharedMemoryCommand),1,m_file);
}
CommandLogger(const char* fileName)
{
m_file = fopen(fileName,"wb");
unsigned char buf[15];
buf[12] = 12;
buf[13] = 13;
buf[14] = 14;
writeHeader(buf);
fwrite(buf,12,1,m_file);
}
virtual ~CommandLogger()
{
fclose(m_file);
}
};
struct CommandLogPlayback
{
unsigned char* m_header[12];
FILE* m_file;
CommandLogPlayback(const char* fileName)
{
m_file = fopen(fileName,"rb");
if (m_file)
{
fread(m_header,12,1,m_file);
}
}
virtual ~CommandLogPlayback()
{
if (m_file)
{
fclose(m_file);
m_file=0;
}
}
bool processNextCommand(SharedMemoryCommand* cmd)
{
btCommandChunk chunk;
size_t s = fread((void*)&chunk,sizeof(btCommandChunk),1,m_file);
if (s==1)
{
s = fread(cmd,sizeof(SharedMemoryCommand),1,m_file);
return (s==1);
}
return false;
}
};
struct PhysicsServerInternalData struct PhysicsServerInternalData
{ {
///handle management ///handle management
@@ -200,6 +317,9 @@ struct PhysicsServerInternalData
SharedMemoryInterface* m_sharedMemory; SharedMemoryInterface* m_sharedMemory;
SharedMemoryBlock* m_testBlock1; SharedMemoryBlock* m_testBlock1;
CommandLogger* m_commandLogger;
CommandLogPlayback* m_logPlayback;
bool m_isConnected; bool m_isConnected;
btScalar m_physicsDeltaTime; btScalar m_physicsDeltaTime;
btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks; btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks;
@@ -217,8 +337,8 @@ struct PhysicsServerInternalData
btMultiBodyConstraintSolver* m_solver; btMultiBodyConstraintSolver* m_solver;
btDefaultCollisionConfiguration* m_collisionConfiguration; btDefaultCollisionConfiguration* m_collisionConfiguration;
btMultiBodyDynamicsWorld* m_dynamicsWorld; btMultiBodyDynamicsWorld* m_dynamicsWorld;
SharedMemoryDebugDrawer* m_debugDrawer; SharedMemoryDebugDrawer* m_remoteDebugDrawer;
@@ -240,10 +360,12 @@ struct PhysicsServerInternalData
PhysicsServerInternalData() PhysicsServerInternalData()
:m_sharedMemory(0), :m_sharedMemory(0),
m_testBlock1(0), m_testBlock1(0),
m_commandLogger(0),
m_logPlayback(0),
m_isConnected(false), m_isConnected(false),
m_physicsDeltaTime(1./240.), m_physicsDeltaTime(1./240.),
m_dynamicsWorld(0), m_dynamicsWorld(0),
m_debugDrawer(0), m_remoteDebugDrawer(0),
m_guiHelper(0), m_guiHelper(0),
m_sharedMemoryKey(SHARED_MEMORY_KEY), m_sharedMemoryKey(SHARED_MEMORY_KEY),
m_verboseOutput(false), m_verboseOutput(false),
@@ -332,6 +454,12 @@ PhysicsServerSharedMemory::PhysicsServerSharedMemory()
PhysicsServerSharedMemory::~PhysicsServerSharedMemory() PhysicsServerSharedMemory::~PhysicsServerSharedMemory()
{ {
deleteDynamicsWorld(); deleteDynamicsWorld();
if (m_data->m_commandLogger)
{
delete m_data->m_commandLogger;
m_data->m_commandLogger = 0;
}
delete m_data; delete m_data;
} }
@@ -356,8 +484,8 @@ void PhysicsServerSharedMemory::createEmptyDynamicsWorld()
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
m_data->m_debugDrawer = new SharedMemoryDebugDrawer(); m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
m_data->m_dynamicsWorld->setDebugDrawer(m_data->m_debugDrawer);
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
} }
@@ -424,8 +552,8 @@ void PhysicsServerSharedMemory::deleteDynamicsWorld()
delete m_data->m_dynamicsWorld; delete m_data->m_dynamicsWorld;
m_data->m_dynamicsWorld=0; m_data->m_dynamicsWorld=0;
delete m_data->m_debugDrawer; delete m_data->m_remoteDebugDrawer;
m_data->m_debugDrawer=0; m_data->m_remoteDebugDrawer =0;
delete m_data->m_solver; delete m_data->m_solver;
m_data->m_solver=0; m_data->m_solver=0;
@@ -445,8 +573,13 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface*
{ {
m_data->m_guiHelper = guiHelper; m_data->m_guiHelper = guiHelper;
if (m_data->m_guiHelper)
{
m_data->m_guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
}
bool allowCreation = true; bool allowCreation = true;
bool allowConnectToExistingSharedMemory = false;
if (m_data->m_isConnected) if (m_data->m_isConnected)
{ {
@@ -455,41 +588,58 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface*
} }
m_data->m_testBlock1 = (SharedMemoryBlock*)m_data->m_sharedMemory->allocateSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE,allowCreation); int counter = 0;
if (m_data->m_testBlock1) do
{ {
int magicId =m_data->m_testBlock1->m_magicId;
if (m_data->m_verboseOutput) m_data->m_testBlock1 = (SharedMemoryBlock*)m_data->m_sharedMemory->allocateSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE,allowCreation);
if (m_data->m_testBlock1)
{ {
b3Printf("magicId = %d\n", magicId); int magicId =m_data->m_testBlock1->m_magicId;
}
if (m_data->m_testBlock1->m_magicId !=SHARED_MEMORY_MAGIC_NUMBER)
{
InitSharedMemoryBlock(m_data->m_testBlock1);
if (m_data->m_verboseOutput) if (m_data->m_verboseOutput)
{ {
b3Printf("Created and initialized shared memory block\n"); b3Printf("magicId = %d\n", magicId);
} }
m_data->m_isConnected = true;
} else if (m_data->m_testBlock1->m_magicId !=SHARED_MEMORY_MAGIC_NUMBER)
{
InitSharedMemoryBlock(m_data->m_testBlock1);
if (m_data->m_verboseOutput)
{
b3Printf("Created and initialized shared memory block\n");
}
m_data->m_isConnected = true;
} else
{
m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE);
m_data->m_testBlock1 = 0;
m_data->m_isConnected = false;
}
} else
{ {
b3Error("Server cannot connect to existing shared memory, disconnecting shared memory.\n"); b3Error("Cannot connect to shared memory");
m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey, SHARED_MEMORY_SIZE); m_data->m_isConnected = false;
m_data->m_testBlock1 = 0;
m_data->m_isConnected = false;
} }
} else } while (counter++ < 10 && !m_data->m_isConnected);
if (!m_data->m_isConnected)
{ {
b3Error("Cannot connect to shared memory"); b3Error("Server cannot connect to shared memory.\n");
m_data->m_isConnected = false;
} }
return m_data->m_isConnected; return m_data->m_isConnected;
} }
void PhysicsServerSharedMemory::disconnectSharedMemory(bool deInitializeSharedMemory) void PhysicsServerSharedMemory::disconnectSharedMemory(bool deInitializeSharedMemory)
{ {
if (m_data->m_guiHelper)
{
if (m_data->m_guiHelper && m_data->m_dynamicsWorld && m_data->m_dynamicsWorld->getDebugDrawer())
{
m_data->m_dynamicsWorld->setDebugDrawer(0);
}
}
if (m_data->m_verboseOutput) if (m_data->m_verboseOutput)
{ {
b3Printf("releaseSharedMemory1\n"); b3Printf("releaseSharedMemory1\n");
@@ -708,15 +858,35 @@ void PhysicsServerSharedMemory::processClientCommands()
{ {
if (m_data->m_isConnected && m_data->m_testBlock1) if (m_data->m_isConnected && m_data->m_testBlock1)
{ {
if (m_data->m_logPlayback)
{
if (m_data->m_testBlock1->m_numServerCommands>m_data->m_testBlock1->m_numProcessedServerCommands)
{
m_data->m_testBlock1->m_numProcessedServerCommands++;
}
//push a command from log file
bool hasCommand = m_data->m_logPlayback->processNextCommand(&m_data->m_testBlock1->m_clientCommands[0]);
if (hasCommand)
{
m_data->m_testBlock1->m_numClientCommands++;
}
}
///we ignore overflow of integer for now ///we ignore overflow of integer for now
if (m_data->m_testBlock1->m_numClientCommands> m_data->m_testBlock1->m_numProcessedClientCommands) if (m_data->m_testBlock1->m_numClientCommands> m_data->m_testBlock1->m_numProcessedClientCommands)
{ {
//until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands
btAssert(m_data->m_testBlock1->m_numClientCommands==m_data->m_testBlock1->m_numProcessedClientCommands+1); btAssert(m_data->m_testBlock1->m_numClientCommands==m_data->m_testBlock1->m_numProcessedClientCommands+1);
const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0]; const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0];
if (m_data->m_commandLogger)
{
m_data->m_commandLogger->logCommand(m_data->m_testBlock1);
}
m_data->m_testBlock1->m_numProcessedClientCommands++; m_data->m_testBlock1->m_numProcessedClientCommands++;
//no timestamp yet //no timestamp yet
int timeStamp = 0; int timeStamp = 0;
@@ -749,7 +919,7 @@ void PhysicsServerSharedMemory::processClientCommands()
} }
case CMD_REQUEST_DEBUG_LINES: case CMD_REQUEST_DEBUG_LINES:
{ {
int curFlags =m_data->m_debugDrawer->getDebugMode(); int curFlags =m_data->m_remoteDebugDrawer->getDebugMode();
int debugMode = clientCmd.m_requestDebugLinesArguments.m_debugMode;//clientCmd.btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb; int debugMode = clientCmd.m_requestDebugLinesArguments.m_debugMode;//clientCmd.btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb;
int startingLineIndex = clientCmd.m_requestDebugLinesArguments.m_startingLineIndex; int startingLineIndex = clientCmd.m_requestDebugLinesArguments.m_startingLineIndex;
@@ -761,23 +931,26 @@ void PhysicsServerSharedMemory::processClientCommands()
if (clientCmd.m_requestDebugLinesArguments.m_startingLineIndex==0) if (clientCmd.m_requestDebugLinesArguments.m_startingLineIndex==0)
{ {
m_data->m_debugDrawer->m_lines2.resize(0); m_data->m_remoteDebugDrawer->m_lines2.resize(0);
//|btIDebugDraw::DBG_DrawAabb| //|btIDebugDraw::DBG_DrawAabb|
// btIDebugDraw::DBG_DrawConstraints |btIDebugDraw::DBG_DrawConstraintLimits ; // btIDebugDraw::DBG_DrawConstraints |btIDebugDraw::DBG_DrawConstraintLimits ;
m_data->m_debugDrawer->setDebugMode(debugMode); m_data->m_remoteDebugDrawer->setDebugMode(debugMode);
btIDebugDraw* oldDebugDrawer = m_data->m_dynamicsWorld->getDebugDrawer();
m_data->m_dynamicsWorld->setDebugDrawer(m_data->m_remoteDebugDrawer);
m_data->m_dynamicsWorld->debugDrawWorld(); m_data->m_dynamicsWorld->debugDrawWorld();
m_data->m_debugDrawer->setDebugMode(curFlags); m_data->m_dynamicsWorld->setDebugDrawer(oldDebugDrawer);
m_data->m_remoteDebugDrawer->setDebugMode(curFlags);
} }
//9 floats per line: 3 floats for 'from', 3 floats for 'to' and 3 floats for 'color' //9 floats per line: 3 floats for 'from', 3 floats for 'to' and 3 floats for 'color'
int maxNumLines = SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE/(sizeof(float)*9)-1; int maxNumLines = SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE/(sizeof(float)*9)-1;
if (startingLineIndex >m_data->m_debugDrawer->m_lines2.size()) if (startingLineIndex >m_data->m_remoteDebugDrawer->m_lines2.size())
{ {
b3Warning("m_startingLineIndex exceeds total number of debug lines"); b3Warning("m_startingLineIndex exceeds total number of debug lines");
startingLineIndex =m_data->m_debugDrawer->m_lines2.size(); startingLineIndex =m_data->m_remoteDebugDrawer->m_lines2.size();
} }
int numLines = btMin(maxNumLines,m_data->m_debugDrawer->m_lines2.size()-startingLineIndex); int numLines = btMin(maxNumLines,m_data->m_remoteDebugDrawer->m_lines2.size()-startingLineIndex);
if (numLines) if (numLines)
{ {
@@ -788,24 +961,24 @@ void PhysicsServerSharedMemory::processClientCommands()
for (int i=0;i<numLines;i++) for (int i=0;i<numLines;i++)
{ {
linesFrom[i*3] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_from.x(); linesFrom[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.x();
linesTo[i*3] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_to.x(); linesTo[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.x();
linesColor[i*3] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_color.x(); linesColor[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.x();
linesFrom[i*3+1] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_from.y(); linesFrom[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.y();
linesTo[i*3+1] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_to.y(); linesTo[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.y();
linesColor[i*3+1] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_color.y(); linesColor[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.y();
linesFrom[i*3+2] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_from.z(); linesFrom[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.z();
linesTo[i*3+2] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_to.z(); linesTo[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.z();
linesColor[i*3+2] = m_data->m_debugDrawer->m_lines2[i+startingLineIndex].m_color.z(); linesColor[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.z();
} }
} }
SharedMemoryStatus& status = m_data->createServerStatus(CMD_DEBUG_LINES_COMPLETED,clientCmd.m_sequenceNumber,timeStamp); SharedMemoryStatus& status = m_data->createServerStatus(CMD_DEBUG_LINES_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
status.m_sendDebugLinesArgs.m_numDebugLines = numLines; status.m_sendDebugLinesArgs.m_numDebugLines = numLines;
status.m_sendDebugLinesArgs.m_startingLineIndex = startingLineIndex; status.m_sendDebugLinesArgs.m_startingLineIndex = startingLineIndex;
status.m_sendDebugLinesArgs.m_numRemainingDebugLines = m_data->m_debugDrawer->m_lines2.size()-(startingLineIndex+numLines); status.m_sendDebugLinesArgs.m_numRemainingDebugLines = m_data->m_remoteDebugDrawer->m_lines2.size()-(startingLineIndex+numLines);
m_data->submitServerStatus(status); m_data->submitServerStatus(status);
break; break;
@@ -1533,17 +1706,14 @@ void PhysicsServerSharedMemory::renderScene()
void PhysicsServerSharedMemory::physicsDebugDraw(int debugDrawFlags) void PhysicsServerSharedMemory::physicsDebugDraw(int debugDrawFlags)
{ {
#if 0
if (m_data->m_dynamicsWorld) if (m_data->m_dynamicsWorld)
{ {
if (m_data->m_dynamicsWorld->getDebugDrawer()) if (m_data->m_dynamicsWorld->getDebugDrawer())
{ {
//m_data->m_debugDrawer->m_lines.clear(); m_data->m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugDrawFlags);
//m_data->m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugDrawFlags); m_data->m_dynamicsWorld->debugDrawWorld();
} }
m_data->m_dynamicsWorld->debugDrawWorld();
} }
#endif
} }
@@ -1665,3 +1835,27 @@ void PhysicsServerSharedMemory::removePickingConstraint()
m_data->m_pickingMultiBodyPoint2Point = 0; m_data->m_pickingMultiBodyPoint2Point = 0;
} }
} }
void PhysicsServerSharedMemory::enableCommandLogging(bool enable, const char* fileName)
{
if (enable)
{
if (0==m_data->m_commandLogger)
{
m_data->m_commandLogger = new CommandLogger(fileName);
}
} else
{
if (0!=m_data->m_commandLogger)
{
delete m_data->m_commandLogger;
m_data->m_commandLogger = 0;
}
}
}
void PhysicsServerSharedMemory::replayFromLogFile(const char* fileName)
{
CommandLogPlayback* pb = new CommandLogPlayback(fileName);
m_data->m_logPlayback = pb;
}

View File

@@ -54,6 +54,10 @@ public:
void physicsDebugDraw(int debugDrawFlags); void physicsDebugDraw(int debugDrawFlags);
void renderScene(); void renderScene();
void enableCommandLogging(bool enable, const char* fileName);
void replayFromLogFile(const char* fileName);
}; };

View File

@@ -29,7 +29,17 @@ public:
virtual void stepSimulation(float deltaTime); virtual void stepSimulation(float deltaTime);
void enableCommandLogging()
{
m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
}
void replayFromLogFile()
{
m_physicsServer.replayFromLogFile("BulletPhysicsCommandLog.bin");
}
virtual void resetCamera() virtual void resetCamera()
{ {
@@ -190,18 +200,7 @@ void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
} }
extern int gSharedMemoryKey;
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
{
PhysicsServerExample* example = new PhysicsServerExample(options.m_guiHelper);
if (gSharedMemoryKey>=0)
{
example->setSharedMemoryKey(gSharedMemoryKey);
}
return example;
}
btVector3 PhysicsServerExample::getRayTo(int x,int y) btVector3 PhysicsServerExample::getRayTo(int x,int y)
{ {
@@ -267,3 +266,24 @@ btVector3 PhysicsServerExample::getRayTo(int x,int y)
return rayTo; return rayTo;
} }
extern int gSharedMemoryKey;
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
{
PhysicsServerExample* example = new PhysicsServerExample(options.m_guiHelper);
if (gSharedMemoryKey>=0)
{
example->setSharedMemoryKey(gSharedMemoryKey);
}
if (options.m_option & PHYSICS_SERVER_ENABLE_COMMAND_LOGGING)
{
example->enableCommandLogging();
}
if (options.m_option & PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG)
{
example->replayFromLogFile();
}
return example;
}

View File

@@ -1,6 +1,11 @@
#ifndef PHYSICS_SERVER_EXAMPLE_H #ifndef PHYSICS_SERVER_EXAMPLE_H
#define PHYSICS_SERVER_EXAMPLE_H #define PHYSICS_SERVER_EXAMPLE_H
enum PhysicsServerOptions
{
PHYSICS_SERVER_ENABLE_COMMAND_LOGGING=1,
PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG=2,
};
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options); class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options);

View File

@@ -2,7 +2,7 @@
#define SHARED_MEMORY_BLOCK_H #define SHARED_MEMORY_BLOCK_H
#define SHARED_MEMORY_MAGIC_NUMBER 64738 #define SHARED_MEMORY_MAGIC_NUMBER 64738
#define SHARED_MEMORY_MAX_COMMANDS 32 #define SHARED_MEMORY_MAX_COMMANDS 4
#define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (256*1024) #define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (256*1024)
#include "SharedMemoryCommands.h" #include "SharedMemoryCommands.h"

View File

@@ -26,7 +26,7 @@
#define SHARED_MEMORY_SERVER_TEST_C #define SHARED_MEMORY_SERVER_TEST_C
#define MAX_DEGREE_OF_FREEDOM 256 #define MAX_DEGREE_OF_FREEDOM 64
#define MAX_NUM_SENSORS 256 #define MAX_NUM_SENSORS 256
#define MAX_URDF_FILENAME_LENGTH 1024 #define MAX_URDF_FILENAME_LENGTH 1024
#define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH

View File

@@ -49,10 +49,10 @@ project ("Test_PhysicsLoopBack")
"../../examples/SharedMemory/PhysicsClient.h", "../../examples/SharedMemory/PhysicsClient.h",
"../../examples/SharedMemory/PhysicsServer.cpp", "../../examples/SharedMemory/PhysicsServer.cpp",
"../../examples/SharedMemory/PhysicsServer.h", "../../examples/SharedMemory/PhysicsServer.h",
"../../examples/SharedMemory/PhysicsLoopback.cpp", "../../examples/SharedMemory/PhysicsLoopBack.cpp",
"../../examples/SharedMemory/PhysicsLoopback.h", "../../examples/SharedMemory/PhysicsLoopBack.h",
"../../examples/SharedMemory/PhysicsLoopbackC_Api.cpp", "../../examples/SharedMemory/PhysicsLoopBackC_Api.cpp",
"../../examples/SharedMemory/PhysicsLoopbackC_Api.h", "../../examples/SharedMemory/PhysicsLoopBackC_Api.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp", "../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h", "../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientC_API.cpp", "../../examples/SharedMemory/PhysicsClientC_API.cpp",
@@ -78,4 +78,4 @@ project ("Test_PhysicsLoopBack")
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
"../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp", "../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp",
} }

View File

@@ -2,7 +2,7 @@
#include "PhysicsClientC_API.h" #include "PhysicsClientC_API.h"
#ifdef PHYSICS_LOOP_BACK #ifdef PHYSICS_LOOP_BACK
#include "PhysicsLoopbackC_API.h" #include "PhysicsLoopBackC_API.h"
#endif //PHYSICS_LOOP_BACK #endif //PHYSICS_LOOP_BACK
#include "SharedMemoryPublic.h" #include "SharedMemoryPublic.h"