Merge pull request #1972 from erwincoumans/master
fix some thread sanitizer (read/write integer, should be a harmless w…
This commit is contained in:
Binary file not shown.
@@ -1008,7 +1008,7 @@ void BenchmarkDemo::createTest4()
|
|||||||
}
|
}
|
||||||
|
|
||||||
//this will enable polyhedral contact clipping, better quality, slightly slower
|
//this will enable polyhedral contact clipping, better quality, slightly slower
|
||||||
//convexHullShape->initializePolyhedralFeatures();
|
convexHullShape->initializePolyhedralFeatures();
|
||||||
|
|
||||||
btTransform trans;
|
btTransform trans;
|
||||||
trans.setIdentity();
|
trans.setIdentity();
|
||||||
|
|||||||
@@ -251,7 +251,6 @@ void MyKeyboardCallback(int key, int state)
|
|||||||
|
|
||||||
if (key == 'p')
|
if (key == 'p')
|
||||||
{
|
{
|
||||||
#ifndef BT_NO_PROFILE
|
|
||||||
if (state)
|
if (state)
|
||||||
{
|
{
|
||||||
b3ChromeUtilsStartTimings();
|
b3ChromeUtilsStartTimings();
|
||||||
@@ -260,7 +259,6 @@ void MyKeyboardCallback(int key, int state)
|
|||||||
{
|
{
|
||||||
b3ChromeUtilsStopTimingsAndWriteJsonFile("timings");
|
b3ChromeUtilsStopTimingsAndWriteJsonFile("timings");
|
||||||
}
|
}
|
||||||
#endif //BT_NO_PROFILE
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef NO_OPENGL3
|
#ifndef NO_OPENGL3
|
||||||
@@ -1129,6 +1127,7 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
|
|||||||
|
|
||||||
gui2->registerFileOpenCallback(fileOpenCallback);
|
gui2->registerFileOpenCallback(fileOpenCallback);
|
||||||
gui2->registerQuitCallback(quitCallback);
|
gui2->registerQuitCallback(quitCallback);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|||||||
@@ -1737,6 +1737,11 @@ void PhysicsServerExample::initPhysics()
|
|||||||
m_args[w].m_cs2 = m_threadSupport->createCriticalSection();
|
m_args[w].m_cs2 = m_threadSupport->createCriticalSection();
|
||||||
m_args[w].m_cs3 = m_threadSupport->createCriticalSection();
|
m_args[w].m_cs3 = m_threadSupport->createCriticalSection();
|
||||||
m_args[w].m_csGUI = m_threadSupport->createCriticalSection();
|
m_args[w].m_csGUI = m_threadSupport->createCriticalSection();
|
||||||
|
m_multiThreadedHelper->setCriticalSection(m_args[w].m_cs);
|
||||||
|
m_multiThreadedHelper->setCriticalSection2(m_args[w].m_cs2);
|
||||||
|
m_multiThreadedHelper->setCriticalSection3(m_args[w].m_cs3);
|
||||||
|
m_multiThreadedHelper->setCriticalSectionGUI(m_args[w].m_csGUI);
|
||||||
|
|
||||||
m_args[w].m_cs->lock();
|
m_args[w].m_cs->lock();
|
||||||
m_args[w].m_cs->setSharedParam(0, eMotionIsUnInitialized);
|
m_args[w].m_cs->setSharedParam(0, eMotionIsUnInitialized);
|
||||||
m_args[w].m_cs->unlock();
|
m_args[w].m_cs->unlock();
|
||||||
@@ -1760,10 +1765,6 @@ void PhysicsServerExample::initPhysics()
|
|||||||
}
|
}
|
||||||
|
|
||||||
m_args[0].m_cs->setSharedParam(1, eGUIHelperIdle);
|
m_args[0].m_cs->setSharedParam(1, eGUIHelperIdle);
|
||||||
m_multiThreadedHelper->setCriticalSection(m_args[0].m_cs);
|
|
||||||
m_multiThreadedHelper->setCriticalSection2(m_args[0].m_cs2);
|
|
||||||
m_multiThreadedHelper->setCriticalSection3(m_args[0].m_cs3);
|
|
||||||
m_multiThreadedHelper->setCriticalSectionGUI(m_args[0].m_csGUI);
|
|
||||||
|
|
||||||
m_args[0].m_cs2->lock();
|
m_args[0].m_cs2->lock();
|
||||||
|
|
||||||
|
|||||||
@@ -928,7 +928,7 @@ enum eFileIOTypes
|
|||||||
};
|
};
|
||||||
|
|
||||||
//limits for vertices/indices in PyBullet::createCollisionShape
|
//limits for vertices/indices in PyBullet::createCollisionShape
|
||||||
#define B3_MAX_NUM_VERTICES 1024
|
#define B3_MAX_NUM_VERTICES 16
|
||||||
#define B3_MAX_NUM_INDICES 1024
|
#define B3_MAX_NUM_INDICES 16
|
||||||
|
|
||||||
#endif //SHARED_MEMORY_PUBLIC_H
|
#endif //SHARED_MEMORY_PUBLIC_H
|
||||||
|
|||||||
@@ -174,7 +174,7 @@ void MyEnterProfileZoneFunc(const char* msg)
|
|||||||
{
|
{
|
||||||
if (gProfileDisabled)
|
if (gProfileDisabled)
|
||||||
return;
|
return;
|
||||||
#ifndef BT_NO_PROFILE
|
|
||||||
int threadId = btQuickprofGetCurrentThreadIndex2();
|
int threadId = btQuickprofGetCurrentThreadIndex2();
|
||||||
if (threadId < 0 || threadId >= BT_QUICKPROF_MAX_THREAD_COUNT)
|
if (threadId < 0 || threadId >= BT_QUICKPROF_MAX_THREAD_COUNT)
|
||||||
return;
|
return;
|
||||||
@@ -191,13 +191,13 @@ void MyEnterProfileZoneFunc(const char* msg)
|
|||||||
gStartTimes[threadId][gStackDepths[threadId]] = 1 + gStartTimes[threadId][gStackDepths[threadId] - 1];
|
gStartTimes[threadId][gStackDepths[threadId]] = 1 + gStartTimes[threadId][gStackDepths[threadId] - 1];
|
||||||
}
|
}
|
||||||
gStackDepths[threadId]++;
|
gStackDepths[threadId]++;
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
void MyLeaveProfileZoneFunc()
|
void MyLeaveProfileZoneFunc()
|
||||||
{
|
{
|
||||||
if (gProfileDisabled)
|
if (gProfileDisabled)
|
||||||
return;
|
return;
|
||||||
#ifndef BT_NO_PROFILE
|
|
||||||
int threadId = btQuickprofGetCurrentThreadIndex2();
|
int threadId = btQuickprofGetCurrentThreadIndex2();
|
||||||
if (threadId < 0 || threadId >= BT_QUICKPROF_MAX_THREAD_COUNT)
|
if (threadId < 0 || threadId >= BT_QUICKPROF_MAX_THREAD_COUNT)
|
||||||
return;
|
return;
|
||||||
@@ -214,7 +214,7 @@ void MyLeaveProfileZoneFunc()
|
|||||||
|
|
||||||
unsigned long long int endTime = clk.getTimeNanoseconds();
|
unsigned long long int endTime = clk.getTimeNanoseconds();
|
||||||
gTimings[threadId].addTiming(name, threadId, startTime, endTime);
|
gTimings[threadId].addTiming(name, threadId, startTime, endTime);
|
||||||
#endif //BT_NO_PROFILE
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void b3ChromeUtilsStartTimings()
|
void b3ChromeUtilsStartTimings()
|
||||||
|
|||||||
@@ -14,7 +14,7 @@ p.setAdditionalSearchPath(pd.getDataPath())
|
|||||||
objs = p.loadMJCF(args.mjcf, flags=p.URDF_USE_IMPLICIT_CYLINDER)
|
objs = p.loadMJCF(args.mjcf, flags=p.URDF_USE_IMPLICIT_CYLINDER)
|
||||||
|
|
||||||
for o in objs:
|
for o in objs:
|
||||||
print("o=",o, p.getBodyInfo(o), p.getNumJoints(o))
|
#print("o=",o, p.getBodyInfo(o), p.getNumJoints(o))
|
||||||
humanoid = objs[o]
|
humanoid = objs[o]
|
||||||
ed0 = ed.UrdfEditor()
|
ed0 = ed.UrdfEditor()
|
||||||
ed0.initializeFromBulletBody(humanoid, p._client)
|
ed0.initializeFromBulletBody(humanoid, p._client)
|
||||||
|
|||||||
@@ -15,9 +15,11 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
#include "b3AlignedAllocator.h"
|
#include "b3AlignedAllocator.h"
|
||||||
|
|
||||||
|
#ifdef B3_ALLOCATOR_STATISTICS
|
||||||
int b3g_numAlignedAllocs = 0;
|
int b3g_numAlignedAllocs = 0;
|
||||||
int b3g_numAlignedFree = 0;
|
int b3g_numAlignedFree = 0;
|
||||||
int b3g_totalBytesAlignedAllocs = 0; //detect memory leaks
|
int b3g_totalBytesAlignedAllocs = 0; //detect memory leaks
|
||||||
|
#endif
|
||||||
|
|
||||||
static void *b3AllocDefault(size_t size)
|
static void *b3AllocDefault(size_t size)
|
||||||
{
|
{
|
||||||
@@ -109,10 +111,10 @@ void *b3AlignedAllocInternal(size_t size, int alignment, int line, char *filenam
|
|||||||
{
|
{
|
||||||
void *ret;
|
void *ret;
|
||||||
char *real;
|
char *real;
|
||||||
|
#ifdef B3_ALLOCATOR_STATISTICS
|
||||||
b3g_totalBytesAlignedAllocs += size;
|
b3g_totalBytesAlignedAllocs += size;
|
||||||
b3g_numAlignedAllocs++;
|
b3g_numAlignedAllocs++;
|
||||||
|
#endif
|
||||||
real = (char *)b3s_allocFunc(size + 2 * sizeof(void *) + (alignment - 1));
|
real = (char *)b3s_allocFunc(size + 2 * sizeof(void *) + (alignment - 1));
|
||||||
if (real)
|
if (real)
|
||||||
{
|
{
|
||||||
@@ -135,14 +137,16 @@ void *b3AlignedAllocInternal(size_t size, int alignment, int line, char *filenam
|
|||||||
void b3AlignedFreeInternal(void *ptr, int line, char *filename)
|
void b3AlignedFreeInternal(void *ptr, int line, char *filename)
|
||||||
{
|
{
|
||||||
void *real;
|
void *real;
|
||||||
|
#ifdef B3_ALLOCATOR_STATISTICS
|
||||||
b3g_numAlignedFree++;
|
b3g_numAlignedFree++;
|
||||||
|
#endif
|
||||||
if (ptr)
|
if (ptr)
|
||||||
{
|
{
|
||||||
real = *((void **)(ptr)-1);
|
real = *((void **)(ptr)-1);
|
||||||
int size = *((int *)(ptr)-2);
|
int size = *((int *)(ptr)-2);
|
||||||
|
#ifdef B3_ALLOCATOR_STATISTICS
|
||||||
b3g_totalBytesAlignedAllocs -= size;
|
b3g_totalBytesAlignedAllocs -= size;
|
||||||
|
#endif
|
||||||
b3Printf("free #%d at address %x, from %s,line %d, size %d\n", b3g_numAlignedFree, real, filename, line, size);
|
b3Printf("free #%d at address %x, from %s,line %d, size %d\n", b3g_numAlignedFree, real, filename, line, size);
|
||||||
|
|
||||||
b3s_freeFunc(real);
|
b3s_freeFunc(real);
|
||||||
@@ -157,7 +161,9 @@ void b3AlignedFreeInternal(void *ptr, int line, char *filename)
|
|||||||
|
|
||||||
void *b3AlignedAllocInternal(size_t size, int alignment)
|
void *b3AlignedAllocInternal(size_t size, int alignment)
|
||||||
{
|
{
|
||||||
|
#ifdef B3_ALLOCATOR_STATISTICS
|
||||||
b3g_numAlignedAllocs++;
|
b3g_numAlignedAllocs++;
|
||||||
|
#endif
|
||||||
void *ptr;
|
void *ptr;
|
||||||
ptr = b3s_alignedAllocFunc(size, alignment);
|
ptr = b3s_alignedAllocFunc(size, alignment);
|
||||||
// b3Printf("b3AlignedAllocInternal %d, %x\n",size,ptr);
|
// b3Printf("b3AlignedAllocInternal %d, %x\n",size,ptr);
|
||||||
@@ -170,8 +176,9 @@ void b3AlignedFreeInternal(void *ptr)
|
|||||||
{
|
{
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#ifdef B3_ALLOCATOR_STATISTICS
|
||||||
b3g_numAlignedFree++;
|
b3g_numAlignedFree++;
|
||||||
|
#endif
|
||||||
// b3Printf("b3AlignedFreeInternal %x\n",ptr);
|
// b3Printf("b3AlignedFreeInternal %x\n",ptr);
|
||||||
b3s_alignedFreeFunc(ptr);
|
b3s_alignedFreeFunc(ptr);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -36,9 +36,6 @@ btScalar gGjkEpaPenetrationTolerance = 1.0e-12;
|
|||||||
btScalar gGjkEpaPenetrationTolerance = 0.001;
|
btScalar gGjkEpaPenetrationTolerance = 0.001;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//temp globals, to improve GJK/EPA/penetration calculations
|
|
||||||
int gNumDeepPenetrationChecks = 0;
|
|
||||||
int gNumGjkChecks = 0;
|
|
||||||
|
|
||||||
btGjkPairDetector::btGjkPairDetector(const btConvexShape *objectA, const btConvexShape *objectB, btSimplexSolverInterface *simplexSolver, btConvexPenetrationDepthSolver *penetrationDepthSolver)
|
btGjkPairDetector::btGjkPairDetector(const btConvexShape *objectA, const btConvexShape *objectB, btSimplexSolverInterface *simplexSolver, btConvexPenetrationDepthSolver *penetrationDepthSolver)
|
||||||
: m_cachedSeparatingAxis(btScalar(0.), btScalar(1.), btScalar(0.)),
|
: m_cachedSeparatingAxis(btScalar(0.), btScalar(1.), btScalar(0.)),
|
||||||
@@ -708,7 +705,6 @@ void btGjkPairDetector::getClosestPointsNonVirtual(const ClosestPointInput &inpu
|
|||||||
btScalar marginA = m_marginA;
|
btScalar marginA = m_marginA;
|
||||||
btScalar marginB = m_marginB;
|
btScalar marginB = m_marginB;
|
||||||
|
|
||||||
gNumGjkChecks++;
|
|
||||||
|
|
||||||
//for CCD we don't use margins
|
//for CCD we don't use margins
|
||||||
if (m_ignoreMargin)
|
if (m_ignoreMargin)
|
||||||
@@ -1021,7 +1017,6 @@ void btGjkPairDetector::getClosestPointsNonVirtual(const ClosestPointInput &inpu
|
|||||||
// Penetration depth case.
|
// Penetration depth case.
|
||||||
btVector3 tmpPointOnA, tmpPointOnB;
|
btVector3 tmpPointOnA, tmpPointOnB;
|
||||||
|
|
||||||
gNumDeepPenetrationChecks++;
|
|
||||||
m_cachedSeparatingAxis.setZero();
|
m_cachedSeparatingAxis.setZero();
|
||||||
|
|
||||||
bool isValid2 = m_penetrationDepthSolver->calcPenDepth(
|
bool isValid2 = m_penetrationDepthSolver->calcPenDepth(
|
||||||
|
|||||||
@@ -1,3 +1,4 @@
|
|||||||
|
|
||||||
/*
|
/*
|
||||||
Bullet Continuous Collision Detection and Physics Library
|
Bullet Continuous Collision Detection and Physics Library
|
||||||
Copyright (c) 2003-2018 Erwin Coumans http://bulletphysics.com
|
Copyright (c) 2003-2018 Erwin Coumans http://bulletphysics.com
|
||||||
@@ -72,7 +73,7 @@ public:
|
|||||||
pthread_t thread;
|
pthread_t thread;
|
||||||
//each tread will wait until this signal to start its work
|
//each tread will wait until this signal to start its work
|
||||||
sem_t* startSemaphore;
|
sem_t* startSemaphore;
|
||||||
|
btCriticalSection* m_cs;
|
||||||
// this is a copy of m_mainSemaphore,
|
// this is a copy of m_mainSemaphore,
|
||||||
//each tread will signal once it is finished with its work
|
//each tread will signal once it is finished with its work
|
||||||
sem_t* m_mainSemaphore;
|
sem_t* m_mainSemaphore;
|
||||||
@@ -90,7 +91,7 @@ private:
|
|||||||
void startThreads(const ConstructionInfo& threadInfo);
|
void startThreads(const ConstructionInfo& threadInfo);
|
||||||
void stopThreads();
|
void stopThreads();
|
||||||
int waitForResponse();
|
int waitForResponse();
|
||||||
|
btCriticalSection* m_cs;
|
||||||
public:
|
public:
|
||||||
btThreadSupportPosix(const ConstructionInfo& threadConstructionInfo);
|
btThreadSupportPosix(const ConstructionInfo& threadConstructionInfo);
|
||||||
virtual ~btThreadSupportPosix();
|
virtual ~btThreadSupportPosix();
|
||||||
@@ -119,6 +120,7 @@ public:
|
|||||||
|
|
||||||
btThreadSupportPosix::btThreadSupportPosix(const ConstructionInfo& threadConstructionInfo)
|
btThreadSupportPosix::btThreadSupportPosix(const ConstructionInfo& threadConstructionInfo)
|
||||||
{
|
{
|
||||||
|
m_cs = createCriticalSection();
|
||||||
startThreads(threadConstructionInfo);
|
startThreads(threadConstructionInfo);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -126,6 +128,8 @@ btThreadSupportPosix::btThreadSupportPosix(const ConstructionInfo& threadConstru
|
|||||||
btThreadSupportPosix::~btThreadSupportPosix()
|
btThreadSupportPosix::~btThreadSupportPosix()
|
||||||
{
|
{
|
||||||
stopThreads();
|
stopThreads();
|
||||||
|
deleteCriticalSection(m_cs);
|
||||||
|
m_cs=0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if (defined(__APPLE__))
|
#if (defined(__APPLE__))
|
||||||
@@ -181,14 +185,18 @@ static void* threadFunction(void* argument)
|
|||||||
{
|
{
|
||||||
btAssert(status->m_status);
|
btAssert(status->m_status);
|
||||||
status->m_userThreadFunc(userPtr);
|
status->m_userThreadFunc(userPtr);
|
||||||
|
status->m_cs->lock();
|
||||||
status->m_status = 2;
|
status->m_status = 2;
|
||||||
|
status->m_cs->unlock();
|
||||||
checkPThreadFunction(sem_post(status->m_mainSemaphore));
|
checkPThreadFunction(sem_post(status->m_mainSemaphore));
|
||||||
status->threadUsed++;
|
status->threadUsed++;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
//exit Thread
|
//exit Thread
|
||||||
|
status->m_cs->lock();
|
||||||
status->m_status = 3;
|
status->m_status = 3;
|
||||||
|
status->m_cs->unlock();
|
||||||
checkPThreadFunction(sem_post(status->m_mainSemaphore));
|
checkPThreadFunction(sem_post(status->m_mainSemaphore));
|
||||||
printf("Thread with taskId %i exiting\n", status->m_taskId);
|
printf("Thread with taskId %i exiting\n", status->m_taskId);
|
||||||
break;
|
break;
|
||||||
@@ -206,7 +214,7 @@ void btThreadSupportPosix::runTask(int threadIndex, void* userData)
|
|||||||
btThreadStatus& threadStatus = m_activeThreadStatus[threadIndex];
|
btThreadStatus& threadStatus = m_activeThreadStatus[threadIndex];
|
||||||
btAssert(threadIndex >= 0);
|
btAssert(threadIndex >= 0);
|
||||||
btAssert(threadIndex < m_activeThreadStatus.size());
|
btAssert(threadIndex < m_activeThreadStatus.size());
|
||||||
|
threadStatus.m_cs = m_cs;
|
||||||
threadStatus.m_commandId = 1;
|
threadStatus.m_commandId = 1;
|
||||||
threadStatus.m_status = 1;
|
threadStatus.m_status = 1;
|
||||||
threadStatus.m_userPtr = userData;
|
threadStatus.m_userPtr = userData;
|
||||||
@@ -231,7 +239,10 @@ int btThreadSupportPosix::waitForResponse()
|
|||||||
|
|
||||||
for (size_t t = 0; t < size_t(m_activeThreadStatus.size()); ++t)
|
for (size_t t = 0; t < size_t(m_activeThreadStatus.size()); ++t)
|
||||||
{
|
{
|
||||||
if (2 == m_activeThreadStatus[t].m_status)
|
m_cs->lock();
|
||||||
|
bool hasFinished = (2 == m_activeThreadStatus[t].m_status);
|
||||||
|
m_cs->unlock();
|
||||||
|
if (hasFinished)
|
||||||
{
|
{
|
||||||
last = t;
|
last = t;
|
||||||
break;
|
break;
|
||||||
@@ -273,15 +284,15 @@ void btThreadSupportPosix::startThreads(const ConstructionInfo& threadConstructi
|
|||||||
printf("starting thread %d\n", i);
|
printf("starting thread %d\n", i);
|
||||||
btThreadStatus& threadStatus = m_activeThreadStatus[i];
|
btThreadStatus& threadStatus = m_activeThreadStatus[i];
|
||||||
threadStatus.startSemaphore = createSem("threadLocal");
|
threadStatus.startSemaphore = createSem("threadLocal");
|
||||||
checkPThreadFunction(pthread_create(&threadStatus.thread, NULL, &threadFunction, (void*)&threadStatus));
|
|
||||||
|
|
||||||
threadStatus.m_userPtr = 0;
|
threadStatus.m_userPtr = 0;
|
||||||
|
threadStatus.m_cs = m_cs;
|
||||||
threadStatus.m_taskId = i;
|
threadStatus.m_taskId = i;
|
||||||
threadStatus.m_commandId = 0;
|
threadStatus.m_commandId = 0;
|
||||||
threadStatus.m_status = 0;
|
threadStatus.m_status = 0;
|
||||||
threadStatus.m_mainSemaphore = m_mainSemaphore;
|
threadStatus.m_mainSemaphore = m_mainSemaphore;
|
||||||
threadStatus.m_userThreadFunc = threadConstructionInfo.m_userThreadFunc;
|
threadStatus.m_userThreadFunc = threadConstructionInfo.m_userThreadFunc;
|
||||||
threadStatus.threadUsed = 0;
|
threadStatus.threadUsed = 0;
|
||||||
|
checkPThreadFunction(pthread_create(&threadStatus.thread, NULL, &threadFunction, (void*)&threadStatus));
|
||||||
|
|
||||||
printf("started thread %d \n", i);
|
printf("started thread %d \n", i);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -694,6 +694,24 @@ void CProfileManager::dumpAll()
|
|||||||
CProfileManager::Release_Iterator(profileIterator);
|
CProfileManager::Release_Iterator(profileIterator);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void btEnterProfileZoneDefault(const char* name)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
void btLeaveProfileZoneDefault()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
void btEnterProfileZoneDefault(const char* name)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
void btLeaveProfileZoneDefault()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
#endif //BT_NO_PROFILE
|
||||||
|
|
||||||
|
|
||||||
// clang-format off
|
// clang-format off
|
||||||
#if defined(_WIN32) && (defined(__MINGW32__) || defined(__MINGW64__))
|
#if defined(_WIN32) && (defined(__MINGW32__) || defined(__MINGW64__))
|
||||||
#define BT_HAVE_TLS 1
|
#define BT_HAVE_TLS 1
|
||||||
@@ -743,22 +761,6 @@ unsigned int btQuickprofGetCurrentThreadIndex2()
|
|||||||
#endif //BT_THREADSAFE
|
#endif //BT_THREADSAFE
|
||||||
}
|
}
|
||||||
|
|
||||||
void btEnterProfileZoneDefault(const char* name)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
void btLeaveProfileZoneDefault()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
#else
|
|
||||||
void btEnterProfileZoneDefault(const char* name)
|
|
||||||
{
|
|
||||||
}
|
|
||||||
void btLeaveProfileZoneDefault()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
#endif //BT_NO_PROFILE
|
|
||||||
|
|
||||||
static btEnterProfileZoneFunc* bts_enterFunc = btEnterProfileZoneDefault;
|
static btEnterProfileZoneFunc* bts_enterFunc = btEnterProfileZoneDefault;
|
||||||
static btLeaveProfileZoneFunc* bts_leaveFunc = btLeaveProfileZoneDefault;
|
static btLeaveProfileZoneFunc* bts_leaveFunc = btLeaveProfileZoneDefault;
|
||||||
|
|
||||||
|
|||||||
@@ -61,18 +61,19 @@ btLeaveProfileZoneFunc* btGetCurrentLeaveProfileZoneFunc();
|
|||||||
void btSetCustomEnterProfileZoneFunc(btEnterProfileZoneFunc* enterFunc);
|
void btSetCustomEnterProfileZoneFunc(btEnterProfileZoneFunc* enterFunc);
|
||||||
void btSetCustomLeaveProfileZoneFunc(btLeaveProfileZoneFunc* leaveFunc);
|
void btSetCustomLeaveProfileZoneFunc(btLeaveProfileZoneFunc* leaveFunc);
|
||||||
|
|
||||||
#ifndef BT_NO_PROFILE // FIX redefinition
|
#ifndef BT_ENABLE_PROFILE
|
||||||
//To disable built-in profiling, please comment out next line
|
#define BT_NO_PROFILE 1
|
||||||
//#define BT_NO_PROFILE 1
|
|
||||||
#endif //BT_NO_PROFILE
|
#endif //BT_NO_PROFILE
|
||||||
|
|
||||||
const unsigned int BT_QUICKPROF_MAX_THREAD_COUNT = 64;
|
const unsigned int BT_QUICKPROF_MAX_THREAD_COUNT = 64;
|
||||||
|
|
||||||
#ifndef BT_NO_PROFILE
|
|
||||||
//btQuickprofGetCurrentThreadIndex will return -1 if thread index cannot be determined,
|
//btQuickprofGetCurrentThreadIndex will return -1 if thread index cannot be determined,
|
||||||
//otherwise returns thread index in range [0..maxThreads]
|
//otherwise returns thread index in range [0..maxThreads]
|
||||||
unsigned int btQuickprofGetCurrentThreadIndex2();
|
unsigned int btQuickprofGetCurrentThreadIndex2();
|
||||||
|
|
||||||
|
#ifndef BT_NO_PROFILE
|
||||||
|
|
||||||
|
|
||||||
#include <stdio.h> //@todo remove this, backwards compatibility
|
#include <stdio.h> //@todo remove this, backwards compatibility
|
||||||
|
|
||||||
#include "btAlignedAllocator.h"
|
#include "btAlignedAllocator.h"
|
||||||
|
|||||||
Reference in New Issue
Block a user