Merge pull request #683 from erwincoumans/master

VR support in PhysicsServerExample, physics runs in its own thread.
This commit is contained in:
erwincoumans
2016-07-09 15:24:40 -07:00
committed by GitHub
48 changed files with 1274 additions and 298 deletions

View File

@@ -389,18 +389,10 @@ void bDNA::init(char *data, int len, bool swap)
cp++;
}
cp = btAlignPointer(cp,4);
{
nr= (long)cp;
//long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
/*
TYPE (4 bytes)
<nr> amount of types (int)
@@ -426,17 +418,8 @@ void bDNA::init(char *data, int len, bool swap)
cp++;
}
{
nr= (long)cp;
// long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = btAlignPointer(cp,4);
/*
TLEN (4 bytes)
<len> (short) the lengths of types

View File

@@ -460,15 +460,7 @@ void bFile::swapDNA(char* ptr)
}
{
nr= (long)cp;
//long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = btAlignPointer(cp,4);
/*
@@ -497,16 +489,7 @@ void bFile::swapDNA(char* ptr)
cp++;
}
{
nr= (long)cp;
// long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = btAlignPointer(cp,4);
/*
TLEN (4 bytes)

View File

@@ -2,7 +2,7 @@
rem premake4 --with-pe vs2010
rem premake4 --bullet2demos vs2010
cd build3
premake4 --targetdir="../bin" vs2010
premake4 --enable_openvr --targetdir="../bin" vs2010
rem premake4 --targetdir="../server2bin" vs2010
rem cd vs2010
rem rename 0_Bullet3Solution.sln 0_server.sln

View File

@@ -9,7 +9,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
<mesh filename="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
</geometry>
</visual>
<collision>
@@ -19,55 +19,5 @@
</geometry>
</collision>
</link>
<link name="childA">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="10.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</collision>
</link>
<joint name="joint_baseLink_childA" type="fixed">
<parent link="baseLink"/>
<child link="childA"/>
<origin xyz="0 0 1.0"/>
</joint>
<link name="childB">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.5"/>
<mass value="10.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.5"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.5"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</collision>
</link>
<joint name="joint_childA_childB" type="continuous">
<parent link="childA"/>
<child link="childB"/>
<axis xyz="0 1 0"/>
<origin xyz="0 0 0.5"/>
</joint>
</robot>

View File

@@ -39,7 +39,7 @@ struct BasicExample : public CommonRigidBodyBase
virtual void renderScene();
void resetCamera()
{
float dist = 41;
float dist = 4;
float pitch = 52;
float yaw = 35;
float targetPos[3]={0,0,0};
@@ -81,7 +81,7 @@ void BasicExample::initPhysics()
//create a few dynamic rigidbodies
// Re-using the same collision is better for memory usage and performance
btBoxShape* colShape = createBoxShape(btVector3(1,1,1));
btBoxShape* colShape = createBoxShape(btVector3(.1,.1,.1));
//btCollisionShape* colShape = new btSphereShape(btScalar(1.));
@@ -108,9 +108,9 @@ void BasicExample::initPhysics()
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
startTransform.setOrigin(btVector3(
btScalar(2.0*i),
btScalar(20+2.0*k),
btScalar(2.0*j)));
btScalar(0.2*i),
btScalar(2+.2*k),
btScalar(0.2*j)));
createRigidBody(mass,startTransform,colShape);
@@ -121,7 +121,9 @@ void BasicExample::initPhysics()
}
}
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}

View File

@@ -53,6 +53,7 @@ SET(AppBasicExampleGui_SRCS
../ExampleBrowser/OpenGLGuiHelper.cpp
../ExampleBrowser/GL_ShapeDrawer.cpp
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
../Utils/b3Clock.cpp
)
#this define maps StandaloneExampleCreateFunc to the right 'CreateFunc'

View File

@@ -49,6 +49,8 @@ files {
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}
if os.is("Linux") then initX11() end
@@ -93,7 +95,9 @@ files {
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp",
"../Utils/b3ResourcePath.cpp"
"../Utils/b3ResourcePath.cpp",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}
if os.is("Linux") then initX11() end
@@ -132,7 +136,9 @@ files {
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp",
"../Utils/b3ResourcePath.cpp"
"../Utils/b3ResourcePath.cpp",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}
@@ -179,6 +185,8 @@ files {
"../ThirdPartyLibs/openvr/samples/shared/pathtools.cpp",
"../ThirdPartyLibs/openvr/samples/shared/pathtools.h",
"../ThirdPartyLibs/openvr/samples/shared/Vectors.h",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}

View File

@@ -6,7 +6,9 @@ struct CommonCameraInterface
virtual void getCameraProjectionMatrix(float m[16])const = 0;
virtual void getCameraViewMatrix(float m[16]) const = 0;
virtual void setVRCamera(const float viewMat[16], const float projectionMatrix[16])=0;
virtual void setVRCamera(const float viewMat[16], const float projectionMatrix[16])=0;
virtual void disableVRCamera()=0;
virtual bool isVRCamera() const =0;
virtual void getCameraTargetPosition(float pos[3]) const = 0;
virtual void getCameraPosition(float pos[3]) const = 0;

View File

@@ -29,10 +29,11 @@ struct GUIHelperInterface
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld)=0;
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices) =0;
virtual int registerTexture(const unsigned char* texels, int width, int height)=0;
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId) = 0;
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) =0;
virtual void removeAllGraphicsInstances()=0;
virtual Common2dCanvasInterface* get2dCanvasInterface()=0;
virtual CommonParameterInterface* getParameterInterface()=0;
@@ -73,10 +74,11 @@ struct DummyGUIHelper : public GUIHelperInterface
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld){}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices) { return -1; }
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) { return -1;}
virtual int registerTexture(const unsigned char* texels, int width, int height){return -1;}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId){return -1;}
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) {return -1;}
virtual void removeAllGraphicsInstances(){}
virtual Common2dCanvasInterface* get2dCanvasInterface()
{
return 0;

View File

@@ -22,7 +22,7 @@ struct CommonRenderInterface
virtual void init()=0;
virtual void updateCamera(int upAxis)=0;
virtual void removeAllInstances() = 0;
virtual const CommonCameraInterface* getActiveCamera() const =0;
virtual CommonCameraInterface* getActiveCamera()=0;
virtual void setActiveCamera(CommonCameraInterface* cam)=0;
@@ -52,6 +52,10 @@ struct CommonRenderInterface
virtual void writeSingleInstanceTransformToCPU(const double* position, const double* orientation, int srcIndex)=0;
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex)=0;
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex)=0;
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex)=0;
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex)=0;
virtual int getTotalNumInstances() const = 0;
virtual void writeTransforms()=0;
virtual void enableBlend(bool blend)=0;

View File

@@ -226,7 +226,7 @@ enum TestExampleBrowserCommunicationEnums
void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
{
printf("thread started\n");
printf("ExampleBrowserThreadFunc started\n");
ExampleBrowserThreadLocalStorage* localStorage = (ExampleBrowserThreadLocalStorage*) lsMemory;
@@ -369,7 +369,7 @@ void btShutDownExampleBrowser(btInProcessExampleBrowserInternalData* data)
}
};
printf("stopping threads\n");
printf("btShutDownExampleBrowser stopping threads\n");
delete data->m_threadSupport;
delete data->m_sharedMem;
delete data;

View File

@@ -199,9 +199,16 @@ void OpenGLGuiHelper::createCollisionObjectGraphicsObject(btCollisionObject* bod
}
}
int OpenGLGuiHelper::registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices)
int OpenGLGuiHelper::registerTexture(const unsigned char* texels, int width, int height)
{
int shapeId = m_data->m_glApp->m_renderer->registerShape(vertices, numvertices,indices,numIndices);
int textureId = m_data->m_glApp->m_renderer->registerTexture(texels,width,height);
return textureId;
}
int OpenGLGuiHelper::registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
{
int shapeId = m_data->m_glApp->m_renderer->registerShape(vertices, numvertices,indices,numIndices,primitiveType, textureId);
return shapeId;
}
@@ -210,6 +217,10 @@ int OpenGLGuiHelper::registerGraphicsInstance(int shapeIndex, const float* posit
return m_data->m_glApp->m_renderer->registerGraphicsInstance(shapeIndex,position,quaternion,color,scaling);
}
void OpenGLGuiHelper::removeAllGraphicsInstances()
{
m_data->m_glApp->m_renderer->removeAllInstances();
}
void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
{
@@ -247,7 +258,7 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli
if (gfxVertices.size() && indices.size())
{
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size());
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size(),B3_GL_TRIANGLES,-1);
collisionShape->setUserIndex(shapeId);
}

View File

@@ -20,12 +20,11 @@ struct OpenGLGuiHelper : public GUIHelperInterface
virtual void createCollisionObjectGraphicsObject(btCollisionObject* body, const btVector3& color);
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices);
virtual int registerTexture(const unsigned char* texels, int width, int height);
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId);
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling);
virtual void removeAllGraphicsInstances();
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape);
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld);

View File

@@ -134,7 +134,8 @@ void RigidBodyFromObjExample::initPhysics()
int shapeId = m_guiHelper->registerGraphicsShape(&glmesh->m_vertices->at(0).xyzw[0],
glmesh->m_numvertices,
&glmesh->m_indices->at(0),
glmesh->m_numIndices);
glmesh->m_numIndices,
B3_GL_TRIANGLES, -1);
shape->setUserIndex(shapeId);
int renderInstance = m_guiHelper->registerGraphicsInstance(shapeId,pos,orn,color,scaling);
body->setUserIndex(renderInstance);

View File

@@ -39,7 +39,7 @@ files {
"../Importers/ImportURDFDemo/UrdfParser.cpp",
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
}
@@ -91,7 +91,9 @@ files {
"../Importers/ImportURDFDemo/UrdfParser.cpp",
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
"../Utils/b3Clock.cpp",
"../Utils/b3Clock.h",
}
if os.is("Linux") then initX11() end
@@ -156,7 +158,7 @@ files {
"../Importers/ImportURDFDemo/UrdfParser.cpp",
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
}
if os.is("Linux") then initX11() end

View File

@@ -108,7 +108,8 @@ struct BulletErrorLogger : public ErrorLogger
bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase)
{
if (strlen(fileName)==0)
return false;
//int argc=0;
char relativeFileName[1024];
@@ -132,7 +133,7 @@ bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase)
std::fstream xml_file(relativeFileName, std::fstream::in);
while ( xml_file.good() )
while ( xml_file.good())
{
std::string line;
std::getline( xml_file, line);
@@ -969,16 +970,17 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
// graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size());
//graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size());
CommonRenderInterface* renderer = m_data->m_guiHelper->getRenderInterface();
//CommonRenderInterface* renderer = m_data->m_guiHelper->getRenderInterface();
if (renderer)
if (1)
{
int textureIndex = -1;
if (textures.size())
{
textureIndex = renderer->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height);
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height);
}
graphicsIndex = renderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES,textureIndex);
graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES,textureIndex);
}
}

View File

@@ -65,7 +65,8 @@ btAlignedObjectArray<std::string> gFileNameArray;
struct ImportUrdfInternalData
{
ImportUrdfInternalData()
:m_numMotors(0)
:m_numMotors(0),
m_mb(0)
{
for (int i=0;i<MAX_NUM_MOTORS;i++)
{
@@ -74,10 +75,13 @@ struct ImportUrdfInternalData
}
}
btScalar m_motorTargetVelocities[MAX_NUM_MOTORS];
btMultiBodyJointMotor* m_jointMotors [MAX_NUM_MOTORS];
btGeneric6DofSpring2Constraint* m_generic6DofJointMotors [MAX_NUM_MOTORS];
int m_numMotors;
btMultiBody* m_mb;
btRigidBody* m_rb;
};
@@ -223,7 +227,6 @@ void ImportUrdfSetup::initPhysics()
{
btMultiBody* mb = 0;
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
@@ -232,8 +235,10 @@ void ImportUrdfSetup::initPhysics()
MyMultiBodyCreator creation(m_guiHelper);
ConvertURDF2Bullet(u2b,creation, identityTrans,m_dynamicsWorld,m_useMultiBody,u2b.getPathPrefix());
mb = creation.getBulletMultiBody();
m_data->m_rb = creation.getRigidBody();
m_data->m_mb = creation.getBulletMultiBody();
btMultiBody* mb = m_data->m_mb;
if (m_useMultiBody && mb )
{
std::string* name = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
@@ -337,7 +342,7 @@ void ImportUrdfSetup::initPhysics()
bool createGround=true;
bool createGround=false;
if (createGround)
{
btVector3 groundHalfExtents(20,20,20);
@@ -357,8 +362,7 @@ void ImportUrdfSetup::initPhysics()
m_guiHelper->createRigidBodyGraphicsObject(body,color);
}
///this extra stepSimulation call makes sure that all the btMultibody transforms are properly propagates.
m_dynamicsWorld->stepSimulation(1. / 240., 0);// 1., 10, 1. / 240.);
}
#ifdef TEST_MULTIBODY_SERIALIZATION

View File

@@ -13,6 +13,7 @@
MyMultiBodyCreator::MyMultiBodyCreator(GUIHelperInterface* guiHelper)
:m_bulletMultiBody(0),
m_rigidBody(0),
m_guiHelper(guiHelper)
{
}
@@ -31,10 +32,10 @@ class btRigidBody* MyMultiBodyCreator::allocateRigidBody(int urdfLinkIndex, btSc
{
btRigidBody::btRigidBodyConstructionInfo rbci(mass, 0, colShape, localInertiaDiagonal);
rbci.m_startWorldTransform = initialWorldTrans;
btRigidBody* body = new btRigidBody(rbci);
body->forceActivationState(DISABLE_DEACTIVATION);
m_rigidBody = new btRigidBody(rbci);
m_rigidBody->forceActivationState(DISABLE_DEACTIVATION);
return body;
return m_rigidBody;
}
class btMultiBodyLinkCollider* MyMultiBodyCreator::allocateMultiBodyLinkCollider(int /*urdfLinkIndex*/, int mbLinkIndex, btMultiBody* multiBody)

View File

@@ -24,6 +24,7 @@ class MyMultiBodyCreator : public MultiBodyCreationInterface
protected:
btMultiBody* m_bulletMultiBody;
btRigidBody* m_rigidBody;
struct GUIHelperInterface* m_guiHelper;
@@ -62,6 +63,10 @@ public:
virtual void addLinkMapping(int urdfLinkIndex, int mbLinkIndex);
btMultiBody* getBulletMultiBody();
btRigidBody* getRigidBody()
{
return m_rigidBody;
}
int getNum6DofConstraints() const
{

View File

@@ -119,7 +119,7 @@ struct SampleThreadLocalStorage
void SampleThreadFunc(void* userPtr,void* lsMemory)
{
printf("thread started\n");
printf("SampleThreadFunc thread started\n");
SampleThreadLocalStorage* localStorage = (SampleThreadLocalStorage*) lsMemory;

View File

@@ -53,7 +53,7 @@ static sem_t* createSem(const char* baseName)
#ifdef NAMED_SEMAPHORES
/// Named semaphore begin
char name[32];
snprintf(name, 32, "/%s-%d-%4.4d", baseName, getpid(), semCount++);
snprintf(name, 32, "/%8.s-%4.d-%4.4d", baseName, getpid(), semCount++);
sem_t* tempSem = sem_open(name, O_CREAT, 0600, 0);
if (tempSem != reinterpret_cast<sem_t *>(SEM_FAILED))

View File

@@ -223,7 +223,8 @@ bool b3Win32ThreadSupport::isTaskCompleted(int *puiArgument0, int *puiArgument1,
void b3Win32ThreadSupport::startThreads(const Win32ThreadConstructionInfo& threadConstructionInfo)
{
static int uniqueId = 0;
uniqueId++;
m_activeThreadStatus.resize(threadConstructionInfo.m_numThreads);
m_completeHandles.resize(threadConstructionInfo.m_numThreads);
@@ -244,18 +245,40 @@ void b3Win32ThreadSupport::startThreads(const Win32ThreadConstructionInfo& threa
threadStatus.m_userPtr=0;
sprintf(threadStatus.m_eventStartHandleName,"eventStart%s%d",threadConstructionInfo.m_uniqueName,i);
sprintf(threadStatus.m_eventStartHandleName,"es%.8s%d%d",threadConstructionInfo.m_uniqueName,uniqueId,i);
threadStatus.m_eventStartHandle = CreateEventA (0,false,false,threadStatus.m_eventStartHandleName);
sprintf(threadStatus.m_eventCompletetHandleName,"eventComplete%s%d",threadConstructionInfo.m_uniqueName,i);
sprintf(threadStatus.m_eventCompletetHandleName,"ec%.8s%d%d",threadConstructionInfo.m_uniqueName,uniqueId,i);
threadStatus.m_eventCompletetHandle = CreateEventA (0,false,false,threadStatus.m_eventCompletetHandleName);
m_completeHandles[i] = threadStatus.m_eventCompletetHandle;
HANDLE handle = CreateThread(lpThreadAttributes,dwStackSize,lpStartAddress,lpParameter, dwCreationFlags,lpThreadId);
//SetThreadPriority(handle,THREAD_PRIORITY_HIGHEST);
SetThreadPriority(handle,THREAD_PRIORITY_TIME_CRITICAL);
switch(threadConstructionInfo.m_priority)
{
case 0:
{
SetThreadPriority(handle,THREAD_PRIORITY_HIGHEST);
break;
}
case 1:
{
SetThreadPriority(handle,THREAD_PRIORITY_TIME_CRITICAL);
break;
}
case 2:
{
SetThreadPriority(handle,THREAD_PRIORITY_BELOW_NORMAL);
break;
}
default:
{
}
}
SetThreadAffinityMask(handle, 1<<i);
threadStatus.m_taskId = i;
@@ -265,7 +288,7 @@ void b3Win32ThreadSupport::startThreads(const Win32ThreadConstructionInfo& threa
threadStatus.m_lsMemory = threadConstructionInfo.m_lsMemoryFunc();
threadStatus.m_userThreadFunc = threadConstructionInfo.m_userThreadFunc;
printf("started thread %d with threadHandle %p\n",i,handle);
printf("started %s thread %d with threadHandle %p\n",threadConstructionInfo.m_uniqueName,i,handle);
}

View File

@@ -74,7 +74,8 @@ public:
m_userThreadFunc(userThreadFunc),
m_lsMemoryFunc(lsMemoryFunc),
m_numThreads(numThreads),
m_threadStackSize(threadStackSize)
m_threadStackSize(threadStackSize),
m_priority(0)
{
}
@@ -84,6 +85,7 @@ public:
b3Win32lsMemorySetupFunc m_lsMemoryFunc;
int m_numThreads;
int m_threadStackSize;
int m_priority;
};

View File

@@ -17,8 +17,8 @@ subject to the following restrictions:
///todo: make this configurable in the gui
bool useShadowMap=true;//false;//true;
int shadowMapWidth=8192;
int shadowMapHeight=8192;
int shadowMapWidth=4096;//8192;
int shadowMapHeight=4096;
float shadowMapWorldSize=50;
#define MAX_POINTS_IN_BATCH 1024
@@ -261,6 +261,8 @@ GLInstancingRenderer::GLInstancingRenderer(int maxNumObjectCapacity, int maxShap
void GLInstancingRenderer::removeAllInstances()
{
m_data->m_totalNumInstances = 0;
for (int i=0;i<m_graphicsInstances.size();i++)
{
if (m_graphicsInstances[i]->m_index_vbo)
@@ -276,6 +278,7 @@ void GLInstancingRenderer::removeAllInstances()
m_graphicsInstances.clear();
}
GLInstancingRenderer::~GLInstancingRenderer()
{
delete m_data->m_shadowMap;
@@ -323,6 +326,7 @@ void GLInstancingRenderer::writeSingleInstanceTransformToCPU(const float* positi
*/
}
void GLInstancingRenderer::writeSingleInstanceColorToCPU(double* color, int srcIndex)
{
m_data->m_instance_colors_ptr[srcIndex*4+0]=float(color[0]);
@@ -340,7 +344,19 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(float* color, int srcIn
m_data->m_instance_colors_ptr[srcIndex*4+3]=color[3];
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(float* scale, int srcIndex)
{
m_data->m_instance_scale_ptr[srcIndex*3+0]=scale[0];
m_data->m_instance_scale_ptr[srcIndex*3+1]=scale[1];
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(double* scale, int srcIndex)
{
m_data->m_instance_scale_ptr[srcIndex*3+0]=scale[0];
m_data->m_instance_scale_ptr[srcIndex*3+1]=scale[1];
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
}
void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, float* orientation, int objectIndex)
{
@@ -386,25 +402,46 @@ void GLInstancingRenderer::writeTransforms()
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
glFlush();
//glFlush();
b3Assert(glGetError() ==GL_NO_ERROR);
#ifdef B3_DEBUG
{
int totalNumInstances= 0;
for (int k=0;k<m_graphicsInstances.size();k++)
{
b3GraphicsInstance* gfxObj = m_graphicsInstances[k];
totalNumInstances+=gfxObj->m_numGraphicsInstances;
}
b3Assert(m_data->m_totalNumInstances == totalNumInstances);
}
#endif//B3_DEBUG
int POSITION_BUFFER_SIZE = (m_data->m_totalNumInstances*sizeof(float)*4);
int ORIENTATION_BUFFER_SIZE = (m_data->m_totalNumInstances*sizeof(float)*4);
int COLOR_BUFFER_SIZE = (m_data->m_totalNumInstances*sizeof(float)*4);
// int SCALE_BUFFER_SIZE = (totalNumInstances*sizeof(float)*3);
#if 1
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes,m_data->m_totalNumInstances*sizeof(float)*4,
&m_data->m_instance_positions_ptr[0]);
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*4,
&m_data->m_instance_quaternion_ptr[0]);
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+ POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE, m_data->m_totalNumInstances*sizeof(float)*4,
&m_data->m_instance_colors_ptr[0]);
glBufferSubData( GL_ARRAY_BUFFER, m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*3,
&m_data->m_instance_scale_ptr[0]);
#else
char* orgBase = (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_READ_WRITE);
if (orgBase)
{
int totalNumInstances= 0;
for (int k=0;k<m_graphicsInstances.size();k++)
{
b3GraphicsInstance* gfxObj = m_graphicsInstances[k];
totalNumInstances+=gfxObj->m_numGraphicsInstances;
}
m_data->m_totalNumInstances = totalNumInstances;
for (int k=0;k<m_graphicsInstances.size();k++)
{
@@ -413,10 +450,7 @@ void GLInstancingRenderer::writeTransforms()
int POSITION_BUFFER_SIZE = (totalNumInstances*sizeof(float)*4);
int ORIENTATION_BUFFER_SIZE = (totalNumInstances*sizeof(float)*4);
int COLOR_BUFFER_SIZE = (totalNumInstances*sizeof(float)*4);
// int SCALE_BUFFER_SIZE = (totalNumInstances*sizeof(float)*3);
char* base = orgBase;
@@ -465,6 +499,9 @@ void GLInstancingRenderer::writeTransforms()
//if this glFinish is removed, the animation is not always working/blocks
//@todo: figure out why
glFlush();
#endif
glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
b3Assert(glGetError() ==GL_NO_ERROR);
@@ -1006,7 +1043,7 @@ void GLInstancingRenderer::renderScene()
{
renderSceneInternal(B3_CREATE_SHADOWMAP_RENDERMODE);
// glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT);
//glClear(GL_COLOR_BUFFER_BIT|GL_DEPTH_BUFFER_BIT);
renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE);
} else
@@ -1075,6 +1112,9 @@ void GLInstancingRenderer::drawPoints(const float* positions, const float color[
void GLInstancingRenderer::drawLines(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, const unsigned int* indices, int numIndices, float lineWidthIn)
{
glActiveTexture(GL_TEXTURE0);
glBindTexture(GL_TEXTURE_2D,0);
float lineWidth = lineWidthIn;
b3Clamp(lineWidth,(float)lineWidthRange[0],(float)lineWidthRange[1]);
glLineWidth(lineWidth);
@@ -1510,7 +1550,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
int curOffset = 0;
//GLuint lastBindTexture = 0;
for (int i=0;i<m_graphicsInstances.size();i++)
{
@@ -1634,6 +1674,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
printf("gfxObj->m_numGraphicsInstances=%d\n",gfxObj->m_numGraphicsInstances);
printf("indexCount=%d\n",indexCount);
*/
glUseProgram(createShadowMapInstancingShader);
glUniformMatrix4fv(createShadow_depthMVP, 1, false, &depthMVP[0][0]);
glDrawElementsInstanced(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, indexOffset, gfxObj->m_numGraphicsInstances);
@@ -1667,6 +1708,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
glDisable (GL_BLEND);
}
glActiveTexture(GL_TEXTURE0);
glBindTexture(GL_TEXTURE_2D,0);
break;
}
default:
@@ -1743,4 +1785,10 @@ void GLInstancingRenderer::setRenderFrameBuffer(unsigned int renderFrameBuffer)
m_data->m_renderFrameBuffer = (GLuint) renderFrameBuffer;
}
int GLInstancingRenderer::getTotalNumInstances() const
{
return m_data->m_totalNumInstances;
}
#endif //NO_OPENGL3

View File

@@ -56,7 +56,7 @@ public:
void InitShaders();
void CleanupShaders();
virtual void removeAllInstances();
virtual void updateShape(int shapeIndex, const float* vertices);
///vertices must be in the format x,y,z, nx,ny,nz, u,v
@@ -95,6 +95,9 @@ public:
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex);
virtual struct GLInstanceRendererInternalData* getInternalData();
@@ -125,6 +128,8 @@ public:
virtual int getInstanceCapacity() const;
virtual int getTotalNumInstances() const;
virtual void enableShadowMap();
virtual void enableBlend(bool blend)
{

View File

@@ -62,6 +62,16 @@ void SimpleCamera::setVRCamera(const float viewMat[16], const float projectionMa
}
}
void SimpleCamera::disableVRCamera()
{
m_data->m_enableVR = false;
}
bool SimpleCamera::isVRCamera() const
{
return m_data->m_enableVR ;
}
static void b3CreateFrustum(
float left,

View File

@@ -15,6 +15,8 @@ struct SimpleCamera : public CommonCameraInterface
virtual void getCameraViewMatrix(float m[16]) const;
virtual void setVRCamera(const float viewMat[16], const float projectionMatrix[16]);
virtual void disableVRCamera();
virtual bool isVRCamera() const;
virtual void getCameraTargetPosition(float pos[3]) const;
virtual void getCameraPosition(float pos[3]) const;

View File

@@ -64,6 +64,20 @@ void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(double* color, int src
{
}
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(float* scale, int srcIndex)
{
}
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(double* scale, int srcIndex)
{
}
int SimpleOpenGL2Renderer::getTotalNumInstances() const
{
return 0;
}
void SimpleOpenGL2Renderer::getCameraViewMatrix(float viewMat[16]) const
{
b3Assert(0);

View File

@@ -32,6 +32,8 @@ struct SimpleOpenGL2Renderer : public CommonRenderInterface
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex);
virtual void getCameraViewMatrix(float viewMat[16]) const;
virtual void getCameraProjectionMatrix(float projMat[16]) const;
@@ -68,6 +70,8 @@ struct SimpleOpenGL2Renderer : public CommonRenderInterface
virtual void writeSingleInstanceTransformToCPU(const double* position, const double* orientation, int srcIndex);
virtual int getTotalNumInstances() const;
virtual void writeTransforms();
virtual void drawLine(const double from[4], const double to[4], const double color[4], double lineWidth);
@@ -82,6 +86,7 @@ struct SimpleOpenGL2Renderer : public CommonRenderInterface
virtual void clearZBuffer();
virtual struct GLInstanceRendererInternalData* getInternalData()
{
return 0;

View File

@@ -835,7 +835,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
enqueueCommand(CMD_STEP_FORWARD_SIMULATION);
if (m_options != eCLIENTEXAMPLE_SERVER)
{
enqueueCommand(CMD_REQUEST_DEBUG_LINES);
//enqueueCommand(CMD_REQUEST_DEBUG_LINES);
}
}
}
@@ -855,3 +855,4 @@ class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOpt
}
return example;
}

View File

@@ -659,6 +659,8 @@ bool PhysicsClientSharedMemory::canSubmitCommand() const {
}
struct SharedMemoryCommand* PhysicsClientSharedMemory::getAvailableSharedMemoryCommand() {
static int sequence = 0;
m_data->m_testBlock1->m_clientCommands[0].m_sequenceNumber = sequence++;
return &m_data->m_testBlock1->m_clientCommands[0];
}

View File

@@ -10,7 +10,7 @@
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h"
#include "../CommonInterfaces/CommonRenderInterface.h"
#include "btBulletDynamicsCommon.h"
@@ -1756,10 +1756,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
case CMD_STEP_FORWARD_SIMULATION:
{
if (m_data->m_verboseOutput)
{
b3Printf("Step simulation request");
b3Printf("CMD_STEP_FORWARD_SIMULATION clientCmd = %d\n", clientCmd.m_sequenceNumber);
}
///todo(erwincoumans) move this damping inside Bullet
for (int i=0;i<m_data->m_bodyHandles.size();i++)
@@ -1864,16 +1865,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
case CMD_RESET_SIMULATION:
{
//clean up all data
if (m_data && m_data->m_guiHelper && m_data->m_guiHelper->getRenderInterface())
{
m_data->m_guiHelper->getRenderInterface()->removeAllInstances();
}
if (m_data && m_data->m_guiHelper)
{
m_data->m_guiHelper->removeAllGraphicsInstances();
}
if (m_data)
{
m_data->m_visualConverter.resetAll();
}
deleteDynamicsWorld();
createEmptyDynamicsWorld();
m_data->exitHandles();
m_data->initHandles();
@@ -2058,6 +2064,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
case CMD_APPLY_EXTERNAL_FORCE:
{
if (m_data->m_verboseOutput)
{
b3Printf("CMD_APPLY_EXTERNAL_FORCE clientCmd = %d\n", clientCmd.m_sequenceNumber);
}
for (int i = 0; i < clientCmd.m_externalForceArguments.m_numForcesAndTorques; ++i)
{
InteralBodyData* body = m_data->getHandle(clientCmd.m_externalForceArguments.m_bodyUniqueIds[i]);

View File

@@ -9,11 +9,371 @@
#include "SharedMemoryCommon.h"
#include "../Utils/b3Clock.h"
#include "../MultiThreading/b3ThreadSupportInterface.h"
int blockme = false;
int blockme2 = false;
void MotionThreadFunc(void* userPtr,void* lsMemory);
void* MotionlsMemoryFunc();
#define MAX_MOTION_NUM_THREADS 1
enum
{
numCubesX = 20,
numCubesY = 20
};
enum TestExampleBrowserCommunicationEnums
{
eRequestTerminateMotion= 13,
eMotionIsUnInitialized,
eMotionIsInitialized,
eMotionInitializationFailed,
eMotionHasTerminated
};
enum MultiThreadedGUIHelperCommunicationEnums
{
eGUIHelperIdle= 13,
eGUIHelperRegisterTexture,
eGUIHelperRegisterGraphicsShape,
eGUIHelperRegisterGraphicsInstance,
eGUIHelperCreateCollisionShapeGraphicsObject,
eGUIHelperCreateCollisionObjectGraphicsObject,
eGUIHelperRemoveAllGraphicsInstances,
};
#include <stdio.h>
//#include "BulletMultiThreaded/PlatformDefinitions.h"
#ifndef _WIN32
#include "../MultiThreading/b3PosixThreadSupport.h"
b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
{
b3PosixThreadSupport::ThreadConstructionInfo constructionInfo("MotionThreads",
MotionThreadFunc,
MotionlsMemoryFunc,
numThreads);
b3ThreadSupportInterface* threadSupport = new b3PosixThreadSupport(constructionInfo);
return threadSupport;
}
#elif defined( _WIN32)
#include "../MultiThreading/b3Win32ThreadSupport.h"
b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
{
b3Win32ThreadSupport::Win32ThreadConstructionInfo threadConstructionInfo("MotionThreads",MotionThreadFunc,MotionlsMemoryFunc,numThreads);
b3Win32ThreadSupport* threadSupport = new b3Win32ThreadSupport(threadConstructionInfo);
return threadSupport;
}
#endif
struct MotionArgs
{
MotionArgs()
:m_physicsServerPtr(0)
{
}
b3CriticalSection* m_cs;
PhysicsServerSharedMemory* m_physicsServerPtr;
b3AlignedObjectArray<b3Vector3> m_positions;
};
struct MotionThreadLocalStorage
{
int threadId;
};
int skip = 0;
void MotionThreadFunc(void* userPtr,void* lsMemory)
{
printf("MotionThreadFunc thread started\n");
MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory;
MotionArgs* args = (MotionArgs*) userPtr;
int workLeft = true;
b3Clock clock;
clock.reset();
bool init = true;
if (init)
{
args->m_cs->lock();
args->m_cs->setSharedParam(0,eMotionIsInitialized);
args->m_cs->unlock();
do
{
double deltaTimeInSeconds = double(clock.getTimeMicroseconds())/1000000.;
if (deltaTimeInSeconds<(1./260.))
{
skip++;
if (deltaTimeInSeconds<.001)
continue;
}
clock.reset();
if (!blockme)
{
args->m_physicsServerPtr->processClientCommands();
}
} while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);
} else
{
args->m_cs->lock();
args->m_cs->setSharedParam(0,eMotionInitializationFailed);
args->m_cs->unlock();
}
printf("finished, #skip = %d\n",skip);
skip=0;
//do nothing
}
void* MotionlsMemoryFunc()
{
//don't create local store memory, just return 0
return new MotionThreadLocalStorage;
}
class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
{
CommonGraphicsApp* m_app;
b3CriticalSection* m_cs;
public:
GUIHelperInterface* m_childGuiHelper;
const unsigned char* m_texels;
int m_textureWidth;
int m_textureHeight;
int m_shapeIndex;
const float* m_position;
const float* m_quaternion;
const float* m_color;
const float* m_scaling;
const float* m_vertices;
int m_numvertices;
const int* m_indices;
int m_numIndices;
int m_primitiveType;
int m_textureId;
int m_instanceId;
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
:m_app(app)
,m_cs(0),
m_texels(0),
m_textureId(-1)
{
m_childGuiHelper = guiHelper;;
}
virtual ~MultiThreadedOpenGLGuiHelper()
{
delete m_childGuiHelper;
}
void setCriticalSection(b3CriticalSection* cs)
{
m_cs = cs;
}
b3CriticalSection* getCriticalSection()
{
return m_cs;
}
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color){}
btCollisionObject* m_obj;
btVector3 m_color2;
virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj,const btVector3& color)
{
m_obj = obj;
m_color2 = color;
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperCreateCollisionObjectGraphicsObject);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
}
btCollisionShape* m_colShape;
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
{
m_colShape = collisionShape;
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperCreateCollisionShapeGraphicsObject);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
}
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld)
{
//this check is to prevent a crash, in case we removed all graphics instances, but there are still physics objects.
//the check will be obsolete, once we have a better/safer way of synchronizing physics->graphics transforms
if ( m_childGuiHelper->getRenderInterface()->getTotalNumInstances()>0)
{
m_childGuiHelper->syncPhysicsToGraphics(rbWorld);
}
}
virtual void render(const btDiscreteDynamicsWorld* rbWorld)
{
m_childGuiHelper->render(0);
}
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld){}
virtual int registerTexture(const unsigned char* texels, int width, int height)
{
m_texels = texels;
m_textureWidth = width;
m_textureHeight = height;
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperRegisterTexture);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
return m_textureId;
}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
{
m_vertices = vertices;
m_numvertices = numvertices;
m_indices = indices;
m_numIndices = numIndices;
m_primitiveType = primitiveType;
m_textureId = textureId;
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperRegisterGraphicsShape);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
return m_shapeIndex;
}
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
{
m_shapeIndex = shapeIndex;
m_position = position;
m_quaternion = quaternion;
m_color = color;
m_scaling = scaling;
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperRegisterGraphicsInstance);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
return m_instanceId;
}
virtual void removeAllGraphicsInstances()
{
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperRemoveAllGraphicsInstances);
m_cs->unlock();
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
}
}
virtual Common2dCanvasInterface* get2dCanvasInterface()
{
return 0;
}
virtual CommonParameterInterface* getParameterInterface()
{
return 0;
}
virtual CommonRenderInterface* getRenderInterface()
{
return 0;
}
virtual CommonGraphicsApp* getAppInterface()
{
return m_childGuiHelper->getAppInterface();
}
virtual void setUpAxis(int axis)
{
m_childGuiHelper->setUpAxis(axis);
}
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
{
}
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* width, int* height, int* numPixelsCopied)
{
if (width)
*width = 0;
if (height)
*height = 0;
if (numPixelsCopied)
*numPixelsCopied = 0;
}
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
{
}
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)
{
}
};
class PhysicsServerExample : public SharedMemoryCommon
{
PhysicsServerSharedMemory m_physicsServer;
b3ThreadSupportInterface* m_threadSupport;
MotionArgs m_args[MAX_MOTION_NUM_THREADS];
MultiThreadedOpenGLGuiHelper* m_multiThreadedHelper;
bool m_wantsShutdown;
bool m_isConnected;
@@ -23,7 +383,7 @@ class PhysicsServerExample : public SharedMemoryCommon
public:
PhysicsServerExample(GUIHelperInterface* helper, SharedMemoryInterface* sharedMem=0, int options=0);
PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0);
virtual ~PhysicsServerExample();
@@ -56,7 +416,7 @@ public:
virtual bool wantsTermination();
virtual bool isConnected();
virtual void renderScene();
virtual void exitPhysics(){}
virtual void exitPhysics();
virtual void physicsDebugDraw(int debugFlags);
@@ -71,7 +431,6 @@ public:
if (!renderer)
{
btAssert(0);
return false;
}
@@ -91,7 +450,6 @@ public:
if (!renderer)
{
btAssert(0);
return false;
}
@@ -134,7 +492,7 @@ public:
};
PhysicsServerExample::PhysicsServerExample(GUIHelperInterface* helper, SharedMemoryInterface* sharedMem, int options)
PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem, int options)
:SharedMemoryCommon(helper),
m_physicsServer(sharedMem),
m_wantsShutdown(false),
@@ -142,6 +500,7 @@ m_isConnected(false),
m_replay(false),
m_options(options)
{
m_multiThreadedHelper = helper;
b3Printf("Started PhysicsServer\n");
}
@@ -165,22 +524,80 @@ void PhysicsServerExample::initPhysics()
int upAxis = 2;
m_guiHelper->setUpAxis(upAxis);
#if 0
createEmptyDynamicsWorld();
//todo: create a special debug drawer that will cache the lines, so we can send the debug info over the wire
btVector3 grav(0,0,0);
grav[upAxis] = 0;//-9.8;
this->m_dynamicsWorld->setGravity(grav);
#endif
m_threadSupport = createMotionThreadSupport(MAX_MOTION_NUM_THREADS);
m_isConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
for (int i=0;i<m_threadSupport->getNumTasks();i++)
{
MotionThreadLocalStorage* storage = (MotionThreadLocalStorage*) m_threadSupport->getThreadLocalMemory(i);
b3Assert(storage);
storage->threadId = i;
//storage->m_sharedMem = data->m_sharedMem;
}
for (int w=0;w<MAX_MOTION_NUM_THREADS;w++)
{
m_args[w].m_cs = m_threadSupport->createCriticalSection();
m_args[w].m_cs->setSharedParam(0,eMotionIsUnInitialized);
int numMoving = 0;
m_args[w].m_positions.resize(numMoving);
m_args[w].m_physicsServerPtr = &m_physicsServer;
int index = 0;
m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*) &this->m_args[w], w);
while (m_args[w].m_cs->getSharedParam(0)==eMotionIsUnInitialized)
{
}
}
m_args[0].m_cs->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->setCriticalSection(m_args[0].m_cs);
m_isConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
}
void PhysicsServerExample::exitPhysics()
{
for (int i=0;i<MAX_MOTION_NUM_THREADS;i++)
{
m_args[i].m_cs->lock();
m_args[i].m_cs->setSharedParam(0,eRequestTerminateMotion);
m_args[i].m_cs->unlock();
}
int numActiveThreads = MAX_MOTION_NUM_THREADS;
while (numActiveThreads)
{
int arg0,arg1;
if (m_threadSupport->isTaskCompleted(&arg0,&arg1,0))
{
numActiveThreads--;
printf("numActiveThreads = %d\n",numActiveThreads);
} else
{
}
};
printf("stopping threads\n");
delete m_threadSupport;
m_threadSupport = 0;
//m_physicsServer.resetDynamicsWorld();
}
bool PhysicsServerExample::wantsTermination()
{
return m_wantsShutdown;
@@ -190,6 +607,93 @@ bool PhysicsServerExample::wantsTermination()
void PhysicsServerExample::stepSimulation(float deltaTime)
{
//this->m_physicsServer.processClientCommands();
//check if any graphics related tasks are requested
switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1))
{
case eGUIHelperCreateCollisionShapeGraphicsObject:
{
m_multiThreadedHelper->m_childGuiHelper->createCollisionShapeGraphicsObject(m_multiThreadedHelper->m_colShape);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperCreateCollisionObjectGraphicsObject:
{
m_multiThreadedHelper->m_childGuiHelper->createCollisionObjectGraphicsObject(m_multiThreadedHelper->m_obj,
m_multiThreadedHelper->m_color2);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperRegisterTexture:
{
m_multiThreadedHelper->m_textureId = m_multiThreadedHelper->m_childGuiHelper->registerTexture(m_multiThreadedHelper->m_texels,
m_multiThreadedHelper->m_textureWidth,m_multiThreadedHelper->m_textureHeight);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperRegisterGraphicsShape:
{
m_multiThreadedHelper->m_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape(
m_multiThreadedHelper->m_vertices,
m_multiThreadedHelper->m_numvertices,
m_multiThreadedHelper->m_indices,
m_multiThreadedHelper->m_numIndices,
m_multiThreadedHelper->m_primitiveType,
m_multiThreadedHelper->m_textureId);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperRegisterGraphicsInstance:
{
m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance(
m_multiThreadedHelper->m_shapeIndex,
m_multiThreadedHelper->m_position,
m_multiThreadedHelper->m_quaternion,
m_multiThreadedHelper->m_color,
m_multiThreadedHelper->m_scaling);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperRemoveAllGraphicsInstances:
{
m_multiThreadedHelper->m_childGuiHelper->removeAllGraphicsInstances();
int numRenderInstances = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
b3Assert(numRenderInstances==0);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperIdle:
default:
{
}
}
#if 0
if (m_options == PHYSICS_SERVER_USE_RTC_CLOCK)
{
btClock rtc;
@@ -201,15 +705,60 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
}
} else
{
for (int i=0;i<10;i++)
//for (int i=0;i<10;i++)
m_physicsServer.processClientCommands();
}
#endif
if (!blockme2)
{
if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
{
m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->writeTransforms();
}
}
}
void PhysicsServerExample::renderScene()
{
///debug rendering
//m_args[0].m_cs->lock();
m_physicsServer.renderScene();
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
{
//some little experiment to add text/HUD to a VR camera (HTC Vive/Oculus Rift)
static int frameCount=0;
frameCount++;
char bla[1024];
sprintf(bla,"VR sub-title text test, frame %d", frameCount/2);
float pos[4];
m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraTargetPosition(pos);
btTransform viewTr;
btScalar m[16];
float mf[16];
m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraViewMatrix(mf);
for (int i=0;i<16;i++)
{
m[i] = mf[i];
}
viewTr.setFromOpenGLMatrix(m);
btTransform viewTrInv = viewTr.inverse();
float upMag = -.6;
btVector3 side = viewTrInv.getBasis().getColumn(0);
btVector3 up = viewTrInv.getBasis().getColumn(1);
up+=0.35*side;
m_guiHelper->getAppInterface()->drawText3D(bla,pos[0]+upMag*up[0],pos[1]+upMag*up[1],pos[2]+upMag*up[2],1);
//btVector3 fwd = viewTrInv.getBasis().getColumn(2);
sprintf(bla,"VR line 2 sub-title text test, frame %d", frameCount/2);
upMag = -0.7;
m_guiHelper->getAppInterface()->drawText3D(bla,pos[0]+upMag*up[0],pos[1]+upMag*up[1],pos[2]+upMag*up[2],1);
}
//m_args[0].m_cs->unlock();
}
void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
@@ -290,7 +839,13 @@ extern int gSharedMemoryKey;
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
{
PhysicsServerExample* example = new PhysicsServerExample(options.m_guiHelper, options.m_sharedMem, options.m_option);
MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(),options.m_guiHelper);
PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
options.m_sharedMem,
options.m_option);
if (gSharedMemoryKey>=0)
{
example->setSharedMemoryKey(gSharedMemoryKey);
@@ -306,3 +861,5 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt
return example;
}
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)

View File

@@ -90,6 +90,11 @@ PhysicsServerSharedMemory::~PhysicsServerSharedMemory()
delete m_data;
}
void PhysicsServerSharedMemory::resetDynamicsWorld()
{
m_data->m_commandProcessor->deleteDynamicsWorld();
m_data->m_commandProcessor ->createEmptyDynamicsWorld();
}
void PhysicsServerSharedMemory::setSharedMemoryKey(int key)
{
m_data->m_sharedMemoryKey = key;

View File

@@ -43,6 +43,7 @@ public:
void enableCommandLogging(bool enable, const char* fileName);
void replayFromLogFile(const char* fileName);
void resetDynamicsWorld();
};

View File

@@ -15,7 +15,8 @@ links {
language "C++"
files {
myfiles =
{
"PhysicsClient.cpp",
"PhysicsClientSharedMemory.cpp",
"PhysicsClientExample.cpp",
@@ -24,7 +25,6 @@ files {
"PhysicsServerSharedMemory.h",
"PhysicsServer.cpp",
"PhysicsServer.h",
"main.cpp",
"PhysicsClientC_API.cpp",
"SharedMemoryCommands.h",
"SharedMemoryPublic.h",
@@ -76,11 +76,211 @@ files {
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
"../Importers/ImportColladaDemo/ColladaGraphicsInstance.h",
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
}
files {
myfiles,
"main.cpp",
}
files {
"../MultiThreading/b3ThreadSupportInterface.cpp",
"../MultiThreading/b3ThreadSupportInterface.h"
}
if os.is("Windows") then
files {
"../MultiThreading/b3Win32ThreadSupport.cpp",
"../MultiThreading/b3Win32ThreadSupport.h"
}
--links {"winmm"}
--defines {"__WINDOWS_MM__", "WIN32"}
end
if os.is("Linux") then
files {
"../MultiThreading/b3PosixThreadSupport.cpp",
"../MultiThreading/b3PosixThreadSupport.h"
}
links {"pthread"}
end
if os.is("MacOSX") then
files {
"../MultiThreading/b3PosixThreadSupport.cpp",
"../MultiThreading/b3PosixThreadSupport.h"
}
links {"pthread"}
--links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
--defines {"__MACOSX_CORE__"}
end
project "App_SharedMemoryPhysics_GUI"
if _OPTIONS["ios"] then
kind "WindowedApp"
else
kind "ConsoleApp"
end
defines {"B3_USE_STANDALONE_EXAMPLE"}
includedirs {"../../src"}
links {
"BulletDynamics","BulletCollision", "LinearMath", "OpenGL_Window","Bullet3Common"
}
initOpenGL()
initGlew()
language "C++"
files {
myfiles,
"../StandaloneMain/main_opengl_single_example.cpp",
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
}
if os.is("Linux") then initX11() end
if os.is("MacOSX") then
links{"Cocoa.framework"}
end
files {
"../MultiThreading/b3ThreadSupportInterface.cpp",
"../MultiThreading/b3ThreadSupportInterface.h"
}
if os.is("Windows") then
files {
"../MultiThreading/b3Win32ThreadSupport.cpp",
"../MultiThreading/b3Win32ThreadSupport.h"
}
--links {"winmm"}
--defines {"__WINDOWS_MM__", "WIN32"}
end
if os.is("Linux") then
files {
"../MultiThreading/b3PosixThreadSupport.cpp",
"../MultiThreading/b3PosixThreadSupport.h"
}
links {"pthread"}
end
if os.is("MacOSX") then
files {
"../MultiThreading/b3PosixThreadSupport.cpp",
"../MultiThreading/b3PosixThreadSupport.h"
}
links {"pthread"}
--links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
--defines {"__MACOSX_CORE__"}
end
if os.is("Windows") then
project "App_SharedMemoryPhysics_VR"
--for now, only enable VR under Windows, until compilation issues are resolved on Mac/Linux
defines {"B3_USE_STANDALONE_EXAMPLE","BT_ENABLE_VR"}
if _OPTIONS["ios"] then
kind "WindowedApp"
else
kind "ConsoleApp"
end
includedirs {
".","../../src", "../ThirdPartyLibs",
"../ThirdPartyLibs/openvr/headers",
"../ThirdPartyLibs/openvr/samples/shared"
}
links {
"Bullet3Common", "BulletDynamics","BulletCollision", "LinearMath","OpenGL_Window","openvr_api"
}
language "C++"
initOpenGL()
initGlew()
files
{
myfiles,
"../StandaloneMain/hellovr_opengl_main.cpp",
"../ExampleBrowser/OpenGLGuiHelper.cpp",
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
"../ThirdPartyLibs/openvr/samples/shared/lodepng.cpp",
"../ThirdPartyLibs/openvr/samples/shared/lodepng.h",
"../ThirdPartyLibs/openvr/samples/shared/Matrices.cpp",
"../ThirdPartyLibs/openvr/samples/shared/Matrices.h",
"../ThirdPartyLibs/openvr/samples/shared/pathtools.cpp",
"../ThirdPartyLibs/openvr/samples/shared/pathtools.h",
"../ThirdPartyLibs/openvr/samples/shared/Vectors.h",
}
if os.is("Windows") then
libdirs {"../ThirdPartyLibs/openvr/lib/win32"}
end
if os.is("Linux") then initX11() end
if os.is("MacOSX") then
links{"Cocoa.framework"}
end
files {
"../MultiThreading/b3ThreadSupportInterface.cpp",
"../MultiThreading/b3ThreadSupportInterface.h"
}
if os.is("Windows") then
files {
"../MultiThreading/b3Win32ThreadSupport.cpp",
"../MultiThreading/b3Win32ThreadSupport.h"
}
--links {"winmm"}
--defines {"__WINDOWS_MM__", "WIN32"}
end
if os.is("Linux") then
files {
"../MultiThreading/b3PosixThreadSupport.cpp",
"../MultiThreading/b3PosixThreadSupport.h"
}
links {"pthread"}
end
if os.is("MacOSX") then
files {
"../MultiThreading/b3PosixThreadSupport.cpp",
"../MultiThreading/b3PosixThreadSupport.h"
}
links {"pthread"}
--links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
--defines {"__MACOSX_CORE__"}
end
end

View File

@@ -11,6 +11,7 @@
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
int gSharedMemoryKey = -1;
//how can you try typing on a keyboard, without seeing it?
//it is pretty funny, to see the desktop in VR!
@@ -27,7 +28,7 @@
#include "pathtools.h"
CommonExampleInterface* sExample;
OpenGLGuiHelper* sGuiPtr = 0;
GUIHelperInterface* sGuiPtr = 0;
#if defined(POSIX)
@@ -139,7 +140,7 @@ private:
SimpleOpenGL3App* m_app;
uint32_t m_nWindowWidth;
uint32_t m_nWindowHeight;
bool m_hasContext;
private: // OpenGL bookkeeping
int m_iTrackedControllerCount;
@@ -234,6 +235,7 @@ private: // OpenGL bookkeeping
//-----------------------------------------------------------------------------
CMainApplication::CMainApplication( int argc, char *argv[] )
: m_app(NULL)
, m_hasContext(false)
, m_nWindowWidth( 1280 )
, m_nWindowHeight( 720 )
, m_unSceneProgramID( 0 )
@@ -373,7 +375,9 @@ bool CMainApplication::BInit()
*/
m_app = new SimpleOpenGL3App("SimpleOpenGL3App",m_nWindowWidth,m_nWindowHeight,true);
sGuiPtr = new OpenGLGuiHelper(m_app,false);
//sGuiPtr = new DummyGUIHelper;
CommonExampleOptions options(sGuiPtr);
@@ -556,13 +560,16 @@ void CMainApplication::Shutdown()
}
m_vecRenderModels.clear();
if( 1)//m_pContext )
if( m_hasContext)
{
glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_FALSE );
glDebugMessageCallback(nullptr, nullptr);
glDeleteBuffers(1, &m_glSceneVertBuffer);
glDeleteBuffers(1, &m_glIDVertBuffer);
glDeleteBuffers(1, &m_glIDIndexBuffer);
if (m_glSceneVertBuffer)
{
glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_FALSE );
glDebugMessageCallback(nullptr, nullptr);
glDeleteBuffers(1, &m_glSceneVertBuffer);
glDeleteBuffers(1, &m_glIDVertBuffer);
glDeleteBuffers(1, &m_glIDIndexBuffer);
}
if ( m_unSceneProgramID )
{
@@ -1067,6 +1074,7 @@ void CMainApplication::SetupScene()
glDisableVertexAttribArray(0);
glDisableVertexAttribArray(1);
m_hasContext = true;
}
@@ -1455,6 +1463,8 @@ void CMainApplication::SetupDistortion()
//-----------------------------------------------------------------------------
void CMainApplication::RenderStereoTargets()
{
sExample->stepSimulation(1./60.);
glClearColor( 0.15f, 0.15f, 0.18f, 1.0f ); // nice background color, but not black
glEnable( GL_MULTISAMPLE );
@@ -1462,31 +1472,75 @@ void CMainApplication::RenderStereoTargets()
m_app->m_instancingRenderer->init();
Matrix4 rotYtoZ = rotYtoZ.identity();
//some Bullet apps (especially robotics related) require Z as up-axis)
if (m_app->getUpAxis()==2)
{
rotYtoZ.rotateX(-90);
}
RenderScene( vr::Eye_Left );
// Left Eye
{
Matrix4 viewMatLeft = m_mat4eyePosLeft * m_mat4HMDPose;
Matrix4 viewMatLeft = m_mat4eyePosLeft * m_mat4HMDPose * rotYtoZ;
Matrix4 viewMatCenter = m_mat4HMDPose * rotYtoZ;
//0,1,2,3
//4,5,6,7,
//8,9,10,11
//12,13,14,15
//m_mat4eyePosLeft.get()[10]
//m_app->m_instancingRenderer->getActiveCamera()->setCameraTargetPosition(
// m_mat4eyePosLeft.get()[3],
// m_mat4eyePosLeft.get()[7],
// m_mat4eyePosLeft.get()[11]);
Matrix4 m;
m = viewMatCenter;
const float* mat = m.invertAffine().get();
/*printf("camera:\n,%f,%f,%f,%f\n%f,%f,%f,%f\n%f,%f,%f,%f\n%f,%f,%f,%f",
mat[0],mat[1],mat[2],mat[3],
mat[4],mat[5],mat[6],mat[7],
mat[8],mat[9],mat[10],mat[11],
mat[12],mat[13],mat[14],mat[15]);
*/
float dist=1;
m_app->m_instancingRenderer->getActiveCamera()->setCameraTargetPosition(
mat[12]-dist*mat[8],
mat[13]-dist*mat[9],
mat[14]-dist*mat[10]
);
m_app->m_instancingRenderer->getActiveCamera()->setCameraUpVector(mat[0],mat[1],mat[2]);
m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatLeft.get(),m_mat4ProjectionLeft.get());
m_app->m_instancingRenderer->updateCamera();
m_app->m_instancingRenderer->updateCamera(m_app->getUpAxis());
}
glBindFramebuffer( GL_FRAMEBUFFER, leftEyeDesc.m_nRenderFramebufferId );
glViewport(0, 0, m_nRenderWidth, m_nRenderHeight );
m_app->m_window->startRendering();
RenderScene( vr::Eye_Left );
m_app->drawGrid();
sExample->stepSimulation(1./60.);
sExample->renderScene();
m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)leftEyeDesc.m_nRenderFramebufferId);
m_app->m_instancingRenderer->renderScene();
sExample->renderScene();
//m_app->m_instancingRenderer->renderScene();
DrawGridData gridUp;
gridUp.upAxis = m_app->getUpAxis();
m_app->drawGrid(gridUp);
glBindFramebuffer( GL_FRAMEBUFFER, 0 );
@@ -1506,22 +1560,25 @@ void CMainApplication::RenderStereoTargets()
// Right Eye
{
Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose;
m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatRight.get(),m_mat4ProjectionRight.get());
m_app->m_instancingRenderer->updateCamera();
}
RenderScene( vr::Eye_Right );
{
Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose * rotYtoZ;
m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatRight.get(),m_mat4ProjectionRight.get());
m_app->m_instancingRenderer->updateCamera(m_app->getUpAxis());
}
glBindFramebuffer( GL_FRAMEBUFFER, rightEyeDesc.m_nRenderFramebufferId );
glViewport(0, 0, m_nRenderWidth, m_nRenderHeight );
m_app->m_window->startRendering();
RenderScene( vr::Eye_Right );
m_app->drawGrid();
m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId);
m_app->m_renderer->renderScene();
//m_app->m_renderer->renderScene();
sExample->renderScene();
m_app->drawGrid(gridUp);
glBindFramebuffer( GL_FRAMEBUFFER, 0 );

