This commit is contained in:
erwincoumans
2018-12-19 20:15:40 -08:00
9 changed files with 12 additions and 5 deletions

View File

@@ -591,6 +591,7 @@ void LoadMeshFromCollada(const char* relativeFileName, btAlignedObjectArray<GLIn
if (actual==size)
{
}
fileIO->fileClose(fileHandle);
}
if (xmlString.size()==0)
return;

View File

@@ -141,6 +141,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
buffer.resize(0);
}
}
fileIO->fileClose(fileId);
}
if (buffer.size())

View File

@@ -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;
}
}

View File

@@ -10244,6 +10244,7 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share
buffer.resize(0);
}
}
fileIO->fileClose(fileId);
}
if (buffer.size())
{

View File

@@ -1361,6 +1361,7 @@ int EGLRendererVisualShapeConverter::loadTextureFile(const char* filename, struc
buffer.resize(0);
}
}
fileIO->fileClose(fileId);
}
if (buffer.size())
{

View File

@@ -1270,6 +1270,7 @@ int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename, stru
buffer.resize(0);
}
}
fileIO->fileClose(fileId);
}
if (buffer.size())
{

View File

@@ -579,7 +579,7 @@ std::string LoadMtl(
// flush last material.
material_map.insert(std::pair<std::string, material_t>(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);
}

View File

@@ -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',

View File

@@ -247,7 +247,9 @@ void btDbvtBroadphase::rayTest(const btVector3& rayFrom, const btVector3& rayTo,
// instead of just a local.
int threadIndex = btGetCurrentThreadIndex();
btAlignedObjectArray<const btDbvtNode*> 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];