From e5d4c73c4040e5df78a170e52a6c13a7f24fffea Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 9 Oct 2017 22:40:53 -0700 Subject: [PATCH] fix very rare threading issue, let main thread compute the UID for user debug items add collision model to cartpole.urdf --- data/cartpole.urdf | 6 ++++++ examples/SharedMemory/PhysicsServerExample.cpp | 15 ++++++++++----- 2 files changed, 16 insertions(+), 5 deletions(-) diff --git a/data/cartpole.urdf b/data/cartpole.urdf index c22ca920c..e78b066c1 100644 --- a/data/cartpole.urdf +++ b/data/cartpole.urdf @@ -62,6 +62,12 @@ + + + + + + diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 3ab943e3c..3c9b4a70c 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -1131,7 +1131,7 @@ public: btAlignedObjectArray m_userDebugText; 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) { @@ -1165,7 +1165,7 @@ public: m_cs->setSharedParam(1, eGUIUserDebugAddText); workerThreadWait(); - return m_userDebugText[m_userDebugText.size()-1].m_itemUniqueId; + return m_resultUserDebugTextUid; } btAlignedObjectArray m_userDebugParams; @@ -1183,6 +1183,7 @@ public: } return 0; } + int m_userDebugParamUid; virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue) { @@ -1196,13 +1197,13 @@ public: m_cs->setSharedParam(1, eGUIUserDebugAddParameter); workerThreadWait(); - return (*m_userDebugParams[m_userDebugParams.size()-1]).m_itemUniqueId; + return m_userDebugParamUid; } btAlignedObjectArray m_userDebugLines; UserDebugDrawLine m_tmpLine; - + int m_resultDebugLineUid; virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex) { m_tmpLine.m_lifeTime = lifeTime; @@ -1223,7 +1224,7 @@ public: m_cs->lock(); m_cs->setSharedParam(1, eGUIUserDebugAddLine); workerThreadWait(); - return m_userDebugLines[m_userDebugLines.size()-1].m_itemUniqueId; + return m_resultDebugLineUid; } int m_removeDebugItemUid; @@ -2171,6 +2172,7 @@ void PhysicsServerExample::updateGraphics() B3_PROFILE("eGUIUserDebugAddText"); 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; } @@ -2190,6 +2192,8 @@ void PhysicsServerExample::updateGraphics() m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->registerSliderFloatParameter(slider); } + m_multiThreadedHelper->m_userDebugParamUid = (*m_multiThreadedHelper->m_userDebugParams[m_multiThreadedHelper->m_userDebugParams.size()-1]).m_itemUniqueId; + //also add actual menu m_multiThreadedHelper->mainThreadRelease(); break; @@ -2199,6 +2203,7 @@ void PhysicsServerExample::updateGraphics() B3_PROFILE("eGUIUserDebugAddLine"); m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine); + m_multiThreadedHelper->m_resultDebugLineUid = m_multiThreadedHelper->m_userDebugLines[m_multiThreadedHelper->m_userDebugLines.size()-1].m_itemUniqueId; m_multiThreadedHelper->mainThreadRelease(); break; }