View File

@@ -17,14 +17,9 @@ subject to the following restrictions:
#include "../CommonInterfaces/CommonExampleInterface.h"
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
#include "../Utils/b3Clock.h"
#include "LinearMath/btTransform.h"
#include "LinearMath/btHashMap.h"
#include "../OpenGLWindow/SimpleOpenGL3App.h"
@@ -32,6 +27,7 @@ subject to the following restrictions:
#include "../ExampleBrowser/OpenGLGuiHelper.h"
CommonExampleInterface* example;
int gSharedMemoryKey=-1;
b3MouseMoveCallback prevMouseMoveCallback = 0;
static void OnMouseMove( float x, float y)
@@ -57,9 +53,23 @@ static void OnMouseDown(int button, int state, float x, float y) {
}
}
class LessDummyGuiHelper : public DummyGUIHelper
{
CommonGraphicsApp* m_app;
public:
virtual CommonGraphicsApp* getAppInterface()
{
return m_app;
}
LessDummyGuiHelper(CommonGraphicsApp* app)
:m_app(app)
{
}
};
int main(int argc, char* argv[])
{
SimpleOpenGL3App* app = new SimpleOpenGL3App("Bullet Standalone Example",1024,768,true);
prevMouseButtonCallback = app->m_window->getMouseButtonCallback();
@@ -69,20 +79,26 @@ int main(int argc, char* argv[])
app->m_window->setMouseMoveCallback((b3MouseMoveCallback)OnMouseMove);
OpenGLGuiHelper gui(app,false);
//LessDummyGuiHelper gui(app);
//DummyGUIHelper gui;
CommonExampleOptions options(&gui);
example = StandaloneExampleCreateFunc(options);
example->initPhysics();
example->initPhysics();
example->resetCamera();
b3Clock clock;
do
{
app->m_instancingRenderer->init();
app->m_instancingRenderer->updateCamera(app->getUpAxis());
example->stepSimulation(1./60.);
btScalar dtSec = btScalar(clock.getTimeInSeconds());
example->stepSimulation(dtSec);
clock.reset();
example->renderScene();
DrawGridData dg;

View File

@@ -105,14 +105,20 @@ public:
}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices)
virtual int registerTexture(const unsigned char* texels, int width, int height)
{
return -1;
}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
{
int shapeIndex = OpenGLGuiHelper::registerGraphicsShape(vertices,numvertices,indices,numIndices);
int shapeIndex = OpenGLGuiHelper::registerGraphicsShape(vertices,numvertices,indices,numIndices,primitiveType, textureId);
if (shapeIndex>=0)
{
TinyRenderObjectData* swObj = new TinyRenderObjectData(m_rgbColorBuffer,m_depthBuffer);
float rgbaColor[4] = {1,1,1,1};
swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor);
float rgbaColor[4] = {1,1,1,1};
swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor);
//swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices);
m_swRenderObjects.insert(shapeIndex,swObj);
}

