This commit is contained in:
Erwin Coumans
2016-05-13 22:42:25 -07:00
15 changed files with 273 additions and 275 deletions

View File

@@ -226,7 +226,7 @@ public:
{ {
char relativeFileName[1024]; char relativeFileName[1024];
sprintf(relativeFileName,"%s%s",prefix[i],filename); sprintf(relativeFileName,"%s%s",prefix[i],filename);
image = stbi_load(relativeFileName, &width, &height, &n, 0); image = stbi_load(relativeFileName, &width, &height, &n, 3);
} }
b3Assert(image); b3Assert(image);

View File

@@ -121,6 +121,7 @@ struct CommonGraphicsApp
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0; virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0;
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)=0; virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)=0;
virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1) = 0; virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1) = 0;
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4])=0; virtual void registerGrid(int xres, int yres, float color0[4], float color1[4])=0;

View File

@@ -29,7 +29,6 @@ ENDIF(WIN32)
ADD_LIBRARY(BulletExampleBrowserLib ADD_LIBRARY(BulletExampleBrowserLib
OpenGLExampleBrowser.cpp OpenGLExampleBrowser.cpp
OpenGLGuiHelper.cpp OpenGLGuiHelper.cpp
InProcessExampleBrowser.cpp
GL_ShapeDrawer.cpp GL_ShapeDrawer.cpp
CollisionShape2TriangleMesh.cpp CollisionShape2TriangleMesh.cpp
CollisionShape2TriangleMesh.h CollisionShape2TriangleMesh.h
@@ -120,7 +119,6 @@ SET(ExtendedTutorialsSources
SET(BulletExampleBrowser_SRCS SET(BulletExampleBrowser_SRCS
../TinyRenderer/Bullet2TinyRenderer.cpp
../TinyRenderer/geometry.cpp ../TinyRenderer/geometry.cpp
../TinyRenderer/model.cpp ../TinyRenderer/model.cpp
../TinyRenderer/tgaimage.cpp ../TinyRenderer/tgaimage.cpp
@@ -205,7 +203,8 @@ SET(BulletExampleBrowser_SRCS
../Importers/ImportBsp/BspConverter.h ../Importers/ImportBsp/BspConverter.h
../Importers/ImportBullet/SerializeSetup.cpp ../Importers/ImportBullet/SerializeSetup.cpp
../Importers/ImportBullet/SerializeSetup.h ../Importers/ImportBullet/SerializeSetup.h
../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../Importers/ImportMeshUtility/b3ImportMeshUtility.h
../../Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp ../../Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp
../../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp ../../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp
../../Extras/Serialize/BulletFileLoader/bChunk.cpp ../../Extras/Serialize/BulletFileLoader/bChunk.cpp
@@ -286,6 +285,7 @@ SET(BulletExampleBrowser_SRCS
../ThirdPartyLibs/tinyxml/tinyxml.cpp ../ThirdPartyLibs/tinyxml/tinyxml.cpp
../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp ../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp ../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
InProcessExampleBrowser.cpp
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc ${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
) )

View File

@@ -0,0 +1,97 @@
#include "b3ImportMeshUtility.h"
#include <vector>
#include "../../OpenGLWindow/GLInstancingRenderer.h"
#include"Wavefront/tiny_obj_loader.h"
#include "../../OpenGLWindow/GLInstanceGraphicsShape.h"
#include "btBulletDynamicsCommon.h"
#include "../../OpenGLWindow/SimpleOpenGL3App.h"
#include "../ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h"
#include "../../Utils/b3ResourcePath.h"
#include "Bullet3Common/b3FileUtils.h"
#include "stb_image/stb_image.h"
int b3ImportMeshUtility::loadAndRegisterMeshFromFile(const std::string& fileName, CommonRenderInterface* renderer)
{
int shapeId = -1;
char relativeFileName[1024];
if (b3ResourcePath::findResourcePath(fileName.c_str(), relativeFileName, 1024))
{
char pathPrefix[1024];
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
btVector3 shift(0,0,0);
// int index=10;
{
std::vector<tinyobj::shape_t> shapes;
std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);
int textureIndex = -1;
//try to load some texture
for (int i=0;i<shapes.size();i++)
{
const tinyobj::shape_t& shape = shapes[i];
if (shape.material.diffuse_texname.length()>0)
{
int width,height,n;
const char* filename = shape.material.diffuse_texname.c_str();
const unsigned char* image=0;
const char* prefix[]={ pathPrefix,"./","./data/","../data/","../../data/","../../../data/","../../../../data/"};
int numprefix = sizeof(prefix)/sizeof(const char*);
for (int i=0;!image && i<numprefix;i++)
{
char relativeFileName[1024];
sprintf(relativeFileName,"%s%s",prefix[i],filename);
char relativeFileName2[1024];
if (b3ResourcePath::findResourcePath(relativeFileName, relativeFileName2, 1024))
{
image = stbi_load(relativeFileName, &width, &height, &n, 3);
} else
{
b3Warning("not found %s\n",relativeFileName);
}
}
if (image)
{
textureIndex = renderer->registerTexture(image,width,height);
if (textureIndex>=0)
{
break;
}
}
}
}
shapeId = renderer->registerShape(&gfxShape->m_vertices->at(0).xyzw[0], gfxShape->m_numvertices, &gfxShape->m_indices->at(0), gfxShape->m_numIndices,B3_GL_TRIANGLES,textureIndex);
}
}
else
{
b3Warning("Cannot find %s\n", fileName.c_str());
}
return shapeId;
}

View File

@@ -0,0 +1,15 @@
#ifndef B3_IMPORT_MESH_UTILITY_H
#define B3_IMPORT_MESH_UTILIY_H
#include <string>
class b3ImportMeshUtility
{
public:
static int loadAndRegisterMeshFromFile(const std::string& fileName, class CommonRenderInterface* renderer);
};
#endif //B3_IMPORT_MESH_UTILITY_H

View File

@@ -12,7 +12,7 @@
#include "stb_image/stb_image.h" #include "stb_image/stb_image.h"
#include "../CommonInterfaces/CommonRigidBodyBase.h" #include "../CommonInterfaces/CommonRigidBodyBase.h"
#include "../ImportMeshUtility/b3ImportMeshUtility.h"
class ImportObjSetup : public CommonRigidBodyBase class ImportObjSetup : public CommonRigidBodyBase
{ {
@@ -45,7 +45,7 @@ ImportObjSetup::ImportObjSetup(struct GUIHelperInterface* helper, const char* fi
m_fileName = fileName; m_fileName = fileName;
} else } else
{ {
m_fileName = "cube.obj";//sphere8.obj";//sponza_closed.obj";//sphere8.obj"; m_fileName = "cube.obj";//"sponza_closed.obj";//sphere8.obj";
} }
} }
@@ -68,82 +68,21 @@ void ImportObjSetup::initPhysics()
m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe); m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe);
btTransform trans;
char relativeFileName[1024]; trans.setIdentity();
if (b3ResourcePath::findResourcePath(m_fileName.c_str(), relativeFileName, 1024)) trans.setRotation(btQuaternion(btVector3(1,0,0),SIMD_HALF_PI));
{ btVector3 position = trans.getOrigin();
char pathPrefix[1024]; btQuaternion orn = trans.getRotation();
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
btVector3 shift(0,0,0);
btVector3 scaling(1,1,1);
// int index=10;
{
std::vector<tinyobj::shape_t> shapes; btVector3 scaling(1,1,1);
std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix); btVector3 color(1,1,1);
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes); int shapeId = b3ImportMeshUtility::loadAndRegisterMeshFromFile(m_fileName, m_guiHelper->getRenderInterface());
if (shapeId>=0)
btTransform trans; {
trans.setIdentity(); //int id =
trans.setRotation(btQuaternion(btVector3(1,0,0),SIMD_HALF_PI)); m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
}
btVector3 position = trans.getOrigin();
btQuaternion orn = trans.getRotation();
btVector3 color(1,1,1);
int textureIndex = -1;
//try to load some texture
for (int i=0;i<shapes.size();i++)
{
const tinyobj::shape_t& shape = shapes[i];
if (shape.material.diffuse_texname.length()>0)
{
int width,height,n;
const char* filename = shape.material.diffuse_texname.c_str();
const unsigned char* image=0;
const char* prefix[]={ pathPrefix,"./","./data/","../data/","../../data/","../../../data/","../../../../data/"};
int numprefix = sizeof(prefix)/sizeof(const char*);
for (int i=0;!image && i<numprefix;i++)
{
char relativeFileName[1024];
sprintf(relativeFileName,"%s%s",prefix[i],filename);
image = stbi_load(relativeFileName, &width, &height, &n, 0);
}
if (image)
{
textureIndex = m_guiHelper->getRenderInterface()->registerTexture(image,width,height);
if (textureIndex>=0)
{
break;
}
}
}
}
int shapeId = m_guiHelper->getRenderInterface()->registerShape(&gfxShape->m_vertices->at(0).xyzw[0], gfxShape->m_numvertices, &gfxShape->m_indices->at(0), gfxShape->m_numIndices,B3_GL_TRIANGLES,textureIndex);
//int id =
m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
}}
else
{
b3Warning("Cannot find %s\n", m_fileName.c_str());
}
} }

