Merge pull request #2037 from araffin/update-gym

Update gym envs
This commit is contained in:
erwincoumans 2019-01-28 10:14:09 -08:00 committed by GitHub
commit c97d1041ed
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
24 changed files with 251 additions and 270 deletions

View File

@ -47,21 +47,19 @@ class CartPoleBulletEnv(gym.Env):
self.action_space = spaces.Discrete(2)
self.observation_space = spaces.Box(-high, high, dtype=np.float32)
self._seed()
self.seed()
# self.reset()
self.viewer = None
self._configure()
def _configure(self, display=None):
self.display = display
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
def _step(self, action):
def step(self, action):
force = self.force_mag if action==1 else -self.force_mag
p.setJointMotorControl2(self.cartpole, 0, p.TORQUE_CONTROL, force=force)
@ -79,7 +77,7 @@ class CartPoleBulletEnv(gym.Env):
#print("state=",self.state)
return np.array(self.state), reward, done, {}
def _reset(self):
def reset(self):
# print("-----------reset simulation---------------")
p.resetSimulation()
self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cartpole.urdf"),[0,0,0])
@ -101,11 +99,5 @@ class CartPoleBulletEnv(gym.Env):
#print("self.state=", self.state)
return np.array(self.state)
def _render(self, mode='human', close=False):
def render(self, mode='human', close=False):
return
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step

View File

