From e03383e612add869ea68efab5e1245cbd8d44f99 Mon Sep 17 00:00:00 2001 From: kwasimensah Date: Thu, 2 Nov 2017 15:35:59 -0400 Subject: [PATCH 1/3] Update support for buggy android NDK Expand logic for when __thread is supported to work around https://github.com/android-ndk/ndk/issues/8 --- src/LinearMath/btQuickprof.cpp | 74 ++++++++++++++++++++-------------- 1 file changed, 44 insertions(+), 30 deletions(-) diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index aed3104a6..8409ee3fe 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -680,46 +680,60 @@ void CProfileManager::dumpAll() CProfileManager::Release_Iterator(profileIterator); } +// BT_HAVE_TLS is defined to 1 when __thread should be supported. +// We assume __thread is supported on Linux when compiled with Clang or compiled +// against libstdc++ with _GLIBCXX_HAVE_TLS defined. +#ifdef BT_HAVE_TLS +#error BT_HAVE_TLS cannot be directly set +#elif defined(__linux__) && (defined(__clang__) || defined(_GLIBCXX_HAVE_TLS)) +#define BT_HAVE_TLS 1 +#endif - +// There are platforms for which TLS should not be used even though the compiler +// makes it seem like it's supported (Android NDK < r12b for example). +// This is primarily because of linker problems and toolchain misconfiguration: +// TLS isn't supported until NDK r12b per +// https://developer.android.com/ndk/downloads/revision_history.html +// Since NDK r16, `__NDK_MAJOR__` and `__NDK_MINOR__` are defined in +// . For NDK < r16, users should define these macros, +// e.g. `-D__NDK_MAJOR__=11 -D__NKD_MINOR__=0` for NDK r11. +#if defined(__ANDROID__) && defined(__clang__) +#if __has_include() +#include +#endif // __has_include() +#if defined(__ANDROID__) && defined(__clang__) && defined(__NDK_MAJOR__) && \ + defined(__NDK_MINOR__) && \ + ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1))) +#undef BT_HAVE_TLS +#endif +#endif // defined(__ANDROID__) && defined(__clang__) unsigned int btQuickprofGetCurrentThreadIndex2() { #if BT_THREADSAFE return btGetCurrentThreadIndex(); -#else // #if BT_THREADSAFE - const unsigned int kNullIndex = ~0U; +#else + const unsigned int kNullIndex = ~0U; #ifdef _WIN32 - #if defined(__MINGW32__) || defined(__MINGW64__) - static __thread unsigned int sThreadIndex = kNullIndex; - #else - __declspec( thread ) static unsigned int sThreadIndex = kNullIndex; - #endif +#if defined(__MINGW32__) || defined(__MINGW64__) + static __thread unsigned int sThreadIndex = kNullIndex; #else -#ifdef __APPLE__ - #if TARGET_OS_IPHONE - unsigned int sThreadIndex = 0; - return -1; - #else - static __thread unsigned int sThreadIndex = kNullIndex; - #endif -#else//__APPLE__ -#if __linux__ - static __thread unsigned int sThreadIndex = kNullIndex; + __declspec(thread) static unsigned int sThreadIndex = kNullIndex; +#endif +#elif defined(BT_HAVE_TLS) + static __thread unsigned int sThreadIndex = kNullIndex; #else - unsigned int sThreadIndex = 0; - return -1; -#endif -#endif//__APPLE__ - -#endif - static int gThreadCounter=0; + unsigned int sThreadIndex = 0; + return -1; +#endif //_WIN32 - if ( sThreadIndex == kNullIndex ) - { - sThreadIndex = gThreadCounter++; - } - return sThreadIndex; + // TODO: Use std::atomic? Not sure if c++11 is a prereq for this library. + static int gThreadCounter = 0; + + if (sThreadIndex == kNullIndex) { + sThreadIndex = gThreadCounter++; + } + return sThreadIndex; #endif // #else // #if BT_THREADSAFE } From 8aefa7e8d05118a09d9bb3a4c49db7678391b7b5 Mon Sep 17 00:00:00 2001 From: kwasimensah Date: Fri, 3 Nov 2017 11:59:12 -0400 Subject: [PATCH 2/3] Updating Macros Don't take away ability to do profiling on MacOS --- src/LinearMath/btQuickprof.cpp | 60 ++++++++++++++-------------------- 1 file changed, 24 insertions(+), 36 deletions(-) diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index 8409ee3fe..d06ddaf54 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -680,61 +680,49 @@ void CProfileManager::dumpAll() CProfileManager::Release_Iterator(profileIterator); } -// BT_HAVE_TLS is defined to 1 when __thread should be supported. -// We assume __thread is supported on Linux when compiled with Clang or compiled -// against libstdc++ with _GLIBCXX_HAVE_TLS defined. -#ifdef BT_HAVE_TLS -#error BT_HAVE_TLS cannot be directly set -#elif defined(__linux__) && (defined(__clang__) || defined(_GLIBCXX_HAVE_TLS)) -#define BT_HAVE_TLS 1 +// clang-format off +#if defined(_WIN32) && (defined(__MINGW32__) || defined(__MINGW64__)) + #define BT_HAVE_TLS 1 +#elif __APPLE__ && !TARGET_OS_IPHONE + // TODO: Modern versions of iOS support TLS now with updated version checking. + #define BT_HAVE_TLS 1 +#elif __linux__ + #define BT_HAVE_TLS 1 #endif -// There are platforms for which TLS should not be used even though the compiler -// makes it seem like it's supported (Android NDK < r12b for example). -// This is primarily because of linker problems and toolchain misconfiguration: -// TLS isn't supported until NDK r12b per -// https://developer.android.com/ndk/downloads/revision_history.html -// Since NDK r16, `__NDK_MAJOR__` and `__NDK_MINOR__` are defined in -// . For NDK < r16, users should define these macros, -// e.g. `-D__NDK_MAJOR__=11 -D__NKD_MINOR__=0` for NDK r11. +// __thread is broken on Andorid clang until r12b. See +// https://github.com/android-ndk/ndk/issues/8 #if defined(__ANDROID__) && defined(__clang__) -#if __has_include() -#include -#endif // __has_include() -#if defined(__ANDROID__) && defined(__clang__) && defined(__NDK_MAJOR__) && \ - defined(__NDK_MINOR__) && \ + #if __has_include() + #include + #endif // __has_include() + #if defined(__NDK_MAJOR__) && \ ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1))) -#undef BT_HAVE_TLS -#endif + #undef BT_HAVE_TLS + #endif #endif // defined(__ANDROID__) && defined(__clang__) +// clang-format on -unsigned int btQuickprofGetCurrentThreadIndex2() -{ -#if BT_THREADSAFE - return btGetCurrentThreadIndex(); -#else +unsigned int btQuickprofGetCurrentThreadIndex2() { const unsigned int kNullIndex = ~0U; -#ifdef _WIN32 -#if defined(__MINGW32__) || defined(__MINGW64__) - static __thread unsigned int sThreadIndex = kNullIndex; -#else - __declspec(thread) static unsigned int sThreadIndex = kNullIndex; -#endif + +#if BT_THREADSAFE + return btGetCurrentThreadIndex(); #elif defined(BT_HAVE_TLS) static __thread unsigned int sThreadIndex = kNullIndex; +#elif defined(_WIN32) + __declspec(thread) static unsigned int sThreadIndex = kNullIndex; #else unsigned int sThreadIndex = 0; return -1; -#endif //_WIN32 +#endif - // TODO: Use std::atomic? Not sure if c++11 is a prereq for this library. static int gThreadCounter = 0; if (sThreadIndex == kNullIndex) { sThreadIndex = gThreadCounter++; } return sThreadIndex; -#endif // #else // #if BT_THREADSAFE } void btEnterProfileZoneDefault(const char* name) From d570730b8eae46b8b6e996c3af7076cb7a78e4e8 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 7 Nov 2017 21:11:16 -0800 Subject: [PATCH 3/3] fix pybullet and bump up version to 1.6.4 --- examples/pybullet/pybullet.c | 12 +++++++----- setup.py | 2 +- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 0825bff8b..d2a7cb2c7 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -5987,17 +5987,19 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec b3GetCameraImageData(sm, &imageData); // TODO(hellojas): error handling if image size is 0 - pyResultList = PyTuple_New(5); - PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); - PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); - + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth, bytesPerPixel}; npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; npy_intp seg_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; - + + pyResultList = PyTuple_New(5); + + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8); pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32); pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32); diff --git a/setup.py b/setup.py index c7109b85f..c191f97ae 100644 --- a/setup.py +++ b/setup.py @@ -441,7 +441,7 @@ print("-----") setup( name = 'pybullet', - version='1.6.3', + version='1.6.4', 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',