This commit is contained in:
erwincoumans
2018-07-01 14:42:48 -07:00
13 changed files with 76 additions and 77 deletions

View File

@@ -201,7 +201,7 @@ struct DummyGUIHelper : public GUIHelperInterface
{
}
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex)
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex, int replaceItemUid)
{
return -1;
}

View File

@@ -181,8 +181,17 @@ bool TcpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryComma
}
else
{
sz = sizeof(SharedMemoryCommand);
data = (unsigned char*)&clientCmd;
if (clientCmd.m_type == CMD_REQUEST_VR_EVENTS_DATA)
{
sz = 3 * sizeof(int) + sizeof(smUint64_t) + 16;
data = (unsigned char*)&clientCmd;
}
else
{
sz = sizeof(SharedMemoryCommand);
data = (unsigned char*)&clientCmd;
}
}
m_data->m_tcpSocket.Send((const uint8 *)data,sz);

View File

@@ -5197,7 +5197,6 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct
}
b3PluginArguments args;
args.m_ints[0] = eSetPDControl;
args.m_ints[1] = bodyUniqueId;
//find the joint motors and apply the desired velocity and maximum force/torque
{
@@ -5250,6 +5249,11 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct
args.m_ints[2] = link;
args.m_numInts = 3;
args.m_numFloats = 5;
args.m_ints[0] = eSetPDControl;
if (args.m_floats[4] < B3_EPSILON) {
args.m_ints[0] = eRemovePDControl;
}
m_data->m_pluginManager.executePluginCommand(m_data->m_pdControlPlugin, &args);
}
}

View File

@@ -107,7 +107,6 @@ B3_SHARED_API int executePluginCommand_pdControlPlugin(struct b3PluginContext* c
if (arguments->m_numInts != 3)
return -1;
switch (arguments->m_ints[0])
{
case eSetPDControl:

View File

@@ -184,11 +184,16 @@ int main(int argc, char *argv[])
cmdPtr = &cmd;
cmd.m_type = *(int*)&bytesReceived[0];
}
if (numBytesRec == sizeof(SharedMemoryCommand))
{
cmdPtr = (SharedMemoryCommand*)&bytesReceived[0];
}
else
{
cmdPtr = (SharedMemoryCommand*)&bytesReceived[0];
}
if (cmdPtr)
{
SharedMemoryStatus serverStatus;
@@ -207,7 +212,7 @@ int main(int argc, char *argv[])
}
if (gVerboseNetworkMessagesServer)
{
printf("buffer.size = %d\n", buffer.size());
//printf("buffer.size = %d\n", buffer.size());
printf("serverStatus.m_numDataStreamBytes = %d\n", serverStatus.m_numDataStreamBytes);
}
if (hasStatus)
@@ -234,25 +239,49 @@ int main(int argc, char *argv[])
}
else
{
//create packetData with [int packetSizeInBytes, status, streamBytes)
packetData.resize(4 + sizeof(SharedMemoryStatus) + serverStatus.m_numDataStreamBytes);
int sz = packetData.size();
int curPos = 0;
MySerializeInt(sz, &packetData[curPos]);
curPos += 4;
for (int i = 0; i < sizeof(SharedMemoryStatus); i++)
if (cmdPtr->m_type == CMD_REQUEST_VR_EVENTS_DATA)
{
packetData[i + curPos] = statBytes[i];
int headerSize = 16+5 * sizeof(int) + sizeof(smUint64_t) + sizeof(char*) + sizeof(b3VRControllerEvent)*serverStatus.m_sendVREvents.m_numVRControllerEvents;
packetData.resize(4 + headerSize);
int sz = packetData.size();
int curPos = 0;
MySerializeInt(sz, &packetData[curPos]);
curPos += 4;
for (int i = 0; i < headerSize; i++)
{
packetData[i + curPos] = statBytes[i];
}
curPos += headerSize;
pClient->Send(&packetData[0], packetData.size());
}
curPos += sizeof(SharedMemoryStatus);
for (int i = 0; i < serverStatus.m_numDataStreamBytes; i++)
else
{
packetData[i + curPos] = buffer[i];
//create packetData with [int packetSizeInBytes, status, streamBytes)
packetData.resize(4 + sizeof(SharedMemoryStatus) + serverStatus.m_numDataStreamBytes);
int sz = packetData.size();
int curPos = 0;
if (gVerboseNetworkMessagesServer)
{
//printf("buffer.size = %d\n", buffer.size());
printf("serverStatus packed size = %d\n", sz);
}
MySerializeInt(sz, &packetData[curPos]);
curPos += 4;
for (int i = 0; i < sizeof(SharedMemoryStatus); i++)
{
packetData[i + curPos] = statBytes[i];
}
curPos += sizeof(SharedMemoryStatus);
for (int i = 0; i < serverStatus.m_numDataStreamBytes; i++)
{
packetData[i + curPos] = buffer[i];
}
pClient->Send(&packetData[0], packetData.size());
}
pClient->Send( &packetData[0], packetData.size() );
}
}