@ -53,7 +53,7 @@ class KukaCamGymEnv(gym.Env):
else:
p.connect(p.DIRECT)
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
self._seed()
self.seed()
self.reset()
observationDim = len(self.getExtendedObservation())
#print("observationDim")
@ -66,11 +66,11 @@ class KukaCamGymEnv(gym.Env):
action_dim = 3
self._action_bound = 1
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4))
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4), dtype=np.uint8)
self.viewer = None
def _reset(self):
def reset(self):
self.terminated = 0
p.resetSimulation()
p.setPhysicsEngineParameter(numSolverIterations=150)
@ -95,7 +95,7 @@ class KukaCamGymEnv(gym.Env):
def __del__(self):
p.disconnect()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -127,7 +127,7 @@ class KukaCamGymEnv(gym.Env):
self._observation = np_img_arr
return self._observation
def _step(self, action):
def step(self, action):
if (self._isDiscrete):
dv = 0.01
dx = [0,-dv,dv,0,0,0,0][action]
@ -167,7 +167,7 @@ class KukaCamGymEnv(gym.Env):
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
def render(self, mode='human', close=False):
if mode != "rgb_array":
return np.array([])
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
@ -256,8 +256,8 @@ class KukaCamGymEnv(gym.Env):
#print(reward)
return reward
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -57,7 +57,7 @@ class KukaGymEnv(gym.Env):
else:
p.connect(p.DIRECT)
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
self._seed()
self.seed()
self.reset()
observationDim = len(self.getExtendedObservation())
#print("observationDim")
@ -74,7 +74,7 @@ class KukaGymEnv(gym.Env):
self.observation_space = spaces.Box(-observation_high, observation_high)
self.viewer = None
def _reset(self):
def reset(self):
#print("KukaGymEnv _reset")
self.terminated = 0
p.resetSimulation()
@ -100,7 +100,7 @@ class KukaGymEnv(gym.Env):
def __del__(self):
p.disconnect()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -138,7 +138,7 @@ class KukaGymEnv(gym.Env):
self._observation.extend(list(blockInGripperPosXYEulZ))
return self._observation
def _step(self, action):
def step(self, action):
if (self._isDiscrete):
dv = 0.005
dx = [0,-dv,dv,0,0,0,0][action]
@ -183,7 +183,7 @@ class KukaGymEnv(gym.Env):
return np.array(self._observation), reward, done, {}
def _render(self, mode="rgb_array", close=False):
def render(self, mode="rgb_array", close=False):
if mode != "rgb_array":
return np.array([])
@ -283,8 +283,8 @@ class KukaGymEnv(gym.Env):
#print(reward)
return reward
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -90,7 +90,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
else:
self.cid = p.connect(p.DIRECT)
self._seed()
self.seed()
if (self._isDiscrete):
if self._removeHeightHack:
@ -105,7 +105,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
shape=(4,)) # dx, dy, dz, da
self.viewer = None
def _reset(self):
def reset(self):
"""Environment reset called at the beginning of an episode.
"""
# Set the camera settings.
@ -185,7 +185,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
return np_img_arr[:, :, :3]
def _step(self, action):
def step(self, action):
"""Environment step.
Args:
@ -326,8 +326,6 @@ class KukaDiverseObjectEnv(KukaGymEnv):
selected_objects_filenames += [found_object_directories[object_index]]
return selected_objects_filenames
if parse_version(gym.__version__)>=parse_version('0.9.6'):
reset = _reset
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_reset = reset
_step = step

View File

@ -2,7 +2,8 @@
"""
import os, inspect
import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
@ -10,6 +11,8 @@ os.sys.path.insert(0,parentdir)
import math
import time
from pkg_resources import parse_version
import gym
from gym import spaces
from gym.utils import seeding
@ -17,7 +20,6 @@ import numpy as np
import pybullet
from . import bullet_client
from . import minitaur
import os
import pybullet_data
from . import minitaur_env_randomizer
@ -155,7 +157,7 @@ class MinitaurBulletDuckEnv(gym.Env):
else:
self._pybullet_client = bullet_client.BulletClient()
self._seed()
self.seed()
self.reset()
observation_high = (
self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
@ -163,8 +165,8 @@ class MinitaurBulletDuckEnv(gym.Env):
self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
action_dim = 8
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(observation_low, observation_high)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(observation_low, observation_high, dtype=np.float32)
self.viewer = None
self._hard_reset = hard_reset # This assignment need to be after reset()
@ -174,7 +176,7 @@ class MinitaurBulletDuckEnv(gym.Env):
def configure(self, args):
self._args = args
def _reset(self):
def reset(self):
if self._hard_reset:
self._pybullet_client.resetSimulation()
self._pybullet_client.setPhysicsEngineParameter(
@ -217,7 +219,7 @@ class MinitaurBulletDuckEnv(gym.Env):
self._pybullet_client.stepSimulation()
return self._noisy_observation()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -231,7 +233,7 @@ class MinitaurBulletDuckEnv(gym.Env):
action = self.minitaur.ConvertFromLegModel(action)
return action
def _step(self, action):
def step(self, action):
"""Step forward the simulation, given the action.
Args:
@ -268,7 +270,7 @@ class MinitaurBulletDuckEnv(gym.Env):
done = self._termination()
return np.array(self._noisy_observation()), reward, done, {}
def _render(self, mode="rgb_array", close=False):
def render(self, mode="rgb_array", close=False):
if mode != "rgb_array":
return np.array([])
base_pos = self.minitaur.GetBasePosition()
@ -386,7 +388,8 @@ class MinitaurBulletDuckEnv(gym.Env):
self.minitaur.GetObservationUpperBound())
return observation
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -152,7 +152,7 @@ class MinitaurBulletEnv(gym.Env):
else:
self._pybullet_client = bullet_client.BulletClient()
self._seed()
self.seed()
self.reset()
observation_high = (
self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
@ -160,8 +160,8 @@ class MinitaurBulletEnv(gym.Env):
self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
action_dim = 8
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(observation_low, observation_high)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(observation_low, observation_high, dtype=np.float32)
self.viewer = None
self._hard_reset = hard_reset # This assignment need to be after reset()
@ -171,7 +171,7 @@ class MinitaurBulletEnv(gym.Env):
def configure(self, args):
self._args = args
def _reset(self):
def reset(self):
if self._hard_reset:
self._pybullet_client.resetSimulation()
self._pybullet_client.setPhysicsEngineParameter(
@ -215,7 +215,7 @@ class MinitaurBulletEnv(gym.Env):
self._pybullet_client.stepSimulation()
return self._noisy_observation()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -229,7 +229,7 @@ class MinitaurBulletEnv(gym.Env):
action = self.minitaur.ConvertFromLegModel(action)
return action
def _step(self, action):
def step(self, action):
"""Step forward the simulation, given the action.
Args:
@ -274,7 +274,7 @@ class MinitaurBulletEnv(gym.Env):
done = self._termination()
return np.array(self._noisy_observation()), reward, done, {}
def _render(self, mode="rgb_array", close=False):
def render(self, mode="rgb_array", close=False):
if mode != "rgb_array":
return np.array([])
base_pos = self.minitaur.GetBasePosition()
@ -388,8 +388,8 @@ class MinitaurBulletEnv(gym.Env):
self.minitaur.GetObservationUpperBound())
return observation
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -1,8 +1,9 @@
import os
import numpy as np
import copy
import math
import numpy as np
class Racecar:
def __init__(self, bullet_client, urdfRootPath='', timeStep=0.01):
@ -80,4 +81,3 @@ class Racecar:
self._p.setJointMotorControl2(self.racecarUniqueId,motor,self._p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
for steer in self.steeringLinks:
self._p.setJointMotorControl2(self.racecarUniqueId,steer,self._p.POSITION_CONTROL,targetPosition=steeringAngle)

View File

@ -5,10 +5,10 @@ os.sys.path.insert(0,parentdir)
import math
import gym
import time
from gym import spaces
from gym.utils import seeding
import numpy as np
import time
import pybullet
from . import racecar
import random
@ -47,7 +47,7 @@ class RacecarGymEnv(gym.Env):
else:
self._p = bullet_client.BulletClient()
self._seed()
self.seed()
#self.reset()
observationDim = 2 #len(self.getExtendedObservation())
#print("observationDim")
@ -60,11 +60,11 @@ class RacecarGymEnv(gym.Env):
action_dim = 2
self._action_bound = 1
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(-observation_high, observation_high)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(-observation_high, observation_high, dtype=np.float32)
self.viewer = None
def _reset(self):
def reset(self):
self._p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
self._p.setTimeStep(self._timeStep)
@ -95,7 +95,7 @@ class RacecarGymEnv(gym.Env):
def __del__(self):
self._p = 0
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -109,7 +109,7 @@ class RacecarGymEnv(gym.Env):
self._observation.extend([ballPosInCar[0],ballPosInCar[1]])
return self._observation
def _step(self, action):
def step(self, action):
if (self._renders):
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
@ -139,7 +139,7 @@ class RacecarGymEnv(gym.Env):
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
def render(self, mode='human', close=False):
if mode != "rgb_array":
return np.array([])
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
@ -176,8 +176,8 @@ class RacecarGymEnv(gym.Env):
#print(reward)
return reward
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -49,7 +49,7 @@ class RacecarZEDGymEnv(gym.Env):
else:
self._p = bullet_client.BulletClient()
self._seed()
self.seed()
self.reset()
observationDim = len(self.getExtendedObservation())
#print("observationDim")
@ -62,12 +62,12 @@ class RacecarZEDGymEnv(gym.Env):
action_dim = 2
self._action_bound = 1
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4))
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4), dtype=np.uint8)
self.viewer = None
def _reset(self):
def reset(self):
self._p.resetSimulation()
#p.setPhysicsEngineParameter(numSolverIterations=300)
self._p.setTimeStep(self._timeStep)
@ -98,7 +98,7 @@ class RacecarZEDGymEnv(gym.Env):
def __del__(self):
self._p = 0
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -124,7 +124,7 @@ class RacecarZEDGymEnv(gym.Env):
self._observation = np_img_arr
return self._observation
def _step(self, action):
def step(self, action):
if (self._renders):
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
@ -154,7 +154,7 @@ class RacecarZEDGymEnv(gym.Env):
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
def render(self, mode='human', close=False):
if mode != "rgb_array":
return np.array([])
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
@ -191,8 +191,8 @@ class RacecarZEDGymEnv(gym.Env):
#print(reward)
return reward
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -56,21 +56,21 @@ class HumanoidDeepMimicGymEnv(gym.Env):
self._pybullet_client = None
self._humanoid = None
self._control_time_step = 8.*(1./240.)#0.033333
self._seed()
self.seed()
observation_high = (self._get_observation_upper_bound())
observation_low = (self._get_observation_lower_bound())
action_dim = 36
self._action_bound = 3.14 #todo: check this
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(observation_low, observation_high)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(observation_low, observation_high, dtype=np.float32)
def _close(self):
def close(self):
self._humanoid = None
self._pybullet_client.disconnect()
def _reset(self):
def reset(self):
if (self._pybullet_client==None):
if self._is_render:
self._pybullet_client = bullet_client.BulletClient(
@ -108,11 +108,11 @@ class HumanoidDeepMimicGymEnv(gym.Env):
self._pybullet_client.COV_ENABLE_RENDERING, 1)
return self._get_observation()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
def _step(self, action):
def step(self, action):
"""Step forward the simulation, given the action.
Args:
@ -157,7 +157,7 @@ class HumanoidDeepMimicGymEnv(gym.Env):
self._env_step_counter += 1
return np.array(self._get_observation()), reward, done, {}
def _render(self, mode="rgb_array", close=False):
def render(self, mode="rgb_array", close=False):
if mode == "human":
self._is_render = True
if mode != "rgb_array":
@ -252,12 +252,12 @@ class HumanoidDeepMimicGymEnv(gym.Env):
def configure(self, args):
pass
if parse_version(gym.__version__)>=parse_version('0.9.6'):
close = _close
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step
_close = close
@property
@ -275,5 +275,3 @@ class HumanoidDeepMimicGymEnv(gym.Env):
@property
def env_step_counter(self):
return self._env_step_counter

View File

@ -24,7 +24,7 @@ class MJCFBaseBulletEnv(gym.Env):
self.camera = Camera()
self.isRender = render
self.robot = robot
self._seed()
self.seed()
self._cam_dist = 3
self._cam_yaw = 0
self._cam_pitch = -30
@ -33,18 +33,19 @@ class MJCFBaseBulletEnv(gym.Env):
self.action_space = robot.action_space
self.observation_space = robot.observation_space
def configure(self, args):
self.robot.args = args
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = gym.utils.seeding.np_random(seed)
self.robot.np_random = self.np_random # use the same np_randomizer for robot as for env
return [seed]
def _reset(self):
def reset(self):
if (self.physicsClientId<0):
self.ownsPhysicsClient = True
if self.isRender:
self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else:
@ -68,8 +69,8 @@ class MJCFBaseBulletEnv(gym.Env):
self.potential = self.robot.calc_potential()
return s
def _render(self, mode, close=False):
if (mode=="human"):
def render(self, mode='human'):
if mode == "human":
self.isRender = True
if mode != "rgb_array":
return np.array([])
@ -99,7 +100,7 @@ class MJCFBaseBulletEnv(gym.Env):
return rgb_array
def _close(self):
def close(self):
if (self.ownsPhysicsClient):
if (self.physicsClientId>=0):
self._p.disconnect()
@ -108,27 +109,23 @@ class MJCFBaseBulletEnv(gym.Env):
def HUD(self, state, a, done):
pass
# backwards compatibility for gym >= v0.9.x
# for extension of this class.
def step(self, *args, **kwargs):
if self.isRender:
base_pos=[0,0,0]
if (hasattr(self,'robot')):
if (hasattr(self.robot,'body_xyz')):
base_pos = self.robot.body_xyz
# Keep the previous orientation of the camera set by the user.
#[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
return self._step(*args, **kwargs)
if parse_version(gym.__version__)>=parse_version('0.9.6'):
close = _close
render = _render
reset = _reset
seed = _seed
# def step(self, *args, **kwargs):
# if self.isRender:
# base_pos=[0,0,0]
# if (hasattr(self,'robot')):
# if (hasattr(self.robot,'body_xyz')):
# base_pos = self.robot.body_xyz
# # Keep the previous orientation of the camera set by the user.
# #[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
# self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
#
#
# return self.step(*args, **kwargs)
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step
class Camera:
def __init__(self):

View File

@ -7,7 +7,7 @@ from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid, Human
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
def __init__(self, robot, render=False):
print("WalkerBase::__init__ start")
# print("WalkerBase::__init__ start")
MJCFBaseBulletEnv.__init__(self, robot, render)
self.camera_x = 0
@ -20,12 +20,12 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
self.stadium_scene = SinglePlayerStadiumScene(bullet_client, gravity=9.8, timestep=0.0165/4, frame_skip=4)
return self.stadium_scene
def _reset(self):
def reset(self):
if (self.stateId>=0):
#print("restoreState self.stateId:",self.stateId)
self._p.restoreState(self.stateId)
r = MJCFBaseBulletEnv._reset(self)
r = MJCFBaseBulletEnv.reset(self)
self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING,0)
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(self._p,
@ -56,7 +56,7 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
foot_ground_object_names = set(["floor"]) # to distinguish ground and other objects
joints_at_limit_cost = -0.1 # discourage stuck joints
def _step(self, a):
def step(self, a):
if not self.scene.multiplayer: # if multiplayer, action first applied to all robots, then global step() called, then _step() for all robots with the same actions
self.robot.apply_action(a)
self.scene.global_step()
@ -125,41 +125,41 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
self.camera.move_and_look_at(self.camera_x, y-2.0, 1.4, x, y, 1.0)
class HopperBulletEnv(WalkerBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Hopper()
WalkerBaseBulletEnv.__init__(self, self.robot)
WalkerBaseBulletEnv.__init__(self, self.robot, render)
class Walker2DBulletEnv(WalkerBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Walker2D()
WalkerBaseBulletEnv.__init__(self, self.robot)
WalkerBaseBulletEnv.__init__(self, self.robot, render)
class HalfCheetahBulletEnv(WalkerBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = HalfCheetah()
WalkerBaseBulletEnv.__init__(self, self.robot)
WalkerBaseBulletEnv.__init__(self, self.robot, render)
def _isDone(self):
return False
class AntBulletEnv(WalkerBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Ant()
WalkerBaseBulletEnv.__init__(self, self.robot)
WalkerBaseBulletEnv.__init__(self, self.robot, render)
class HumanoidBulletEnv(WalkerBaseBulletEnv):
def __init__(self, robot=Humanoid()):
def __init__(self, robot=Humanoid(), render=False):
self.robot = robot
WalkerBaseBulletEnv.__init__(self, self.robot)
WalkerBaseBulletEnv.__init__(self, self.robot, render)
self.electricity_cost = 4.25*WalkerBaseBulletEnv.electricity_cost
self.stall_torque_cost = 4.25*WalkerBaseBulletEnv.stall_torque_cost
class HumanoidFlagrunBulletEnv(HumanoidBulletEnv):
random_yaw = True
def __init__(self):
def __init__(self, render=False):
self.robot = HumanoidFlagrun()
HumanoidBulletEnv.__init__(self, self.robot)
HumanoidBulletEnv.__init__(self, self.robot, render)
def create_single_player_scene(self, bullet_client):
s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
@ -169,10 +169,10 @@ class HumanoidFlagrunBulletEnv(HumanoidBulletEnv):
class HumanoidFlagrunHarderBulletEnv(HumanoidBulletEnv):
random_lean = True # can fall on start
def __init__(self):
def __init__(self, render=False):
self.robot = HumanoidFlagrunHarder()
self.electricity_cost /= 4 # don't care that much about electricity, just stand up!
HumanoidBulletEnv.__init__(self, self.robot)
HumanoidBulletEnv.__init__(self, self.robot, render)
def create_single_player_scene(self, bullet_client):
s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)

View File

@ -5,14 +5,14 @@ from robot_manipulators import Reacher, Pusher, Striker, Thrower
class ReacherBulletEnv(MJCFBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Reacher()
MJCFBaseBulletEnv.__init__(self, self.robot)
MJCFBaseBulletEnv.__init__(self, self.robot, render)
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):
def step(self, a):
assert (not self.scene.multiplayer)
self.robot.apply_action(a)
self.scene.global_step()
@ -39,14 +39,14 @@ class ReacherBulletEnv(MJCFBaseBulletEnv):
class PusherBulletEnv(MJCFBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Pusher()
MJCFBaseBulletEnv.__init__(self, self.robot)
MJCFBaseBulletEnv.__init__(self, self.robot, render)
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):
def step(self, a):
self.robot.apply_action(a)
self.scene.global_step()
@ -93,9 +93,9 @@ class PusherBulletEnv(MJCFBaseBulletEnv):
class StrikerBulletEnv(MJCFBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Striker()
MJCFBaseBulletEnv.__init__(self, self.robot)
MJCFBaseBulletEnv.__init__(self, self.robot, render)
self._striked = False
self._min_strike_dist = np.inf
self.strike_threshold = 0.1
@ -103,7 +103,7 @@ class StrikerBulletEnv(MJCFBaseBulletEnv):
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):
def step(self, a):
self.robot.apply_action(a)
self.scene.global_step()
@ -169,14 +169,14 @@ class StrikerBulletEnv(MJCFBaseBulletEnv):
class ThrowerBulletEnv(MJCFBaseBulletEnv):
def __init__(self):
def __init__(self, render=False):
self.robot = Thrower()
MJCFBaseBulletEnv.__init__(self, self.robot)
MJCFBaseBulletEnv.__init__(self, self.robot, render)
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):
def step(self, a):
self.robot.apply_action(a)
self.scene.global_step()
state = self.robot.calc_state() # sets self.to_target_vec
@ -231,4 +231,3 @@ class ThrowerBulletEnv(MJCFBaseBulletEnv):
x *= 0.5
y *= 0.5
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)

View File

@ -15,17 +15,17 @@ class InvertedPendulumBulletEnv(MJCFBaseBulletEnv):
def create_single_player_scene(self, bullet_client):
return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
def _reset(self):
def reset(self):
if (self.stateId>=0):
#print("InvertedPendulumBulletEnv reset p.restoreState(",self.stateId,")")
self._p.restoreState(self.stateId)
r = MJCFBaseBulletEnv._reset(self)
r = MJCFBaseBulletEnv.reset(self)
if (self.stateId<0):
self.stateId = self._p.saveState()
#print("InvertedPendulumBulletEnv reset self.stateId=",self.stateId)
return r
def _step(self, a):
def step(self, a):
self.robot.apply_action(a)
self.scene.global_step()
state = self.robot.calc_state() # sets self.pos_x self.pos_y
@ -57,15 +57,15 @@ class InvertedDoublePendulumBulletEnv(MJCFBaseBulletEnv):
def create_single_player_scene(self, bullet_client):
return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
def _reset(self):
def reset(self):
if (self.stateId>=0):
self._p.restoreState(self.stateId)
r = MJCFBaseBulletEnv._reset(self)
r = MJCFBaseBulletEnv.reset(self)
if (self.stateId<0):
self.stateId = self._p.saveState()
return r
def _step(self, a):
def step(self, a):
self.robot.apply_action(a)
self.scene.global_step()
state = self.robot.calc_state() # sets self.pos_x self.pos_y

View File

@ -74,7 +74,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
be running, but only first num_steps_to_log will be recorded in logging.
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
randomize the environment during when env.reset() is called and add
perturbations when env._step() is called.
perturbations when env.step() is called.
log_path: The path to write out logs. For the details of logging, refer to
minitaur_logging.proto.
"""
@ -107,7 +107,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
self._cam_yaw = 30
self._cam_pitch = -30
def _reset(self):
def reset(self):
self.desired_pitch = DESIRED_PITCH
# In this environment, the actions are
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
@ -123,7 +123,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
INIT_EXTENSION_POS + self._extension_offset[3]
]
initial_motor_angles = self._convert_from_leg_model(init_pose)
super(MinitaurAlternatingLegsEnv, self)._reset(
super(MinitaurAlternatingLegsEnv, self).reset(
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
return self._get_observation()

View File

@ -66,9 +66,9 @@ class MinitaurBallGymEnv(minitaur_gym_env.MinitaurGymEnv):
self.observation_space = spaces.Box(np.array([-math.pi, 0]),
np.array([math.pi, 100]))
def _reset(self):
def reset(self):
self._ball_id = 0
super(MinitaurBallGymEnv, self)._reset()
super(MinitaurBallGymEnv, self).reset()
self._init_ball_theta = random.uniform(-INIT_BALL_ANGLE, INIT_BALL_ANGLE)
self._init_ball_distance = INIT_BALL_DISTANCE
self._ball_pos = [self._init_ball_distance *

View File

@ -85,7 +85,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
render: Whether to render the simulation.
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
randomize the environment during when env.reset() is called and add
perturbations when env._step() is called.
perturbations when env.step() is called.
use_angular_velocity_in_observation: Whether to include roll_dot and
pitch_dot of the base in the observation.
use_motor_angle_in_observation: Whether to include motor angles in the
@ -132,7 +132,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
self._cur_ori = [0, 0, 0, 1]
self._goal_ori = [0, 0, 0, 1]
def _reset(self):
def reset(self):
self.desired_pitch = DESIRED_PITCH
# In this environment, the actions are
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
@ -150,11 +150,11 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
initial_motor_angles = self._convert_from_leg_model(init_pose)
self._pybullet_client.resetBasePositionAndOrientation(
0, [0, 0, 0], [0, 0, 0, 1])
super(MinitaurFourLegStandEnv, self)._reset(
super(MinitaurFourLegStandEnv, self).reset(
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
return self._get_observation()
def _step(self, action):
def step(self, action):
"""Step forward the simulation, given the action.
Args:
@ -187,9 +187,9 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
action = self._transform_action_to_motor_command(action)
t = self._env_step_counter % MOVING_FLOOR_TOTAL_STEP
if t == 0:
self._seed()
self.seed()
orientation_x = random.uniform(-0.2, 0.2)
self._seed()
self.seed()
orientation_y = random.uniform(-0.2, 0.2)
_, self._cur_ori = self._pybullet_client.getBasePositionAndOrientation(0)
self._goal_ori = self._pybullet_client.getQuaternionFromEuler(

View File

@ -237,7 +237,7 @@ class MinitaurGymEnv(gym.Env):
if self._urdf_version is None:
self._urdf_version = DEFAULT_URDF_VERSION
self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0)
self._seed()
self.seed()
self.reset()
observation_high = (self._get_observation_upper_bound() + OBSERVATION_EPS)
observation_low = (self._get_observation_lower_bound() - OBSERVATION_EPS)
@ -248,14 +248,14 @@ class MinitaurGymEnv(gym.Env):
self.viewer = None
self._hard_reset = hard_reset # This assignment need to be after reset()
def _close(self):
def close(self):
self.logging.save_episode(self._episode_proto)
self.minitaur.Terminate()
def add_env_randomizer(self, env_randomizer):
self._env_randomizers.append(env_randomizer)
def _reset(self, initial_motor_angles=None, reset_duration=1.0):
def reset(self, initial_motor_angles=None, reset_duration=1.0):
self._pybullet_client.configureDebugVisualizer(
self._pybullet_client.COV_ENABLE_RENDERING, 0)
self.logging.save_episode(self._episode_proto)
@ -317,7 +317,7 @@ class MinitaurGymEnv(gym.Env):
self._pybullet_client.COV_ENABLE_RENDERING, 1)
return self._get_observation()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
@ -331,7 +331,7 @@ class MinitaurGymEnv(gym.Env):
action = self.minitaur.ConvertFromLegModel(action)
return action
def _step(self, action):
def step(self, action):
"""Step forward the simulation, given the action.
Args:
@ -379,7 +379,7 @@ class MinitaurGymEnv(gym.Env):
self.minitaur.Terminate()
return np.array(self._get_observation()), reward, done, {}
def _render(self, mode="rgb_array", close=False):
def render(self, mode="rgb_array", close=False):
if mode != "rgb_array":
return np.array([])
base_pos = self.minitaur.GetBasePosition()
@ -569,12 +569,12 @@ class MinitaurGymEnv(gym.Env):
"""
return len(self._get_observation())
if parse_version(gym.__version__)>=parse_version('0.9.6'):
close = _close
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step
def set_time_step(self, control_step, simulation_step=0.001):
"""Sets the time step of the environment.
@ -617,5 +617,3 @@ class MinitaurGymEnv(gym.Env):
@property
def env_step_counter(self):
return self._env_step_counter

View File

@ -27,7 +27,7 @@ class MinitaurRandomizeTerrainGymEnv(minitaur_gym_env.MinitaurGymEnv):
"""
def _reset(self):
def reset(self):
self._pybullet_client.resetSimulation()
self._pybullet_client.setPhysicsEngineParameter(
numSolverIterations=self._num_bullet_solver_iterations)

View File

@ -90,7 +90,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
and moved to the origin.
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
randomize the environment during when env.reset() is called and add
perturbations when env._step() is called.
perturbations when env.step() is called.
log_path: The path to write out logs. For the details of logging, refer to
minitaur_logging.proto.
"""
@ -123,7 +123,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
self._cam_yaw = 30
self._cam_pitch = -30
def _reset(self):
def reset(self):
# TODO(b/73666007): Use composition instead of inheritance.
# (http://go/design-for-testability-no-inheritance).
init_pose = MinitaurPose(
@ -137,7 +137,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
extension_angle_4=INIT_EXTENSION_POS)
# TODO(b/73734502): Refactor input of _convert_from_leg_model to namedtuple.
initial_motor_angles = self._convert_from_leg_model(list(init_pose))
super(MinitaurReactiveEnv, self)._reset(
super(MinitaurReactiveEnv, self).reset(
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
return self._get_observation()

View File

@ -101,13 +101,13 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
done = self._termination()
return np.array(self._get_observation()), reward, done, {}
def _step(self, action):
def step(self, action):
# At start, use policy_flip to lift the robot to its two legs. After the
# robot reaches the lift up stage, give control back to the agent by
# returning the current state and reward.
if self._env_step_counter < 1:
return self._stand_up()
return super(MinitaurStandGymEnv, self)._step(action)
return super(MinitaurStandGymEnv, self).step(action)
def _reward(self):
"""Reward function for standing up pose.

View File

@ -85,7 +85,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
reposition the robot.
env_randomizer: A list of EnvRandomizers that can randomize the
environment during when env.reset() is called and add perturbation
forces when env._step() is called.
forces when env.step() is called.
log_path: The path to write out logs. For the details of logging, refer to
minitaur_logging.proto.
init_extension: The initial reset length of the leg.
@ -139,12 +139,12 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
self._cam_yaw = 30
self._cam_pitch = -30
def _reset(self):
def reset(self):
# In this environment, the actions are
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
initial_motor_angles = self._convert_from_leg_model(self._init_pose)
super(MinitaurTrottingEnv, self)._reset(
super(MinitaurTrottingEnv, self).reset(
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
return self._get_observation()

View File

@ -87,7 +87,7 @@ class PyBulletSimGymEnv(gym.Env):
self._pybullet_client.setAdditionalSearchPath(urdf_root)
self._seed()
self.seed()
self.reset()
observation_high = (
@ -108,7 +108,7 @@ class PyBulletSimGymEnv(gym.Env):
def configure(self, args):
self._args = args
def _reset(self):
def reset(self):
if self._hard_reset:
self._pybullet_client.resetSimulation()
@ -130,11 +130,11 @@ class PyBulletSimGymEnv(gym.Env):
return self._get_observation()
def _seed(self, seed=None):
def seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
def _step(self, action):
def step(self, action):
"""Step forward the simulation, given the action.
Args:
@ -173,7 +173,7 @@ class PyBulletSimGymEnv(gym.Env):
done = self._termination()
return np.array(self._get_observation()), reward, done, {}
def _render(self, mode="rgb_array", close=False):
def render(self, mode="rgb_array", close=False):
if mode != "rgb_array":
return np.array([])
base_pos = [0,0,0]
@ -196,8 +196,6 @@ class PyBulletSimGymEnv(gym.Env):
rgb_array = rgb_array[:, :, :3]
return rgb_array
def _termination(self):
terminate=self._example_sim.Termination()
return terminate
@ -206,14 +204,12 @@ class PyBulletSimGymEnv(gym.Env):
reward = 0
return reward
def _get_observation(self):
self._observation = self._example_sim.GetObservation()
return self._observation
if parse_version(gym.__version__)>=parse_version('0.9.6'):
render = _render
reset = _reset
seed = _seed
step = _step
if parse_version(gym.__version__) < parse_version('0.9.6'):
_render = render
_reset = reset
_seed = seed
_step = step

View File

@ -22,9 +22,9 @@ class XmlBasedRobot:
self.robot_body = None
high = np.ones([action_dim])
self.action_space = gym.spaces.Box(-high, high)
self.action_space = gym.spaces.Box(-high, high, dtype=np.float32)
high = np.inf * np.ones([obs_dim])
self.observation_space = gym.spaces.Box(-high, high)
self.observation_space = gym.spaces.Box(-high, high, dtype=np.float32)
#self.model_xml = model_xml
self.robot_name = robot_name