From d570730b8eae46b8b6e996c3af7076cb7a78e4e8 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 7 Nov 2017 21:11:16 -0800 Subject: [PATCH] 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',