From 0d4392af5882878d26aad67f27874fed7968d920 Mon Sep 17 00:00:00 2001 From: Erwin Coumans <erwincoumans@google.com> Date: Thu, 18 Apr 2019 14:18:34 -0700 Subject: [PATCH 1/3] rename laikago_walk.json -> txt --- .../data/motions/{laikago_walk.json => laikago_walk.txt} | 0 .../pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename examples/pybullet/gym/pybullet_data/data/motions/{laikago_walk.json => laikago_walk.txt} (100%) 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()) From 72c6ed9abe8b2145bc10124ef7fff6eeb7f19b75 Mon Sep 17 00:00:00 2001 From: Erwin Coumans <erwincoumans@google.com> Date: Thu, 25 Apr 2019 07:04:22 -0700 Subject: [PATCH 2/3] fix file caching issue --- examples/SharedMemory/b3PluginManager.cpp | 2 +- .../plugins/fileIOPlugin/fileIOPlugin.cpp | 40 ++++++++++--------- 2 files changed, 22 insertions(+), 20 deletions(-) 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 (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; } From 1c6aa4b67e841f4a319f2f8f697ec231a491e6c9 Mon Sep 17 00:00:00 2001 From: Erwin Coumans <erwincoumans@google.com> Date: Thu, 25 Apr 2019 08:07:36 -0700 Subject: [PATCH 3/3] bump up PyBullet to 2.4.9 --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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',