Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
@@ -5987,9 +5987,6 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
|
|
||||||
b3GetCameraImageData(sm, &imageData);
|
b3GetCameraImageData(sm, &imageData);
|
||||||
// TODO(hellojas): error handling if image size is 0
|
// 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
|
int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
|
||||||
|
|
||||||
@@ -5998,6 +5995,11 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
|
||||||
npy_intp seg_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);
|
pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8);
|
||||||
pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32);
|
pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32);
|
||||||
pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32);
|
pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32);
|
||||||
|
|||||||
2
setup.py
2
setup.py
@@ -441,7 +441,7 @@ print("-----")
|
|||||||
|
|
||||||
setup(
|
setup(
|
||||||
name = 'pybullet',
|
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',
|
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.',
|
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',
|
url='https://github.com/bulletphysics/bullet3',
|
||||||
|
|||||||
@@ -680,47 +680,49 @@ void CProfileManager::dumpAll()
|
|||||||
CProfileManager::Release_Iterator(profileIterator);
|
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(<android/ndk-version.h>)
|
||||||
|
#include <android/ndk-version.h>
|
||||||
|
#endif // __has_include(<android/ndk-version.h>)
|
||||||
|
#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
|
#if BT_THREADSAFE
|
||||||
return btGetCurrentThreadIndex();
|
return btGetCurrentThreadIndex();
|
||||||
#else // #if BT_THREADSAFE
|
#elif defined(BT_HAVE_TLS)
|
||||||
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
|
|
||||||
#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;
|
static __thread unsigned int sThreadIndex = kNullIndex;
|
||||||
|
#elif defined(_WIN32)
|
||||||
|
__declspec(thread) static unsigned int sThreadIndex = kNullIndex;
|
||||||
#else
|
#else
|
||||||
unsigned int sThreadIndex = 0;
|
unsigned int sThreadIndex = 0;
|
||||||
return -1;
|
return -1;
|
||||||
#endif
|
#endif
|
||||||
#endif//__APPLE__
|
|
||||||
|
|
||||||
#endif
|
static int gThreadCounter = 0;
|
||||||
static int gThreadCounter=0;
|
|
||||||
|
|
||||||
if ( sThreadIndex == kNullIndex )
|
if (sThreadIndex == kNullIndex) {
|
||||||
{
|
|
||||||
sThreadIndex = gThreadCounter++;
|
sThreadIndex = gThreadCounter++;
|
||||||
}
|
}
|
||||||
return sThreadIndex;
|
return sThreadIndex;
|
||||||
#endif // #else // #if BT_THREADSAFE
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void btEnterProfileZoneDefault(const char* name)
|
void btEnterProfileZoneDefault(const char* name)
|
||||||
|
|||||||
Reference in New Issue
Block a user