2017-07-14 21:38:15 +00:00
|
|
|
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
|
|
|
import numpy as np
|
|
|
|
import pybullet as p
|
|
|
|
|
|
|
|
|
2017-08-23 22:03:57 +00:00
|
|
|
class MJCFBaseBulletEnv(gym.Env):
|
2017-07-14 21:38:15 +00:00
|
|
|
"""
|
2017-08-15 19:33:55 +00:00
|
|
|
Base class for MuJoCo .xml environments in a Scene.
|
2017-07-14 21:38:15 +00:00
|
|
|
These environments create single-player scenes and behave like normal Gym environments, if
|
|
|
|
you don't use multiplayer.
|
|
|
|
"""
|
|
|
|
|
|
|
|
metadata = {
|
|
|
|
'render.modes': ['human', 'rgb_array'],
|
|
|
|
'video.frames_per_second': 60
|
|
|
|
}
|
|
|
|
|
2017-08-26 21:58:48 +00:00
|
|
|
def __init__(self, robot, render=False):
|
2017-07-14 21:38:15 +00:00
|
|
|
self.scene = None
|
2017-08-26 21:58:48 +00:00
|
|
|
self.physicsClientId=-1
|
2017-08-15 19:33:55 +00:00
|
|
|
self.camera = Camera()
|
2017-08-26 21:58:48 +00:00
|
|
|
self.isRender = render
|
2017-08-15 19:33:55 +00:00
|
|
|
self.robot = robot
|
2017-07-14 21:38:15 +00:00
|
|
|
|
|
|
|
self._seed()
|
|
|
|
|
2017-08-15 19:33:55 +00:00
|
|
|
self.action_space = robot.action_space
|
|
|
|
self.observation_space = robot.observation_space
|
2017-07-14 21:38:15 +00:00
|
|
|
|
|
|
|
def _seed(self, seed=None):
|
|
|
|
self.np_random, seed = gym.utils.seeding.np_random(seed)
|
2017-08-15 19:33:55 +00:00
|
|
|
self.robot.np_random = self.np_random # use the same np_randomizer for robot as for env
|
2017-07-14 21:38:15 +00:00
|
|
|
return [seed]
|
|
|
|
|
|
|
|
def _reset(self):
|
2017-08-26 21:58:48 +00:00
|
|
|
print("self.isRender=")
|
|
|
|
print(self.isRender)
|
|
|
|
if (self.physicsClientId<0):
|
|
|
|
if (self.isRender):
|
|
|
|
self.physicsClientId = p.connect(p.GUI)
|
|
|
|
else:
|
|
|
|
self.physicsClientId = p.connect(p.DIRECT)
|
|
|
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
|
|
|
|
2017-07-14 21:38:15 +00:00
|
|
|
if self.scene is None:
|
|
|
|
self.scene = self.create_single_player_scene()
|
|
|
|
if not self.scene.multiplayer:
|
|
|
|
self.scene.episode_restart()
|
|
|
|
|
2017-08-15 19:33:55 +00:00
|
|
|
self.robot.scene = self.scene
|
|
|
|
|
2017-07-14 21:38:15 +00:00
|
|
|
self.frame = 0
|
|
|
|
self.done = 0
|
|
|
|
self.reward = 0
|
|
|
|
dump = 0
|
2017-08-15 19:33:55 +00:00
|
|
|
s = self.robot.reset()
|
|
|
|
self.potential = self.robot.calc_potential()
|
2017-07-14 21:38:15 +00:00
|
|
|
return s
|
|
|
|
|
|
|
|
def _render(self, mode, close):
|
2017-08-26 21:58:48 +00:00
|
|
|
if (mode=="human"):
|
|
|
|
self.isRender = True
|
|
|
|
|
|
|
|
def _close(self):
|
|
|
|
if (self.physicsClientId>=0):
|
|
|
|
p.disconnect(self.physicsClientId)
|
|
|
|
self.physicsClientId = -1
|
2017-07-14 21:38:15 +00:00
|
|
|
|
|
|
|
def HUD(self, state, a, done):
|
|
|
|
pass
|
|
|
|
|
|
|
|
class Camera:
|
|
|
|
def __init__(self):
|
|
|
|
pass
|
|
|
|
|
|
|
|
def move_and_look_at(self,i,j,k,x,y,z):
|
|
|
|
lookat = [x,y,z]
|
|
|
|
distance = 10
|
|
|
|
yaw = 10
|
|
|
|
p.resetDebugVisualizerCamera(distance, yaw, -20, lookat)
|