From ed8de36ffa1641dafc3e63ddec4c1d829248cc22 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Wed, 25 Oct 2017 08:15:01 -0700 Subject: [PATCH] pybullet: allow to replace existing text, to avoid flickering (remove/add) allow texture caching (disable using the disable file caching) --- .../CommonGUIHelperInterface.h | 2 +- .../ImportMeshUtility/b3ImportMeshUtility.cpp | 83 +++++++++++++++---- .../ImportMeshUtility/b3ImportMeshUtility.h | 3 +- .../ImportURDFDemo/BulletUrdfImporter.cpp | 12 ++- .../ImportURDFDemo/BulletUrdfImporter.h | 3 +- examples/OpenGLWindow/SimpleOpenGL2App.cpp | 1 + examples/RenderingExamples/TinyVRGui.cpp | 5 +- examples/SharedMemory/PhysicsClientC_API.cpp | 12 +++ examples/SharedMemory/PhysicsClientC_API.h | 2 + .../PhysicsClientSharedMemory.cpp | 2 +- .../PhysicsServerCommandProcessor.cpp | 48 +++++++---- .../SharedMemory/PhysicsServerExample.cpp | 69 ++++++++++++--- examples/SharedMemory/SharedMemoryCommands.h | 4 +- .../TinyRendererVisualShapeConverter.cpp | 30 ++++--- examples/SimpleOpenGL3/main.cpp | 55 +++++++----- examples/SimpleOpenGL3/main_imgui.cpp | 3 +- examples/pybullet/pybullet.c | 10 ++- 17 files changed, 256 insertions(+), 88 deletions(-) diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index cbd52aa6f..d7c4f536c 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -99,7 +99,7 @@ struct GUIHelperInterface virtual void drawText3D( const char* txt, float posX, float posY, float posZ, float size){} virtual void drawText3D( const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag){} - virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags){return -1;} + virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid){return -1;} virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex){return -1;}; virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue){return -1;}; virtual int readUserDebugParameter(int itemUniqueId, double* value) { return 0;} diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 4d5a54599..87495f8b9 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -8,14 +8,37 @@ #include "Bullet3Common/b3FileUtils.h" #include "stb_image/stb_image.h" #include "../ImportObjDemo/LoadMeshFromObj.h" +#include "Bullet3Common/b3HashMap.h" + + +struct CachedTextureResult +{ + std::string m_textureName; + + int m_width; + int m_height; + unsigned char* m_pixels; + CachedTextureResult() + :m_width(0), + m_height(0), + m_pixels(0) + { + } + + + +}; + +static b3HashMap gCachedTextureResults; + bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData) { B3_PROFILE("loadAndRegisterMeshFromFileInternal"); meshData.m_gfxShape = 0; - meshData.m_textureImage = 0; + meshData.m_textureImage1 = 0; meshData.m_textureHeight = 0; meshData.m_textureWidth = 0; - + meshData.m_isCached = false; char relativeFileName[1024]; if (b3ResourcePath::findResourcePath(fileName.c_str(), relativeFileName, 1024)) @@ -37,7 +60,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& B3_PROFILE("Load Texture"); //int textureIndex = -1; //try to load some texture - for (int i = 0; meshData.m_textureImage == 0 && i < shapes.size(); i++) + for (int i = 0; meshData.m_textureImage1 == 0 && i < shapes.size(); i++) { const tinyobj::shape_t& shape = shapes[i]; if (shape.material.diffuse_texname.length() > 0) @@ -57,21 +80,51 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& char relativeFileName2[1024]; if (b3ResourcePath::findResourcePath(relativeFileName, relativeFileName2, 1024)) { - image = stbi_load(relativeFileName, &width, &height, &n, 3); - meshData.m_textureImage = image; - if (image) + if (b3IsFileCachingEnabled()) { - 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; + CachedTextureResult* texture = gCachedTextureResults[relativeFileName]; + if (texture) + { + image = texture->m_pixels; + width = texture->m_width; + height = texture->m_height; + meshData.m_textureWidth = width; + meshData.m_textureHeight = height; + meshData.m_textureImage1 = image; + meshData.m_isCached = true; + } } + if (image==0) + { + image = stbi_load(relativeFileName, &width, &height, &n, 3); + + meshData.m_textureImage1 = image; + + if (image) + { + meshData.m_textureWidth = width; + meshData.m_textureHeight = height; + + if (b3IsFileCachingEnabled()) + { + CachedTextureResult result; + result.m_textureName = relativeFileName; + result.m_width = width; + result.m_height = height; + result.m_pixels = image; + meshData.m_isCached = true; + gCachedTextureResults.insert(relativeFileName,result); + } + } + else + { + b3Warning("Unsupported texture image format [%s]\n", relativeFileName); + + break; + } + } + } else { diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h index 7bf6af841..07017c59e 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h @@ -7,7 +7,8 @@ struct b3ImportMeshData { struct GLInstanceGraphicsShape* m_gfxShape; - unsigned char* m_textureImage;//in 3 component 8-bit RGB data + unsigned char* m_textureImage1;//in 3 component 8-bit RGB data + bool m_isCached; int m_textureWidth; int m_textureHeight; }; diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 6deb798f9..ecf175ca8 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -878,12 +878,13 @@ void BulletURDFImporter::convertURDFToVisualShapeInternal(const UrdfVisual* visu if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData)) { - if (meshData.m_textureImage) + if (meshData.m_textureImage1) { BulletURDFTexture texData; texData.m_width = meshData.m_textureWidth; texData.m_height = meshData.m_textureHeight; - texData.textureData = meshData.m_textureImage; + texData.textureData1 = meshData.m_textureImage1; + texData.m_isCached = meshData.m_isCached; texturesOut.push_back(texData); } glmesh = meshData.m_gfxShape; @@ -1137,7 +1138,7 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP if (textures.size()) { - textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height); + textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData1,textures[0].m_width,textures[0].m_height); } { B3_PROFILE("registerGraphicsShape"); @@ -1151,7 +1152,10 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP for (int i=0;im_type == CMD_USER_DEBUG_DRAW); + b3Assert(command->m_updateFlags & USER_DEBUG_HAS_TEXT); + command->m_userDebugDrawArgs.m_replaceItemUniqueId = replaceItemUniqueId; + command->m_updateFlags |= USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID; +} + + + B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex) { diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 539dacfa5..bfd67ca22 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -170,6 +170,8 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3Physics B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[/*3*/], double colorRGB[/*3*/], double textSize, double lifeTime); B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags); B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[/*4*/]); +B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHandle commandHandle, int replaceItem); + B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 20eaf0ad5..2f2b8aa1f 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -78,7 +78,7 @@ struct PhysicsClientSharedMemoryInternalData { m_hasLastServerStatus(false), m_sharedMemoryKey(SHARED_MEMORY_KEY), m_verboseOutput(false), - m_timeOutInSeconds(30) + m_timeOutInSeconds(1e30) {} void processServerStatus(); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index d3cfa2d5b..6b624a3dd 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1,5 +1,4 @@ #include "PhysicsServerCommandProcessor.h" - #include "../CommonInterfaces/CommonRenderInterface.h" #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" @@ -4483,7 +4482,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (textures.size()) { - textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height); + textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData1,textures[0].m_width,textures[0].m_height); } int graphicsIndex = -1; { @@ -8146,27 +8145,35 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId>=0) { InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId); - if (bodyHandle && bodyHandle->m_multiBody) + if (bodyHandle) { - int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex; - if (linkIndex ==-1) + int linkIndex = -1; + + if (bodyHandle->m_multiBody) { - if (bodyHandle->m_multiBody->getBaseCollider()) + int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex; + if (linkIndex ==-1) { - trackingVisualShapeIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex(); - } - } else - { - if (linkIndex >=0 && linkIndex < bodyHandle->m_multiBody->getNumLinks()) - { - if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider) + if (bodyHandle->m_multiBody->getBaseCollider()) { - trackingVisualShapeIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex(); + trackingVisualShapeIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex(); } + } else + { + if (linkIndex >=0 && linkIndex < bodyHandle->m_multiBody->getNumLinks()) + { + if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider) + { + trackingVisualShapeIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex(); + } + } + } - } - + if (bodyHandle->m_rigidBody) + { + trackingVisualShapeIndex = bodyHandle->m_rigidBody->getUserIndex(); + } } } @@ -8252,7 +8259,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } - + int replaceItemUniqueId = -1; + if ((clientCmd.m_updateFlags & USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID)!=0) + { + replaceItemUniqueId = clientCmd.m_userDebugDrawArgs.m_replaceItemUniqueId; + } int uid = m_data->m_guiHelper->addUserDebugText3D(clientCmd.m_userDebugDrawArgs.m_text, @@ -8262,7 +8273,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm clientCmd.m_userDebugDrawArgs.m_textSize, clientCmd.m_userDebugDrawArgs.m_lifeTime, trackingVisualShapeIndex, - optionFlags); + optionFlags, + replaceItemUniqueId); if (uid>=0) { diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 342f32574..39766cc48 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -13,13 +13,14 @@ #include "../Utils/b3Clock.h" #include "../MultiThreading/b3ThreadSupportInterface.h" #include "SharedMemoryPublic.h" +//#define BT_ENABLE_VR #ifdef BT_ENABLE_VR #include "../RenderingExamples/TinyVRGui.h" #endif//BT_ENABLE_VR #include "../CommonInterfaces/CommonParameterInterface.h" - +#include "../Importers/ImportURDFDemo/urdfStringSplit.h" //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet! bool gEnablePicking=true; @@ -36,9 +37,7 @@ static bool gEnableDefaultKeyboardShortcuts = true; static bool gEnableDefaultMousePicking = true; -//extern btVector3 gLastPickPos; -btVector3 gVRTeleportPosLocal(0,0,0); -btQuaternion gVRTeleportOrnLocal(0,0,0,1); + btScalar gVRTeleportRotZ = 0; @@ -1132,10 +1131,17 @@ public: UserDebugText m_tmpText; int m_resultUserDebugTextUid; - virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags) + + virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid) { - m_tmpText.m_itemUniqueId = m_uidGenerator++; + if (replaceItemUid>=0) + { + m_tmpText.m_itemUniqueId = replaceItemUid; + } else + { + m_tmpText.m_itemUniqueId = m_uidGenerator++; + } m_tmpText.m_lifeTime = lifeTime; m_tmpText.textSize = size; //int len = strlen(txt); @@ -2171,10 +2177,26 @@ void PhysicsServerExample::updateGraphics() case eGUIUserDebugAddText: { B3_PROFILE("eGUIUserDebugAddText"); + + bool replaced = false; - m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText); - m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size()-1].m_itemUniqueId; + for (int i=0;im_userDebugText.size();i++) + { + if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpText.m_itemUniqueId) + { + m_multiThreadedHelper->m_userDebugText[i] = m_multiThreadedHelper->m_tmpText; + m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_tmpText.m_itemUniqueId; + replaced = true; + } + } + + if (!replaced) + { + m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText); + m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size()-1].m_itemUniqueId; + } m_multiThreadedHelper->mainThreadRelease(); + break; } case eGUIUserDebugAddParameter: @@ -2503,10 +2525,35 @@ void PhysicsServerExample::drawUserDebugLines() } + { + btAlignedObjectArray pieces; + btAlignedObjectArray separators; + separators.push_back("\n"); + urdfStringSplit(pieces,m_multiThreadedHelper->m_userDebugText[i].m_text,separators); + + double sz = m_multiThreadedHelper->m_userDebugText[i].textSize; + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(pos[0],pos[1],pos[2])); + tr.setRotation(btQuaternion(orientation[0],orientation[1],orientation[2],orientation[3])); - m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text, - pos,orientation,colorRGBA, - m_multiThreadedHelper->m_userDebugText[i].textSize,optionFlag); + //float newpos[3]={pos[0]-float(t)*sz,pos[1],pos[2]}; + + for (int t=0;tgetAppInterface()->drawText3D(pieces[t].c_str(), + newpos,orientation,colorRGBA, + sz,optionFlag); + + } + } /*m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text, diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index c4c82762d..5455ca9e3 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -700,7 +700,7 @@ enum EnumUserDebugDrawFlags USER_DEBUG_HAS_OPTION_FLAGS=256, USER_DEBUG_HAS_TEXT_ORIENTATION = 512, USER_DEBUG_HAS_PARENT_OBJECT=1024, - + USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID=2048, }; struct UserDebugDrawArgs @@ -721,7 +721,7 @@ struct UserDebugDrawArgs double m_textColorRGB[3]; double m_textSize; int m_optionFlags; - + int m_replaceItemUniqueId; double m_rangeMin; double m_rangeMax; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index b72f9ce82..e9ca947c7 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -38,9 +38,10 @@ subject to the following restrictions: struct MyTexture2 { - unsigned char* textureData; + unsigned char* textureData1; int m_width; int m_height; + bool m_isCached; }; struct TinyRendererObjectArray @@ -308,12 +309,13 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData)) { - if (meshData.m_textureImage) + if (meshData.m_textureImage1) { MyTexture2 texData; texData.m_width = meshData.m_textureWidth; texData.m_height = meshData.m_textureHeight; - texData.textureData = meshData.m_textureImage; + texData.textureData1 = meshData.m_textureImage1; + texData.m_isCached = meshData.m_isCached; texturesOut.push_back(texData); } glmesh = meshData.m_gfxShape; @@ -628,27 +630,32 @@ void TinyRendererVisualShapeConverter::convertVisualShapes( if (vertices.size() && indices.size()) { TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId); - unsigned char* textureImage=0; + unsigned char* textureImage1=0; int textureWidth=0; int textureHeight=0; + bool isCached = false; if (textures.size()) { - textureImage = textures[0].textureData; + textureImage1 = textures[0].textureData1; textureWidth = textures[0].m_width; textureHeight = textures[0].m_height; + isCached = textures[0].m_isCached; } { B3_PROFILE("registerMeshShape"); tinyObj->registerMeshShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), rgbaColor, - textureImage, textureWidth, textureHeight); + textureImage1, textureWidth, textureHeight); } visuals->m_renderObjects.push_back(tinyObj); } for (int i=0;im_textures.size();i++) { - free(m_data->m_textures[i].textureData); + if (!m_data->m_textures[i].m_isCached) + { + free(m_data->m_textures[i].textureData1); + } } m_data->m_textures.clear(); m_data->m_swRenderInstances.clear(); @@ -1117,7 +1127,7 @@ void TinyRendererVisualShapeConverter::activateShapeTexture(int objectUniqueId, TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v]; if ((shapeIndex < 0) || (shapeIndex == v)) { - renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height); + renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData1, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height); } } } @@ -1131,7 +1141,7 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int MyTexture2 texData; texData.m_width = width; texData.m_height = height; - texData.textureData = texels; + texData.textureData1 = texels; m_data->m_textures.push_back(texData); return m_data->m_textures.size()-1; } diff --git a/examples/SimpleOpenGL3/main.cpp b/examples/SimpleOpenGL3/main.cpp index 0422c96cc..295c43521 100644 --- a/examples/SimpleOpenGL3/main.cpp +++ b/examples/SimpleOpenGL3/main.cpp @@ -1,14 +1,27 @@ +//#define USE_OPENGL2 +#ifdef USE_OPENGL2 +#include "OpenGLWindow/SimpleOpenGL2App.h" +typedef SimpleOpenGL2App SimpleOpenGLApp ; + +#else #include "OpenGLWindow/SimpleOpenGL3App.h" +typedef SimpleOpenGL3App SimpleOpenGLApp ; + +#endif //USE_OPENGL2 + + + + #include "Bullet3Common/b3Quaternion.h" #include "Bullet3Common/b3CommandLineArgs.h" #include "assert.h" #include -char* gVideoFileName = 0; -char* gPngFileName = 0; +static char* gVideoFileName = 0; +static char* gPngFileName = 0; static b3WheelCallback sOldWheelCB = 0; static b3ResizeCallback sOldResizeCB = 0; @@ -17,15 +30,15 @@ static b3MouseButtonCallback sOldMouseButtonCB = 0; static b3KeyboardCallback sOldKeyboardCB = 0; //static b3RenderCallback sOldRenderCB = 0; -float gWidth = 1024; -float gHeight = 768; +static float gWidth = 1024; +static float gHeight = 768; -void MyWheelCallback(float deltax, float deltay) +void MyWheelCallback2(float deltax, float deltay) { if (sOldWheelCB) sOldWheelCB(deltax,deltay); } -void MyResizeCallback( float width, float height) +void MyResizeCallback2( float width, float height) { gWidth = width; gHeight = height; @@ -33,21 +46,21 @@ void MyResizeCallback( float width, float height) if (sOldResizeCB) sOldResizeCB(width,height); } -void MyMouseMoveCallback( float x, float y) +void MyMouseMoveCallback2( float x, float y) { printf("Mouse Move: %f, %f\n", x,y); if (sOldMouseMoveCB) sOldMouseMoveCB(x,y); } -void MyMouseButtonCallback(int button, int state, float x, float y) +void MyMouseButtonCallback2(int button, int state, float x, float y) { if (sOldMouseButtonCB) sOldMouseButtonCB(button,state,x,y); } -void MyKeyboardCallback(int keycode, int state) +static void MyKeyboardCallback2(int keycode, int state) { //keycodes are in examples/CommonInterfaces/CommonWindowInterface.h //for example B3G_ESCAPE for escape key @@ -65,21 +78,21 @@ int main(int argc, char* argv[]) b3CommandLineArgs myArgs(argc, argv); - SimpleOpenGL3App* app = new SimpleOpenGL3App("SimpleOpenGL3App", gWidth, gHeight, true); + SimpleOpenGLApp* app = new SimpleOpenGLApp("SimpleOpenGL3App", gWidth, gHeight); - app->m_instancingRenderer->getActiveCamera()->setCameraDistance(13); - app->m_instancingRenderer->getActiveCamera()->setCameraPitch(0); - app->m_instancingRenderer->getActiveCamera()->setCameraTargetPosition(0, 0, 0); + app->m_renderer->getActiveCamera()->setCameraDistance(13); + app->m_renderer->getActiveCamera()->setCameraPitch(0); + app->m_renderer->getActiveCamera()->setCameraTargetPosition(0, 0, 0); sOldKeyboardCB = app->m_window->getKeyboardCallback(); - app->m_window->setKeyboardCallback(MyKeyboardCallback); + app->m_window->setKeyboardCallback(MyKeyboardCallback2); sOldMouseMoveCB = app->m_window->getMouseMoveCallback(); - app->m_window->setMouseMoveCallback(MyMouseMoveCallback); + app->m_window->setMouseMoveCallback(MyMouseMoveCallback2); sOldMouseButtonCB = app->m_window->getMouseButtonCallback(); - app->m_window->setMouseButtonCallback(MyMouseButtonCallback); + app->m_window->setMouseButtonCallback(MyMouseButtonCallback2); sOldWheelCB = app->m_window->getWheelCallback(); - app->m_window->setWheelCallback(MyWheelCallback); + app->m_window->setWheelCallback(MyWheelCallback2); sOldResizeCB = app->m_window->getResizeCallback(); - app->m_window->setResizeCallback(MyResizeCallback); + app->m_window->setResizeCallback(MyResizeCallback2); myArgs.GetCmdLineArgument("mp4_file", gVideoFileName); @@ -134,10 +147,12 @@ int main(int argc, char* argv[]) app->m_primRenderer->drawTexturedRect(100, 200, gWidth / 2 - 50, gHeight / 2 - 50, color, 0, 0, 1, 1, true); - app->m_instancingRenderer->init(); - app->m_instancingRenderer->updateCamera(); + app->m_renderer->init(); + int upAxis = 1; + app->m_renderer->updateCamera(upAxis); app->m_renderer->renderScene(); + app->drawGrid(); char bla[1024]; sprintf(bla, "2d text:%d", frameCount); diff --git a/examples/SimpleOpenGL3/main_imgui.cpp b/examples/SimpleOpenGL3/main_imgui.cpp index 998412c1a..1bd07f7d1 100644 --- a/examples/SimpleOpenGL3/main_imgui.cpp +++ b/examples/SimpleOpenGL3/main_imgui.cpp @@ -73,6 +73,7 @@ void ImGui_ImplBullet_CreateDeviceObjects() void ImGui_ImplBullet_RenderDrawLists(ImDrawData* draw_data) { + glEnable(GL_COLOR_MATERIAL); // Avoid rendering when minimized, scale coordinates for retina displays (screen coordinates != framebuffer coordinates) ImGuiIO& io = ImGui::GetIO(); int fb_width = (int)(io.DisplaySize.x * io.DisplayFramebufferScale.x); @@ -96,7 +97,7 @@ void ImGui_ImplBullet_RenderDrawLists(ImDrawData* draw_data) glEnableClientState(GL_TEXTURE_COORD_ARRAY); glEnableClientState(GL_COLOR_ARRAY); glEnable(GL_TEXTURE_2D); - //glUseProgram(0); // You may want this if using this code in an OpenGL 3+ context + glUseProgram(0); // You may want this if using this code in an OpenGL 3+ context // Setup viewport, orthographic projection matrix glViewport(0, 0, (GLsizei)fb_width, (GLsizei)fb_height); diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 508e6c461..fd578f7d1 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -3444,11 +3444,12 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj double lifeTime = 0.f; int physicsClientId = 0; int debugItemUniqueId = -1; + int replaceItemUniqueId = -1; b3PhysicsClientHandle sm = 0; - static char* kwlist[] = {"text", "textPosition", "textColorRGB", "textSize", "lifeTime", "textOrientation", "parentObjectUniqueId", "parentLinkIndex", "physicsClientId", NULL}; + static char* kwlist[] = {"text", "textPosition", "textColorRGB", "textSize", "lifeTime", "textOrientation", "parentObjectUniqueId", "parentLinkIndex", "replaceItemUniqueId", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "sO|OddOiii", kwlist, &text, &textPositionObj, &textColorRGBObj, &textSize, &lifeTime, &textOrientationObj, &parentObjectUniqueId, &parentLinkIndex, &physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "sO|OddOiiii", kwlist, &text, &textPositionObj, &textColorRGBObj, &textSize, &lifeTime, &textOrientationObj, &parentObjectUniqueId, &parentLinkIndex, &replaceItemUniqueId, &physicsClientId)) { return NULL; } @@ -3495,6 +3496,11 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj } } + if (replaceItemUniqueId>=0) + { + b3UserDebugItemSetReplaceItemUniqueId(commandHandle,replaceItemUniqueId); + } + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle);