mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-05 01:50:05 +00:00
Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
commit
c591735042
@ -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)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
@ -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)
|
||||
{
|
||||
buffer = m_cachedFiles.allocateBuffer(fileSize);
|
||||
if (buffer)
|
||||
{
|
||||
int readBytes = childFileIO->fileRead(childHandle, buffer, fileSize);
|
||||
if (readBytes!=fileSize)
|
||||
{
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
//potentially register a zero byte file, or files that only can be read partially
|
||||
if (m_enableFileCaching)
|
||||
{
|
||||
int fileSize = childFileIO->getFileSize(childHandle);
|
||||
char* buffer = 0;
|
||||
if (fileSize)
|
||||
{
|
||||
buffer = m_cachedFiles.allocateBuffer(fileSize);
|
||||
if (buffer)
|
||||
{
|
||||
int readBytes = childFileIO->fileRead(childHandle, buffer, fileSize);
|
||||
if (readBytes!=fileSize)
|
||||
{
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
//potentially register a zero byte file, or files that only can be read partially
|
||||
|
||||
m_cachedFiles.registerFile(fileName, buffer, fileSize);
|
||||
}
|
||||
|
||||
childFileIO->fileClose(childHandle);
|
||||
break;
|
||||
}
|
||||
|
@ -116,7 +116,7 @@ joints=[]
|
||||
|
||||
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())
|
||||
|
2
setup.py
2
setup.py
@ -468,7 +468,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
|
||||
|
||||
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',
|
||||
|
Loading…
Reference in New Issue
Block a user