Merge pull request #1942 from erwincoumans/master

add missing file in MANIFEST.in,  fix potential memory leak in InMemoryFileIO, bump up PyBullet version
This commit is contained in:
erwincoumans
2018-10-20 12:25:50 -07:00
committed by GitHub
5 changed files with 43 additions and 22 deletions

View File

@@ -8,5 +8,6 @@ recursive-include src *.hpp
recursive-include examples/pybullet/gym *.* recursive-include examples/pybullet/gym *.*
include examples/ThirdPartyLibs/enet/unix.c include examples/ThirdPartyLibs/enet/unix.c
include examples/OpenGLWindow/*.* include examples/OpenGLWindow/*.*
recursive-include examples/SharedMemory/plugins *.*
recursive-include examples/ThirdPartyLibs/glad *.* recursive-include examples/ThirdPartyLibs/glad *.*
include examples/ThirdPartyLibs/enet/win32.c include examples/ThirdPartyLibs/enet/win32.c

View File

@@ -399,8 +399,8 @@ end
else else
xcodebuildsettings xcodebuildsettings
{ {
'ARCHS = "$(ARCHS_STANDARD_32_BIT) $(ARCHS_STANDARD_64_BIT)"', 'ARCHS = "$(ARCHS_STANDARD_64_BIT)"',
'VALID_ARCHS = "x86_64 i386"', 'VALID_ARCHS = "x86_64"',
-- 'SDKROOT = "macosx10.9"', -- 'SDKROOT = "macosx10.9"',
} }
end end

View File

@@ -1,5 +1,3 @@
#include "fileIOPlugin.h" #include "fileIOPlugin.h"
#include "../../SharedMemoryPublic.h" #include "../../SharedMemoryPublic.h"
#include "../b3PluginContext.h" #include "../b3PluginContext.h"
@@ -46,9 +44,14 @@ struct InMemoryFileIO : public CommonFileIOInterface
{ {
b3HashMap<b3HashString,InMemoryFile*> m_fileCache; b3HashMap<b3HashString,InMemoryFile*> m_fileCache;
InMemoryFileAccessor m_fileHandles[B3_MAX_FILEIO_INTERFACES]; InMemoryFileAccessor m_fileHandles[B3_MAX_FILEIO_INTERFACES];
int m_numAllocs;
int m_numFrees;
InMemoryFileIO() InMemoryFileIO()
{ {
m_numAllocs=0;
m_numFrees=0;
for (int i=0;i<B3_FILEIO_MAX_FILES;i++) for (int i=0;i<B3_FILEIO_MAX_FILES;i++)
{ {
m_fileHandles[i].m_curPos = 0; m_fileHandles[i].m_curPos = 0;
@@ -59,8 +62,11 @@ struct InMemoryFileIO : public CommonFileIOInterface
virtual ~InMemoryFileIO() virtual ~InMemoryFileIO()
{ {
clearCache(); clearCache();
if (m_numAllocs != m_numFrees)
{
printf("Error: InMemoryFile::~InMemoryFileIO (numAllocs %d numFrees %d\n", m_numAllocs, m_numFrees);
}
} }
void clearCache() void clearCache()
{ {
for (int i=0;i<m_fileCache.size();i++) for (int i=0;i<m_fileCache.size();i++)
@@ -70,7 +76,9 @@ struct InMemoryFileIO : public CommonFileIOInterface
{ {
InMemoryFile* mem = *memPtr; InMemoryFile* mem = *memPtr;
freeBuffer(mem->m_buffer); freeBuffer(mem->m_buffer);
m_numFrees++;
delete (mem); delete (mem);
m_numFrees++;
} }
} }
} }
@@ -80,6 +88,7 @@ struct InMemoryFileIO : public CommonFileIOInterface
char* buffer = 0; char* buffer = 0;
if (len) if (len)
{ {
m_numAllocs++;
buffer = new char[len]; buffer = new char[len];
} }
return buffer; return buffer;
@@ -92,6 +101,7 @@ struct InMemoryFileIO : public CommonFileIOInterface
virtual int registerFile(const char* fileName, char* buffer, int len) virtual int registerFile(const char* fileName, char* buffer, int len)
{ {
m_numAllocs++;
InMemoryFile* f = new InMemoryFile(); InMemoryFile* f = new InMemoryFile();
f->m_buffer = buffer; f->m_buffer = buffer;
f->m_fileSize = len; f->m_fileSize = len;
@@ -227,7 +237,6 @@ struct InMemoryFileIO : public CommonFileIOInterface
} }
if (c && c!='\n') if (c && c!='\n')
{ {
char a='\r';
if (c!=13) if (c!=13)
{ {
destBuffer[numRead++]=c; destBuffer[numRead++]=c;
@@ -347,8 +356,12 @@ struct WrapperFileIO : public CommonFileIOInterface
if (slot>=0) if (slot>=0)
{ {
//first check the cache //first check the cache
int childHandle = m_cachedFiles.fileOpen(fileName, mode); int cacheHandle = m_cachedFiles.fileOpen(fileName, mode);
if (childHandle<0) if (cacheHandle>=0)
{
m_cachedFiles.fileClose(cacheHandle);
}
if (cacheHandle<0)
{ {
for (int i=0;i<B3_MAX_FILEIO_INTERFACES;i++) for (int i=0;i<B3_MAX_FILEIO_INTERFACES;i++)
{ {
@@ -444,7 +457,6 @@ struct WrapperFileIO : public CommonFileIOInterface
} }
virtual void fileClose(int fileHandle) virtual void fileClose(int fileHandle)
{ {
int fileReadResult=-1;
if (fileHandle>=0 && fileHandle<B3_MAX_FILEIO_INTERFACES) if (fileHandle>=0 && fileHandle<B3_MAX_FILEIO_INTERFACES)
{ {
if (m_wrapperFileHandles[fileHandle].childFileIO) if (m_wrapperFileHandles[fileHandle].childFileIO)
@@ -477,7 +489,6 @@ struct WrapperFileIO : public CommonFileIOInterface
{ {
char* result = 0; char* result = 0;
int fileReadResult=-1;
if (fileHandle>=0 && fileHandle<B3_MAX_FILEIO_INTERFACES) if (fileHandle>=0 && fileHandle<B3_MAX_FILEIO_INTERFACES)
{ {
if (m_wrapperFileHandles[fileHandle].childFileIO) if (m_wrapperFileHandles[fileHandle].childFileIO)
@@ -493,7 +504,6 @@ struct WrapperFileIO : public CommonFileIOInterface
{ {
int numBytes = 0; int numBytes = 0;
int fileReadResult=-1;
if (fileHandle>=0 && fileHandle<B3_MAX_FILEIO_INTERFACES) if (fileHandle>=0 && fileHandle<B3_MAX_FILEIO_INTERFACES)
{ {
if (m_wrapperFileHandles[fileHandle].childFileIO) if (m_wrapperFileHandles[fileHandle].childFileIO)
@@ -589,8 +599,7 @@ B3_SHARED_API int executePluginCommand_fileIOPlugin(struct b3PluginContext* cont
case eCNSFileIO: case eCNSFileIO:
{ {
#ifdef B3_USE_CNS_FILEIO #ifdef B3_USE_CNS_FILEIO
B3_USE_ZIPFILE_FILEIO if (strlen(arguments->m_text))
if (arguments->m_text)
{ {
obj->m_fileIO.addFileIOInterface(new CNSFileIO(arguments->m_text)); obj->m_fileIO.addFileIOInterface(new CNSFileIO(arguments->m_text));
} }

View File

@@ -581,7 +581,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
setup( setup(
name = 'pybullet', name = 'pybullet',
version='2.3.0', version='2.3.2',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', 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.', 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', url='https://github.com/bulletphysics/bullet3',

View File

@@ -1711,7 +1711,7 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link,
const btVector3 &normal_ang, const btVector3 &normal_ang,
const btVector3 &normal_lin, const btVector3 &normal_lin,
btScalar *jac, btScalar *jac,
btAlignedObjectArray<btScalar> &scratch_r, btAlignedObjectArray<btScalar> &scratch_r1,
btAlignedObjectArray<btVector3> &scratch_v, btAlignedObjectArray<btVector3> &scratch_v,
btAlignedObjectArray<btMatrix3x3> &scratch_m) const btAlignedObjectArray<btMatrix3x3> &scratch_m) const
{ {
@@ -1730,8 +1730,19 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link,
v_ptr += num_links + 1; v_ptr += num_links + 1;
btAssert(v_ptr - &scratch_v[0] == scratch_v.size()); btAssert(v_ptr - &scratch_v[0] == scratch_v.size());
scratch_r.resize(m_dofCount); //scratch_r.resize(m_dofCount);
btScalar *results = m_dofCount > 0 ? &scratch_r[0] : 0; //btScalar *results = m_dofCount > 0 ? &scratch_r[0] : 0;
scratch_r1.resize(m_dofCount+num_links);
btScalar * results = m_dofCount > 0 ? &scratch_r1[0] : 0;
btScalar* links = num_links? &scratch_r1[m_dofCount] : 0;
int numLinksChildToRoot=0;
int l = link;
while (l != -1)
{
links[numLinksChildToRoot++]=l;
l = m_links[l].m_parent;
}
btMatrix3x3 *rot_from_world = &scratch_m[0]; btMatrix3x3 *rot_from_world = &scratch_m[0];
@@ -1766,14 +1777,14 @@ void btMultiBody::fillConstraintJacobianMultiDof(int link,
// Qdot coefficients, if necessary. // Qdot coefficients, if necessary.
if (num_links > 0 && link > -1) if (num_links > 0 && link > -1)
{ {
// TODO: speed this up -- don't calculate for m_links we don't need. // TODO: (Also, we are making 3 separate calls to this function, for the normal & the 2 friction directions,
// (Also, we are making 3 separate calls to this function, for the normal & the 2 friction directions,
// which is resulting in repeated work being done...) // which is resulting in repeated work being done...)
// calculate required normals & positions in the local frames. // calculate required normals & positions in the local frames.
for (int i = 0; i < num_links; ++i) for (int a = 0; a < numLinksChildToRoot; a++)
{ {
// transform to local frame int i = links[numLinksChildToRoot-1-a];
// transform to local frame
const int parent = m_links[i].m_parent; const int parent = m_links[i].m_parent;
const btMatrix3x3 mtx(m_links[i].m_cachedRotParentToThis); const btMatrix3x3 mtx(m_links[i].m_cachedRotParentToThis);
rot_from_world[i + 1] = mtx * rot_from_world[parent + 1]; rot_from_world[i + 1] = mtx * rot_from_world[parent + 1];