From a23cfd078259e7bab670a67809424c9cdbeeaedc Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 29 Nov 2018 16:50:37 -0800 Subject: [PATCH 1/4] bump up pybullet version to 2.4.0 --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index f4f6b4fed..98efabdbf 100644 --- a/setup.py +++ b/setup.py @@ -585,7 +585,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS: setup( name = 'pybullet', - version='2.3.9', + version='2.4.0', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', url='https://github.com/bulletphysics/bullet3', From d4db50f66850d7f87bad9b8c8612816f00a4e1cb Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 4 Dec 2018 19:37:25 +0100 Subject: [PATCH 2/4] PyBullet: fix some file leaks. --- examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp | 1 + examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 1 + examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp | 4 ++-- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 5f553bcbe..b4e02243d 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -141,6 +141,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& buffer.resize(0); } } + fileIO->fileClose(fileId); } if (buffer.size()) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index db69fa956..54329ec27 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -10244,6 +10244,7 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share buffer.resize(0); } } + fileIO->fileClose(fileId); } if (buffer.size()) { diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index 115cde02a..9cd2f2092 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -579,7 +579,7 @@ std::string LoadMtl( // flush last material. material_map.insert(std::pair(material.name, material)); - if (fileHandle) + if (fileHandle>=0) { fileIO->fileClose(fileHandle); } @@ -858,7 +858,7 @@ LoadObj( } faceGroup.resize(0); // for safety - if (fileHandle) + if (fileHandle>=0) { fileIO->fileClose(fileHandle); } From e3c03401c80b23d3e8cc67ffbf0efcd5885e556d Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 4 Dec 2018 19:58:24 +0100 Subject: [PATCH 3/4] PyBullet: fixed a few more file leaks --- examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp | 1 + examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h | 2 +- .../plugins/eglPlugin/eglRendererVisualShapeConverter.cpp | 1 + .../tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp | 1 + 4 files changed, 4 insertions(+), 1 deletion(-) diff --git a/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp b/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp index bf5a39002..2f550e254 100644 --- a/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp +++ b/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp @@ -591,6 +591,7 @@ void LoadMeshFromCollada(const char* relativeFileName, btAlignedObjectArrayfileClose(fileHandle); } if (xmlString.size()==0) return; diff --git a/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h b/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h index b9e3bed5e..53331e147 100644 --- a/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h +++ b/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h @@ -1,4 +1,3 @@ - #ifndef LOAD_MESH_FROM_STL_H #define LOAD_MESH_FROM_STL_H @@ -46,6 +45,7 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName, st if (expectedBinaryFileSize != size) { delete[] memoryBuffer; + fileIO->fileClose(fileHandle); return 0; } } diff --git a/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp b/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp index 0eca8b221..76910fe14 100644 --- a/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp @@ -1361,6 +1361,7 @@ int EGLRendererVisualShapeConverter::loadTextureFile(const char* filename, struc buffer.resize(0); } } + fileIO->fileClose(fileId); } if (buffer.size()) { diff --git a/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp index e3b5d7992..d9d8eb203 100644 --- a/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp @@ -1270,6 +1270,7 @@ int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename, stru buffer.resize(0); } } + fileIO->fileClose(fileId); } if (buffer.size()) { From 74223ced566f9bdefb5f53f970249a197c1127bc Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 4 Dec 2018 20:00:05 +0100 Subject: [PATCH 4/4] disable per-thread tsan issue, todo: checkout why it fails --- src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp index 69e9ee748..7b39dbdc0 100644 --- a/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp +++ b/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp @@ -247,7 +247,9 @@ void btDbvtBroadphase::rayTest(const btVector3& rayFrom, const btVector3& rayTo, // instead of just a local. int threadIndex = btGetCurrentThreadIndex(); btAlignedObjectArray localStack; - if (threadIndex < m_rayTestStacks.size()) + //todo(erwincoumans, "why do we get tsan issue here?") + if (0)//threadIndex < m_rayTestStacks.size()) + //if (threadIndex < m_rayTestStacks.size()) { // use per-thread preallocated stack if possible to avoid dynamic allocations stack = &m_rayTestStacks[threadIndex];