Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/erwincoumans/bullet3
Browse files Browse the repository at this point in the history
  • Loading branch information
Erwin Coumans committed Apr 27, 2019
2 parents 73ecd49 + 1c6aa4b commit c591735
Show file tree
Hide file tree
Showing 5 changed files with 24 additions and 22 deletions.
2 changes: 1 addition & 1 deletion examples/SharedMemory/b3PluginManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ struct b3PluginManagerInternalData
b3BulletDefaultFileIO m_defaultFileIO;

b3PluginManagerInternalData()
: m_rpcCommandProcessorInterface(0), m_activeNotificationsBufferIndex(0), m_activeRendererPluginUid(-1), m_activeCollisionPluginUid(-1), m_numNotificationPlugins(0), m_activeFileIOPluginUid(-1)
: m_physicsDirect(0), m_rpcCommandProcessorInterface(0), m_activeNotificationsBufferIndex(0), m_activeRendererPluginUid(-1), m_activeCollisionPluginUid(-1), m_numNotificationPlugins(0), m_activeFileIOPluginUid(-1)
{
}
};
Expand Down
40 changes: 21 additions & 19 deletions examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,35 +388,37 @@ struct WrapperFileIO : public CommonFileIOInterface
int childHandle = childFileIO->fileOpen(fileName, mode);
if (childHandle>=0)
{
int fileSize = childFileIO->getFileSize(childHandle);
char* buffer = 0;
if (fileSize)
if (m_enableFileCaching)
{
buffer = m_cachedFiles.allocateBuffer(fileSize);
if (buffer)
int fileSize = childFileIO->getFileSize(childHandle);
char* buffer = 0;
if (fileSize)
{
int readBytes = childFileIO->fileRead(childHandle, buffer, fileSize);
if (readBytes!=fileSize)
buffer = m_cachedFiles.allocateBuffer(fileSize);
if (buffer)
{
if (readBytes<fileSize)
{
fileSize = readBytes;
} else
int readBytes = childFileIO->fileRead(childHandle, buffer, fileSize);
if (readBytes!=fileSize)
{
printf("WrapperFileIO error: reading more bytes (%d) then reported file size (%d) of file %s.\n", readBytes, fileSize, fileName);
if (readBytes<fileSize)
{
fileSize = readBytes;
} else
{
printf("WrapperFileIO error: reading more bytes (%d) then reported file size (%d) of file %s.\n", readBytes, fileSize, fileName);
}
}
} else
{
fileSize=0;
}
} else
{
fileSize=0;
}
}

//potentially register a zero byte file, or files that only can be read partially
if (m_enableFileCaching)
{
//potentially register a zero byte file, or files that only can be read partially

m_cachedFiles.registerFile(fileName, buffer, fileSize);
}

childFileIO->fileClose(childHandle);
break;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@

mocapData = motion_capture_data.MotionCaptureData()

motionPath = pybullet_data.getDataPath()+"/data/motions/laikago_walk.json"
motionPath = pybullet_data.getDataPath()+"/data/motions/laikago_walk.txt"

mocapData.Load(motionPath)
print("mocapData.NumFrames=",mocapData.NumFrames())
Expand Down
2 changes: 1 addition & 1 deletion setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -468,7 +468,7 @@ def _single_compile(obj):

setup(
name = 'pybullet',
version='2.4.8',
version='2.4.9',
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',
Expand Down

0 comments on commit c591735

Please sign in to comment.