fix issue in BulletClient (pybullet_utils.bullet_client) that may disconnect multiple times, causing issues when repeatedly creating a gym env

bump up pybullet to version 2.5.7
This commit is contained in:
Erwin Coumans
2019-11-07 10:47:56 -08:00
parent 0cdddb874c
commit 9f44d76b67
2 changed files with 10 additions and 6 deletions

View File

@@ -21,7 +21,6 @@ class BulletClient(object):
`pybullet.SHARED_MEMORY` connects to an existing simulation.
"""
self._shapes = {}
if connection_mode is None:
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
if self._client >= 0:
@@ -32,14 +31,17 @@ class BulletClient(object):
def __del__(self):
"""Clean up connection if not already done."""
try:
pybullet.disconnect(physicsClientId=self._client)
except pybullet.error:
pass
if self._client>=0:
try:
pybullet.disconnect(physicsClientId=self._client)
self._client = -1
except pybullet.error:
pass
def __getattr__(self, name):
"""Inject the client id into Bullet functions."""
attribute = getattr(pybullet, name)
if inspect.isbuiltin(attribute):
if name not in [
"invertTransform",
@@ -51,4 +53,6 @@ class BulletClient(object):
"getQuaternionFromEuler",
]: # A temporary hack for now.
attribute = functools.partial(attribute, physicsClientId=self._client)
if name=="disconnect":
self._client = -1
return attribute

View File

@@ -491,7 +491,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
setup(
name='pybullet',
version='2.5.6',
version='2.5.7',
description=
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description=