View File

@@ -37,6 +37,12 @@ static btVector4 sMyColors[4] =
//btVector4(1,1,0,1),
};
struct TinyRendererTexture
{
const unsigned char* m_texels;
int m_width;
int m_height;
};
struct TinyRendererGUIHelper : public GUIHelperInterface
{
@@ -45,6 +51,7 @@ struct TinyRendererGUIHelper : public GUIHelperInterface
btHashMap<btHashInt,TinyRenderObjectData*> m_swRenderObjects;
btHashMap<btHashInt,int> m_swInstances;
btHashMap<btHashInt,TinyRendererTexture> m_textures;
int m_swWidth;
int m_swHeight;
@@ -151,7 +158,8 @@ struct TinyRendererGUIHelper : public GUIHelperInterface
if (gfxVertices.size() && indices.size())
{
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size());
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size(),
1,-1);
collisionShape->setUserIndex(shapeId);
}
}
@@ -249,18 +257,41 @@ struct TinyRendererGUIHelper : public GUIHelperInterface
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld){}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices)
virtual int registerTexture(const unsigned char* texels, int width, int height)
{
//do we need to make a copy?
int textureId = m_textures.size();
TinyRendererTexture t;
t.m_texels = texels;
t.m_width = width;
t.m_height = height;
this->m_textures.insert(textureId,t);
return textureId;
}
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
{
int shapeIndex = m_swRenderObjects.size();
TinyRenderObjectData* swObj = new TinyRenderObjectData(m_rgbColorBuffer,m_depthBuffer);
float rgbaColor[4] = {1,1,1,1};
swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor);
//if (textureId>=0)
//{
// swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor);
//} else
{
swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor);
}
//swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices);
m_swRenderObjects.insert(shapeIndex,swObj);
return shapeIndex;
}
virtual void removeAllGraphicsInstances()
{
}
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
{
int colIndex = m_colObjUniqueIndex++;

View File

@@ -0,0 +1,27 @@
Copyright (c) 2015, Valve Corporation
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation and/or
other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

View File

@@ -0,0 +1,9 @@
OpenVR is an API and runtime that allows access to VR hardware from multiple
vendors without requiring that applications have specific knowledge of the
hardware they are targeting. This repository is an SDK that contains the API
and samples. The runtime is under SteamVR in Tools on Steam.
Documentation for the API is available in the wiki: https://github.com/ValveSoftware/openvr/wiki/API-Documentation
More information on OpenVR and SteamVR can be found on http://steamvr.com

View File

@@ -166,7 +166,7 @@ unsigned long int b3Clock::getTimeMilliseconds()
/// Returns the time in us since the last call to reset or since
/// the Clock was created.
unsigned long int b3Clock::getTimeMicroseconds()
unsigned long long int b3Clock::getTimeMicroseconds()
{
#ifdef B3_USE_WINDOWS_TIMERS
LARGE_INTEGER currentTime;
@@ -175,14 +175,14 @@ unsigned long int b3Clock::getTimeMicroseconds()
m_data->mStartTime.QuadPart;
// Compute the number of millisecond ticks elapsed.
unsigned long msecTicks = (unsigned long)(1000 * elapsedTime /
unsigned long long msecTicks = (unsigned long long)(1000 * elapsedTime /
m_data->mClockFrequency.QuadPart);
// Check for unexpected leaps in the Win32 performance counter.
// (This is caused by unexpected data across the PCI to ISA
// bridge, aka south bridge. See Microsoft KB274323.)
unsigned long elapsedTicks = GetTickCount() - m_data->mStartTick;
signed long msecOff = (signed long)(msecTicks - elapsedTicks);
unsigned long long elapsedTicks = GetTickCount() - m_data->mStartTick;
signed long long msecOff = (signed long)(msecTicks - elapsedTicks);
if (msecOff < -100 || msecOff > 100)
{
// Adjust the starting time forwards.
@@ -197,7 +197,7 @@ unsigned long int b3Clock::getTimeMicroseconds()
m_data->mPrevElapsedTime = elapsedTime;
// Convert to microseconds.
unsigned long usecTicks = (unsigned long)(1000000 * elapsedTime /
unsigned long long usecTicks = (unsigned long)(1000000 * elapsedTime /
m_data->mClockFrequency.QuadPart);
return usecTicks;
@@ -222,3 +222,8 @@ unsigned long int b3Clock::getTimeMicroseconds()
#endif
}
double b3Clock::getTimeInSeconds()
{
return double(getTimeMicroseconds()/1.e6);
}

View File

@@ -22,7 +22,12 @@ public:
/// Returns the time in us since the last call to reset or since
/// the Clock was created.
unsigned long int getTimeMicroseconds();
unsigned long long int getTimeMicroseconds();
/// Returns the time in seconds since the last call to reset or since
/// the Clock was created.
double getTimeInSeconds();
private:
struct b3ClockData* m_data;
};

View File

@@ -172,6 +172,8 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
&startOrnX,&startOrnY,&startOrnZ, &startOrnW))
return NULL;
}
if (strlen(urdfFileName))
{
// printf("(%f, %f, %f) (%f, %f, %f, %f)\n", startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW);
@@ -185,12 +187,16 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType!=CMD_URDF_LOADING_COMPLETED)
{
PyErr_SetString(SpamError, "Cannot load URDF file.");
return NULL;
}
{
PyErr_SetString(SpamError, "Cannot load URDF file.");
return NULL;
}
bodyIndex = b3GetStatusBodyIndex(statusHandle);
}
} else
{
PyErr_SetString(SpamError, "Empty filename, method expects 1, 4 or 8 arguments.");
return NULL;
}
return PyLong_FromLong(bodyIndex);
}
@@ -368,8 +374,8 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args)
{
case CONTROL_MODE_VELOCITY:
{
double kd = gains;
b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetValue);
double kd = gains;
b3JointControlSetKd(commandHandle,info.m_uIndex,kd);
b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce);
break;
@@ -383,8 +389,8 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args)
case CONTROL_MODE_POSITION_VELOCITY_PD:
{
double kp = gains;
b3JointControlSetDesiredPosition( commandHandle, info.m_qIndex, targetValue);
double kp = gains;
b3JointControlSetKp(commandHandle,info.m_uIndex,kp);
b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce);
break;
@@ -1264,10 +1270,12 @@ static PyObject* pybullet_applyExternalTorque(PyObject* self, PyObject* args)
PyErr_SetString(SpamError, "flag has to be either WORLD_FRAME or LINK_FRAME");
return NULL;
}
b3SharedMemoryStatusHandle statusHandle;
b3SharedMemoryCommandHandle command = b3ApplyExternalForceCommandInit(sm);
b3ApplyExternalTorque(command,objectUniqueId,-1,torque, flags);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
{
b3SharedMemoryStatusHandle statusHandle;
b3SharedMemoryCommandHandle command = b3ApplyExternalForceCommandInit(sm);
b3ApplyExternalTorque(command,objectUniqueId,-1,torque, flags);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
}
}
}
@@ -1383,12 +1391,13 @@ static PyObject* pybullet_getEulerFromQuaternion(PyObject* self, PyObject* args)
{
double rpy[3];
sqx = quat[0] * quat[0];
double sarg;
sqx = quat[0] * quat[0];
sqy = quat[1] * quat[1];
sqz = quat[2] * quat[2];
squ = quat[3] * quat[3];
rpy[0] = atan2(2 * (quat[1]*quat[2] + quat[3]*quat[0]), squ - sqx - sqy + sqz);
double sarg = -2 * (quat[0]*quat[2] - quat[3] * quat[1]);
sarg = -2 * (quat[0]*quat[2] - quat[3] * quat[1]);
rpy[1] = sarg <= -1.0 ? -0.5*3.141592538 : (sarg >= 1.0 ? 0.5*3.141592538 : asin(sarg));
rpy[2] = atan2(2 * (quat[0]*quat[1] + quat[3]*quat[2]), squ + sqx - sqy - sqz);
{

View File

@@ -389,16 +389,8 @@ void bDNA::init(char *data, int len, bool swap)
}
{
nr= (long)cp;
//long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = b3AlignPointer(cp,4);
/*
TYPE (4 bytes)
@@ -425,16 +417,8 @@ void bDNA::init(char *data, int len, bool swap)
cp++;
}
{
nr= (long)cp;
// long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = b3AlignPointer(cp,4);
/*
TLEN (4 bytes)

View File

@@ -428,16 +428,7 @@ void bFile::swapDNA(char* ptr)
}
{
nr= (long)cp;
//long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = b3AlignPointer(cp,4);
/*
TYPE (4 bytes)
@@ -465,16 +456,7 @@ void bFile::swapDNA(char* ptr)
cp++;
}
{
nr= (long)cp;
// long mask=3;
nr= ((nr+3)&~3)-nr;
while (nr--)
{
cp++;
}
}
cp = b3AlignPointer(cp,4);
/*
TLEN (4 bytes)

View File

@@ -106,7 +106,7 @@ void testSharedMemory(b3PhysicsClientHandle sm)
b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName);
//setting the initial position, orientation and other arguments are optional
startPosX =0;
startPosX =2;
startPosY =0;
startPosZ = 1;
ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);