some work towards streaming Bullet data over shared memory for client/server

This commit is contained in:
erwincoumans
2015-07-09 14:04:58 -07:00
parent 7f4beba7ee
commit 285ac286fa
10 changed files with 179 additions and 79 deletions

View File

@@ -75,7 +75,7 @@ public:
void RollingFrictionDemo::initPhysics()
{
m_guiHelper->setUpAxis(1);
m_guiHelper->setUpAxis(2);
///collision configuration contains default setup for memory, collision setup
@@ -93,23 +93,22 @@ void RollingFrictionDemo::initPhysics()
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
// m_dynamicsWorld->getSolverInfo().m_singleAxisRollingFrictionThreshold = 0.f;//faster but lower quality
m_dynamicsWorld->setGravity(btVector3(0,-10,0));
m_dynamicsWorld->setGravity(btVector3(0,0,-10));
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
{
///create a few basic rigid bodies
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(20.),btScalar(50.),btScalar(10.)));
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(10.),btScalar(5.),btScalar(25.)));
// btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0,-50,0));
groundTransform.setRotation(btQuaternion(btVector3(0,0,1),SIMD_PI*0.03));
groundTransform.setOrigin(btVector3(0,0,-28));
groundTransform.setRotation(btQuaternion(btVector3(0,1,0),SIMD_PI*0.03));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
@@ -133,13 +132,13 @@ void RollingFrictionDemo::initPhysics()
{
///create a few basic rigid bodies
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(100.),btScalar(50.),btScalar(100.)));
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(100.),btScalar(100.),btScalar(50.)));
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0,-54,0));
groundTransform.setOrigin(btVector3(0,0,-54));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
btScalar mass(0.);
@@ -165,16 +164,16 @@ void RollingFrictionDemo::initPhysics()
// Re-using the same collision is better for memory usage and performance
#define NUM_SHAPES 10
btCollisionShape* colShapes[NUM_SHAPES] = {
new btSphereShape(btScalar(1.)),
new btCapsuleShape(0.5,1),
new btCapsuleShapeX(0.5,1),
new btCapsuleShapeZ(0.5,1),
new btConeShape(0.5,1),
new btConeShapeX(0.5,1),
new btConeShapeZ(0.5,1),
new btCylinderShape(btVector3(0.5,1,0.5)),
new btCylinderShapeX(btVector3(1,0.5,0.5)),
new btCylinderShapeZ(btVector3(0.5,0.5,1)),
new btSphereShape(btScalar(0.5)),
new btCapsuleShape(0.25,0.5),
new btCapsuleShapeX(0.25,0.5),
new btCapsuleShapeZ(0.25,0.5),
new btConeShape(0.25,0.5),
new btConeShapeX(0.25,0.5),
new btConeShapeZ(0.25,0.5),
new btCylinderShape(btVector3(0.25,0.5,0.25)),
new btCylinderShapeX(btVector3(0.5,0.25,0.25)),
new btCylinderShapeZ(btVector3(0.25,0.25,0.5)),
};
for (int i=0;i<NUM_SHAPES;i++)
m_collisionShapes.push_back(colShapes[i]);
@@ -200,9 +199,9 @@ void RollingFrictionDemo::initPhysics()
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
startTransform.setOrigin(SCALING*btVector3(
btScalar(2.0*i + start_x),
btScalar(20+2.0*k + start_y),
btScalar(2.0*j + start_z)));
btScalar(2.0*i + start_x)+25,
btScalar(2.0*j + start_z),
btScalar(20+2.0*k + start_y)));
shapeIndex++;
@@ -230,7 +229,11 @@ void RollingFrictionDemo::initPhysics()
}
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
btSerializer* s = new btDefaultSerializer;
m_dynamicsWorld->serialize(s);
FILE* f = fopen("slope.bullet","wb");
fwrite(s->getBufferPointer(),s->getCurrentBufferSize(),1,f);
fclose(f);
}

View File

