diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index ade0ec1c8..42a43a818 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -5997,21 +5997,21 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec PyObject* pySeg; int i, j, p; + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values + b3GetCameraImageData(sm, &imageData); // TODO(hellojas): error handling if image size is 0 - 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); + pyResultList = PyTuple_New(5); - PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); - PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + 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); @@ -6427,6 +6427,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) PyObject* pySeg; int i, j, p; + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values b3GetCameraImageData(sm, &imageData); // TODO(hellojas): error handling if image size is 0 @@ -6434,8 +6435,6 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) 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}; diff --git a/setup.py b/setup.py index b7422545d..1fe7ddb44 100644 --- a/setup.py +++ b/setup.py @@ -442,7 +442,7 @@ print("-----") setup( name = 'pybullet', - version='1.7.1', + version='1.7.2', 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',