minor refactoring
This commit is contained in:
@@ -15,6 +15,7 @@ SET(App_ExampleBrowser_SRCS
|
|||||||
main.cpp
|
main.cpp
|
||||||
ExampleEntries.cpp
|
ExampleEntries.cpp
|
||||||
ExampleEntries.h
|
ExampleEntries.h
|
||||||
|
../SharedMemory/PhysicsClientC_API.cpp
|
||||||
../SharedMemory/PhysicsServer.cpp
|
../SharedMemory/PhysicsServer.cpp
|
||||||
../SharedMemory/PhysicsClient.cpp
|
../SharedMemory/PhysicsClient.cpp
|
||||||
../SharedMemory/PhysicsServerExample.cpp
|
../SharedMemory/PhysicsServerExample.cpp
|
||||||
|
|||||||
@@ -50,6 +50,7 @@
|
|||||||
files {
|
files {
|
||||||
"**.cpp",
|
"**.cpp",
|
||||||
"**.h",
|
"**.h",
|
||||||
|
"../SharedMemory/PhysicsClientC_API.cpp",
|
||||||
"../SharedMemory/PhysicsServerExample.cpp",
|
"../SharedMemory/PhysicsServerExample.cpp",
|
||||||
"../SharedMemory/PhysicsClientExample.cpp",
|
"../SharedMemory/PhysicsClientExample.cpp",
|
||||||
"../SharedMemory/RobotControlExample.cpp",
|
"../SharedMemory/RobotControlExample.cpp",
|
||||||
|
|||||||
@@ -6,6 +6,7 @@
|
|||||||
#include "../Utils/b3ResourcePath.h"
|
#include "../Utils/b3ResourcePath.h"
|
||||||
#include "../../Extras/Serialize/BulletFileLoader/btBulletFile.h"
|
#include "../../Extras/Serialize/BulletFileLoader/btBulletFile.h"
|
||||||
#include "../../Extras/Serialize/BulletFileLoader/autogenerated/bullet.h"
|
#include "../../Extras/Serialize/BulletFileLoader/autogenerated/bullet.h"
|
||||||
|
#include "SharedMemoryBlock.h"
|
||||||
|
|
||||||
|
|
||||||
//copied from btMultiBodyLink.h
|
//copied from btMultiBodyLink.h
|
||||||
@@ -18,7 +19,7 @@ enum JointType
|
|||||||
struct PhysicsClientSharedMemoryInternalData
|
struct PhysicsClientSharedMemoryInternalData
|
||||||
{
|
{
|
||||||
SharedMemoryInterface* m_sharedMemory;
|
SharedMemoryInterface* m_sharedMemory;
|
||||||
SharedMemoryExampleData* m_testBlock1;
|
SharedMemoryBlock* m_testBlock1;
|
||||||
|
|
||||||
btAlignedObjectArray<bParse::btBulletFile*> m_robotMultiBodyData;
|
btAlignedObjectArray<bParse::btBulletFile*> m_robotMultiBodyData;
|
||||||
btAlignedObjectArray<PoweredJointInfo> m_poweredJointInfo;
|
btAlignedObjectArray<PoweredJointInfo> m_poweredJointInfo;
|
||||||
@@ -89,7 +90,7 @@ bool PhysicsClientSharedMemory::isConnected() const
|
|||||||
bool PhysicsClientSharedMemory::connect(bool allowSharedMemoryInitialization)
|
bool PhysicsClientSharedMemory::connect(bool allowSharedMemoryInitialization)
|
||||||
{
|
{
|
||||||
bool allowCreation = true;
|
bool allowCreation = true;
|
||||||
m_data->m_testBlock1 = (SharedMemoryExampleData*)m_data->m_sharedMemory->allocateSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE, allowCreation);
|
m_data->m_testBlock1 = (SharedMemoryBlock*)m_data->m_sharedMemory->allocateSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE, allowCreation);
|
||||||
|
|
||||||
if (m_data->m_testBlock1)
|
if (m_data->m_testBlock1)
|
||||||
{
|
{
|
||||||
@@ -97,7 +98,7 @@ bool PhysicsClientSharedMemory::connect(bool allowSharedMemoryInitialization)
|
|||||||
{
|
{
|
||||||
if (allowSharedMemoryInitialization)
|
if (allowSharedMemoryInitialization)
|
||||||
{
|
{
|
||||||
InitSharedMemoryExampleData(m_data->m_testBlock1);
|
InitSharedMemoryBlock(m_data->m_testBlock1);
|
||||||
b3Printf("Created and initialized shared memory block");
|
b3Printf("Created and initialized shared memory block");
|
||||||
m_data->m_isConnected = true;
|
m_data->m_isConnected = true;
|
||||||
} else
|
} else
|
||||||
@@ -123,7 +124,7 @@ bool PhysicsClientSharedMemory::connect(bool allowSharedMemoryInitialization)
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
bool PhysicsClientSharedMemory::processServerStatus(ServerStatus& serverStatus)
|
bool PhysicsClientSharedMemory::processServerStatus(SharedMemoryStatus& serverStatus)
|
||||||
{
|
{
|
||||||
btAssert(m_data->m_testBlock1);
|
btAssert(m_data->m_testBlock1);
|
||||||
bool hasStatus = false;
|
bool hasStatus = false;
|
||||||
|
|||||||
@@ -3,17 +3,6 @@
|
|||||||
|
|
||||||
#include "SharedMemoryCommands.h"
|
#include "SharedMemoryCommands.h"
|
||||||
|
|
||||||
#include <string>
|
|
||||||
|
|
||||||
struct PoweredJointInfo
|
|
||||||
{
|
|
||||||
std::string m_linkName;
|
|
||||||
std::string m_jointName;
|
|
||||||
int m_jointType;
|
|
||||||
int m_qIndex;
|
|
||||||
int m_uIndex;
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
class PhysicsClientSharedMemory //: public CommonPhysicsClientInterface
|
class PhysicsClientSharedMemory //: public CommonPhysicsClientInterface
|
||||||
{
|
{
|
||||||
@@ -31,7 +20,7 @@ public:
|
|||||||
virtual bool isConnected() const;
|
virtual bool isConnected() const;
|
||||||
|
|
||||||
// return true if there is a status, and fill in 'serverStatus'
|
// return true if there is a status, and fill in 'serverStatus'
|
||||||
virtual bool processServerStatus(ServerStatus& serverStatus);
|
virtual bool processServerStatus(SharedMemoryStatus& serverStatus);
|
||||||
|
|
||||||
virtual bool canSubmitCommand() const;
|
virtual bool canSubmitCommand() const;
|
||||||
|
|
||||||
|
|||||||
@@ -211,7 +211,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
|||||||
|
|
||||||
if (m_physicsClient.isConnected())
|
if (m_physicsClient.isConnected())
|
||||||
{
|
{
|
||||||
ServerStatus status;
|
SharedMemoryStatus status;
|
||||||
bool hasStatus = m_physicsClient.processServerStatus(status);
|
bool hasStatus = m_physicsClient.processServerStatus(status);
|
||||||
if (hasStatus && status.m_type == CMD_URDF_LOADING_COMPLETED)
|
if (hasStatus && status.m_type == CMD_URDF_LOADING_COMPLETED)
|
||||||
{
|
{
|
||||||
@@ -219,7 +219,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
|||||||
{
|
{
|
||||||
PoweredJointInfo info;
|
PoweredJointInfo info;
|
||||||
m_physicsClient.getPoweredJointInfo(i,info);
|
m_physicsClient.getPoweredJointInfo(i,info);
|
||||||
b3Printf("1-DOF PoweredJoint %s at q-index %d and u-index %d\n",info.m_jointName.c_str(),info.m_qIndex,info.m_uIndex);
|
b3Printf("1-DOF PoweredJoint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -17,6 +17,7 @@
|
|||||||
#include "LinearMath/btSerializer.h"
|
#include "LinearMath/btSerializer.h"
|
||||||
#include "Bullet3Common/b3Logging.h"
|
#include "Bullet3Common/b3Logging.h"
|
||||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
|
#include "SharedMemoryBlock.h"
|
||||||
|
|
||||||
struct UrdfLinkNameMapUtil
|
struct UrdfLinkNameMapUtil
|
||||||
{
|
{
|
||||||
@@ -31,7 +32,7 @@ struct UrdfLinkNameMapUtil
|
|||||||
struct PhysicsServerInternalData
|
struct PhysicsServerInternalData
|
||||||
{
|
{
|
||||||
SharedMemoryInterface* m_sharedMemory;
|
SharedMemoryInterface* m_sharedMemory;
|
||||||
SharedMemoryExampleData* m_testBlock1;
|
SharedMemoryBlock* m_testBlock1;
|
||||||
bool m_isConnected;
|
bool m_isConnected;
|
||||||
btScalar m_physicsDeltaTime;
|
btScalar m_physicsDeltaTime;
|
||||||
//btAlignedObjectArray<btJointFeedback*> m_jointFeedbacks;
|
//btAlignedObjectArray<btJointFeedback*> m_jointFeedbacks;
|
||||||
@@ -84,14 +85,14 @@ bool PhysicsServerSharedMemory::connectSharedMemory(bool allowSharedMemoryInitia
|
|||||||
|
|
||||||
bool allowCreation = true;
|
bool allowCreation = true;
|
||||||
|
|
||||||
m_data->m_testBlock1 = (SharedMemoryExampleData*)m_data->m_sharedMemory->allocateSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE,allowCreation);
|
m_data->m_testBlock1 = (SharedMemoryBlock*)m_data->m_sharedMemory->allocateSharedMemory(SHARED_MEMORY_KEY, SHARED_MEMORY_SIZE,allowCreation);
|
||||||
if (m_data->m_testBlock1)
|
if (m_data->m_testBlock1)
|
||||||
{
|
{
|
||||||
if (m_data->m_testBlock1->m_magicId !=SHARED_MEMORY_MAGIC_NUMBER)
|
if (m_data->m_testBlock1->m_magicId !=SHARED_MEMORY_MAGIC_NUMBER)
|
||||||
{
|
{
|
||||||
if (allowSharedMemoryInitialization)
|
if (allowSharedMemoryInitialization)
|
||||||
{
|
{
|
||||||
InitSharedMemoryExampleData(m_data->m_testBlock1);
|
InitSharedMemoryBlock(m_data->m_testBlock1);
|
||||||
b3Printf("Created and initialized shared memory block");
|
b3Printf("Created and initialized shared memory block");
|
||||||
m_data->m_isConnected = true;
|
m_data->m_isConnected = true;
|
||||||
} else
|
} else
|
||||||
@@ -212,7 +213,7 @@ bool PhysicsServerSharedMemory::loadUrdf(const char* fileName, const btVector3&
|
|||||||
tr.setIdentity();
|
tr.setIdentity();
|
||||||
tr.setOrigin(pos);
|
tr.setOrigin(pos);
|
||||||
tr.setRotation(orn);
|
tr.setRotation(orn);
|
||||||
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_data->m_guiHelper);
|
MyMultiBodyCreator creation(m_data->m_guiHelper);
|
||||||
|
|
||||||
|
|||||||
@@ -57,7 +57,6 @@ PhysicsServerExample::PhysicsServerExample(GUIHelperInterface* helper)
|
|||||||
m_wantsShutdown(false)
|
m_wantsShutdown(false)
|
||||||
{
|
{
|
||||||
b3Printf("Started PhysicsServer\n");
|
b3Printf("Started PhysicsServer\n");
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -10,6 +10,7 @@
|
|||||||
#include "PhysicsClient.h"
|
#include "PhysicsClient.h"
|
||||||
#include "SharedMemoryCommon.h"
|
#include "SharedMemoryCommon.h"
|
||||||
#include "../Utils/b3Clock.h"
|
#include "../Utils/b3Clock.h"
|
||||||
|
#include "PhysicsClientC_API.h"
|
||||||
|
|
||||||
//const char* blaatnaam = "basename";
|
//const char* blaatnaam = "basename";
|
||||||
|
|
||||||
@@ -100,11 +101,20 @@ void MyCallback2(int buttonId, bool buttonState, void* userPtr)
|
|||||||
|
|
||||||
case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
|
case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
|
||||||
{
|
{
|
||||||
command.m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
|
//#ifdef USE_C_API
|
||||||
command.m_physSimParamArgs.m_gravityAcceleration[0] = 0;
|
b3InitPhysicsParamCommand(&command);
|
||||||
command.m_physSimParamArgs.m_gravityAcceleration[1] = 0;
|
b3PhysicsParamSetGravity(&command, 0,0,-10);
|
||||||
command.m_physSimParamArgs.m_gravityAcceleration[2] = -10;
|
|
||||||
command.m_updateFlags = SIM_PARAM_UPDATE_GRAVITY;
|
|
||||||
|
// #else
|
||||||
|
//
|
||||||
|
// command.m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
|
||||||
|
// command.m_physSimParamArgs.m_gravityAcceleration[0] = 0;
|
||||||
|
// command.m_physSimParamArgs.m_gravityAcceleration[1] = 0;
|
||||||
|
// command.m_physSimParamArgs.m_gravityAcceleration[2] = -10;
|
||||||
|
// command.m_physSimParamArgs.m_updateFlags = SIM_PARAM_UPDATE_GRAVITY;
|
||||||
|
// #endif // USE_C_API
|
||||||
|
|
||||||
cl->enqueueCommand(command);
|
cl->enqueueCommand(command);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@@ -286,7 +296,7 @@ void RobotControlExample::stepSimulation(float deltaTime)
|
|||||||
if (m_physicsClient.isConnected())
|
if (m_physicsClient.isConnected())
|
||||||
{
|
{
|
||||||
|
|
||||||
ServerStatus status;
|
SharedMemoryStatus status;
|
||||||
bool hasStatus = m_physicsClient.processServerStatus(status);
|
bool hasStatus = m_physicsClient.processServerStatus(status);
|
||||||
if (hasStatus && status.m_type == CMD_URDF_LOADING_COMPLETED)
|
if (hasStatus && status.m_type == CMD_URDF_LOADING_COMPLETED)
|
||||||
{
|
{
|
||||||
@@ -294,12 +304,12 @@ void RobotControlExample::stepSimulation(float deltaTime)
|
|||||||
{
|
{
|
||||||
PoweredJointInfo info;
|
PoweredJointInfo info;
|
||||||
m_physicsClient.getPoweredJointInfo(i,info);
|
m_physicsClient.getPoweredJointInfo(i,info);
|
||||||
b3Printf("1-DOF PoweredJoint %s at q-index %d and u-index %d\n",info.m_jointName.c_str(),info.m_qIndex,info.m_uIndex);
|
b3Printf("1-DOF PoweredJoint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
|
||||||
|
|
||||||
if (m_numMotors<MAX_NUM_MOTORS)
|
if (m_numMotors<MAX_NUM_MOTORS)
|
||||||
{
|
{
|
||||||
char motorName[1024];
|
char motorName[1024];
|
||||||
sprintf(motorName,"%s q'", info.m_jointName.c_str());
|
sprintf(motorName,"%s q'", info.m_jointName);
|
||||||
MyMotorInfo* motorInfo = &m_motorTargetVelocities[m_numMotors];
|
MyMotorInfo* motorInfo = &m_motorTargetVelocities[m_numMotors];
|
||||||
motorInfo->m_velTarget = 0.f;
|
motorInfo->m_velTarget = 0.f;
|
||||||
motorInfo->m_uIndex = info.m_uIndex;
|
motorInfo->m_uIndex = info.m_uIndex;
|
||||||
|
|||||||
@@ -63,11 +63,11 @@ enum EnumSharedMemoryServerStatus
|
|||||||
|
|
||||||
struct UrdfArgs
|
struct UrdfArgs
|
||||||
{
|
{
|
||||||
char m_urdfFileName[MAX_URDF_FILENAME_LENGTH];
|
char m_urdfFileName[MAX_URDF_FILENAME_LENGTH];
|
||||||
double m_initialPosition[3];
|
double m_initialPosition[3];
|
||||||
double m_initialOrientation[4];
|
double m_initialOrientation[4];
|
||||||
bool m_useMultiBody;
|
int m_useMultiBody;
|
||||||
bool m_useFixedBase;
|
int m_useFixedBase;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
@@ -81,7 +81,7 @@ struct SetJointFeedbackArgs
|
|||||||
{
|
{
|
||||||
int m_bodyUniqueId;
|
int m_bodyUniqueId;
|
||||||
int m_linkId;
|
int m_linkId;
|
||||||
bool m_isEnabled;
|
int m_isEnabled;
|
||||||
};
|
};
|
||||||
|
|
||||||
//todo: discuss and decide about control mode and combinations
|
//todo: discuss and decide about control mode and combinations
|
||||||
@@ -132,7 +132,6 @@ enum EnumUpdateFlags
|
|||||||
///The control mode determines the state variables used for motor control.
|
///The control mode determines the state variables used for motor control.
|
||||||
struct SendPhysicsSimulationParameters
|
struct SendPhysicsSimulationParameters
|
||||||
{
|
{
|
||||||
|
|
||||||
double m_deltaTime;
|
double m_deltaTime;
|
||||||
double m_gravityAcceleration[3];
|
double m_gravityAcceleration[3];
|
||||||
int m_numSimulationSubSteps;
|
int m_numSimulationSubSteps;
|
||||||
@@ -161,25 +160,26 @@ struct SendActualStateArgs
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct SharedMemoryCommand SharedMemoryCommand_t;
|
||||||
|
|
||||||
|
|
||||||
struct SharedMemoryCommand
|
struct SharedMemoryCommand
|
||||||
{
|
{
|
||||||
int m_type;
|
int m_type;
|
||||||
|
smUint64_t m_timeStamp;
|
||||||
int m_sequenceNumber;
|
int m_sequenceNumber;
|
||||||
smUint64_t m_timeStamp;
|
//a bit fields to tell which parameters need updating
|
||||||
//a bit fields to tell which parameters need updating
|
//for example m_updateFlags = SIM_PARAM_UPDATE_DELTA_TIME | SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
|
||||||
//for example m_updateFlags = SIM_PARAM_UPDATE_DELTA_TIME | SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
|
int m_updateFlags;
|
||||||
smUint64_t m_updateFlags;
|
|
||||||
|
|
||||||
union
|
union
|
||||||
{
|
{
|
||||||
UrdfArgs m_urdfArguments;
|
struct UrdfArgs m_urdfArguments;
|
||||||
InitPoseArgs m_initPoseArgs;
|
struct InitPoseArgs m_initPoseArgs;
|
||||||
SendPhysicsSimulationParameters m_physSimParamArgs;
|
struct SendPhysicsSimulationParameters m_physSimParamArgs;
|
||||||
BulletDataStreamArgs m_dataStreamArguments;
|
struct BulletDataStreamArgs m_dataStreamArguments;
|
||||||
SendDesiredStateArgs m_sendDesiredStateCommandArgument;
|
struct SendDesiredStateArgs m_sendDesiredStateCommandArgument;
|
||||||
RequestActualStateArgs m_requestActualStateInformationCommandArgument;
|
struct RequestActualStateArgs m_requestActualStateInformationCommandArgument;
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -193,11 +193,20 @@ struct SharedMemoryStatus
|
|||||||
|
|
||||||
union
|
union
|
||||||
{
|
{
|
||||||
BulletDataStreamArgs m_dataStreamArguments;
|
struct BulletDataStreamArgs m_dataStreamArguments;
|
||||||
SendActualStateArgs m_sendActualStateArgs;
|
struct SendActualStateArgs m_sendActualStateArgs;
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef SharedMemoryStatus ServerStatus;
|
struct PoweredJointInfo
|
||||||
|
{
|
||||||
|
char* m_linkName;
|
||||||
|
char* m_jointName;
|
||||||
|
int m_jointType;
|
||||||
|
int m_qIndex;
|
||||||
|
int m_uIndex;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif //SHARED_MEMORY_COMMANDS_H
|
#endif //SHARED_MEMORY_COMMANDS_H
|
||||||
|
|||||||
@@ -1,49 +1,6 @@
|
|||||||
#ifndef SHARED_MEMORY_INTERFACE_H
|
#ifndef SHARED_MEMORY_INTERFACE_H
|
||||||
#define SHARED_MEMORY_INTERFACE_H
|
#define SHARED_MEMORY_INTERFACE_H
|
||||||
|
|
||||||
#define SHARED_MEMORY_KEY 12347
|
|
||||||
#define SHARED_MEMORY_MAGIC_NUMBER 64738
|
|
||||||
#define SHARED_MEMORY_MAX_COMMANDS 32
|
|
||||||
#define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (256*1024)
|
|
||||||
|
|
||||||
#include "SharedMemoryCommands.h"
|
|
||||||
|
|
||||||
struct SharedMemoryExampleData
|
|
||||||
{
|
|
||||||
int m_magicId;
|
|
||||||
SharedMemoryCommand m_clientCommands[SHARED_MEMORY_MAX_COMMANDS];
|
|
||||||
SharedMemoryStatus m_serverCommands[SHARED_MEMORY_MAX_COMMANDS];
|
|
||||||
|
|
||||||
int m_numClientCommands;
|
|
||||||
int m_numProcessedClientCommands;
|
|
||||||
|
|
||||||
int m_numServerCommands;
|
|
||||||
int m_numProcessedServerCommands;
|
|
||||||
|
|
||||||
//m_bulletStreamDataClientToServer is a way for the client to create collision shapes, rigid bodies and constraints
|
|
||||||
//the Bullet data structures are more general purpose than the capabilities of a URDF file.
|
|
||||||
char m_bulletStreamDataClientToServer[SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE];
|
|
||||||
|
|
||||||
//m_bulletStreamDataServerToClient is used to send (debug) data from server to client, for
|
|
||||||
//example to provide all details of a multibody including joint/link names, after loading a URDF file.
|
|
||||||
char m_bulletStreamDataServerToClient[SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE];
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
inline void InitSharedMemoryExampleData(SharedMemoryExampleData* sharedMemoryBlock)
|
|
||||||
{
|
|
||||||
sharedMemoryBlock->m_numClientCommands = 0;
|
|
||||||
sharedMemoryBlock->m_numServerCommands = 0;
|
|
||||||
sharedMemoryBlock->m_numProcessedClientCommands=0;
|
|
||||||
sharedMemoryBlock->m_numProcessedServerCommands=0;
|
|
||||||
sharedMemoryBlock->m_magicId = SHARED_MEMORY_MAGIC_NUMBER;
|
|
||||||
}
|
|
||||||
|
|
||||||
#define SHARED_MEMORY_SIZE sizeof(SharedMemoryExampleData)
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
class SharedMemoryInterface
|
class SharedMemoryInterface
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@@ -54,5 +11,6 @@ class SharedMemoryInterface
|
|||||||
virtual void* allocateSharedMemory(int key, int size, bool allowCreation) =0;
|
virtual void* allocateSharedMemory(int key, int size, bool allowCreation) =0;
|
||||||
virtual void releaseSharedMemory(int key, int size) =0;
|
virtual void releaseSharedMemory(int key, int size) =0;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|||||||
@@ -27,7 +27,6 @@ int main(int argc, char* argv[])
|
|||||||
{
|
{
|
||||||
|
|
||||||
b3CommandLineArgs args(argc, argv);
|
b3CommandLineArgs args(argc, argv);
|
||||||
struct PhysicsInterface* pint = 0;
|
|
||||||
|
|
||||||
DummyGUIHelper noGfx;
|
DummyGUIHelper noGfx;
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user