@@ -6,7 +6,7 @@
#include "Win32SharedMemory.h"
#include "SharedMemoryCommon.h"
#include "../CommonInterfaces/CommonParameterInterface.h"
#include "../Utils/b3ResourcePath.h"
class PhysicsClient : public SharedMemoryCommon
{
@@ -24,6 +24,8 @@ protected:
void createClientCommand();
void createButton(const char* name, int id, bool isTrigger );
public:
PhysicsClient(GUIHelperInterface* helper);
@@ -57,23 +59,13 @@ void MyCallback(int buttonId, bool buttonState, void* userPtr)
switch (buttonId)
{
case CMD_LOAD_URDF:
{
cl->submitCommand(CMD_LOAD_URDF);
break;
}
case CMD_CREATE_BOX_COLLISION_SHAPE:
case CMD_REQUEST_ACTUAL_STATE:
{
cl->submitCommand(CMD_REQUEST_ACTUAL_STATE);
break;
}
case CMD_STEP_FORWARD_SIMULATION:
{
cl->submitCommand(CMD_STEP_FORWARD_SIMULATION);
break;
}
case CMD_SHUTDOWN:
case CMD_SEND_BULLET_DATA_STREAM:
{
cl->submitCommand(CMD_SHUTDOWN);
cl->submitCommand(buttonId);
break;
}
@@ -116,50 +108,26 @@ PhysicsClient::~PhysicsClient()
delete m_sharedMemory;
}
void PhysicsClient::createButton(const char* name, int buttonId, bool isTrigger )
{
ButtonParams button(name,buttonId, isTrigger);
button.m_callback = MyCallback;
button.m_userPointer = this;
m_guiHelper->getParameterInterface()->registerButtonParameter(button);
}
void PhysicsClient::initPhysics()
{
if (m_guiHelper && m_guiHelper->getParameterInterface())
{
{
bool isTrigger = false;
ButtonParams button("Load URDF",CMD_LOAD_URDF, isTrigger);
button.m_callback = MyCallback;
button.m_userPointer = this;
m_guiHelper->getParameterInterface()->registerButtonParameter(button);
}
{
bool isTrigger = false;
ButtonParams button("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
button.m_callback = MyCallback;
button.m_userPointer = this;
m_guiHelper->getParameterInterface()->registerButtonParameter(button);
}
{
bool isTrigger = false;
ButtonParams button("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
button.m_callback = MyCallback;
button.m_userPointer = this;
m_guiHelper->getParameterInterface()->registerButtonParameter(button);
}
bool isTrigger = false;
{
bool isTrigger = false;
ButtonParams button("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
button.m_callback = MyCallback;
button.m_userPointer = this;
m_guiHelper->getParameterInterface()->registerButtonParameter(button);
}
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
{
bool isTrigger = false;
ButtonParams button("Shut Down",CMD_SHUTDOWN, isTrigger);
button.m_callback = MyCallback;
button.m_userPointer = this;
m_guiHelper->getParameterInterface()->registerButtonParameter(button);
}
} else
{
m_userCommandRequests.push_back(CMD_LOAD_URDF);
@@ -167,7 +135,7 @@ void PhysicsClient::initPhysics()
//m_userCommandRequests.push_back(CMD_SEND_DESIRED_STATE);
m_userCommandRequests.push_back(CMD_REQUEST_ACTUAL_STATE);
//m_userCommandRequests.push_back(CMD_SET_JOINT_FEEDBACK);
//m_userCommandRequests.push_back(CMD_CREATE_BOX_COLLISION_SHAPE);
m_userCommandRequests.push_back(CMD_CREATE_BOX_COLLISION_SHAPE);
//m_userCommandRequests.push_back(CMD_CREATE_RIGID_BODY);
m_userCommandRequests.push_back(CMD_STEP_FORWARD_SIMULATION);
m_userCommandRequests.push_back(CMD_REQUEST_ACTUAL_STATE);
@@ -225,6 +193,17 @@ void PhysicsClient::processServerCommands()
m_serverLoadUrdfOK = false;
break;
}
case CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED:
{
break;
}
case CMD_BULLET_DATA_STREAM_RECEIVED_FAILED:
{
break;
}
case CMD_ACTUAL_STATE_UPDATE_COMPLETED:
{
b3Printf("Received actual state\n");
@@ -312,6 +291,67 @@ void PhysicsClient::createClientCommand()
{
b3Warning("Server already loaded URDF, no client command submitted\n");
}
break;
}
case CMD_CREATE_BOX_COLLISION_SHAPE:
{
if (m_serverLoadUrdfOK)
{
b3Printf("Requesting create box collision shape\n");
m_testBlock1->m_clientCommands[0].m_type =CMD_CREATE_BOX_COLLISION_SHAPE;
m_testBlock1->m_numClientCommands++;
} else
{
b3Warning("No URDF loaded\n");
}
break;
}
case CMD_SEND_BULLET_DATA_STREAM:
{
b3Printf("Sending a Bullet Data Stream\n");
///The idea is to pass a stream of chunks from client to server
///over shared memory. The server will process it
///Initially we will just copy an entire .bullet file into shared
///memory but we can also send individual chunks one at a time
///so it becomes a streaming solution
///In addition, we can make a separate API to create those chunks
///if needed, instead of using a 3d modeler or the Bullet SDK btSerializer
char relativeFileName[1024];
const char* fileName = "slope.bullet";
bool fileFound = b3ResourcePath::findResourcePath(fileName,relativeFileName,1024);
if (fileFound)
{
FILE *fp = fopen(relativeFileName, "rb");
if (fp)
{
fseek(fp, 0L, SEEK_END);
int mFileLen = ftell(fp);
fseek(fp, 0L, SEEK_SET);
if (mFileLen<SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE)
{
fread(m_testBlock1->m_bulletStreamDataClientToServer, mFileLen, 1, fp);
fclose(fp);
m_testBlock1->m_clientCommands[0].m_type =CMD_SEND_BULLET_DATA_STREAM;
m_testBlock1->m_clientCommands[0].m_dataStreamArguments.m_streamChunkLength = mFileLen;
m_testBlock1->m_numClientCommands++;
b3Printf("Send bullet data stream command\n");
} else
{
b3Warning("Bullet file size (%d) exceeds of streaming memory chunk size (%d)\n", mFileLen,SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
}
} else
{
b3Warning("Cannot open file %s\n", relativeFileName);
}
} else
{
b3Warning("Cannot find file %s\n", fileName);
}
break;
}
case CMD_REQUEST_ACTUAL_STATE:

View File

@@ -7,6 +7,7 @@
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
#include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
#include "SharedMemoryCommon.h"
@@ -17,6 +18,8 @@ class PhysicsServer : public SharedMemoryCommon
SharedMemoryExampleData* m_testBlock1;
btAlignedObjectArray<btJointFeedback*> m_jointFeedbacks;
btAlignedObjectArray<btBulletWorldImporter*> m_worldImporters;
bool m_wantsShutdown;
public:
@@ -196,6 +199,29 @@ void PhysicsServer::stepSimulation(float deltaTime)
//consume the command
switch (clientCmd.m_type)
{
case CMD_SEND_BULLET_DATA_STREAM:
{
b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength);
btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_dynamicsWorld);
this->m_worldImporters.push_back(worldImporter);
bool completedOk = worldImporter->loadFileFromMemory(m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength);
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
SharedMemoryCommand& serverCmd =m_testBlock1->m_serverCommands[0];
if (completedOk)
{
serverCmd.m_type =CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED;
} else
{
serverCmd.m_type =CMD_BULLET_DATA_STREAM_RECEIVED_FAILED;
}
m_testBlock1->m_numServerCommands++;
break;
}
case CMD_LOAD_URDF:
{
b3Printf("Processed CMD_LOAD_URDF:%s",clientCmd.m_urdfArguments.m_urdfFileName);
@@ -330,6 +356,21 @@ void PhysicsServer::stepSimulation(float deltaTime)
wantsShutdown = true;
break;
}
case CMD_CREATE_BOX_COLLISION_SHAPE:
{
btVector3 halfExtents(30,30,1);
btTransform startTrans;
startTrans.setIdentity();
startTrans.setOrigin(btVector3(0,0,-4));
btCollisionShape* shape = createBoxShape(halfExtents);
btScalar mass = 0.f;
createRigidBody(mass,startTrans,shape);
this->m_guiHelper->autogenerateGraphicsObjects(this->m_dynamicsWorld);
SharedMemoryCommand& serverCmd =m_testBlock1->m_serverCommands[0];
serverCmd.m_type =CMD_STEP_FORWARD_SIMULATION_COMPLETED;
m_testBlock1->m_numServerCommands++;
break;
}
default:
{
b3Error("Unsupported command encountered");

View File

@@ -8,6 +8,8 @@ enum SharedMemoryServerCommand
{
CMD_URDF_LOADING_COMPLETED,
CMD_URDF_LOADING_FAILED,
CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,
CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,
CMD_BOX_COLLISION_SHAPE_CREATION_COMPLETED,
CMD_RIGID_BODY_CREATION_COMPLETED,
CMD_SET_JOINT_FEEDBACK_COMPLETED,
@@ -20,6 +22,7 @@ enum SharedMemoryServerCommand
enum SharedMemoryClientCommand
{
CMD_LOAD_URDF,
CMD_SEND_BULLET_DATA_STREAM,
CMD_CREATE_BOX_COLLISION_SHAPE,
CMD_DELETE_BOX_COLLISION_SHAPE,
CMD_CREATE_RIGID_BODY,
@@ -45,6 +48,12 @@ struct UrdfArgs
bool m_useFixedBase;
};
struct BulletDataStreamArgs
{
int m_streamChunkLength;
};
struct SetJointFeedbackArgs
{
int m_bodyUniqueId;
@@ -96,6 +105,7 @@ struct SharedMemoryCommand
union
{
UrdfArgs m_urdfArguments;
BulletDataStreamArgs m_dataStreamArguments;
StepSimulationArgs m_stepSimulationArguments;
SendDesiredStateArgs m_sendDesiredQandUStateCommandArgument;
RequestActualStateArgs m_requestActualStateInformationCommandArgument;

View File

@@ -4,6 +4,7 @@
#define SHARED_MEMORY_KEY 12347
#define SHARED_MEMORY_MAGIC_NUMBER 64738
#define SHARED_MEMORY_MAX_COMMANDS 64
#define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (256*1024)
#include "SharedMemoryCommands.h"
@@ -31,6 +32,8 @@ struct SharedMemoryExampleData
double m_actualStateQdot[MAX_DEGREE_OF_FREEDOM];
double m_actualStateSensors[MAX_NUM_SENSORS];//these are force sensors and IMU information
char m_bulletStreamDataClientToServer[SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE];
char m_bulletStreamDataServerToClient[SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE];
};
#define SHARED_MEMORY_SIZE sizeof(SharedMemoryExampleData)

View File

@@ -33,6 +33,8 @@ files {
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
"../Importers/ImportURDFDemo/URDF2Bullet.h",
"../Utils/b3ResourcePath.cpp",
"../../Extras/Serialize/BulletWorldImporter/*",
"../../Extras/Serialize/BulletFileLoader/*",
"../Importers/ImportURDFDemo/URDFImporterInterface.h",
"../Importers/ImportURDFDemo/URDFJointTypes.h",
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",