Merge pull request #2247 from erwincoumans/master

fix test compilation
This commit is contained in:
erwincoumans
2019-05-08 18:06:28 -07:00
committed by GitHub
2 changed files with 13 additions and 3 deletions

View File

@@ -3394,6 +3394,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char*
} }
streamSizeInBytes = ser.getCurrentBufferSize(); streamSizeInBytes = ser.getCurrentBufferSize();
} }
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
else if(bodyHandle->m_softBody){ else if(bodyHandle->m_softBody){
//minimum serialization, registerNameForPointer //minimum serialization, registerNameForPointer
btSoftBody* sb = bodyHandle->m_softBody; btSoftBody* sb = bodyHandle->m_softBody;
@@ -3408,7 +3409,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char*
ser.finalizeChunk(chunk, structType, BT_SOFTBODY_CODE, sb); ser.finalizeChunk(chunk, structType, BT_SOFTBODY_CODE, sb);
streamSizeInBytes = ser.getCurrentBufferSize(); streamSizeInBytes = ser.getCurrentBufferSize();
} }
#endif
return streamSizeInBytes; return streamSizeInBytes;
} }
@@ -5515,7 +5516,11 @@ bool PhysicsServerCommandProcessor::processSyncBodyInfoCommand(const struct Shar
{ {
int usedHandle = usedHandles[i]; int usedHandle = usedHandles[i];
InternalBodyData* body = m_data->m_bodyHandles.getHandle(usedHandle); InternalBodyData* body = m_data->m_bodyHandles.getHandle(usedHandle);
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
if (body && (body->m_multiBody || body->m_rigidBody || body->m_softBody)) if (body && (body->m_multiBody || body->m_rigidBody || body->m_softBody))
#else
if (body && (body->m_multiBody || body->m_rigidBody))
#endif
{ {
serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[actualNumBodies++] = usedHandle; serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[actualNumBodies++] = usedHandle;
} }
@@ -6579,6 +6584,7 @@ bool PhysicsServerCommandProcessor::processRequestActualStateCommand(const struc
hasStatus = true; hasStatus = true;
} }
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
else if (body && body->m_softBody) else if (body && body->m_softBody)
{ {
btSoftBody* sb = body->m_softBody; btSoftBody* sb = body->m_softBody;
@@ -6625,6 +6631,7 @@ bool PhysicsServerCommandProcessor::processRequestActualStateCommand(const struc
hasStatus = true; hasStatus = true;
} }
#endif
else else
{ {
//b3Warning("Request state but no multibody or rigid body available"); //b3Warning("Request state but no multibody or rigid body available");
@@ -7633,13 +7640,14 @@ bool PhysicsServerCommandProcessor::processRequestCollisionInfoCommand(const str
serverCmd.m_sendCollisionInfoArgs.m_rootWorldAABBMax[2] = aabbMax[2]; serverCmd.m_sendCollisionInfoArgs.m_rootWorldAABBMax[2] = aabbMax[2];
} }
} }
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
else if (body && body->m_softBody){ else if (body && body->m_softBody){
SharedMemoryStatus& serverCmd = serverStatusOut; SharedMemoryStatus& serverCmd = serverStatusOut;
serverStatusOut.m_type = CMD_REQUEST_COLLISION_INFO_COMPLETED; serverStatusOut.m_type = CMD_REQUEST_COLLISION_INFO_COMPLETED;
serverCmd.m_sendCollisionInfoArgs.m_numLinks = 0; serverCmd.m_sendCollisionInfoArgs.m_numLinks = 0;
setDefaultRootWorldAABB(serverCmd); setDefaultRootWorldAABB(serverCmd);
} }
#endif
return hasStatus; return hasStatus;
} }
@@ -8236,12 +8244,14 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S
} }
hasStatus = true; hasStatus = true;
} }
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
else if (body && body->m_softBody){ else if (body && body->m_softBody){
//todo: @fuchuyuan implement dynamics info //todo: @fuchuyuan implement dynamics info
b3Warning("Softbody dynamics info not set!!!"); b3Warning("Softbody dynamics info not set!!!");
SharedMemoryStatus& serverCmd = serverStatusOut; SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED; serverCmd.m_type = CMD_GET_DYNAMICS_INFO_COMPLETED;
} }
#endif
return hasStatus; return hasStatus;
} }

View File

@@ -483,7 +483,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
setup( setup(
name='pybullet', name='pybullet',
version='2.4.9', version='2.5.0',
description= description=
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', 'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description= long_description=