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', diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index aed3104a6..d06ddaf54 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -680,47 +680,49 @@ void CProfileManager::dumpAll() CProfileManager::Release_Iterator(profileIterator); } +// 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 +// __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(__NDK_MAJOR__) && \ + ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1))) + #undef BT_HAVE_TLS + #endif +#endif // defined(__ANDROID__) && defined(__clang__) +// clang-format on +unsigned int btQuickprofGetCurrentThreadIndex2() { + const unsigned int kNullIndex = ~0U; -unsigned int btQuickprofGetCurrentThreadIndex2() -{ #if BT_THREADSAFE - return btGetCurrentThreadIndex(); -#else // #if BT_THREADSAFE - 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 + return btGetCurrentThreadIndex(); +#elif defined(BT_HAVE_TLS) + static __thread unsigned int sThreadIndex = kNullIndex; +#elif defined(_WIN32) + __declspec(thread) static 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; -#else - unsigned int sThreadIndex = 0; - return -1; + unsigned int sThreadIndex = 0; + return -1; #endif -#endif//__APPLE__ - -#endif - static int gThreadCounter=0; - if ( sThreadIndex == kNullIndex ) - { - sThreadIndex = gThreadCounter++; - } - return sThreadIndex; -#endif // #else // #if BT_THREADSAFE + static int gThreadCounter = 0; + + if (sThreadIndex == kNullIndex) { + sThreadIndex = gThreadCounter++; + } + return sThreadIndex; } void btEnterProfileZoneDefault(const char* name)