mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
improve loading performance of large textures:
option to disable tinyrenderer, use p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER,0) also make sure to use p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0) before loadURDF, and enable rendering afterwards using p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1) reorder 2 loops, making the flip texels twice as fast (cache coherency), single memcpy of entire texture in tinyrenderer, instead of per-pixel copy (memory layout is the same) add lots of B3_PROFILE timings, to see where time is going
This commit is contained in:
parent
b572fe43f9
commit
26d32f2aa8
@ -33,47 +33,51 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
|
||||
}
|
||||
|
||||
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);
|
||||
|
||||
//int textureIndex = -1;
|
||||
//try to load some texture
|
||||
for (int i=0; meshData.m_textureImage==0 && i<shapes.size();i++)
|
||||
{
|
||||
const tinyobj::shape_t& shape = shapes[i];
|
||||
if (shape.material.diffuse_texname.length()>0)
|
||||
B3_PROFILE("Load Texture");
|
||||
//int textureIndex = -1;
|
||||
//try to load some texture
|
||||
for (int i = 0; meshData.m_textureImage == 0 && i < shapes.size(); i++)
|
||||
{
|
||||
|
||||
int width,height,n;
|
||||
const char* filename = shape.material.diffuse_texname.c_str();
|
||||
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++)
|
||||
const tinyobj::shape_t& shape = shapes[i];
|
||||
if (shape.material.diffuse_texname.length() > 0)
|
||||
{
|
||||
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);
|
||||
meshData.m_textureImage = image;
|
||||
if (image)
|
||||
{
|
||||
meshData.m_textureWidth = width;
|
||||
meshData.m_textureHeight = height;
|
||||
} else
|
||||
{
|
||||
b3Warning("Unsupported texture image format [%s]\n",relativeFileName);
|
||||
meshData.m_textureWidth = 0;
|
||||
meshData.m_textureHeight = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
} else
|
||||
{
|
||||
b3Warning("not found [%s]\n",relativeFileName);
|
||||
}
|
||||
int width, height, n;
|
||||
const char* filename = shape.material.diffuse_texname.c_str();
|
||||
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);
|
||||
meshData.m_textureImage = image;
|
||||
if (image)
|
||||
{
|
||||
meshData.m_textureWidth = width;
|
||||
meshData.m_textureHeight = height;
|
||||
}
|
||||
else
|
||||
{
|
||||
b3Warning("Unsupported texture image format [%s]\n", relativeFileName);
|
||||
meshData.m_textureWidth = 0;
|
||||
meshData.m_textureHeight = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
b3Warning("not found [%s]\n", relativeFileName);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -55,7 +55,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
|
||||
vtx0.uv[1] = shape.mesh.texcoords[uv1Index];
|
||||
} else
|
||||
{
|
||||
b3Warning("obj texture coordinate out-of-range!");
|
||||
// b3Warning("obj texture coordinate out-of-range!");
|
||||
vtx0.uv[0] = 0;
|
||||
vtx0.uv[1] = 0;
|
||||
}
|
||||
@ -82,7 +82,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
|
||||
vtx1.uv[1] = shape.mesh.texcoords[uv1Index];
|
||||
} else
|
||||
{
|
||||
b3Warning("obj texture coordinate out-of-range!");
|
||||
// b3Warning("obj texture coordinate out-of-range!");
|
||||
vtx1.uv[0] = 0;
|
||||
vtx1.uv[1] = 0;
|
||||
}
|
||||
|
@ -57,6 +57,7 @@ ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
|
||||
mutable btAlignedObjectArray<btTriangleMesh*> m_allocatedMeshInterfaces;
|
||||
|
||||
LinkVisualShapesConverter* m_customVisualShapesConverter;
|
||||
bool m_enableTinyRenderer;
|
||||
|
||||
void setSourceFile(const std::string& relativeFileName, const std::string& prefix)
|
||||
{
|
||||
@ -68,6 +69,7 @@ ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
|
||||
|
||||
BulletURDFInternalData()
|
||||
{
|
||||
m_enableTinyRenderer = true;
|
||||
m_pathPrefix[0] = 0;
|
||||
}
|
||||
|
||||
@ -1143,7 +1145,10 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
|
||||
|
||||
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height);
|
||||
}
|
||||
graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES,textureIndex);
|
||||
{
|
||||
B3_PROFILE("registerGraphicsShape");
|
||||
graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), B3_GL_TRIANGLES, textureIndex);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@ -1151,6 +1156,7 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
|
||||
//delete textures
|
||||
for (int i=0;i<textures.size();i++)
|
||||
{
|
||||
B3_PROFILE("free textureData");
|
||||
free( textures[i].textureData);
|
||||
}
|
||||
return graphicsIndex;
|
||||
@ -1206,10 +1212,15 @@ bool BulletURDFImporter::getLinkAudioSource(int linkIndex, SDFAudioSource& audio
|
||||
return false;
|
||||
}
|
||||
|
||||
void BulletURDFImporter::setEnableTinyRenderer(bool enable)
|
||||
{
|
||||
m_data->m_enableTinyRenderer = enable;
|
||||
}
|
||||
|
||||
|
||||
void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionObject* colObj, int bodyUniqueId) const
|
||||
{
|
||||
if (m_data->m_customVisualShapesConverter)
|
||||
if (m_data->m_enableTinyRenderer && m_data->m_customVisualShapesConverter)
|
||||
{
|
||||
const UrdfModel& model = m_data->m_urdfParser.getModel();
|
||||
UrdfLink*const* linkPtr = model.m_links.getAtIndex(urdfIndex);
|
||||
|
@ -74,6 +74,7 @@ public:
|
||||
virtual int getNumAllocatedMeshInterfaces() const;
|
||||
virtual class btStridingMeshInterface* getAllocatedMeshInterface(int index);
|
||||
|
||||
virtual void setEnableTinyRenderer(bool enable);
|
||||
};
|
||||
|
||||
|
||||
|
@ -10,6 +10,7 @@
|
||||
#include "URDFImporterInterface.h"
|
||||
#include "MultiBodyCreationInterface.h"
|
||||
#include <string>
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
|
||||
//static int bodyCollisionFilterGroup=btBroadphaseProxy::CharacterFilter;
|
||||
//static int bodyCollisionFilterMask=btBroadphaseProxy::AllFilter&(~btBroadphaseProxy::CharacterFilter);
|
||||
@ -183,6 +184,7 @@ void ConvertURDF2BulletInternal(
|
||||
bool createMultiBody, const char* pathPrefix,
|
||||
int flags = 0)
|
||||
{
|
||||
B3_PROFILE("ConvertURDF2BulletInternal2");
|
||||
//b3Printf("start converting/extracting data from URDF interface\n");
|
||||
|
||||
btTransform linkTransformInWorldSpace;
|
||||
@ -264,8 +266,12 @@ void ConvertURDF2BulletInternal(
|
||||
compoundShape = tmpShape->getChildShape(0);
|
||||
}
|
||||
|
||||
int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
|
||||
|
||||
|
||||
int graphicsIndex;
|
||||
{
|
||||
B3_PROFILE("convertLinkVisualShapes");
|
||||
graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex, pathPrefix, localInertialFrame);
|
||||
}
|
||||
|
||||
|
||||
|
||||
@ -525,11 +531,14 @@ void ConvertURDF2BulletInternal(
|
||||
color2 = matCol.m_rgbaColor;
|
||||
specularColor = matCol.m_specularColor;
|
||||
}
|
||||
|
||||
creation.createCollisionObjectGraphicsInstance2(urdfLinkIndex,col,color2,specularColor);
|
||||
|
||||
u2b.convertLinkVisualShapes2(mbLinkIndex, urdfLinkIndex, pathPrefix, localInertialFrame,col, u2b.getBodyUniqueId());
|
||||
|
||||
{
|
||||
B3_PROFILE("createCollisionObjectGraphicsInstance2");
|
||||
creation.createCollisionObjectGraphicsInstance2(urdfLinkIndex, col, color2, specularColor);
|
||||
}
|
||||
{
|
||||
B3_PROFILE("convertLinkVisualShapes2");
|
||||
u2b.convertLinkVisualShapes2(mbLinkIndex, urdfLinkIndex, pathPrefix, localInertialFrame, col, u2b.getBodyUniqueId());
|
||||
}
|
||||
URDFLinkContactInfo contactInfo;
|
||||
u2b.getLinkContactInfo(urdfLinkIndex,contactInfo);
|
||||
|
||||
@ -571,7 +580,6 @@ void ConvertURDF2BulletInternal(
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void ConvertURDF2Bullet(
|
||||
const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation,
|
||||
const btTransform& rootTransformInWorldSpace,
|
||||
@ -582,10 +590,12 @@ void ConvertURDF2Bullet(
|
||||
|
||||
InitURDF2BulletCache(u2b,cache);
|
||||
int urdfLinkIndex = u2b.getRootLinkIndex();
|
||||
ConvertURDF2BulletInternal(u2b, creation, cache, urdfLinkIndex,rootTransformInWorldSpace,world1,createMultiBody,pathPrefix,flags);
|
||||
B3_PROFILE("ConvertURDF2Bullet");
|
||||
ConvertURDF2BulletInternal(u2b, creation, cache, urdfLinkIndex,rootTransformInWorldSpace,world1,createMultiBody,pathPrefix,flags);
|
||||
|
||||
if (world1 && cache.m_bulletMultiBody)
|
||||
{
|
||||
B3_PROFILE("Post process");
|
||||
btMultiBody* mb = cache.m_bulletMultiBody;
|
||||
|
||||
mb->setHasSelfCollision((flags&CUF_USE_SELF_COLLISION)!=0);
|
||||
|
@ -945,6 +945,7 @@ int GLInstancingRenderer::registerGraphicsInstance(int shapeIndex, const float*
|
||||
|
||||
int GLInstancingRenderer::registerTexture(const unsigned char* texels, int width, int height, bool flipPixelsY)
|
||||
{
|
||||
B3_PROFILE("GLInstancingRenderer::registerTexture");
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
glActiveTexture(GL_TEXTURE0);
|
||||
int textureIndex = m_data->m_textureHandles.size();
|
||||
@ -963,6 +964,7 @@ int GLInstancingRenderer::registerTexture(const unsigned char* texels, int width
|
||||
m_data->m_textureHandles.push_back(h);
|
||||
if (texels)
|
||||
{
|
||||
B3_PROFILE("updateTexture");
|
||||
updateTexture(textureIndex, texels, flipPixelsY);
|
||||
}
|
||||
return textureIndex;
|
||||
@ -985,6 +987,7 @@ void GLInstancingRenderer::replaceTexture(int shapeIndex, int textureId)
|
||||
|
||||
void GLInstancingRenderer::updateTexture(int textureIndex, const unsigned char* texels, bool flipPixelsY)
|
||||
{
|
||||
B3_PROFILE("updateTexture");
|
||||
if ((textureIndex>=0) && (textureIndex < m_data->m_textureHandles.size()))
|
||||
{
|
||||
glActiveTexture(GL_TEXTURE0);
|
||||
@ -995,13 +998,14 @@ void GLInstancingRenderer::updateTexture(int textureIndex, const unsigned cha
|
||||
|
||||
if (flipPixelsY)
|
||||
{
|
||||
B3_PROFILE("flipPixelsY");
|
||||
//textures need to be flipped for OpenGL...
|
||||
b3AlignedObjectArray<unsigned char> flippedTexels;
|
||||
flippedTexels.resize(h.m_width* h.m_height * 3);
|
||||
|
||||
for (int i = 0; i < h.m_width; i++)
|
||||
for (int j = 0; j < h.m_height; j++)
|
||||
{
|
||||
for (int j = 0; j < h.m_height; j++)
|
||||
for (int i = 0; i < h.m_width; i++)
|
||||
{
|
||||
flippedTexels[(i + j*h.m_width) * 3] = texels[(i + (h.m_height - 1 -j )*h.m_width) * 3];
|
||||
flippedTexels[(i + j*h.m_width) * 3+1] = texels[(i + (h.m_height - 1 - j)*h.m_width) * 3+1];
|
||||
@ -1017,6 +1021,7 @@ void GLInstancingRenderer::updateTexture(int textureIndex, const unsigned cha
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
if (h.m_enableFiltering)
|
||||
{
|
||||
B3_PROFILE("glGenerateMipmap");
|
||||
glGenerateMipmap(GL_TEXTURE_2D);
|
||||
}
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
@ -1512,6 +1512,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
int m_sharedMemoryKey;
|
||||
bool m_enableTinyRenderer;
|
||||
|
||||
bool m_verboseOutput;
|
||||
|
||||
@ -1553,6 +1554,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
m_guiHelper(0),
|
||||
m_sharedMemoryKey(SHARED_MEMORY_KEY),
|
||||
m_verboseOutput(false),
|
||||
m_enableTinyRenderer(true),
|
||||
m_pickedBody(0),
|
||||
m_pickedConstraint(0),
|
||||
m_pickingMultiBodyPoint2Point(0)
|
||||
@ -2659,6 +2661,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
|
||||
m_data->m_sdfRecentLoadedBodies.clear();
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling);
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
|
||||
bool forceFixedBase = false;
|
||||
bool loadOk =u2b.loadSDF(fileName,forceFixedBase);
|
||||
@ -2690,7 +2693,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
|
||||
|
||||
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling);
|
||||
|
||||
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
|
||||
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
|
||||
|
||||
|
||||
@ -6253,8 +6256,13 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverCmd.m_type =CMD_CLIENT_COMMAND_COMPLETED;
|
||||
|
||||
hasStatus = true;
|
||||
if (clientCmd.m_updateFlags&COV_SET_FLAGS)
|
||||
{
|
||||
|
||||
if (clientCmd.m_updateFlags&COV_SET_FLAGS)
|
||||
{
|
||||
if (clientCmd.m_configureOpenGLVisualizerArguments.m_setFlag == COV_ENABLE_TINY_RENDERER)
|
||||
{
|
||||
m_data->m_enableTinyRenderer = clientCmd.m_configureOpenGLVisualizerArguments.m_setEnabled!=0;
|
||||
}
|
||||
m_data->m_guiHelper->setVisualizerFlag(clientCmd.m_configureOpenGLVisualizerArguments.m_setFlag,
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_setEnabled);
|
||||
}
|
||||
|
@ -1840,12 +1840,15 @@ void PhysicsServerExample::updateGraphics()
|
||||
{
|
||||
case eGUIHelperCreateCollisionShapeGraphicsObject:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperCreateCollisionShapeGraphicsObject");
|
||||
m_multiThreadedHelper->m_childGuiHelper->createCollisionShapeGraphicsObject(m_multiThreadedHelper->m_colShape);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
case eGUIHelperCreateCollisionObjectGraphicsObject:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperCreateCollisionObjectGraphicsObject");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->createCollisionObjectGraphicsObject(m_multiThreadedHelper->m_obj,
|
||||
m_multiThreadedHelper->m_color2);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
@ -1854,13 +1857,14 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperCreateRigidBodyGraphicsObject:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperCreateRigidBodyGraphicsObject");
|
||||
m_multiThreadedHelper->m_childGuiHelper->createRigidBodyGraphicsObject(m_multiThreadedHelper->m_body,m_multiThreadedHelper->m_color3);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
case eGUIHelperRegisterTexture:
|
||||
{
|
||||
|
||||
B3_PROFILE("eGUIHelperRegisterTexture");
|
||||
m_multiThreadedHelper->m_textureId = m_multiThreadedHelper->m_childGuiHelper->registerTexture(m_multiThreadedHelper->m_texels,
|
||||
m_multiThreadedHelper->m_textureWidth,m_multiThreadedHelper->m_textureHeight);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
@ -1868,6 +1872,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperRegisterGraphicsShape:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperRegisterGraphicsShape");
|
||||
m_multiThreadedHelper->m_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape(
|
||||
m_multiThreadedHelper->m_vertices,
|
||||
m_multiThreadedHelper->m_numvertices,
|
||||
@ -1881,6 +1886,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIHelperSetVisualizerFlag:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperSetVisualizerFlag");
|
||||
int flag = m_multiThreadedHelper->m_visualizerFlag;
|
||||
int enable = m_multiThreadedHelper->m_visualizerEnable;
|
||||
|
||||
@ -1922,6 +1928,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIHelperRegisterGraphicsInstance:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperRegisterGraphicsInstance");
|
||||
m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance(
|
||||
m_multiThreadedHelper->m_shapeIndex,
|
||||
m_multiThreadedHelper->m_position,
|
||||
@ -1933,6 +1940,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperRemoveAllGraphicsInstances:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperRemoveAllGraphicsInstances");
|
||||
#ifdef BT_ENABLE_VR
|
||||
if (m_tinyVrGui)
|
||||
{
|
||||
@ -1953,6 +1961,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperRemoveGraphicsInstance:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperRemoveGraphicsInstance");
|
||||
m_multiThreadedHelper->m_childGuiHelper->removeGraphicsInstance(m_multiThreadedHelper->m_graphicsInstanceRemove);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
@ -1960,6 +1969,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIHelperGetShapeIndexFromInstance:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperGetShapeIndexFromInstance");
|
||||
m_multiThreadedHelper->getShapeIndex_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->getShapeIndexFromInstance(m_multiThreadedHelper->m_getShapeIndex_instance);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
@ -1967,6 +1977,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIHelperChangeGraphicsInstanceTextureId:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperChangeGraphicsInstanceTextureId");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->replaceTexture(
|
||||
m_multiThreadedHelper->m_graphicsInstanceChangeTextureShapeIndex,
|
||||
m_multiThreadedHelper->m_graphicsInstanceChangeTextureId);
|
||||
@ -1977,6 +1989,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIHelperChangeTexture:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperChangeTexture");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->changeTexture(
|
||||
m_multiThreadedHelper->m_changeTextureUniqueId,
|
||||
m_multiThreadedHelper->m_changeTextureRgbTexels,
|
||||
@ -1988,12 +2002,16 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIHelperChangeGraphicsInstanceRGBAColor:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperChangeGraphicsInstanceRGBAColor");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->changeRGBAColor(m_multiThreadedHelper->m_graphicsInstanceChangeColor,m_multiThreadedHelper->m_rgbaColor);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
case eGUIHelperChangeGraphicsInstanceSpecularColor:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperChangeGraphicsInstanceSpecularColor");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->changeSpecularColor(m_multiThreadedHelper->m_graphicsInstanceChangeSpecular,m_multiThreadedHelper->m_specularColor);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
@ -2001,6 +2019,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperDisplayCameraImageData:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperDisplayCameraImageData");
|
||||
|
||||
if (m_canvas)
|
||||
{
|
||||
|
||||
@ -2119,6 +2139,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperCopyCameraImageData:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperCopyCameraImageData");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
|
||||
m_multiThreadedHelper->m_projectionMatrix,
|
||||
m_multiThreadedHelper->m_pixelsRGBA,
|
||||
@ -2137,6 +2159,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIHelperAutogenerateGraphicsObjects:
|
||||
{
|
||||
B3_PROFILE("eGUIHelperAutogenerateGraphicsObjects");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->autogenerateGraphicsObjects(m_multiThreadedHelper->m_dynamicsWorld);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
@ -2144,12 +2168,16 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIUserDebugAddText:
|
||||
{
|
||||
B3_PROFILE("eGUIUserDebugAddText");
|
||||
|
||||
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
case eGUIUserDebugAddParameter:
|
||||
{
|
||||
B3_PROFILE("eGUIUserDebugAddParameter");
|
||||
|
||||
UserDebugParameter* param = new UserDebugParameter(m_multiThreadedHelper->m_tmpParam);
|
||||
m_multiThreadedHelper->m_userDebugParams.push_back(param);
|
||||
|
||||
@ -2168,12 +2196,16 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIUserDebugAddLine:
|
||||
{
|
||||
B3_PROFILE("eGUIUserDebugAddLine");
|
||||
|
||||
m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
case eGUIUserDebugRemoveItem:
|
||||
{
|
||||
B3_PROFILE("eGUIUserDebugRemoveItem");
|
||||
|
||||
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
|
||||
{
|
||||
if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
|
||||
@ -2200,6 +2232,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
}
|
||||
case eGUIUserDebugRemoveAllItems:
|
||||
{
|
||||
B3_PROFILE("eGUIUserDebugRemoveAllItems");
|
||||
|
||||
m_multiThreadedHelper->m_userDebugLines.clear();
|
||||
m_multiThreadedHelper->m_userDebugText.clear();
|
||||
m_multiThreadedHelper->m_uidGenerator = 0;
|
||||
@ -2209,6 +2243,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
case eGUIDumpFramesToVideo:
|
||||
{
|
||||
B3_PROFILE("eGUIDumpFramesToVideo");
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->dumpFramesToVideo(m_multiThreadedHelper->m_mp4FileName);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
|
@ -578,6 +578,7 @@ enum b3ConfigureDebugVisualizerEnum
|
||||
COV_ENABLE_KEYBOARD_SHORTCUTS,
|
||||
COV_ENABLE_MOUSE_PICKING,
|
||||
COV_ENABLE_Y_AXIS_UP,
|
||||
COV_ENABLE_TINY_RENDERER,
|
||||
};
|
||||
|
||||
enum b3AddUserDebugItemEnum
|
||||
|
@ -619,7 +619,10 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
visualShape.m_rgbaColor[2] = rgbaColor[2];
|
||||
visualShape.m_rgbaColor[3] = rgbaColor[3];
|
||||
|
||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures, visualShape);
|
||||
{
|
||||
B3_PROFILE("convertURDFToVisualShape");
|
||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices, textures, visualShape);
|
||||
}
|
||||
m_data->m_visualShapes.push_back(visualShape);
|
||||
|
||||
if (vertices.size() && indices.size())
|
||||
@ -635,8 +638,12 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
textureHeight = textures[0].m_height;
|
||||
}
|
||||
|
||||
tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size(),rgbaColor,
|
||||
textureImage,textureWidth,textureHeight);
|
||||
{
|
||||
B3_PROFILE("registerMeshShape");
|
||||
|
||||
tinyObj->registerMeshShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), rgbaColor,
|
||||
textureImage, textureWidth, textureHeight);
|
||||
}
|
||||
visuals->m_renderObjects.push_back(tinyObj);
|
||||
}
|
||||
for (int i=0;i<textures.size();i++)
|
||||
@ -1145,6 +1152,7 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
|
||||
|
||||
int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
{
|
||||
B3_PROFILE("loadTextureFile");
|
||||
int width,height,n;
|
||||
unsigned char* image=0;
|
||||
image = stbi_load(filename, &width, &height, &n, 3);
|
||||
|
@ -285,11 +285,18 @@ void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVerti
|
||||
{
|
||||
if (0==m_model)
|
||||
{
|
||||
m_model = new Model();
|
||||
m_model->setColorRGBA(rgbaColor);
|
||||
{
|
||||
B3_PROFILE("setColorRGBA");
|
||||
|
||||
m_model = new Model();
|
||||
m_model->setColorRGBA(rgbaColor);
|
||||
}
|
||||
if (textureImage)
|
||||
{
|
||||
m_model->setDiffuseTextureFromData(textureImage,textureWidth,textureHeight);
|
||||
{
|
||||
B3_PROFILE("setDiffuseTextureFromData");
|
||||
m_model->setDiffuseTextureFromData(textureImage, textureWidth, textureHeight);
|
||||
}
|
||||
} else
|
||||
{
|
||||
/*char relativeFileName[1024];
|
||||
@ -299,25 +306,33 @@ void TinyRenderObjectData::registerMeshShape(const float* vertices, int numVerti
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
m_model->reserveMemory(numVertices,numIndices);
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
m_model->addVertex(vertices[i*9],
|
||||
vertices[i*9+1],
|
||||
vertices[i*9+2],
|
||||
vertices[i*9+4],
|
||||
vertices[i*9+5],
|
||||
vertices[i*9+6],
|
||||
vertices[i*9+7],
|
||||
vertices[i*9+8]);
|
||||
}
|
||||
for (int i=0;i<numIndices;i+=3)
|
||||
{
|
||||
m_model->addTriangle(indices[i],indices[i],indices[i],
|
||||
indices[i+1],indices[i+1],indices[i+1],
|
||||
indices[i+2],indices[i+2],indices[i+2]);
|
||||
}
|
||||
{
|
||||
B3_PROFILE("reserveMemory");
|
||||
m_model->reserveMemory(numVertices, numIndices);
|
||||
}
|
||||
{
|
||||
B3_PROFILE("addVertex");
|
||||
for (int i = 0; i < numVertices; i++)
|
||||
{
|
||||
m_model->addVertex(vertices[i * 9],
|
||||
vertices[i * 9 + 1],
|
||||
vertices[i * 9 + 2],
|
||||
vertices[i * 9 + 4],
|
||||
vertices[i * 9 + 5],
|
||||
vertices[i * 9 + 6],
|
||||
vertices[i * 9 + 7],
|
||||
vertices[i * 9 + 8]);
|
||||
}
|
||||
}
|
||||
{
|
||||
B3_PROFILE("addTriangle");
|
||||
for (int i = 0; i < numIndices; i += 3)
|
||||
{
|
||||
m_model->addTriangle(indices[i], indices[i], indices[i],
|
||||
indices[i + 1], indices[i + 1], indices[i + 1],
|
||||
indices[i + 2], indices[i + 2], indices[i + 2]);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -3,7 +3,7 @@
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include "model.h"
|
||||
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
Model::Model(const char *filename) : verts_(), faces_(), norms_(), uv_(), diffusemap_(), normalmap_(), specularmap_() {
|
||||
std::ifstream in;
|
||||
in.open (filename, std::ifstream::in);
|
||||
@ -51,24 +51,22 @@ Model::Model():verts_(), faces_(), norms_(), uv_(), diffusemap_(), normalmap_(),
|
||||
|
||||
void Model::setDiffuseTextureFromData(unsigned char* textureImage,int textureWidth,int textureHeight)
|
||||
{
|
||||
diffusemap_ = TGAImage(textureWidth, textureHeight, TGAImage::RGB);
|
||||
for (int i=0;i<textureWidth;i++)
|
||||
{
|
||||
for (int j=0;j<textureHeight;j++)
|
||||
{
|
||||
TGAColor color;
|
||||
color.bgra[0] = textureImage[(i+j*textureWidth)*3+0];
|
||||
color.bgra[1] = textureImage[(i+j*textureWidth)*3+1];
|
||||
color.bgra[2] = textureImage[(i+j*textureWidth)*3+2];
|
||||
color.bgra[3] = 255;
|
||||
|
||||
color.bytespp = 3;
|
||||
diffusemap_.set(i,j,color);
|
||||
|
||||
}
|
||||
B3_PROFILE("new TGAImage");
|
||||
diffusemap_ = TGAImage(textureWidth, textureHeight, TGAImage::RGB);
|
||||
}
|
||||
TGAColor color;
|
||||
color.bgra[3] = 255;
|
||||
|
||||
color.bytespp = 3;
|
||||
{
|
||||
B3_PROFILE("copy texels");
|
||||
memcpy(diffusemap_.buffer(), textureImage, textureHeight*textureWidth * 3);
|
||||
}
|
||||
{
|
||||
B3_PROFILE("flip_vertically");
|
||||
diffusemap_.flip_vertically();
|
||||
}
|
||||
|
||||
diffusemap_.flip_vertically();
|
||||
}
|
||||
|
||||
void Model::loadDiffuseTexture(const char* relativeFileName)
|
||||
|
@ -10,13 +10,13 @@ TGAImage::TGAImage() : data(NULL), width(0), height(0), bytespp(0) {}
|
||||
TGAImage::TGAImage(int w, int h, int bpp) : data(NULL), width(w), height(h), bytespp(bpp) {
|
||||
unsigned long nbytes = width*height*bytespp;
|
||||
data = new unsigned char[nbytes];
|
||||
memset(data, 0, nbytes);
|
||||
//memset(data, 0, nbytes);
|
||||
}
|
||||
|
||||
TGAImage::TGAImage(const TGAImage &img) : data(NULL), width(img.width), height(img.height), bytespp(img.bytespp) {
|
||||
unsigned long nbytes = width*height*bytespp;
|
||||
data = new unsigned char[nbytes];
|
||||
memcpy(data, img.data, nbytes);
|
||||
//memcpy(data, img.data, nbytes);
|
||||
}
|
||||
|
||||
TGAImage::~TGAImage() {
|
||||
|
@ -7987,6 +7987,8 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_VR_PICKING", COV_ENABLE_VR_PICKING);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_VR_TELEPORTING", COV_ENABLE_VR_TELEPORTING);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_RENDERING", COV_ENABLE_RENDERING);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_TINY_RENDERER", COV_ENABLE_TINY_RENDERER);
|
||||
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_VR_RENDER_CONTROLLERS", COV_ENABLE_VR_RENDER_CONTROLLERS);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_KEYBOARD_SHORTCUTS", COV_ENABLE_KEYBOARD_SHORTCUTS);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_MOUSE_PICKING", COV_ENABLE_MOUSE_PICKING);
|
||||
|
Loading…
Reference in New Issue
Block a user