Use pybullet_utils.bullet_client for all our BulletClient needs

This commit is contained in:
David Rusu
2019-12-08 20:10:12 -05:00
parent 08bc887b19
commit dd3bdf0da1
8 changed files with 18 additions and 101 deletions

View File

@@ -1,54 +0,0 @@
"""A wrapper for pybullet to manage different clients."""
from __future__ import absolute_import
from __future__ import division
import functools
import inspect
import pybullet
class BulletClient(object):
"""A wrapper for pybullet to manage different clients."""
def __init__(self, connection_mode=None):
"""Creates a Bullet client and connects to a simulation.
Args:
connection_mode:
`None` connects to an existing simulation or, if fails, creates a
new headless simulation,
`pybullet.GUI` creates a new simulation with a GUI,
`pybullet.DIRECT` creates a headless simulation,
`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:
return
else:
connection_mode = pybullet.DIRECT
self._client = pybullet.connect(connection_mode)
def __del__(self):
"""Clean up connection if not already done."""
try:
pybullet.disconnect(physicsClientId=self._client)
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",
"multiplyTransforms",
"getMatrixFromQuaternion",
"getEulerFromQuaternion",
"computeViewMatrixFromYawPitchRoll",
"computeProjectionMatrixFOV",
"getQuaternionFromEuler",
]: # A temporary hack for now.
attribute = functools.partial(attribute, physicsClientId=self._client)
return attribute

View File

@@ -14,7 +14,7 @@ from gym import spaces
from gym.utils import seeding
import numpy as np
import pybullet
from pybullet_envs.minitaur.envs import bullet_client
import pybullet_utils.bullet_client as bc
import pybullet_data
from pybullet_envs.minitaur.envs import minitaur
from pybullet_envs.minitaur.envs import minitaur_derpy
@@ -223,9 +223,9 @@ class MinitaurGymEnv(gym.Env):
self._env_randomizers = convert_to_list(env_randomizer) if env_randomizer else []
self._episode_proto = minitaur_logging_pb2.MinitaurEpisode()
if self._is_render:
self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
self._pybullet_client = bc.BulletClient(connection_mode=pybullet.GUI)
else:
self._pybullet_client = bullet_client.BulletClient()
self._pybullet_client = bc.BulletClient()
if self._urdf_version is None:
self._urdf_version = DEFAULT_URDF_VERSION
self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0)