diff --git a/data/multibody.bullet b/data/multibody.bullet index fec2a61a8..67a198781 100644 Binary files a/data/multibody.bullet and b/data/multibody.bullet differ diff --git a/examples/pybullet/examples/inverse_kinematics.py b/examples/pybullet/examples/inverse_kinematics.py index 7293c15c2..c311c3ca1 100644 --- a/examples/pybullet/examples/inverse_kinematics.py +++ b/examples/pybullet/examples/inverse_kinematics.py @@ -48,6 +48,7 @@ p.setRealTimeSimulation(useRealTimeSimulation) trailDuration = 15 while 1: + p.getCameraImage(320,200, flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX, renderer=p.ER_HARDWARE_OPENGL_RENDERER) if (useRealTimeSimulation): dt = datetime.now() t = (dt.second/60.)*2.*math.pi diff --git a/examples/pybullet/examples/testrender_egl.py b/examples/pybullet/examples/testrender_egl.py index ee25f64b7..0625a363a 100644 --- a/examples/pybullet/examples/testrender_egl.py +++ b/examples/pybullet/examples/testrender_egl.py @@ -54,7 +54,7 @@ while (1): viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) aspect = pixelWidth / pixelHeight; projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); - img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,flags=pybullet.ER_SEGMENTATION_MASK, lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) stop = time.time() print ("renderImage %f" % (stop - start)) diff --git a/examples/pybullet/examples/transparent.py b/examples/pybullet/examples/transparent.py index 5c6cc09c6..6e66ad982 100644 --- a/examples/pybullet/examples/transparent.py +++ b/examples/pybullet/examples/transparent.py @@ -15,4 +15,5 @@ while (1): blue = p.readUserDebugParameter(blueSlider) alpha = p.readUserDebugParameter(alphaSlider) p.changeVisualShape(sphereUid,-1,rgbaColor=[red,green,blue,alpha]) - time.sleep(0.01) \ No newline at end of file + p.getCameraImage(320,200,flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX, renderer=p.ER_BULLET_HARDWARE_OPENGL) + time.sleep(0.01) diff --git a/examples/pybullet/examples/userData.py b/examples/pybullet/examples/userData.py index 164c470b5..139f3186c 100644 --- a/examples/pybullet/examples/userData.py +++ b/examples/pybullet/examples/userData.py @@ -3,7 +3,7 @@ import time from pybullet_utils import bullet_client -server = bullet_client.BulletClient(connection_mode=pb.GUI_SERVER) +server = bullet_client.BulletClient(connection_mode=pb.SHARED_MEMORY_SERVER) print ("Connecting to bullet server") diff --git a/setup.py b/setup.py index 9ceafeeb0..ae9ec4f66 100644 --- a/setup.py +++ b/setup.py @@ -559,7 +559,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS: setup( name = 'pybullet', - version='2.2.8', + version='2.2.9', 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',