summaryrefslogtreecommitdiff
path: root/examples/pybullet/gym/pybullet_utils/bullet_client.py
blob: 6543313d01ac995e9dde586df0be0132e7ef4407 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
"""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, hostName=None, options=''):
    """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, options=options)
      if self._client >= 0:
        return
      else:
        connection_mode = pybullet.DIRECT
    if hostName is None:
        self._client = pybullet.connect(connection_mode, options=options)
    else:
        self._client = pybullet.connect(connection_mode, hostName=hostName, options=options)

  def __del__(self):
    """Clean up connection if not already done."""
    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):
      attribute = functools.partial(attribute, physicsClientId=self._client)
    if name=="disconnect":
      self._client = -1 
    return attribute