Fix for 1643, allow to instantiate multiple PyBullet Gym environments (Ant, Humanoid, Hopper, Pendula etc) in the same process (same or other thread). It uses the pybullet_utils.bullet_client to achieve this.
This commit is contained in:
@@ -9,8 +9,8 @@ class ReacherBulletEnv(MJCFBaseBulletEnv):
|
||||
self.robot = Reacher()
|
||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=0.0, timestep=0.0165, frame_skip=1)
|
||||
def create_single_player_scene(self, bullet_client):
|
||||
return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0165, frame_skip=1)
|
||||
|
||||
def _step(self, a):
|
||||
assert (not self.scene.multiplayer)
|
||||
@@ -43,8 +43,8 @@ class PusherBulletEnv(MJCFBaseBulletEnv):
|
||||
self.robot = Pusher()
|
||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=9.81, timestep=0.0020, frame_skip=5)
|
||||
def create_single_player_scene(self, bullet_client):
|
||||
return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
|
||||
|
||||
def _step(self, a):
|
||||
self.robot.apply_action(a)
|
||||
@@ -100,8 +100,8 @@ class StrikerBulletEnv(MJCFBaseBulletEnv):
|
||||
self._min_strike_dist = np.inf
|
||||
self.strike_threshold = 0.1
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=9.81, timestep=0.0020, frame_skip=5)
|
||||
def create_single_player_scene(self, bullet_client):
|
||||
return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
|
||||
|
||||
def _step(self, a):
|
||||
self.robot.apply_action(a)
|
||||
@@ -173,8 +173,8 @@ class ThrowerBulletEnv(MJCFBaseBulletEnv):
|
||||
self.robot = Thrower()
|
||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
||||
|
||||
def create_single_player_scene(self):
|
||||
return SingleRobotEmptyScene(gravity=0.0, timestep=0.0020, frame_skip=5)
|
||||
def create_single_player_scene(self, bullet_client):
|
||||
return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0020, frame_skip=5)
|
||||
|
||||
def _step(self, a):
|
||||
self.robot.apply_action(a)
|
||||
|
||||
Reference in New Issue
Block a user