View File

@@ -8,7 +8,7 @@
#include "../../OpenGLWindow/GLInstancingRenderer.h" #include "../../OpenGLWindow/GLInstancingRenderer.h"
#include "../../OpenGLWindow/GLInstanceGraphicsShape.h" #include "../../OpenGLWindow/GLInstanceGraphicsShape.h"
GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tinyobj::shape_t>& shapes) GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tinyobj::shape_t>& shapes, bool flatShading)
{ {
b3AlignedObjectArray<GLInstanceVertex>* vertices = new b3AlignedObjectArray<GLInstanceVertex>; b3AlignedObjectArray<GLInstanceVertex>* vertices = new b3AlignedObjectArray<GLInstanceVertex>;
@@ -82,29 +82,59 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
} }
btVector3 v0(vtx0.xyzw[0],vtx0.xyzw[1],vtx0.xyzw[2]); btVector3 v0(vtx0.xyzw[0],vtx0.xyzw[1],vtx0.xyzw[2]);
btVector3 v1(vtx1.xyzw[0],vtx1.xyzw[1],vtx1.xyzw[2]); btVector3 v1(vtx1.xyzw[0],vtx1.xyzw[1],vtx1.xyzw[2]);
btVector3 v2(vtx2.xyzw[0],vtx2.xyzw[1],vtx2.xyzw[2]); btVector3 v2(vtx2.xyzw[0],vtx2.xyzw[1],vtx2.xyzw[2]);
normal = (v1-v0).cross(v2-v0); unsigned int maxIndex = 0;
btScalar len2 = normal.length2(); maxIndex = b3Max(maxIndex,shape.mesh.indices[f]*3+0);
//skip degenerate triangles maxIndex = b3Max(maxIndex,shape.mesh.indices[f]*3+1);
if (len2 > SIMD_EPSILON) maxIndex = b3Max(maxIndex,shape.mesh.indices[f]*3+2);
maxIndex = b3Max(maxIndex,shape.mesh.indices[f+1]*3+0);
maxIndex = b3Max(maxIndex,shape.mesh.indices[f+1]*3+1);
maxIndex = b3Max(maxIndex,shape.mesh.indices[f+1]*3+2);
maxIndex = b3Max(maxIndex,shape.mesh.indices[f+2]*3+0);
maxIndex = b3Max(maxIndex,shape.mesh.indices[f+2]*3+1);
maxIndex = b3Max(maxIndex,shape.mesh.indices[f+2]*3+2);
bool hasNormals = (shape.mesh.normals.size() && maxIndex<shape.mesh.normals.size() );
if (flatShading || !hasNormals)
{ {
normal.normalize(); normal = (v1-v0).cross(v2-v0);
btScalar len2 = normal.length2();
//skip degenerate triangles
if (len2 > SIMD_EPSILON)
{
normal.normalize();
} else
{
normal.setValue(0,0,0);
}
vtx0.normal[0] = normal[0];
vtx0.normal[1] = normal[1];
vtx0.normal[2] = normal[2];
vtx1.normal[0] = normal[0];
vtx1.normal[1] = normal[1];
vtx1.normal[2] = normal[2];
vtx2.normal[0] = normal[0];
vtx2.normal[1] = normal[1];
vtx2.normal[2] = normal[2];
} else } else
{ {
normal.setValue(0,0,0);
vtx0.normal[0] = shape.mesh.normals[shape.mesh.indices[f]*3+0];
vtx0.normal[1] = shape.mesh.normals[shape.mesh.indices[f]*3+1];
vtx0.normal[2] = shape.mesh.normals[shape.mesh.indices[f]*3+2]; //shape.mesh.indices[f+1]*3+0
vtx1.normal[0] = shape.mesh.normals[shape.mesh.indices[f+1]*3+0];
vtx1.normal[1] = shape.mesh.normals[shape.mesh.indices[f+1]*3+1];
vtx1.normal[2] = shape.mesh.normals[shape.mesh.indices[f+1]*3+2];
vtx2.normal[0] = shape.mesh.normals[shape.mesh.indices[f+2]*3+0];
vtx2.normal[1] = shape.mesh.normals[shape.mesh.indices[f+2]*3+1];
vtx2.normal[2] = shape.mesh.normals[shape.mesh.indices[f+2]*3+2];
} }
vtx0.normal[0] = normal[0];
vtx0.normal[1] = normal[1];
vtx0.normal[2] = normal[2];
vtx1.normal[0] = normal[0];
vtx1.normal[1] = normal[1];
vtx1.normal[2] = normal[2];
vtx2.normal[0] = normal[0];
vtx2.normal[1] = normal[1];
vtx2.normal[2] = normal[2];
vertices->push_back(vtx0); vertices->push_back(vtx0);
vertices->push_back(vtx1); vertices->push_back(vtx1);
vertices->push_back(vtx2); vertices->push_back(vtx2);