View File

@@ -291,10 +291,6 @@ void SoftDemo::createStack( btCollisionShape* boxShape, float halfCubeSize, int
////////////////////////////////////
extern int gNumManifold;
extern int gOverlappingPairs;
///for mouse picking
void pickingPreTickCallback (btDynamicsWorld *world, btScalar timeStep)
{
@@ -1727,13 +1723,6 @@ void SoftDemo::clientMoveAndDisplay()
btProfiler::endBlock("render");
#endif
glFlush();
//some additional debugging info
#ifdef PRINT_CONTACT_STATISTICS
printf("num manifolds: %i\n",gNumManifold);
printf("num gOverlappingPairs: %i\n",gOverlappingPairs);
#endif //PRINT_CONTACT_STATISTICS
swapBuffers();

View File

@@ -452,7 +452,7 @@ print("-----")
setup(
name = 'pybullet',
version='2.0.8',
version='2.0.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',

View File

@@ -628,7 +628,6 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::resetPool(btDispatcher* /*dispatcher*
}
extern int gOverlappingPairs;
//#include <stdio.h>
template <typename BP_FP_INT_TYPE>
@@ -695,10 +694,9 @@ void btAxisSweep3Internal<BP_FP_INT_TYPE>::calculateOverlappingPairs(btDispatche
pair.m_pProxy0 = 0;
pair.m_pProxy1 = 0;
m_invalidPair++;
gOverlappingPairs--;
}
}
}
}
///if you don't like to skip the invalid pairs in the array, execute following code:
#define CLEAN_INVALID_PAIRS 1

View File

@@ -23,11 +23,6 @@ subject to the following restrictions:
#include <stdio.h>
int gOverlappingPairs = 0;
int gRemovePairs =0;
int gAddedPairs =0;
int gFindPairs =0;
@@ -134,13 +129,12 @@ void btHashedOverlappingPairCache::removeOverlappingPairsContainingProxy(btBroad
btBroadphasePair* btHashedOverlappingPairCache::findPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1)
{
gFindPairs++;
if(proxy0->m_uniqueId>proxy1->m_uniqueId)
if(proxy0->m_uniqueId>proxy1->m_uniqueId)
btSwap(proxy0,proxy1);
int proxyId1 = proxy0->getUid();
int proxyId2 = proxy1->getUid();
/*if (proxyId1 > proxyId2)
/*if (proxyId1 > proxyId2)
btSwap(proxyId1, proxyId2);*/
int hash = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1), static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1));
@@ -271,13 +265,12 @@ btBroadphasePair* btHashedOverlappingPairCache::internalAddPair(btBroadphaseProx
void* btHashedOverlappingPairCache::removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1,btDispatcher* dispatcher)
{
gRemovePairs++;
if(proxy0->m_uniqueId>proxy1->m_uniqueId)
if(proxy0->m_uniqueId>proxy1->m_uniqueId)
btSwap(proxy0,proxy1);
int proxyId1 = proxy0->getUid();
int proxyId2 = proxy1->getUid();
/*if (proxyId1 > proxyId2)
/*if (proxyId1 > proxyId2)
btSwap(proxyId1, proxyId2);*/
int hash = static_cast<int>(getHash(static_cast<unsigned int>(proxyId1),static_cast<unsigned int>(proxyId2)) & (m_overlappingPairArray.capacity()-1));
@@ -386,8 +379,6 @@ void btHashedOverlappingPairCache::processAllOverlappingPairs(btOverlapCallback*
if (callback->processOverlap(*pair))
{
removeOverlappingPair(pair->m_pProxy0,pair->m_pProxy1,dispatcher);
gOverlappingPairs--;
} else
{
i++;
@@ -499,7 +490,6 @@ void* btSortedOverlappingPairCache::removeOverlappingPair(btBroadphaseProxy* pro
int findIndex = m_overlappingPairArray.findLinearSearch(findPair);
if (findIndex < m_overlappingPairArray.size())
{
gOverlappingPairs--;
btBroadphasePair& pair = m_overlappingPairArray[findIndex];
void* userData = pair.m_internalInfo1;
cleanOverlappingPair(pair,dispatcher);
@@ -532,11 +522,8 @@ btBroadphasePair* btSortedOverlappingPairCache::addOverlappingPair(btBroadphaseP
void* mem = &m_overlappingPairArray.expandNonInitializing();
btBroadphasePair* pair = new (mem) btBroadphasePair(*proxy0,*proxy1);
gOverlappingPairs++;
gAddedPairs++;
if (m_ghostPairCallback)
if (m_ghostPairCallback)
m_ghostPairCallback->addOverlappingPair(proxy0, proxy1);
return pair;
@@ -590,7 +577,6 @@ void btSortedOverlappingPairCache::processAllOverlappingPairs(btOverlapCallback*
pair->m_pProxy1 = 0;
m_overlappingPairArray.swap(i,m_overlappingPairArray.size()-1);
m_overlappingPairArray.pop_back();
gOverlappingPairs--;
} else
{
i++;
@@ -623,7 +609,6 @@ void btSortedOverlappingPairCache::cleanOverlappingPair(btBroadphasePair& pair,b
pair.m_algorithm->~btCollisionAlgorithm();
dispatcher->freeCollisionAlgorithm(pair.m_algorithm);
pair.m_algorithm=0;
gRemovePairs--;
}
}
}

View File

@@ -49,10 +49,6 @@ struct btOverlapFilterCallback
extern int gRemovePairs;
extern int gAddedPairs;
extern int gFindPairs;
const int BT_NULL_PAIR=0xffffffff;
///The btOverlappingPairCache provides an interface for overlapping pair management (add, remove, storage), used by the btBroadphaseInterface broadphases.
@@ -133,8 +129,6 @@ public:
// no new pair is created and the old one is returned.
virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1)
{
gAddedPairs++;
if (!needsBroadphaseCollision(proxy0,proxy1))
return 0;

View File

@@ -24,8 +24,6 @@ subject to the following restrictions:
#include <new>
extern int gOverlappingPairs;
void btSimpleBroadphase::validate()
{
for (int i=0;i<m_numHandles;i++)
@@ -315,8 +313,7 @@ void btSimpleBroadphase::calculateOverlappingPairs(btDispatcher* dispatcher)
pair.m_pProxy0 = 0;
pair.m_pProxy1 = 0;
m_invalidPair++;
gOverlappingPairs--;
}
}
}

View File

@@ -27,8 +27,6 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btCollisionConfiguration.h"
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
int gNumManifold = 0;
#ifdef BT_DEBUG
#include <stdio.h>
#endif
@@ -77,8 +75,6 @@ btCollisionDispatcher::~btCollisionDispatcher()
btPersistentManifold* btCollisionDispatcher::getNewManifold(const btCollisionObject* body0,const btCollisionObject* body1)
{
gNumManifold++;
//btAssert(gNumManifold < 65535);
@@ -121,7 +117,6 @@ void btCollisionDispatcher::clearManifold(btPersistentManifold* manifold)
void btCollisionDispatcher::releaseManifold(btPersistentManifold* manifold)
{
gNumManifold--;
//printf("releaseManifold: gNumManifold %d\n",gNumManifold);
clearManifold(manifold);

View File

@@ -15,9 +15,11 @@ subject to the following restrictions:
#include "btAlignedAllocator.h"
#ifdef BT_DEBUG_MEMORY_ALLOCATIONS
int gNumAlignedAllocs = 0;
int gNumAlignedFree = 0;
int gTotalBytesAlignedAllocs = 0;//detect memory leaks
#endif //BT_DEBUG_MEMORY_ALLOCATIONST_DEBUG_ALLOCATIONS
static void *btAllocDefault(size_t size)
{
@@ -246,7 +248,6 @@ void btAlignedFreeInternal (void* ptr,int line,char* filename)
void* btAlignedAllocInternal (size_t size, int alignment)
{
gNumAlignedAllocs++;
void* ptr;
ptr = sAlignedAllocFunc(size, alignment);
// printf("btAlignedAllocInternal %d, %x\n",size,ptr);
@@ -260,7 +261,6 @@ void btAlignedFreeInternal (void* ptr)
return;
}
gNumAlignedFree++;
// printf("btAlignedFreeInternal %x\n",ptr);
sAlignedFreeFunc(ptr);
}