Clean up environment loading

This commit is contained in:
hzyjerry 2017-10-22 16:51:28 -07:00
parent e0a0e6e31a
commit 3a28de4cf0
7 changed files with 88 additions and 72 deletions

View File

@ -1,2 +1,57 @@
#from realenv.client.client_actions import client_actions as actions
#from realenv.client.vnc_client import VNCClient as VNCClient
#from realenv.client.vnc_client import VNCClient as VNCClient
from gym.envs.registration import registry, register, make, spec
#===================== Full Environments =====================#
register(
id='HumanoidWalking-v0',
entry_point='realenv.envs.simple_env:HumanoidWalkingEnv'
)
register(
id='AntWalkingEnv-v0',
entry_point='realenv.envs.simple_env:AntWalkingEnv'
)
register(
id='HuskyWalkingEnv-v0',
entry_point='realenv.envs.simple_env:HuskyWalkingEnv'
)
#==================== Physics Environments ====================#
register(
id='PhysicsSimpleHumanoidEnv-v0',
entry_point='realenv.core.physics.simple_humanoid_env:SimpleHumanoidEnv'
)
register(
id='PhysicsHumanoidWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:HumanoidWalkingEnv'
)
register(
id='PhysicsAntWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:AntWalkingEnv'
)
register(
id='PhysicsHuskyWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:HuskyWalkingEnv'
)
'''
register(
id='PhysicsEnv-v0',
entry_point='realenv.core.physics.physics_env:PhysicsEnv'
)
'''

View File

@ -16,21 +16,21 @@ from realenv.data.datasets import get_model_path
class Engine(object):
def __init__(self, model_id, human, debug):
def __init__(self, model_id, human, debug, physics_env):
self.dataset = ViewDataSet3D(transform = np.array, mist_transform = np.array, seqlen = 2, off_3d = False, train = False)
self.model_id = model_id
self.scale_up = 1
self.human = human
self.debug = debug
self.physics_env = physics_env
self.r_visuals = None
self.r_physics = None
self.p_channel = None
def setup_all(self):
def channel_excepthook(exctype, value, tb):
#if self.p_channel.is_alive():
print("killing", self.p_channel)
#os.system("kill -9 {}".format(self.p_channel))
self.p_channel.terminate()
while tb:
filename = tb.tb_frame.f_code.co_filename
@ -128,7 +128,7 @@ class Engine(object):
renderer = PhysicsEnv(self.dataset.get_model_obj(), render_mode="human_play",fps=framePerSec, pose=pose_init)
self.r_physics = renderer
"""
env = gym.make("HumanoidWalkingEnv-v0")
env = gym.make(self.physics_env)
env.render(mode="human")
env.reset()
self.r_physics = env

View File

@ -1,3 +1,6 @@
*.urdf
*.obj
__pycache__
drivers/baselines/
drivers/baselines/
archive/
drivers/test/

View File

@ -1,28 +0,0 @@
from gym.envs.registration import registry, register, make, spec
register(
id='SimpleHumanoidEnv-v0',
entry_point='realenv.core.physics.simple_humanoid_env:SimpleHumanoidEnv'
)
register(
id='PhysicsEnv-v0',
entry_point='realenv.core.physics.physics_env:PhysicsEnv'
)
register(
id='HumanoidWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:HumanoidWalkingEnv'
)
register(
id='AntWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:AntWalkingEnv'
)
register(
id='HuskyWalkingEnv-v0',
entry_point='realenv.core.physics.physics_env:HuskyWalkingEnv'
)

View File

@ -1,7 +0,0 @@
from gym.envs.registration import registry, register, make, spec
register(
id='HumanoidWalking-v0',
entry_point='realenv.envs.simple_env:SimpleEnv'
)

View File

@ -13,19 +13,18 @@ import random
import cv2
import gym
class SimpleEnv(gym.Env):
"""Bare bone room environment with no addtional constraint (disturbance, friction, gravity change)
"""
def __init__(self, human=False, debug=True, model_id="11HB6XZSh1Q", scale_up = 1):
self.debug_mode = debug
self.human = human
self.model_id = model_id
self.scale_up = scale_up
self.engine = None
file_dir = os.path.dirname(__file__)
self.model_id = model_id
self.scale_up = scale_up
self.engine = Engine(model_id, human, debug)
def _engine_setup(self):
self.r_visuals, self.r_physics, self.p_channel = self.engine.setup_all()
if self.debug_mode:
self.r_displayer = RewardDisplayer()
@ -33,7 +32,6 @@ class SimpleEnv(gym.Env):
def _step(self, action):
try:
with Profiler("Physics to screen"):
#pose, state = self.r_physics._render(action)
obs, reward, done, meta = self.r_physics.step(action)
pose = [meta['eye_pos'], meta['eye_quat']]
@ -45,7 +43,6 @@ class SimpleEnv(gym.Env):
visuals = self.r_visuals.renderToScreen(pose)
return visuals, reward , done, {}
#return visuals, reward, done, dict(state_old=self.state_old['distance_to_target'], state_new=state['distance_to_target'])
except Exception as e:
self._end()
raise(e)
@ -68,26 +65,22 @@ class SimpleEnv(gym.Env):
return self.r_physics.action_space
if __name__ == "__main__":
env = SimpleEnv()
t_start = time.time()
r_current = 0
try:
while True:
t0 = time.time()
img, reward = env._step({})
t1 = time.time()
t = t1-t0
r_current = r_current + 1
print('(Round %d) fps %.3f total time %.3f' %(r_current, 1/t, time.time() - t0))
except KeyboardInterrupt:
env._end()
print("Program finished")
'''
r_displayer = MPRewardDisplayer()
for i in range(10000):
num = random.random() * 100 - 30
r_displayer.add_reward(num)
if i % 40 == 0:
r_displayer.reset()
'''
class HumanoidWalkingEnv(SimpleEnv):
def __init__(self):
SimpleEnv.__init__(self)
self.engine = Engine(self.model_id, self.human, self.debug_mode, "PhysicsHumanoidWalkingEnv-v0")
self._engine_setup()
class AntWalkingEnv(SimpleEnv):
def __init__(self):
SimpleEnv.__init__(self)
self.engine = Engine(self.model_id, self.human, self.debug_mode, "PhysicsAntWalkingEnv-v0")
self._engine_setup()
class HuskyWalkingEnv(SimpleEnv):
def __init__(self):
SimpleEnv.__init__(self)
self.engine = Engine(self.model_id, self.human, self.debug_mode, "PhysicsHuskyWalkingEnv-v0")
self._engine_setup()