Use more googley colors in the examples.

Add high-resolution textured sphere, and automatically convert sphere, capsule and multi-sphere shape to use this, with caching to avoid duplicates.
This commit is contained in:
Erwin Coumans
2017-05-11 22:59:27 -07:00
parent 951da22e59
commit b22ffcf61c
4 changed files with 7758 additions and 9 deletions

View File

@@ -7,6 +7,7 @@
#include "Bullet3Common/b3Scalar.h"
#include "CollisionShape2TriangleMesh.h"
#include "../OpenGLWindow/ShapeData.h"
#include "../OpenGLWindow/SimpleCamera.h"
#include "../OpenGLWindow/GLInstanceGraphicsShape.h"
@@ -35,6 +36,8 @@ ATTRIBUTE_ALIGNED16( class )MyDebugDrawer : public btIDebugDraw
btAlignedObjectArray<MyDebugVec3> m_linePoints;
btAlignedObjectArray<unsigned int> m_lineIndices;
btVector3 m_currentLineColor;
DefaultColors m_ourColors;
@@ -133,14 +136,67 @@ public:
static btVector4 sColors[4] =
{
btVector4(0.3,0.3,1,1),
btVector4(0.6,0.6,1,1),
btVector4(0,1,0,1),
btVector4(0,1,1,1),
btVector4(60./256.,186./256.,84./256.,1),
btVector4(244./256.,194./256.,13./256.,1),
btVector4(219./256.,50./256.,54./256.,1),
btVector4(72./256.,133./256.,237./256.,1),
//btVector4(1,1,0,1),
};
struct MyHashShape
{
int m_shapeKey;
int m_shapeType;
btVector3 m_sphere0Pos;
btVector3 m_sphere1Pos;
btScalar m_radius0;
btScalar m_radius1;
btTransform m_childTransform;
int m_deformFunc;
int m_upAxis;
btScalar m_halfHeight;
MyHashShape()
:m_shapeKey(0),
m_shapeType(0),
m_sphere0Pos(btVector3(0,0,0)),
m_sphere1Pos(btVector3(0,0,0)),
m_radius0(0),
m_radius1(0),
m_deformFunc(0),
m_upAxis(-1),
m_halfHeight(0)
{
m_childTransform.setIdentity();
}
bool equals(const MyHashShape& other) const
{
bool sameShapeType = m_shapeType==other.m_shapeType;
bool sameSphere0= m_sphere0Pos == other.m_sphere0Pos;
bool sameSphere1= m_sphere1Pos == other.m_sphere1Pos;
bool sameRadius0 = m_radius0== other.m_radius0;
bool sameRadius1 = m_radius1== other.m_radius1;
bool sameTransform = m_childTransform== other.m_childTransform;
bool sameUpAxis = m_upAxis == other.m_upAxis;
bool sameHalfHeight = m_halfHeight == other.m_halfHeight;
return sameShapeType && sameSphere0 && sameSphere1 && sameRadius0 && sameRadius1 && sameTransform && sameUpAxis && sameHalfHeight;
}
//to our success
SIMD_FORCE_INLINE unsigned int getHash()const
{
unsigned int key = m_shapeKey;
// Thomas Wang's hash
key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16);
return key;
}
};
struct OpenGLGuiHelperInternalData
{
struct CommonGraphicsApp* m_glApp;
@@ -150,12 +206,20 @@ struct OpenGLGuiHelperInternalData
btAlignedObjectArray<unsigned char> m_rgbaPixelBuffer1;
btAlignedObjectArray<float> m_depthBuffer1;
btHashMap<MyHashShape, int> m_hashShapes;
VisualizerFlagCallback m_visualizerFlagCallback;
int m_checkedTexture;
int m_checkedTextureGrey;
OpenGLGuiHelperInternalData()
:m_vrMode(false),
m_vrSkipShadowPass(0),
m_visualizerFlagCallback(0)
m_visualizerFlagCallback(0),
m_checkedTexture(-1),
m_checkedTextureGrey(-1)
{
}
@@ -238,6 +302,7 @@ int OpenGLGuiHelper::registerGraphicsInstance(int shapeIndex, const float* posit
void OpenGLGuiHelper::removeAllGraphicsInstances()
{
m_data->m_hashShapes.clear();
m_data->m_glApp->m_renderer->removeAllInstances();
}
@@ -249,6 +314,45 @@ void OpenGLGuiHelper::removeGraphicsInstance(int graphicsUid)
};
}
int OpenGLGuiHelper::createCheckeredTexture(int red,int green, int blue)
{
int texWidth=1024;
int texHeight=1024;
btAlignedObjectArray<unsigned char> texels;
texels.resize(texWidth*texHeight*3);
for (int i=0;i<texWidth*texHeight*3;i++)
texels[i]=255;
for (int i=0;i<texWidth;i++)
{
for (int j=0;j<texHeight;j++)
{
int a = i<texWidth/2? 1 : 0;
int b = j<texWidth/2? 1 : 0;
if (a==b)
{
texels[(i+j*texWidth)*3+0] = red;
texels[(i+j*texWidth)*3+1] = green;
texels[(i+j*texWidth)*3+2] = blue;
// texels[(i+j*texWidth)*4+3] = 255;
}
/*else
{
texels[i*3+0+j*texWidth] = 255;
texels[i*3+1+j*texWidth] = 255;
texels[i*3+2+j*texWidth] = 255;
}
*/
}
}
int texId = registerTexture(&texels[0],texWidth,texHeight);
return texId;
}
void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
{
@@ -256,10 +360,472 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli
if (collisionShape->getUserIndex()>=0)
return;
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
if (m_data->m_checkedTexture<0)
{
m_data->m_checkedTexture = createCheckeredTexture(192,192,255);
}
if (m_data->m_checkedTextureGrey<0)
{
m_data->m_checkedTextureGrey = createCheckeredTexture(192,192,192);
}
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
btAlignedObjectArray<int> indices;
int strideInBytes = 9*sizeof(float);
//if (collisionShape->getShapeType()==BOX_SHAPE_PROXYTYPE)
{
}
if (collisionShape->getShapeType()==MULTI_SPHERE_SHAPE_PROXYTYPE)
{
btMultiSphereShape* ms = (btMultiSphereShape*) collisionShape;
if (ms->getSphereCount()==2)
{
btAlignedObjectArray<float> transformedVertices;
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
transformedVertices.resize(numVertices*9);
btVector3 sphere0Pos = ms->getSpherePosition(0);
btVector3 sphere1Pos = ms->getSpherePosition(1);
btVector3 fromTo = sphere1Pos-sphere0Pos;
MyHashShape shape;
shape.m_sphere0Pos = sphere0Pos;
shape.m_sphere1Pos = sphere1Pos;
shape.m_radius0 = 2.*ms->getSphereRadius(0);
shape.m_radius1 = 2.*ms->getSphereRadius(1);
shape.m_deformFunc = 1;//vert.dot(fromTo)
int graphicsShapeIndex = -1;
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
if (graphicsShapeIndexPtr)
{
//cache hit
graphicsShapeIndex = *graphicsShapeIndexPtr;
} else
{
//cache miss
for (int i=0;i<numVertices;i++)
{
btVector3 vert;
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
textured_detailed_sphere_vertices[i*9+1],
textured_detailed_sphere_vertices[i*9+2]);
btVector3 trVer(0,0,0);
if (vert.dot(fromTo)>0)
{
btScalar radiusScale = 2.*ms->getSphereRadius(1);
trVer = radiusScale*vert;
trVer+=sphere1Pos;
} else
{
btScalar radiusScale = 2.*ms->getSphereRadius(0);
trVer = radiusScale*vert;
trVer+=sphere0Pos;
}
transformedVertices[i*9+0] = trVer[0];
transformedVertices[i*9+1] = trVer[1];
transformedVertices[i*9+2] = trVer[2];
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
}
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
}
collisionShape->setUserIndex(graphicsShapeIndex);
return;
}
}
if (collisionShape->getShapeType()==SPHERE_SHAPE_PROXYTYPE)
{
btSphereShape* sphereShape = (btSphereShape*) collisionShape;
btScalar radius = sphereShape->getRadius();
btScalar sphereSize = 2.*radius;
btVector3 radiusScale(sphereSize,sphereSize,sphereSize);
btAlignedObjectArray<float> transformedVertices;
MyHashShape shape;
shape.m_radius0 = sphereSize;
shape.m_deformFunc = 0;////no deform
int graphicsShapeIndex = -1;
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
if (graphicsShapeIndexPtr)
{
graphicsShapeIndex = *graphicsShapeIndexPtr;
} else
{
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
transformedVertices.resize(numVertices*9);
for (int i=0;i<numVertices;i++)
{
btVector3 vert;
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
textured_detailed_sphere_vertices[i*9+1],
textured_detailed_sphere_vertices[i*9+2]);
btVector3 trVer = radiusScale*vert;
transformedVertices[i*9+0] = trVer[0];
transformedVertices[i*9+1] = trVer[1];
transformedVertices[i*9+2] = trVer[2];
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
}
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
}
collisionShape->setUserIndex(graphicsShapeIndex);
return;
}
if (collisionShape->getShapeType()==COMPOUND_SHAPE_PROXYTYPE)
{
btCompoundShape* compound = (btCompoundShape*)collisionShape;
if (compound->getNumChildShapes()==1)
{
if (compound->getChildShape(0)->getShapeType()==SPHERE_SHAPE_PROXYTYPE)
{
btSphereShape* sphereShape = (btSphereShape*) compound->getChildShape(0);
btScalar radius = sphereShape->getRadius();
btScalar sphereSize = 2.*radius;
btVector3 radiusScale(sphereSize,sphereSize,sphereSize);
MyHashShape shape;
shape.m_radius0 = sphereSize;
shape.m_deformFunc = 0;//no deform
shape.m_childTransform = compound->getChildTransform(0);
int graphicsShapeIndex = -1;
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
if (graphicsShapeIndexPtr)
{
graphicsShapeIndex = *graphicsShapeIndexPtr;
}
else
{
btAlignedObjectArray<float> transformedVertices;
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
transformedVertices.resize(numVertices*9);
for (int i=0;i<numVertices;i++)
{
btVector3 vert;
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
textured_detailed_sphere_vertices[i*9+1],
textured_detailed_sphere_vertices[i*9+2]);
btVector3 trVer = compound->getChildTransform(0)*(radiusScale*vert);
transformedVertices[i*9+0] = trVer[0];
transformedVertices[i*9+1] = trVer[1];
transformedVertices[i*9+2] = trVer[2];
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
}
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
}
collisionShape->setUserIndex(graphicsShapeIndex);
return;
}
if (compound->getChildShape(0)->getShapeType()==CAPSULE_SHAPE_PROXYTYPE)
{
btCapsuleShape* sphereShape = (btCapsuleShape*) compound->getChildShape(0);
int up = sphereShape->getUpAxis();
btScalar halfHeight = sphereShape->getHalfHeight();
btScalar radius = sphereShape->getRadius();
btScalar sphereSize = 2.*radius;
btVector3 radiusScale = btVector3(sphereSize,sphereSize,sphereSize);
MyHashShape shape;
shape.m_radius0 = sphereSize;
shape.m_deformFunc = 2;//no deform
shape.m_childTransform = compound->getChildTransform(0);
shape.m_upAxis = up;
int graphicsShapeIndex = -1;
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
if (graphicsShapeIndexPtr)
{
graphicsShapeIndex = *graphicsShapeIndexPtr;
}
else
{
btAlignedObjectArray<float> transformedVertices;
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
transformedVertices.resize(numVertices*9);
for (int i=0;i<numVertices;i++)
{
btVector3 vert;
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
textured_detailed_sphere_vertices[i*9+1],
textured_detailed_sphere_vertices[i*9+2]);
btVector3 trVer = compound->getChildTransform(0)*(radiusScale*vert);
if (trVer[up]>0)
trVer[up]+=halfHeight;
else
trVer[up]-=halfHeight;
transformedVertices[i*9+0] = trVer[0];
transformedVertices[i*9+1] = trVer[1];
transformedVertices[i*9+2] = trVer[2];
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
}
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
}
collisionShape->setUserIndex(graphicsShapeIndex);
return;
}
if (compound->getChildShape(0)->getShapeType()==MULTI_SPHERE_SHAPE_PROXYTYPE)
{
btMultiSphereShape* ms = (btMultiSphereShape*) compound->getChildShape(0);
if (ms->getSphereCount()==2)
{
btAlignedObjectArray<float> transformedVertices;
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
transformedVertices.resize(numVertices*9);
btVector3 sphere0Pos = ms->getSpherePosition(0);
btVector3 sphere1Pos = ms->getSpherePosition(1);
btVector3 fromTo = sphere1Pos-sphere0Pos;
btScalar radiusScale1 = 2.0*ms->getSphereRadius(1);
btScalar radiusScale0 = 2.0*ms->getSphereRadius(0);
MyHashShape shape;
shape.m_radius0 = radiusScale0;
shape.m_radius1 = radiusScale1;
shape.m_deformFunc = 4;
shape.m_sphere0Pos = sphere0Pos;
shape.m_sphere1Pos = sphere1Pos;
shape.m_childTransform = compound->getChildTransform(0);
int graphicsShapeIndex = -1;
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
if (graphicsShapeIndexPtr)
{
graphicsShapeIndex = *graphicsShapeIndexPtr;
}
else
{
for (int i=0;i<numVertices;i++)
{
btVector3 vert;
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
textured_detailed_sphere_vertices[i*9+1],
textured_detailed_sphere_vertices[i*9+2]);
btVector3 trVer(0,0,0);
if (vert.dot(fromTo)>0)
{
trVer = vert*radiusScale1;
trVer+=sphere1Pos;
trVer = compound->getChildTransform(0)*trVer;
} else
{
trVer = vert*radiusScale0;
trVer+=sphere0Pos;
trVer=compound->getChildTransform(0)*trVer;
}
transformedVertices[i*9+0] = trVer[0];
transformedVertices[i*9+1] = trVer[1];
transformedVertices[i*9+2] = trVer[2];
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
}
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
}
collisionShape->setUserIndex(graphicsShapeIndex);
return;
}
}
}
}
if (collisionShape->getShapeType()==CAPSULE_SHAPE_PROXYTYPE)
{
btCapsuleShape* sphereShape = (btCapsuleShape*) collisionShape;//Y up
int up = sphereShape->getUpAxis();
btScalar halfHeight = sphereShape->getHalfHeight();
btScalar radius = sphereShape->getRadius();
btScalar sphereSize = 2.*radius;
btVector3 radiusScale(sphereSize,sphereSize,sphereSize);
MyHashShape shape;
shape.m_radius0 = sphereSize;
shape.m_deformFunc = 3;
shape.m_upAxis = up;
shape.m_halfHeight = halfHeight;
int graphicsShapeIndex = -1;
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
if (graphicsShapeIndexPtr)
{
graphicsShapeIndex = *graphicsShapeIndexPtr;
}
else
{
btAlignedObjectArray<float> transformedVertices;
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
transformedVertices.resize(numVertices*9);
for (int i=0;i<numVertices;i++)
{
btVector3 vert;
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
textured_detailed_sphere_vertices[i*9+1],
textured_detailed_sphere_vertices[i*9+2]);
btVector3 trVer = radiusScale*vert;
if (trVer[up]>0)
trVer[up]+=halfHeight;
else
trVer[up]-=halfHeight;
transformedVertices[i*9+0] = trVer[0];
transformedVertices[i*9+1] = trVer[1];
transformedVertices[i*9+2] = trVer[2];
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
}
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
}
collisionShape->setUserIndex(graphicsShapeIndex);
return;
}
if (collisionShape->getShapeType()==STATIC_PLANE_PROXYTYPE)
{
const btStaticPlaneShape* staticPlaneShape = static_cast<const btStaticPlaneShape*>(collisionShape);
btScalar planeConst = staticPlaneShape->getPlaneConstant();
const btVector3& planeNormal = staticPlaneShape->getPlaneNormal();
btVector3 planeOrigin = planeNormal * planeConst;
btVector3 vec0,vec1;
btPlaneSpace1(planeNormal,vec0,vec1);
btScalar vecLen = 128;
btVector3 verts[4];
verts[0] = planeOrigin + vec0*vecLen + vec1*vecLen;
verts[1] = planeOrigin - vec0*vecLen + vec1*vecLen;
verts[2] = planeOrigin - vec0*vecLen - vec1*vecLen;
verts[3] = planeOrigin + vec0*vecLen - vec1*vecLen;
int startIndex = 0;
indices.push_back(startIndex+0);
indices.push_back(startIndex+1);
indices.push_back(startIndex+2);
indices.push_back(startIndex+0);
indices.push_back(startIndex+2);
indices.push_back(startIndex+3);
btTransform parentTransform;
parentTransform.setIdentity();
btVector3 triNormal = parentTransform.getBasis()*planeNormal;
gfxVertices.resize(4);
for (int i=0;i<4;i++)
{
btVector3 vtxPos;
btVector3 pos =parentTransform*verts[i];
gfxVertices[i].xyzw[0] = pos[0];
gfxVertices[i].xyzw[1] = pos[1];
gfxVertices[i].xyzw[2] = pos[2];
gfxVertices[i].xyzw[3] = 1;
gfxVertices[i].normal[0] = triNormal[0];
gfxVertices[i].normal[1] = triNormal[1];
gfxVertices[i].normal[2] = triNormal[2];
}
//verts[0] = planeOrigin + vec0*vecLen + vec1*vecLen;
//verts[1] = planeOrigin - vec0*vecLen + vec1*vecLen;
//verts[2] = planeOrigin - vec0*vecLen - vec1*vecLen;
//verts[3] = planeOrigin + vec0*vecLen - vec1*vecLen;
gfxVertices[0].uv[0] = vecLen/2;
gfxVertices[0].uv[1] = vecLen/2;
gfxVertices[1].uv[0] = -vecLen/2;
gfxVertices[1].uv[1] = vecLen/2;
gfxVertices[2].uv[0] = -vecLen/2;
gfxVertices[2].uv[1] = -vecLen/2;
gfxVertices[3].uv[0] = vecLen/2;
gfxVertices[3].uv[1] = -vecLen/2;
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size(),B3_GL_TRIANGLES,m_data->m_checkedTexture);
collisionShape->setUserIndex(shapeId);
return;
}
btTransform startTrans;startTrans.setIdentity();
//todo: create some textured objects for popular objects, like plane, cube, sphere, capsule
{
btAlignedObjectArray<btVector3> vertexPositions;
@@ -605,7 +1171,12 @@ void OpenGLGuiHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWor
createCollisionShapeGraphicsObject(colObj->getCollisionShape());
int colorIndex = colObj->getBroadphaseHandle()->getUid() & 3;
btVector3 color= sColors[colorIndex];
btVector3 color;
color = sColors[colorIndex];
if (colObj->getCollisionShape()->getShapeType()==STATIC_PLANE_PROXYTYPE)
{
color.setValue(1,1,1);
}
createCollisionObjectGraphicsObject(colObj,color);
}

View File

@@ -90,6 +90,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
virtual void dumpFramesToVideo(const char* mp4FileName);
int createCheckeredTexture(int r,int g, int b);
};
#endif //OPENGL_GUI_HELPER_H