View File

@@ -4,6 +4,6 @@
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h" #include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
#include <vector> #include <vector>
struct GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tinyobj::shape_t>& shapes); struct GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tinyobj::shape_t>& shapes, bool flatShading=false);
#endif //WAVEFRONT2GRAPHICS_H #endif //WAVEFRONT2GRAPHICS_H

View File

@@ -356,7 +356,7 @@ b3Vector3 GpuRigidBodyDemo::getRayTo(int x,int y)
unsigned char* GpuRigidBodyDemo::loadImage(const char* fileName, int& width, int& height, int& n) unsigned char* GpuRigidBodyDemo::loadImage(const char* fileName, int& width, int& height, int& n)
{ {
unsigned char *data = stbi_load(fileName, &width, &height, &n, 0); unsigned char *data = stbi_load(fileName, &width, &height, &n, 3);
return data; return data;
} }

View File

@@ -114,7 +114,7 @@ struct TinyRendererSetupInternalData
for (int i=0;i<numObjects;i++) for (int i=0;i<numObjects;i++)
{ {
m_transforms[i].setIdentity(); m_transforms[i].setIdentity();
btVector3 pos(0.f,0.f,-(2.5* numObjects * 0.5)+i*2.5f); btVector3 pos(0.f,-(2.5* numObjects * 0.5)+i*2.5f, 0.f);
m_transforms[i].setIdentity(); m_transforms[i].setIdentity();
m_transforms[i].setOrigin( pos ); m_transforms[i].setOrigin( pos );
btQuaternion orn; btQuaternion orn;
@@ -146,7 +146,8 @@ void TinyRendererSetup::initPhysics()
//request a visual bitma/texture we can render to //request a visual bitma/texture we can render to
m_app->setUpAxis(2);
m_internalData->m_canvas = m_app->m_2dCanvasInterface; m_internalData->m_canvas = m_app->m_2dCanvasInterface;
@@ -206,7 +207,7 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
} }
ATTRIBUTE_ALIGNED16(float modelMat[16]); ATTRIBUTE_ALIGNED16(btScalar modelMat2[16]);
ATTRIBUTE_ALIGNED16(float viewMat[16]); ATTRIBUTE_ALIGNED16(float viewMat[16]);
CommonRenderInterface* render = this->m_app->m_renderer; CommonRenderInterface* render = this->m_app->m_renderer;
render->getActiveCamera()->getCameraViewMatrix(viewMat); render->getActiveCamera()->getCameraViewMatrix(viewMat);
@@ -215,15 +216,16 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
for (int o=0;o<this->m_internalData->m_renderObjects.size();o++) for (int o=0;o<this->m_internalData->m_renderObjects.size();o++)
{ {
const btTransform& tr = m_internalData->m_transforms[o]; const btTransform& tr = m_internalData->m_transforms[o];
tr.getOpenGLMatrix(modelMat); tr.getOpenGLMatrix(modelMat2);
for (int i=0;i<4;i++) for (int i=0;i<4;i++)
{ {
for (int j=0;j<4;j++) for (int j=0;j<4;j++)
{ {
m_internalData->m_renderObjects[o]->m_modelMatrix[i][j] = modelMat[i+4*j]; m_internalData->m_renderObjects[o]->m_modelMatrix[i][j] = float(modelMat2[i+4*j]);
m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j]; m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j];
} }
} }

