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:
@@ -21,7 +21,6 @@ class BulletClient(object):
|
|||||||
`pybullet.SHARED_MEMORY` connects to an existing simulation.
|
`pybullet.SHARED_MEMORY` connects to an existing simulation.
|
||||||
"""
|
"""
|
||||||
self._shapes = {}
|
self._shapes = {}
|
||||||
|
|
||||||
if connection_mode is None:
|
if connection_mode is None:
|
||||||
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
|
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
|
||||||
if self._client >= 0:
|
if self._client >= 0:
|
||||||
@@ -32,14 +31,17 @@ class BulletClient(object):
|
|||||||
|
|
||||||
def __del__(self):
|
def __del__(self):
|
||||||
"""Clean up connection if not already done."""
|
"""Clean up connection if not already done."""
|
||||||
try:
|
if self._client>=0:
|
||||||
pybullet.disconnect(physicsClientId=self._client)
|
try:
|
||||||
except pybullet.error:
|
pybullet.disconnect(physicsClientId=self._client)
|
||||||
pass
|
self._client = -1
|
||||||
|
except pybullet.error:
|
||||||
|
pass
|
||||||
|
|
||||||
def __getattr__(self, name):
|
def __getattr__(self, name):
|
||||||
"""Inject the client id into Bullet functions."""
|
"""Inject the client id into Bullet functions."""
|
||||||
attribute = getattr(pybullet, name)
|
attribute = getattr(pybullet, name)
|
||||||
|
|
||||||
if inspect.isbuiltin(attribute):
|
if inspect.isbuiltin(attribute):
|
||||||
if name not in [
|
if name not in [
|
||||||
"invertTransform",
|
"invertTransform",
|
||||||
@@ -51,4 +53,6 @@ class BulletClient(object):
|
|||||||
"getQuaternionFromEuler",
|
"getQuaternionFromEuler",
|
||||||
]: # A temporary hack for now.
|
]: # A temporary hack for now.
|
||||||
attribute = functools.partial(attribute, physicsClientId=self._client)
|
attribute = functools.partial(attribute, physicsClientId=self._client)
|
||||||
|
if name=="disconnect":
|
||||||
|
self._client = -1
|
||||||
return attribute
|
return attribute
|
||||||
|
|||||||
2
setup.py
2
setup.py
@@ -491,7 +491,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
|
|||||||
|
|
||||||
setup(
|
setup(
|
||||||
name='pybullet',
|
name='pybullet',
|
||||||
version='2.5.6',
|
version='2.5.7',
|
||||||
description=
|
description=
|
||||||
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||||
long_description=
|
long_description=
|
||||||
|
|||||||
Reference in New Issue
Block a user