diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp index fa06cd52b4..7703abb548 100644 --- a/examples/SharedMemory/b3PluginManager.cpp +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -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) { } }; diff --git a/examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp b/examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp index 43d20387a3..0be09d9db1 100644 --- a/examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp +++ b/examples/SharedMemory/plugins/fileIOPlugin/fileIOPlugin.cpp @@ -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 (readBytesfileRead(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 (readBytesfileClose(childHandle); break; } diff --git a/examples/pybullet/gym/pybullet_data/data/motions/laikago_walk.json b/examples/pybullet/gym/pybullet_data/data/motions/laikago_walk.txt similarity index 100% rename from examples/pybullet/gym/pybullet_data/data/motions/laikago_walk.json rename to examples/pybullet/gym/pybullet_data/data/motions/laikago_walk.txt diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py index 1ad8972ed5..c7543639f5 100644 --- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py +++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py @@ -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()) diff --git a/setup.py b/setup.py index 0e7429efc8..dbd4f35ccb 100644 --- a/setup.py +++ b/setup.py @@ -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',