View File

@@ -30,6 +30,40 @@
namespace tinyobj { namespace tinyobj {
//See http://stackoverflow.com/questions/6089231/getting-std-ifstream-to-handle-lf-cr-and-crlf
std::istream& safeGetline(std::istream& is, std::string& t)
{
t.clear();
// The characters in the stream are read one-by-one using a std::streambuf.
// That is faster than reading them one-by-one using the std::istream.
// Code that uses streambuf this way must be guarded by a sentry object.
// The sentry object performs various tasks,
// such as thread synchronization and updating the stream state.
std::istream::sentry se(is, true);
std::streambuf* sb = is.rdbuf();
for(;;) {
int c = sb->sbumpc();
switch (c) {
case '\n':
return is;
case '\r':
if(sb->sgetc() == '\n')
sb->sbumpc();
return is;
case EOF:
// Also handle the case when the last line has no line ending
if(t.empty())
is.setstate(std::ios::eofbit);
return is;
default:
t += (char)c;
}
}
}
struct vertex_index { struct vertex_index {
int v_idx, vt_idx, vn_idx, dummy; int v_idx, vt_idx, vn_idx, dummy;
}; };
@@ -313,9 +347,11 @@ std::string LoadMtl (
int maxchars = 8192; // Alloc enough size. int maxchars = 8192; // Alloc enough size.
std::vector<char> buf(maxchars); // Alloc enough size. std::vector<char> buf(maxchars); // Alloc enough size.
while (ifs.peek() != -1) { while (ifs.peek() != -1) {
ifs.getline(&buf[0], maxchars);
std::string linebuf(&buf[0]); std::string linebuf;
safeGetline(ifs,linebuf);
// Trim newline '\r\n' or '\r' // Trim newline '\r\n' or '\r'
if (linebuf.size() > 0) { if (linebuf.size() > 0) {
@@ -502,9 +538,9 @@ LoadObj(
int maxchars = 8192; // Alloc enough size. int maxchars = 8192; // Alloc enough size.
std::vector<char> buf(maxchars); // Alloc enough size. std::vector<char> buf(maxchars); // Alloc enough size.
while (ifs.peek() != -1) { while (ifs.peek() != -1) {
ifs.getline(&buf[0], maxchars);
std::string linebuf(&buf[0]); std::string linebuf;
safeGetline(ifs,linebuf);
// Trim newline '\r\n' or '\r' // Trim newline '\r\n' or '\r'
if (linebuf.size() > 0) { if (linebuf.size() > 0) {

View File

@@ -1,164 +0,0 @@
#include "TinyRenderer.h"
#include <stdio.h>
#include "LinearMath/btHashMap.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
class Bullet2TinyRenderer
{
btAlignedObjectArray<TinyRenderObjectData*> m_swRenderObjects;
btHashMap<btHashPtr,int> m_colObject2gfxIndex;
btHashMap<btHashPtr,int> m_colShape2gfxIndex;
int m_swWidth;
int m_swHeight;
TGAImage m_rgbColorBuffer;
b3AlignedObjectArray<float> m_depthBuffer;
int m_textureHandle;
unsigned char* m_image;
public:
Bullet2TinyRenderer (int swWidth, int swHeight):
m_swWidth(swWidth),
m_swHeight(swHeight),
m_rgbColorBuffer(swWidth,swHeight,TGAImage::RGB)
{
m_depthBuffer.resize(swWidth*swHeight);
m_image=new unsigned char[m_swWidth*m_swHeight*4];
}
virtual ~Bullet2TinyRenderer()
{
for (int i=0;i<m_swRenderObjects.size();i++)
{
TinyRenderObjectData* d = m_swRenderObjects[i];
delete d;
}
}
void clearBuffers(TGAColor& clearColor)
{
for(int y=0;y<m_swHeight;++y)
{
for(int x=0;x<m_swWidth;++x)
{
m_rgbColorBuffer.set(x,y,clearColor);
m_depthBuffer[x+y*m_swWidth] = -1e30f;
}
}
}
const TGAImage& getFrameBuffer() const
{
return m_rgbColorBuffer;
}
virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj,const btVector3& color)
{
int* colIndexPtr = m_colObject2gfxIndex[obj];
int* shapeIndexPtr = m_colShape2gfxIndex[obj->getCollisionShape()];
//if (colIndex>=0 && shapeIndex>=0)
//{
// m_col2gfxIndex.insert(colIndex,shapeIndex);
//}
}
/* virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices)
{
if (shapeIndex>=0)
{
TinyRenderObjectData* swObj = new TinyRenderObjectData(m_swWidth,m_swHeight,m_rgbColorBuffer,m_depthBuffer);
swObj->registerMeshShape(vertices,numvertices,indices,numIndices);
//swObj->createCube(1,1,1);
m_swRenderObjects.insert(shapeIndex,swObj);
}
return shapeIndex;
}
*/
virtual void render(const btDiscreteDynamicsWorld* rbWorld, float viewMat[16])
{
//clear the color buffer
TGAColor clearColor;
clearColor.bgra[0] = 255;
clearColor.bgra[1] = 255;
clearColor.bgra[2] = 255;
clearColor.bgra[3] = 255;
clearBuffers(clearColor);
ATTRIBUTE_ALIGNED16(float modelMat[16]);
for (int i=0;i<rbWorld->getNumCollisionObjects();i++)
{
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
int* colObjIndexPtr = m_colObject2gfxIndex[colObj];
if (colObjIndexPtr)
{
int colObjIndex = *colObjIndexPtr;
TinyRenderObjectData* renderObj = m_swRenderObjects[colObjIndex];
//sync the object transform
const btTransform& tr = colObj->getWorldTransform();
tr.getOpenGLMatrix(modelMat);
for (int i=0;i<4;i++)
{
for (int j=0;j<4;j++)
{
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
}
}
TinyRenderer::renderObject(*renderObj);
}
}
for(int y=0;y<m_swHeight;++y)
{
unsigned char* pi=m_image+(y)*m_swWidth*3;
for(int x=0;x<m_swWidth;++x)
{
const TGAColor& color = getFrameBuffer().get(x,y);
pi[0] = color.bgra[2];
pi[1] = color.bgra[1];
pi[2] = color.bgra[0];
pi+=3;
}
}
static int counter=0;
counter++;
if (counter>10)
{
counter=0;
getFrameBuffer().write_tga_file("/Users/erwincoumans/develop/bullet3/framebuf.tga",true);
}
}
};

View File

@@ -415,7 +415,7 @@ public:
{ {
char relativeFileName[1024]; char relativeFileName[1024];
sprintf(relativeFileName,"%s%s",prefix[i],filename); sprintf(relativeFileName,"%s%s",prefix[i],filename);
image = stbi_load(relativeFileName, &width, &height, &n, 0); image = stbi_load(relativeFileName, &width, &height, &n, 3);
} }
b3Assert(image); b3Assert(image);

View File

@@ -161,7 +161,7 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
-- } -- }
hasCL = findOpenCL("clew") hasCL = findOpenCL("clew")
links{"BulletExampleBrowserLib","gwen", "OpenGL_Window","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","Bullet3Common"} links{"BulletExampleBrowserLib","gwen", "OpenGL_Window","BulletFileLoader","BulletWorldImporter","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","Bullet3Common"}
initOpenGL() initOpenGL()
initGlew() initGlew()
@@ -188,7 +188,49 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
files { files {
"test.c", "test.c",
"../../examples/ExampleBrowser/ExampleEntries.cpp", "../../examples/ExampleBrowser/InProcessExampleBrowser.cpp",
"../../examples/SharedMemory/InProcessMemory.cpp",
"../../examples/SharedMemory/PhysicsClient.cpp",
"../../examples/SharedMemory/PhysicsClient.h",
"../../examples/SharedMemory/PhysicsServer.cpp",
"../../examples/SharedMemory/PhysicsServer.h",
"../../examples/SharedMemory/PhysicsServerExample.cpp",
"../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp",
"../../examples/SharedMemory/PhysicsServerSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsServerSharedMemory.h",
"../../examples/SharedMemory/PhysicsDirect.cpp",
"../../examples/SharedMemory/PhysicsDirect.h",
"../../examples/SharedMemory/PhysicsDirectC_API.cpp",
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientC_API.cpp",
"../../examples/SharedMemory/PhysicsClientC_API.h",
"../../examples/SharedMemory/Win32SharedMemory.cpp",
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/Utils/b3ResourcePath.cpp",
"../../examples/Utils/b3ResourcePath.h",
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
"../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp",
"../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
"../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp",
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
"../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../../examples/MultiThreading/b3PosixThreadSupport.cpp",
"../../examples/MultiThreading/b3Win32ThreadSupport.cpp",
"../../examples/MultiThreading/b3ThreadSupportInterface.cpp",
} }
if os.is("Linux") then if os.is("Linux") then
initX11() initX11()