Fix gym deprecation warnings
This commit is contained in:
@@ -34,8 +34,8 @@ class CartPoleBulletEnv(gym.Env):
|
|||||||
p.connect(p.GUI)
|
p.connect(p.GUI)
|
||||||
else:
|
else:
|
||||||
p.connect(p.DIRECT)
|
p.connect(p.DIRECT)
|
||||||
self.theta_threshold_radians = 12 * 2 * math.pi / 360
|
self.theta_threshold_radians = 12 * 2 * math.pi / 360
|
||||||
self.x_threshold = 0.4 #2.4
|
self.x_threshold = 0.4 #2.4
|
||||||
high = np.array([
|
high = np.array([
|
||||||
self.x_threshold * 2,
|
self.x_threshold * 2,
|
||||||
np.finfo(np.float32).max,
|
np.finfo(np.float32).max,
|
||||||
@@ -47,21 +47,19 @@ class CartPoleBulletEnv(gym.Env):
|
|||||||
self.action_space = spaces.Discrete(2)
|
self.action_space = spaces.Discrete(2)
|
||||||
self.observation_space = spaces.Box(-high, high, dtype=np.float32)
|
self.observation_space = spaces.Box(-high, high, dtype=np.float32)
|
||||||
|
|
||||||
self._seed()
|
self.seed()
|
||||||
# self.reset()
|
# self.reset()
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
self._configure()
|
self._configure()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
def _configure(self, display=None):
|
def _configure(self, display=None):
|
||||||
self.display = display
|
self.display = display
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
force = self.force_mag if action==1 else -self.force_mag
|
force = self.force_mag if action==1 else -self.force_mag
|
||||||
|
|
||||||
p.setJointMotorControl2(self.cartpole, 0, p.TORQUE_CONTROL, force=force)
|
p.setJointMotorControl2(self.cartpole, 0, p.TORQUE_CONTROL, force=force)
|
||||||
@@ -79,7 +77,7 @@ class CartPoleBulletEnv(gym.Env):
|
|||||||
#print("state=",self.state)
|
#print("state=",self.state)
|
||||||
return np.array(self.state), reward, done, {}
|
return np.array(self.state), reward, done, {}
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
# print("-----------reset simulation---------------")
|
# print("-----------reset simulation---------------")
|
||||||
p.resetSimulation()
|
p.resetSimulation()
|
||||||
self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cartpole.urdf"),[0,0,0])
|
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)
|
#print("self.state=", self.state)
|
||||||
return np.array(self.state)
|
return np.array(self.state)
|
||||||
|
|
||||||
def _render(self, mode='human', close=False):
|
def render(self, mode='human', close=False):
|
||||||
return
|
return
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
|
||||||
render = _render
|
|
||||||
reset = _reset
|
|
||||||
seed = _seed
|
|
||||||
step = _step
|
|
||||||
|
|||||||
@@ -53,7 +53,7 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
else:
|
else:
|
||||||
p.connect(p.DIRECT)
|
p.connect(p.DIRECT)
|
||||||
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
|
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
observationDim = len(self.getExtendedObservation())
|
observationDim = len(self.getExtendedObservation())
|
||||||
#print("observationDim")
|
#print("observationDim")
|
||||||
@@ -66,11 +66,11 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
action_dim = 3
|
action_dim = 3
|
||||||
self._action_bound = 1
|
self._action_bound = 1
|
||||||
action_high = np.array([self._action_bound] * action_dim)
|
action_high = np.array([self._action_bound] * action_dim)
|
||||||
self.action_space = spaces.Box(-action_high, action_high)
|
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))
|
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4), dtype=np.uint8)
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self.terminated = 0
|
self.terminated = 0
|
||||||
p.resetSimulation()
|
p.resetSimulation()
|
||||||
p.setPhysicsEngineParameter(numSolverIterations=150)
|
p.setPhysicsEngineParameter(numSolverIterations=150)
|
||||||
@@ -95,7 +95,7 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
def __del__(self):
|
def __del__(self):
|
||||||
p.disconnect()
|
p.disconnect()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -127,7 +127,7 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
self._observation = np_img_arr
|
self._observation = np_img_arr
|
||||||
return self._observation
|
return self._observation
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
if (self._isDiscrete):
|
if (self._isDiscrete):
|
||||||
dv = 0.01
|
dv = 0.01
|
||||||
dx = [0,-dv,dv,0,0,0,0][action]
|
dx = [0,-dv,dv,0,0,0,0][action]
|
||||||
@@ -167,7 +167,7 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
|
|
||||||
return np.array(self._observation), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
||||||
@@ -256,8 +256,8 @@ class KukaCamGymEnv(gym.Env):
|
|||||||
#print(reward)
|
#print(reward)
|
||||||
return reward
|
return reward
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
render = _render
|
_render = render
|
||||||
reset = _reset
|
_reset = reset
|
||||||
seed = _seed
|
_seed = seed
|
||||||
step = _step
|
_step = step
|
||||||
|
|||||||
@@ -57,7 +57,7 @@ class KukaGymEnv(gym.Env):
|
|||||||
else:
|
else:
|
||||||
p.connect(p.DIRECT)
|
p.connect(p.DIRECT)
|
||||||
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
|
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
observationDim = len(self.getExtendedObservation())
|
observationDim = len(self.getExtendedObservation())
|
||||||
#print("observationDim")
|
#print("observationDim")
|
||||||
@@ -74,7 +74,7 @@ class KukaGymEnv(gym.Env):
|
|||||||
self.observation_space = spaces.Box(-observation_high, observation_high)
|
self.observation_space = spaces.Box(-observation_high, observation_high)
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
#print("KukaGymEnv _reset")
|
#print("KukaGymEnv _reset")
|
||||||
self.terminated = 0
|
self.terminated = 0
|
||||||
p.resetSimulation()
|
p.resetSimulation()
|
||||||
@@ -100,7 +100,7 @@ class KukaGymEnv(gym.Env):
|
|||||||
def __del__(self):
|
def __del__(self):
|
||||||
p.disconnect()
|
p.disconnect()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -138,7 +138,7 @@ class KukaGymEnv(gym.Env):
|
|||||||
self._observation.extend(list(blockInGripperPosXYEulZ))
|
self._observation.extend(list(blockInGripperPosXYEulZ))
|
||||||
return self._observation
|
return self._observation
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
if (self._isDiscrete):
|
if (self._isDiscrete):
|
||||||
dv = 0.005
|
dv = 0.005
|
||||||
dx = [0,-dv,dv,0,0,0,0][action]
|
dx = [0,-dv,dv,0,0,0,0][action]
|
||||||
@@ -183,10 +183,10 @@ class KukaGymEnv(gym.Env):
|
|||||||
|
|
||||||
return np.array(self._observation), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
|
|
||||||
base_pos,orn = self._p.getBasePositionAndOrientation(self._kuka.kukaUid)
|
base_pos,orn = self._p.getBasePositionAndOrientation(self._kuka.kukaUid)
|
||||||
view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
|
view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
|
||||||
cameraTargetPosition=base_pos,
|
cameraTargetPosition=base_pos,
|
||||||
@@ -203,10 +203,10 @@ class KukaGymEnv(gym.Env):
|
|||||||
projectionMatrix=proj_matrix, renderer=self._p.ER_BULLET_HARDWARE_OPENGL)
|
projectionMatrix=proj_matrix, renderer=self._p.ER_BULLET_HARDWARE_OPENGL)
|
||||||
#renderer=self._p.ER_TINY_RENDERER)
|
#renderer=self._p.ER_TINY_RENDERER)
|
||||||
|
|
||||||
|
|
||||||
rgb_array = np.array(px, dtype=np.uint8)
|
rgb_array = np.array(px, dtype=np.uint8)
|
||||||
rgb_array = np.reshape(rgb_array, (RENDER_HEIGHT, RENDER_WIDTH, 4))
|
rgb_array = np.reshape(rgb_array, (RENDER_HEIGHT, RENDER_WIDTH, 4))
|
||||||
|
|
||||||
rgb_array = rgb_array[:, :, :3]
|
rgb_array = rgb_array[:, :, :3]
|
||||||
return rgb_array
|
return rgb_array
|
||||||
|
|
||||||
@@ -283,8 +283,8 @@ class KukaGymEnv(gym.Env):
|
|||||||
#print(reward)
|
#print(reward)
|
||||||
return reward
|
return reward
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
render = _render
|
_render = render
|
||||||
reset = _reset
|
_reset = reset
|
||||||
seed = _seed
|
_seed = seed
|
||||||
step = _step
|
_step = step
|
||||||
|
|||||||
@@ -35,7 +35,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
height=48,
|
height=48,
|
||||||
numObjects=5,
|
numObjects=5,
|
||||||
isTest=False):
|
isTest=False):
|
||||||
"""Initializes the KukaDiverseObjectEnv.
|
"""Initializes the KukaDiverseObjectEnv.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
urdfRoot: The diretory from which to load environment URDF's.
|
urdfRoot: The diretory from which to load environment URDF's.
|
||||||
@@ -71,7 +71,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
self._maxSteps = maxSteps
|
self._maxSteps = maxSteps
|
||||||
self.terminated = 0
|
self.terminated = 0
|
||||||
self._cam_dist = 1.3
|
self._cam_dist = 1.3
|
||||||
self._cam_yaw = 180
|
self._cam_yaw = 180
|
||||||
self._cam_pitch = -40
|
self._cam_pitch = -40
|
||||||
self._dv = dv
|
self._dv = dv
|
||||||
self._p = p
|
self._p = p
|
||||||
@@ -90,7 +90,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
|
p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
|
||||||
else:
|
else:
|
||||||
self.cid = p.connect(p.DIRECT)
|
self.cid = p.connect(p.DIRECT)
|
||||||
self._seed()
|
self.seed()
|
||||||
|
|
||||||
if (self._isDiscrete):
|
if (self._isDiscrete):
|
||||||
if self._removeHeightHack:
|
if self._removeHeightHack:
|
||||||
@@ -105,7 +105,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
shape=(4,)) # dx, dy, dz, da
|
shape=(4,)) # dx, dy, dz, da
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
"""Environment reset called at the beginning of an episode.
|
"""Environment reset called at the beginning of an episode.
|
||||||
"""
|
"""
|
||||||
# Set the camera settings.
|
# Set the camera settings.
|
||||||
@@ -122,7 +122,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
far = 10
|
far = 10
|
||||||
self._proj_matrix = p.computeProjectionMatrixFOV(
|
self._proj_matrix = p.computeProjectionMatrixFOV(
|
||||||
fov, aspect, near, far)
|
fov, aspect, near, far)
|
||||||
|
|
||||||
self._attempted_grasp = False
|
self._attempted_grasp = False
|
||||||
self._env_step = 0
|
self._env_step = 0
|
||||||
self.terminated = 0
|
self.terminated = 0
|
||||||
@@ -131,9 +131,9 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
p.setPhysicsEngineParameter(numSolverIterations=150)
|
p.setPhysicsEngineParameter(numSolverIterations=150)
|
||||||
p.setTimeStep(self._timeStep)
|
p.setTimeStep(self._timeStep)
|
||||||
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
|
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
|
||||||
|
|
||||||
p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
|
p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
|
||||||
|
|
||||||
p.setGravity(0,0,-10)
|
p.setGravity(0,0,-10)
|
||||||
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
|
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
|
||||||
self._envStepCounter = 0
|
self._envStepCounter = 0
|
||||||
@@ -185,7 +185,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
|
np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
|
||||||
return np_img_arr[:, :, :3]
|
return np_img_arr[:, :, :3]
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Environment step.
|
"""Environment step.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -325,9 +325,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
|
|||||||
for object_index in selected_objects:
|
for object_index in selected_objects:
|
||||||
selected_objects_filenames += [found_object_directories[object_index]]
|
selected_objects_filenames += [found_object_directories[object_index]]
|
||||||
return selected_objects_filenames
|
return selected_objects_filenames
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
|
_reset = reset
|
||||||
reset = _reset
|
_step = step
|
||||||
|
|
||||||
step = _step
|
|
||||||
|
|||||||
@@ -2,7 +2,8 @@
|
|||||||
|
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import os, inspect
|
import os
|
||||||
|
import inspect
|
||||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||||
os.sys.path.insert(0,parentdir)
|
os.sys.path.insert(0,parentdir)
|
||||||
@@ -10,6 +11,8 @@ os.sys.path.insert(0,parentdir)
|
|||||||
|
|
||||||
import math
|
import math
|
||||||
import time
|
import time
|
||||||
|
from pkg_resources import parse_version
|
||||||
|
|
||||||
import gym
|
import gym
|
||||||
from gym import spaces
|
from gym import spaces
|
||||||
from gym.utils import seeding
|
from gym.utils import seeding
|
||||||
@@ -17,7 +20,6 @@ import numpy as np
|
|||||||
import pybullet
|
import pybullet
|
||||||
from . import bullet_client
|
from . import bullet_client
|
||||||
from . import minitaur
|
from . import minitaur
|
||||||
import os
|
|
||||||
import pybullet_data
|
import pybullet_data
|
||||||
from . import minitaur_env_randomizer
|
from . import minitaur_env_randomizer
|
||||||
|
|
||||||
@@ -155,7 +157,7 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
else:
|
else:
|
||||||
self._pybullet_client = bullet_client.BulletClient()
|
self._pybullet_client = bullet_client.BulletClient()
|
||||||
|
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
observation_high = (
|
observation_high = (
|
||||||
self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
|
self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
|
||||||
@@ -163,8 +165,8 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
|
self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
|
||||||
action_dim = 8
|
action_dim = 8
|
||||||
action_high = np.array([self._action_bound] * action_dim)
|
action_high = np.array([self._action_bound] * action_dim)
|
||||||
self.action_space = spaces.Box(-action_high, action_high)
|
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
|
||||||
self.observation_space = spaces.Box(observation_low, observation_high)
|
self.observation_space = spaces.Box(observation_low, observation_high, dtype=np.float32)
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
self._hard_reset = hard_reset # This assignment need to be after reset()
|
self._hard_reset = hard_reset # This assignment need to be after reset()
|
||||||
|
|
||||||
@@ -174,7 +176,7 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
def configure(self, args):
|
def configure(self, args):
|
||||||
self._args = args
|
self._args = args
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if self._hard_reset:
|
if self._hard_reset:
|
||||||
self._pybullet_client.resetSimulation()
|
self._pybullet_client.resetSimulation()
|
||||||
self._pybullet_client.setPhysicsEngineParameter(
|
self._pybullet_client.setPhysicsEngineParameter(
|
||||||
@@ -217,7 +219,7 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
self._pybullet_client.stepSimulation()
|
self._pybullet_client.stepSimulation()
|
||||||
return self._noisy_observation()
|
return self._noisy_observation()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -231,7 +233,7 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
action = self.minitaur.ConvertFromLegModel(action)
|
action = self.minitaur.ConvertFromLegModel(action)
|
||||||
return action
|
return action
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Step forward the simulation, given the action.
|
"""Step forward the simulation, given the action.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -268,7 +270,7 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
done = self._termination()
|
done = self._termination()
|
||||||
return np.array(self._noisy_observation()), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos = self.minitaur.GetBasePosition()
|
base_pos = self.minitaur.GetBasePosition()
|
||||||
@@ -386,7 +388,8 @@ class MinitaurBulletDuckEnv(gym.Env):
|
|||||||
self.minitaur.GetObservationUpperBound())
|
self.minitaur.GetObservationUpperBound())
|
||||||
return observation
|
return observation
|
||||||
|
|
||||||
render = _render
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
reset = _reset
|
_render = render
|
||||||
seed = _seed
|
_reset = reset
|
||||||
step = _step
|
_seed = seed
|
||||||
|
_step = step
|
||||||
|
|||||||
@@ -152,7 +152,7 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
else:
|
else:
|
||||||
self._pybullet_client = bullet_client.BulletClient()
|
self._pybullet_client = bullet_client.BulletClient()
|
||||||
|
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
observation_high = (
|
observation_high = (
|
||||||
self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
|
self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
|
||||||
@@ -160,8 +160,8 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
|
self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
|
||||||
action_dim = 8
|
action_dim = 8
|
||||||
action_high = np.array([self._action_bound] * action_dim)
|
action_high = np.array([self._action_bound] * action_dim)
|
||||||
self.action_space = spaces.Box(-action_high, action_high)
|
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
|
||||||
self.observation_space = spaces.Box(observation_low, observation_high)
|
self.observation_space = spaces.Box(observation_low, observation_high, dtype=np.float32)
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
self._hard_reset = hard_reset # This assignment need to be after reset()
|
self._hard_reset = hard_reset # This assignment need to be after reset()
|
||||||
|
|
||||||
@@ -171,7 +171,7 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
def configure(self, args):
|
def configure(self, args):
|
||||||
self._args = args
|
self._args = args
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if self._hard_reset:
|
if self._hard_reset:
|
||||||
self._pybullet_client.resetSimulation()
|
self._pybullet_client.resetSimulation()
|
||||||
self._pybullet_client.setPhysicsEngineParameter(
|
self._pybullet_client.setPhysicsEngineParameter(
|
||||||
@@ -215,7 +215,7 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
self._pybullet_client.stepSimulation()
|
self._pybullet_client.stepSimulation()
|
||||||
return self._noisy_observation()
|
return self._noisy_observation()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -229,7 +229,7 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
action = self.minitaur.ConvertFromLegModel(action)
|
action = self.minitaur.ConvertFromLegModel(action)
|
||||||
return action
|
return action
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Step forward the simulation, given the action.
|
"""Step forward the simulation, given the action.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -260,8 +260,8 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
yaw = camInfo[8]
|
yaw = camInfo[8]
|
||||||
pitch=camInfo[9]
|
pitch=camInfo[9]
|
||||||
targetPos = [0.95*curTargetPos[0]+0.05*base_pos[0],0.95*curTargetPos[1]+0.05*base_pos[1],curTargetPos[2]]
|
targetPos = [0.95*curTargetPos[0]+0.05*base_pos[0],0.95*curTargetPos[1]+0.05*base_pos[1],curTargetPos[2]]
|
||||||
|
|
||||||
|
|
||||||
self._pybullet_client.resetDebugVisualizerCamera(
|
self._pybullet_client.resetDebugVisualizerCamera(
|
||||||
distance, yaw, pitch, base_pos)
|
distance, yaw, pitch, base_pos)
|
||||||
action = self._transform_action_to_motor_command(action)
|
action = self._transform_action_to_motor_command(action)
|
||||||
@@ -274,7 +274,7 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
done = self._termination()
|
done = self._termination()
|
||||||
return np.array(self._noisy_observation()), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos = self.minitaur.GetBasePosition()
|
base_pos = self.minitaur.GetBasePosition()
|
||||||
@@ -388,8 +388,8 @@ class MinitaurBulletEnv(gym.Env):
|
|||||||
self.minitaur.GetObservationUpperBound())
|
self.minitaur.GetObservationUpperBound())
|
||||||
return observation
|
return observation
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
render = _render
|
_render = render
|
||||||
reset = _reset
|
_reset = reset
|
||||||
seed = _seed
|
_seed = seed
|
||||||
step = _step
|
_step = step
|
||||||
|
|||||||
@@ -1,8 +1,9 @@
|
|||||||
import os
|
import os
|
||||||
import numpy as np
|
|
||||||
import copy
|
import copy
|
||||||
import math
|
import math
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
class Racecar:
|
class Racecar:
|
||||||
|
|
||||||
def __init__(self, bullet_client, urdfRootPath='', timeStep=0.01):
|
def __init__(self, bullet_client, urdfRootPath='', timeStep=0.01):
|
||||||
@@ -18,7 +19,7 @@ class Racecar:
|
|||||||
# print (self._p.getJointInfo(car,i))
|
# print (self._p.getJointInfo(car,i))
|
||||||
for wheel in range(self._p.getNumJoints(car)):
|
for wheel in range(self._p.getNumJoints(car)):
|
||||||
self._p.setJointMotorControl2(car,wheel,self._p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
self._p.setJointMotorControl2(car,wheel,self._p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||||
self._p.getJointInfo(car,wheel)
|
self._p.getJointInfo(car,wheel)
|
||||||
|
|
||||||
#self._p.setJointMotorControl2(car,10,self._p.VELOCITY_CONTROL,targetVelocity=1,force=10)
|
#self._p.setJointMotorControl2(car,10,self._p.VELOCITY_CONTROL,targetVelocity=1,force=10)
|
||||||
c = self._p.createConstraint(car,9,car,11,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
c = self._p.createConstraint(car,9,car,11,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
|
||||||
@@ -80,4 +81,3 @@ class Racecar:
|
|||||||
self._p.setJointMotorControl2(self.racecarUniqueId,motor,self._p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
|
self._p.setJointMotorControl2(self.racecarUniqueId,motor,self._p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
|
||||||
for steer in self.steeringLinks:
|
for steer in self.steeringLinks:
|
||||||
self._p.setJointMotorControl2(self.racecarUniqueId,steer,self._p.POSITION_CONTROL,targetPosition=steeringAngle)
|
self._p.setJointMotorControl2(self.racecarUniqueId,steer,self._p.POSITION_CONTROL,targetPosition=steeringAngle)
|
||||||
|
|
||||||
|
|||||||
@@ -5,10 +5,10 @@ os.sys.path.insert(0,parentdir)
|
|||||||
|
|
||||||
import math
|
import math
|
||||||
import gym
|
import gym
|
||||||
|
import time
|
||||||
from gym import spaces
|
from gym import spaces
|
||||||
from gym.utils import seeding
|
from gym.utils import seeding
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import time
|
|
||||||
import pybullet
|
import pybullet
|
||||||
from . import racecar
|
from . import racecar
|
||||||
import random
|
import random
|
||||||
@@ -47,7 +47,7 @@ class RacecarGymEnv(gym.Env):
|
|||||||
else:
|
else:
|
||||||
self._p = bullet_client.BulletClient()
|
self._p = bullet_client.BulletClient()
|
||||||
|
|
||||||
self._seed()
|
self.seed()
|
||||||
#self.reset()
|
#self.reset()
|
||||||
observationDim = 2 #len(self.getExtendedObservation())
|
observationDim = 2 #len(self.getExtendedObservation())
|
||||||
#print("observationDim")
|
#print("observationDim")
|
||||||
@@ -60,11 +60,11 @@ class RacecarGymEnv(gym.Env):
|
|||||||
action_dim = 2
|
action_dim = 2
|
||||||
self._action_bound = 1
|
self._action_bound = 1
|
||||||
action_high = np.array([self._action_bound] * action_dim)
|
action_high = np.array([self._action_bound] * action_dim)
|
||||||
self.action_space = spaces.Box(-action_high, action_high)
|
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
|
||||||
self.observation_space = spaces.Box(-observation_high, observation_high)
|
self.observation_space = spaces.Box(-observation_high, observation_high, dtype=np.float32)
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self._p.resetSimulation()
|
self._p.resetSimulation()
|
||||||
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
||||||
self._p.setTimeStep(self._timeStep)
|
self._p.setTimeStep(self._timeStep)
|
||||||
@@ -95,7 +95,7 @@ class RacecarGymEnv(gym.Env):
|
|||||||
def __del__(self):
|
def __del__(self):
|
||||||
self._p = 0
|
self._p = 0
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -109,7 +109,7 @@ class RacecarGymEnv(gym.Env):
|
|||||||
self._observation.extend([ballPosInCar[0],ballPosInCar[1]])
|
self._observation.extend([ballPosInCar[0],ballPosInCar[1]])
|
||||||
return self._observation
|
return self._observation
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
if (self._renders):
|
if (self._renders):
|
||||||
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
||||||
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
|
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
|
||||||
@@ -139,7 +139,7 @@ class RacecarGymEnv(gym.Env):
|
|||||||
|
|
||||||
return np.array(self._observation), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
||||||
@@ -176,8 +176,8 @@ class RacecarGymEnv(gym.Env):
|
|||||||
#print(reward)
|
#print(reward)
|
||||||
return reward
|
return reward
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
render = _render
|
_render = render
|
||||||
reset = _reset
|
_reset = reset
|
||||||
seed = _seed
|
_seed = seed
|
||||||
step = _step
|
_step = step
|
||||||
|
|||||||
@@ -49,7 +49,7 @@ class RacecarZEDGymEnv(gym.Env):
|
|||||||
else:
|
else:
|
||||||
self._p = bullet_client.BulletClient()
|
self._p = bullet_client.BulletClient()
|
||||||
|
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
observationDim = len(self.getExtendedObservation())
|
observationDim = len(self.getExtendedObservation())
|
||||||
#print("observationDim")
|
#print("observationDim")
|
||||||
@@ -62,12 +62,12 @@ class RacecarZEDGymEnv(gym.Env):
|
|||||||
action_dim = 2
|
action_dim = 2
|
||||||
self._action_bound = 1
|
self._action_bound = 1
|
||||||
action_high = np.array([self._action_bound] * action_dim)
|
action_high = np.array([self._action_bound] * action_dim)
|
||||||
self.action_space = spaces.Box(-action_high, action_high)
|
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))
|
self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4), dtype=np.uint8)
|
||||||
|
|
||||||
self.viewer = None
|
self.viewer = None
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self._p.resetSimulation()
|
self._p.resetSimulation()
|
||||||
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
#p.setPhysicsEngineParameter(numSolverIterations=300)
|
||||||
self._p.setTimeStep(self._timeStep)
|
self._p.setTimeStep(self._timeStep)
|
||||||
@@ -98,7 +98,7 @@ class RacecarZEDGymEnv(gym.Env):
|
|||||||
def __del__(self):
|
def __del__(self):
|
||||||
self._p = 0
|
self._p = 0
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -124,7 +124,7 @@ class RacecarZEDGymEnv(gym.Env):
|
|||||||
self._observation = np_img_arr
|
self._observation = np_img_arr
|
||||||
return self._observation
|
return self._observation
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
if (self._renders):
|
if (self._renders):
|
||||||
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
||||||
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
|
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
|
||||||
@@ -154,7 +154,7 @@ class RacecarZEDGymEnv(gym.Env):
|
|||||||
|
|
||||||
return np.array(self._observation), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
|
||||||
@@ -191,8 +191,8 @@ class RacecarZEDGymEnv(gym.Env):
|
|||||||
#print(reward)
|
#print(reward)
|
||||||
return reward
|
return reward
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
render = _render
|
_render = render
|
||||||
reset = _reset
|
_reset = reset
|
||||||
seed = _seed
|
_seed = seed
|
||||||
step = _step
|
_step = step
|
||||||
|
|||||||
@@ -56,21 +56,21 @@ class HumanoidDeepMimicGymEnv(gym.Env):
|
|||||||
self._pybullet_client = None
|
self._pybullet_client = None
|
||||||
self._humanoid = None
|
self._humanoid = None
|
||||||
self._control_time_step = 8.*(1./240.)#0.033333
|
self._control_time_step = 8.*(1./240.)#0.033333
|
||||||
self._seed()
|
self.seed()
|
||||||
observation_high = (self._get_observation_upper_bound())
|
observation_high = (self._get_observation_upper_bound())
|
||||||
observation_low = (self._get_observation_lower_bound())
|
observation_low = (self._get_observation_lower_bound())
|
||||||
action_dim = 36
|
action_dim = 36
|
||||||
self._action_bound = 3.14 #todo: check this
|
self._action_bound = 3.14 #todo: check this
|
||||||
action_high = np.array([self._action_bound] * action_dim)
|
action_high = np.array([self._action_bound] * action_dim)
|
||||||
self.action_space = spaces.Box(-action_high, action_high)
|
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
|
||||||
self.observation_space = spaces.Box(observation_low, observation_high)
|
self.observation_space = spaces.Box(observation_low, observation_high, dtype=np.float32)
|
||||||
|
|
||||||
def _close(self):
|
def close(self):
|
||||||
self._humanoid = None
|
self._humanoid = None
|
||||||
self._pybullet_client.disconnect()
|
self._pybullet_client.disconnect()
|
||||||
|
|
||||||
|
|
||||||
def _reset(self):
|
|
||||||
|
def reset(self):
|
||||||
if (self._pybullet_client==None):
|
if (self._pybullet_client==None):
|
||||||
if self._is_render:
|
if self._is_render:
|
||||||
self._pybullet_client = bullet_client.BulletClient(
|
self._pybullet_client = bullet_client.BulletClient(
|
||||||
@@ -93,7 +93,7 @@ class HumanoidDeepMimicGymEnv(gym.Env):
|
|||||||
#self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,self._ground_id)
|
#self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,self._ground_id)
|
||||||
shift=[0,0,0]
|
shift=[0,0,0]
|
||||||
self._humanoid = Humanoid(self._pybullet_client,self._motion,shift)
|
self._humanoid = Humanoid(self._pybullet_client,self._motion,shift)
|
||||||
|
|
||||||
self._humanoid.Reset()
|
self._humanoid.Reset()
|
||||||
simTime = random.randint(0,self._motion.NumFrames()-2)
|
simTime = random.randint(0,self._motion.NumFrames()-2)
|
||||||
self._humanoid.SetSimTime(simTime)
|
self._humanoid.SetSimTime(simTime)
|
||||||
@@ -108,11 +108,11 @@ class HumanoidDeepMimicGymEnv(gym.Env):
|
|||||||
self._pybullet_client.COV_ENABLE_RENDERING, 1)
|
self._pybullet_client.COV_ENABLE_RENDERING, 1)
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Step forward the simulation, given the action.
|
"""Step forward the simulation, given the action.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -155,7 +155,7 @@ class HumanoidDeepMimicGymEnv(gym.Env):
|
|||||||
self._env_step_counter += 1
|
self._env_step_counter += 1
|
||||||
return np.array(self._get_observation()), reward, done, {}
|
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":
|
if mode == "human":
|
||||||
self._is_render = True
|
self._is_render = True
|
||||||
if mode != "rgb_array":
|
if mode != "rgb_array":
|
||||||
@@ -273,5 +273,3 @@ class HumanoidDeepMimicGymEnv(gym.Env):
|
|||||||
@property
|
@property
|
||||||
def env_step_counter(self):
|
def env_step_counter(self):
|
||||||
return self._env_step_counter
|
return self._env_step_counter
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -1,6 +1,6 @@
|
|||||||
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
import gym, gym.spaces, gym.utils, gym.utils.seeding
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet
|
import pybullet
|
||||||
from pybullet_utils import bullet_client
|
from pybullet_utils import bullet_client
|
||||||
|
|
||||||
from pkg_resources import parse_version
|
from pkg_resources import parse_version
|
||||||
@@ -24,7 +24,7 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
self.camera = Camera()
|
self.camera = Camera()
|
||||||
self.isRender = render
|
self.isRender = render
|
||||||
self.robot = robot
|
self.robot = robot
|
||||||
self._seed()
|
self.seed()
|
||||||
self._cam_dist = 3
|
self._cam_dist = 3
|
||||||
self._cam_yaw = 0
|
self._cam_yaw = 0
|
||||||
self._cam_pitch = -30
|
self._cam_pitch = -30
|
||||||
@@ -33,23 +33,24 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
|
|
||||||
self.action_space = robot.action_space
|
self.action_space = robot.action_space
|
||||||
self.observation_space = robot.observation_space
|
self.observation_space = robot.observation_space
|
||||||
|
|
||||||
def configure(self, args):
|
def configure(self, args):
|
||||||
self.robot.args = 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.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
|
self.robot.np_random = self.np_random # use the same np_randomizer for robot as for env
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if (self.physicsClientId<0):
|
if (self.physicsClientId<0):
|
||||||
self.ownsPhysicsClient = True
|
self.ownsPhysicsClient = True
|
||||||
|
|
||||||
|
|
||||||
if self.isRender:
|
if self.isRender:
|
||||||
self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
||||||
else:
|
else:
|
||||||
self._p = bullet_client.BulletClient()
|
self._p = bullet_client.BulletClient()
|
||||||
|
|
||||||
self.physicsClientId = self._p._client
|
self.physicsClientId = self._p._client
|
||||||
self._p.configureDebugVisualizer(pybullet.COV_ENABLE_GUI,0)
|
self._p.configureDebugVisualizer(pybullet.COV_ENABLE_GUI,0)
|
||||||
|
|
||||||
@@ -68,8 +69,8 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
self.potential = self.robot.calc_potential()
|
self.potential = self.robot.calc_potential()
|
||||||
return s
|
return s
|
||||||
|
|
||||||
def _render(self, mode, close=False):
|
def render(self, mode, close=False):
|
||||||
if (mode=="human"):
|
if mode == "human":
|
||||||
self.isRender = True
|
self.isRender = True
|
||||||
if mode != "rgb_array":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
@@ -99,7 +100,7 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
return rgb_array
|
return rgb_array
|
||||||
|
|
||||||
|
|
||||||
def _close(self):
|
def close(self):
|
||||||
if (self.ownsPhysicsClient):
|
if (self.ownsPhysicsClient):
|
||||||
if (self.physicsClientId>=0):
|
if (self.physicsClientId>=0):
|
||||||
self._p.disconnect()
|
self._p.disconnect()
|
||||||
@@ -108,27 +109,23 @@ class MJCFBaseBulletEnv(gym.Env):
|
|||||||
def HUD(self, state, a, done):
|
def HUD(self, state, a, done):
|
||||||
pass
|
pass
|
||||||
|
|
||||||
# backwards compatibility for gym >= v0.9.x
|
# def step(self, *args, **kwargs):
|
||||||
# for extension of this class.
|
# if self.isRender:
|
||||||
def step(self, *args, **kwargs):
|
# base_pos=[0,0,0]
|
||||||
if self.isRender:
|
# if (hasattr(self,'robot')):
|
||||||
base_pos=[0,0,0]
|
# if (hasattr(self.robot,'body_xyz')):
|
||||||
if (hasattr(self,'robot')):
|
# base_pos = self.robot.body_xyz
|
||||||
if (hasattr(self.robot,'body_xyz')):
|
# # Keep the previous orientation of the camera set by the user.
|
||||||
base_pos = self.robot.body_xyz
|
# #[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
|
||||||
# Keep the previous orientation of the camera set by the user.
|
# self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
|
||||||
#[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'):
|
||||||
return self._step(*args, **kwargs)
|
_render = render
|
||||||
|
_reset = reset
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
_seed = seed
|
||||||
close = _close
|
_step = step
|
||||||
render = _render
|
|
||||||
reset = _reset
|
|
||||||
seed = _seed
|
|
||||||
|
|
||||||
|
|
||||||
class Camera:
|
class Camera:
|
||||||
def __init__(self):
|
def __init__(self):
|
||||||
|
|||||||
@@ -1,31 +1,31 @@
|
|||||||
from .scene_stadium import SinglePlayerStadiumScene
|
from .scene_stadium import SinglePlayerStadiumScene
|
||||||
from .env_bases import MJCFBaseBulletEnv
|
from .env_bases import MJCFBaseBulletEnv
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import pybullet
|
import pybullet
|
||||||
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid, HumanoidFlagrun, HumanoidFlagrunHarder
|
from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid, HumanoidFlagrun, HumanoidFlagrunHarder
|
||||||
|
|
||||||
|
|
||||||
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
||||||
def __init__(self, robot, render=False):
|
def __init__(self, robot, render=False):
|
||||||
print("WalkerBase::__init__ start")
|
# print("WalkerBase::__init__ start")
|
||||||
MJCFBaseBulletEnv.__init__(self, robot, render)
|
MJCFBaseBulletEnv.__init__(self, robot, render)
|
||||||
|
|
||||||
self.camera_x = 0
|
self.camera_x = 0
|
||||||
self.walk_target_x = 1e3 # kilometer away
|
self.walk_target_x = 1e3 # kilometer away
|
||||||
self.walk_target_y = 0
|
self.walk_target_y = 0
|
||||||
self.stateId=-1
|
self.stateId=-1
|
||||||
|
|
||||||
|
|
||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
self.stadium_scene = SinglePlayerStadiumScene(bullet_client, gravity=9.8, timestep=0.0165/4, frame_skip=4)
|
self.stadium_scene = SinglePlayerStadiumScene(bullet_client, gravity=9.8, timestep=0.0165/4, frame_skip=4)
|
||||||
return self.stadium_scene
|
return self.stadium_scene
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if (self.stateId>=0):
|
if (self.stateId>=0):
|
||||||
#print("restoreState self.stateId:",self.stateId)
|
#print("restoreState self.stateId:",self.stateId)
|
||||||
self._p.restoreState(self.stateId)
|
self._p.restoreState(self.stateId)
|
||||||
|
|
||||||
r = MJCFBaseBulletEnv._reset(self)
|
r = MJCFBaseBulletEnv.reset(self)
|
||||||
self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING,0)
|
self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING,0)
|
||||||
|
|
||||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(self._p,
|
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(self._p,
|
||||||
@@ -36,10 +36,10 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
|||||||
if (self.stateId<0):
|
if (self.stateId<0):
|
||||||
self.stateId=self._p.saveState()
|
self.stateId=self._p.saveState()
|
||||||
#print("saving state self.stateId:",self.stateId)
|
#print("saving state self.stateId:",self.stateId)
|
||||||
|
|
||||||
|
|
||||||
return r
|
return r
|
||||||
|
|
||||||
def _isDone(self):
|
def _isDone(self):
|
||||||
return self._alive < 0
|
return self._alive < 0
|
||||||
|
|
||||||
@@ -56,7 +56,7 @@ class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
|
|||||||
foot_ground_object_names = set(["floor"]) # to distinguish ground and other objects
|
foot_ground_object_names = set(["floor"]) # to distinguish ground and other objects
|
||||||
joints_at_limit_cost = -0.1 # discourage stuck joints
|
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
|
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.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
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)
|
self.camera.move_and_look_at(self.camera_x, y-2.0, 1.4, x, y, 1.0)
|
||||||
|
|
||||||
class HopperBulletEnv(WalkerBaseBulletEnv):
|
class HopperBulletEnv(WalkerBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Hopper()
|
self.robot = Hopper()
|
||||||
WalkerBaseBulletEnv.__init__(self, self.robot)
|
WalkerBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
class Walker2DBulletEnv(WalkerBaseBulletEnv):
|
class Walker2DBulletEnv(WalkerBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Walker2D()
|
self.robot = Walker2D()
|
||||||
WalkerBaseBulletEnv.__init__(self, self.robot)
|
WalkerBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
class HalfCheetahBulletEnv(WalkerBaseBulletEnv):
|
class HalfCheetahBulletEnv(WalkerBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = HalfCheetah()
|
self.robot = HalfCheetah()
|
||||||
WalkerBaseBulletEnv.__init__(self, self.robot)
|
WalkerBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
def _isDone(self):
|
def _isDone(self):
|
||||||
return False
|
return False
|
||||||
|
|
||||||
class AntBulletEnv(WalkerBaseBulletEnv):
|
class AntBulletEnv(WalkerBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Ant()
|
self.robot = Ant()
|
||||||
WalkerBaseBulletEnv.__init__(self, self.robot)
|
WalkerBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
class HumanoidBulletEnv(WalkerBaseBulletEnv):
|
class HumanoidBulletEnv(WalkerBaseBulletEnv):
|
||||||
def __init__(self, robot=Humanoid()):
|
def __init__(self, robot=Humanoid(), render=False):
|
||||||
self.robot = robot
|
self.robot = robot
|
||||||
WalkerBaseBulletEnv.__init__(self, self.robot)
|
WalkerBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
self.electricity_cost = 4.25*WalkerBaseBulletEnv.electricity_cost
|
self.electricity_cost = 4.25*WalkerBaseBulletEnv.electricity_cost
|
||||||
self.stall_torque_cost = 4.25*WalkerBaseBulletEnv.stall_torque_cost
|
self.stall_torque_cost = 4.25*WalkerBaseBulletEnv.stall_torque_cost
|
||||||
|
|
||||||
class HumanoidFlagrunBulletEnv(HumanoidBulletEnv):
|
class HumanoidFlagrunBulletEnv(HumanoidBulletEnv):
|
||||||
random_yaw = True
|
random_yaw = True
|
||||||
|
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = HumanoidFlagrun()
|
self.robot = HumanoidFlagrun()
|
||||||
HumanoidBulletEnv.__init__(self, self.robot)
|
HumanoidBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
s = HumanoidBulletEnv.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):
|
class HumanoidFlagrunHarderBulletEnv(HumanoidBulletEnv):
|
||||||
random_lean = True # can fall on start
|
random_lean = True # can fall on start
|
||||||
|
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = HumanoidFlagrunHarder()
|
self.robot = HumanoidFlagrunHarder()
|
||||||
self.electricity_cost /= 4 # don't care that much about electricity, just stand up!
|
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):
|
def create_single_player_scene(self, bullet_client):
|
||||||
s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
|
s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
|
||||||
|
|||||||
@@ -5,14 +5,14 @@ from robot_manipulators import Reacher, Pusher, Striker, Thrower
|
|||||||
|
|
||||||
|
|
||||||
class ReacherBulletEnv(MJCFBaseBulletEnv):
|
class ReacherBulletEnv(MJCFBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Reacher()
|
self.robot = Reacher()
|
||||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
MJCFBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0165, frame_skip=1)
|
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)
|
assert (not self.scene.multiplayer)
|
||||||
self.robot.apply_action(a)
|
self.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
self.scene.global_step()
|
||||||
@@ -39,14 +39,14 @@ class ReacherBulletEnv(MJCFBaseBulletEnv):
|
|||||||
|
|
||||||
|
|
||||||
class PusherBulletEnv(MJCFBaseBulletEnv):
|
class PusherBulletEnv(MJCFBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Pusher()
|
self.robot = Pusher()
|
||||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
MJCFBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
|
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.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
self.scene.global_step()
|
||||||
|
|
||||||
@@ -93,9 +93,9 @@ class PusherBulletEnv(MJCFBaseBulletEnv):
|
|||||||
|
|
||||||
|
|
||||||
class StrikerBulletEnv(MJCFBaseBulletEnv):
|
class StrikerBulletEnv(MJCFBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Striker()
|
self.robot = Striker()
|
||||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
MJCFBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
self._striked = False
|
self._striked = False
|
||||||
self._min_strike_dist = np.inf
|
self._min_strike_dist = np.inf
|
||||||
self.strike_threshold = 0.1
|
self.strike_threshold = 0.1
|
||||||
@@ -103,7 +103,7 @@ class StrikerBulletEnv(MJCFBaseBulletEnv):
|
|||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
|
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.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
self.scene.global_step()
|
||||||
|
|
||||||
@@ -169,14 +169,14 @@ class StrikerBulletEnv(MJCFBaseBulletEnv):
|
|||||||
|
|
||||||
|
|
||||||
class ThrowerBulletEnv(MJCFBaseBulletEnv):
|
class ThrowerBulletEnv(MJCFBaseBulletEnv):
|
||||||
def __init__(self):
|
def __init__(self, render=False):
|
||||||
self.robot = Thrower()
|
self.robot = Thrower()
|
||||||
MJCFBaseBulletEnv.__init__(self, self.robot)
|
MJCFBaseBulletEnv.__init__(self, self.robot, render)
|
||||||
|
|
||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0020, frame_skip=5)
|
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.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
self.scene.global_step()
|
||||||
state = self.robot.calc_state() # sets self.to_target_vec
|
state = self.robot.calc_state() # sets self.to_target_vec
|
||||||
@@ -231,4 +231,3 @@ class ThrowerBulletEnv(MJCFBaseBulletEnv):
|
|||||||
x *= 0.5
|
x *= 0.5
|
||||||
y *= 0.5
|
y *= 0.5
|
||||||
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
|
self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
|
||||||
|
|
||||||
|
|||||||
@@ -15,17 +15,17 @@ class InvertedPendulumBulletEnv(MJCFBaseBulletEnv):
|
|||||||
def create_single_player_scene(self, bullet_client):
|
def create_single_player_scene(self, bullet_client):
|
||||||
return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
|
return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if (self.stateId>=0):
|
if (self.stateId>=0):
|
||||||
#print("InvertedPendulumBulletEnv reset p.restoreState(",self.stateId,")")
|
#print("InvertedPendulumBulletEnv reset p.restoreState(",self.stateId,")")
|
||||||
self._p.restoreState(self.stateId)
|
self._p.restoreState(self.stateId)
|
||||||
r = MJCFBaseBulletEnv._reset(self)
|
r = MJCFBaseBulletEnv.reset(self)
|
||||||
if (self.stateId<0):
|
if (self.stateId<0):
|
||||||
self.stateId = self._p.saveState()
|
self.stateId = self._p.saveState()
|
||||||
#print("InvertedPendulumBulletEnv reset self.stateId=",self.stateId)
|
#print("InvertedPendulumBulletEnv reset self.stateId=",self.stateId)
|
||||||
return r
|
return r
|
||||||
|
|
||||||
def _step(self, a):
|
def step(self, a):
|
||||||
self.robot.apply_action(a)
|
self.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
self.scene.global_step()
|
||||||
state = self.robot.calc_state() # sets self.pos_x self.pos_y
|
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):
|
def create_single_player_scene(self, bullet_client):
|
||||||
return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
|
return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if (self.stateId>=0):
|
if (self.stateId>=0):
|
||||||
self._p.restoreState(self.stateId)
|
self._p.restoreState(self.stateId)
|
||||||
r = MJCFBaseBulletEnv._reset(self)
|
r = MJCFBaseBulletEnv.reset(self)
|
||||||
if (self.stateId<0):
|
if (self.stateId<0):
|
||||||
self.stateId = self._p.saveState()
|
self.stateId = self._p.saveState()
|
||||||
return r
|
return r
|
||||||
|
|
||||||
def _step(self, a):
|
def step(self, a):
|
||||||
self.robot.apply_action(a)
|
self.robot.apply_action(a)
|
||||||
self.scene.global_step()
|
self.scene.global_step()
|
||||||
state = self.robot.calc_state() # sets self.pos_x self.pos_y
|
state = self.robot.calc_state() # sets self.pos_x self.pos_y
|
||||||
|
|||||||
@@ -74,7 +74,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
be running, but only first num_steps_to_log will be recorded in logging.
|
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
|
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
|
||||||
randomize the environment during when env.reset() is called and add
|
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
|
log_path: The path to write out logs. For the details of logging, refer to
|
||||||
minitaur_logging.proto.
|
minitaur_logging.proto.
|
||||||
"""
|
"""
|
||||||
@@ -107,7 +107,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
self._cam_yaw = 30
|
self._cam_yaw = 30
|
||||||
self._cam_pitch = -30
|
self._cam_pitch = -30
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self.desired_pitch = DESIRED_PITCH
|
self.desired_pitch = DESIRED_PITCH
|
||||||
# In this environment, the actions are
|
# In this environment, the actions are
|
||||||
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
# [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]
|
INIT_EXTENSION_POS + self._extension_offset[3]
|
||||||
]
|
]
|
||||||
initial_motor_angles = self._convert_from_leg_model(init_pose)
|
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)
|
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
|
|||||||
@@ -66,9 +66,9 @@ class MinitaurBallGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
self.observation_space = spaces.Box(np.array([-math.pi, 0]),
|
self.observation_space = spaces.Box(np.array([-math.pi, 0]),
|
||||||
np.array([math.pi, 100]))
|
np.array([math.pi, 100]))
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self._ball_id = 0
|
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_theta = random.uniform(-INIT_BALL_ANGLE, INIT_BALL_ANGLE)
|
||||||
self._init_ball_distance = INIT_BALL_DISTANCE
|
self._init_ball_distance = INIT_BALL_DISTANCE
|
||||||
self._ball_pos = [self._init_ball_distance *
|
self._ball_pos = [self._init_ball_distance *
|
||||||
|
|||||||
@@ -85,7 +85,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
render: Whether to render the simulation.
|
render: Whether to render the simulation.
|
||||||
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
|
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
|
||||||
randomize the environment during when env.reset() is called and add
|
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
|
use_angular_velocity_in_observation: Whether to include roll_dot and
|
||||||
pitch_dot of the base in the observation.
|
pitch_dot of the base in the observation.
|
||||||
use_motor_angle_in_observation: Whether to include motor angles in the
|
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._cur_ori = [0, 0, 0, 1]
|
||||||
self._goal_ori = [0, 0, 0, 1]
|
self._goal_ori = [0, 0, 0, 1]
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self.desired_pitch = DESIRED_PITCH
|
self.desired_pitch = DESIRED_PITCH
|
||||||
# In this environment, the actions are
|
# In this environment, the actions are
|
||||||
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
# [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)
|
initial_motor_angles = self._convert_from_leg_model(init_pose)
|
||||||
self._pybullet_client.resetBasePositionAndOrientation(
|
self._pybullet_client.resetBasePositionAndOrientation(
|
||||||
0, [0, 0, 0], [0, 0, 0, 1])
|
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)
|
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Step forward the simulation, given the action.
|
"""Step forward the simulation, given the action.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -187,9 +187,9 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
action = self._transform_action_to_motor_command(action)
|
action = self._transform_action_to_motor_command(action)
|
||||||
t = self._env_step_counter % MOVING_FLOOR_TOTAL_STEP
|
t = self._env_step_counter % MOVING_FLOOR_TOTAL_STEP
|
||||||
if t == 0:
|
if t == 0:
|
||||||
self._seed()
|
self.seed()
|
||||||
orientation_x = random.uniform(-0.2, 0.2)
|
orientation_x = random.uniform(-0.2, 0.2)
|
||||||
self._seed()
|
self.seed()
|
||||||
orientation_y = random.uniform(-0.2, 0.2)
|
orientation_y = random.uniform(-0.2, 0.2)
|
||||||
_, self._cur_ori = self._pybullet_client.getBasePositionAndOrientation(0)
|
_, self._cur_ori = self._pybullet_client.getBasePositionAndOrientation(0)
|
||||||
self._goal_ori = self._pybullet_client.getQuaternionFromEuler(
|
self._goal_ori = self._pybullet_client.getQuaternionFromEuler(
|
||||||
|
|||||||
@@ -237,7 +237,7 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
if self._urdf_version is None:
|
if self._urdf_version is None:
|
||||||
self._urdf_version = DEFAULT_URDF_VERSION
|
self._urdf_version = DEFAULT_URDF_VERSION
|
||||||
self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0)
|
self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0)
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
observation_high = (self._get_observation_upper_bound() + OBSERVATION_EPS)
|
observation_high = (self._get_observation_upper_bound() + OBSERVATION_EPS)
|
||||||
observation_low = (self._get_observation_lower_bound() - OBSERVATION_EPS)
|
observation_low = (self._get_observation_lower_bound() - OBSERVATION_EPS)
|
||||||
@@ -248,14 +248,14 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
self.viewer = None
|
self.viewer = None
|
||||||
self._hard_reset = hard_reset # This assignment need to be after reset()
|
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.logging.save_episode(self._episode_proto)
|
||||||
self.minitaur.Terminate()
|
self.minitaur.Terminate()
|
||||||
|
|
||||||
def add_env_randomizer(self, env_randomizer):
|
def add_env_randomizer(self, env_randomizer):
|
||||||
self._env_randomizers.append(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.configureDebugVisualizer(
|
||||||
self._pybullet_client.COV_ENABLE_RENDERING, 0)
|
self._pybullet_client.COV_ENABLE_RENDERING, 0)
|
||||||
self.logging.save_episode(self._episode_proto)
|
self.logging.save_episode(self._episode_proto)
|
||||||
@@ -317,7 +317,7 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
self._pybullet_client.COV_ENABLE_RENDERING, 1)
|
self._pybullet_client.COV_ENABLE_RENDERING, 1)
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
@@ -331,7 +331,7 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
action = self.minitaur.ConvertFromLegModel(action)
|
action = self.minitaur.ConvertFromLegModel(action)
|
||||||
return action
|
return action
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Step forward the simulation, given the action.
|
"""Step forward the simulation, given the action.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -379,7 +379,7 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
self.minitaur.Terminate()
|
self.minitaur.Terminate()
|
||||||
return np.array(self._get_observation()), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos = self.minitaur.GetBasePosition()
|
base_pos = self.minitaur.GetBasePosition()
|
||||||
@@ -569,12 +569,12 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
"""
|
"""
|
||||||
return len(self._get_observation())
|
return len(self._get_observation())
|
||||||
|
|
||||||
if parse_version(gym.__version__)>=parse_version('0.9.6'):
|
if parse_version(gym.__version__) < parse_version('0.9.6'):
|
||||||
close = _close
|
_render = render
|
||||||
render = _render
|
_reset = reset
|
||||||
reset = _reset
|
_seed = seed
|
||||||
seed = _seed
|
_step = step
|
||||||
step = _step
|
|
||||||
|
|
||||||
def set_time_step(self, control_step, simulation_step=0.001):
|
def set_time_step(self, control_step, simulation_step=0.001):
|
||||||
"""Sets the time step of the environment.
|
"""Sets the time step of the environment.
|
||||||
@@ -617,5 +617,3 @@ class MinitaurGymEnv(gym.Env):
|
|||||||
@property
|
@property
|
||||||
def env_step_counter(self):
|
def env_step_counter(self):
|
||||||
return self._env_step_counter
|
return self._env_step_counter
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -27,7 +27,7 @@ class MinitaurRandomizeTerrainGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
|
|
||||||
"""
|
"""
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
self._pybullet_client.resetSimulation()
|
self._pybullet_client.resetSimulation()
|
||||||
self._pybullet_client.setPhysicsEngineParameter(
|
self._pybullet_client.setPhysicsEngineParameter(
|
||||||
numSolverIterations=self._num_bullet_solver_iterations)
|
numSolverIterations=self._num_bullet_solver_iterations)
|
||||||
|
|||||||
@@ -90,7 +90,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
and moved to the origin.
|
and moved to the origin.
|
||||||
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
|
env_randomizer: An instance (or a list) of EnvRanzomier(s) that can
|
||||||
randomize the environment during when env.reset() is called and add
|
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
|
log_path: The path to write out logs. For the details of logging, refer to
|
||||||
minitaur_logging.proto.
|
minitaur_logging.proto.
|
||||||
"""
|
"""
|
||||||
@@ -123,7 +123,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
self._cam_yaw = 30
|
self._cam_yaw = 30
|
||||||
self._cam_pitch = -30
|
self._cam_pitch = -30
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
# TODO(b/73666007): Use composition instead of inheritance.
|
# TODO(b/73666007): Use composition instead of inheritance.
|
||||||
# (http://go/design-for-testability-no-inheritance).
|
# (http://go/design-for-testability-no-inheritance).
|
||||||
init_pose = MinitaurPose(
|
init_pose = MinitaurPose(
|
||||||
@@ -137,7 +137,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
extension_angle_4=INIT_EXTENSION_POS)
|
extension_angle_4=INIT_EXTENSION_POS)
|
||||||
# TODO(b/73734502): Refactor input of _convert_from_leg_model to namedtuple.
|
# TODO(b/73734502): Refactor input of _convert_from_leg_model to namedtuple.
|
||||||
initial_motor_angles = self._convert_from_leg_model(list(init_pose))
|
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)
|
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
|
|||||||
@@ -101,13 +101,13 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
done = self._termination()
|
done = self._termination()
|
||||||
return np.array(self._get_observation()), reward, done, {}
|
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
|
# 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
|
# robot reaches the lift up stage, give control back to the agent by
|
||||||
# returning the current state and reward.
|
# returning the current state and reward.
|
||||||
if self._env_step_counter < 1:
|
if self._env_step_counter < 1:
|
||||||
return self._stand_up()
|
return self._stand_up()
|
||||||
return super(MinitaurStandGymEnv, self)._step(action)
|
return super(MinitaurStandGymEnv, self).step(action)
|
||||||
|
|
||||||
def _reward(self):
|
def _reward(self):
|
||||||
"""Reward function for standing up pose.
|
"""Reward function for standing up pose.
|
||||||
|
|||||||
@@ -85,7 +85,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
|
|||||||
reposition the robot.
|
reposition the robot.
|
||||||
env_randomizer: A list of EnvRandomizers that can randomize the
|
env_randomizer: A list of EnvRandomizers that can randomize the
|
||||||
environment during when env.reset() is called and add perturbation
|
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
|
log_path: The path to write out logs. For the details of logging, refer to
|
||||||
minitaur_logging.proto.
|
minitaur_logging.proto.
|
||||||
init_extension: The initial reset length of the leg.
|
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_yaw = 30
|
||||||
self._cam_pitch = -30
|
self._cam_pitch = -30
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
# In this environment, the actions are
|
# In this environment, the actions are
|
||||||
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
|
||||||
# extension leg 1, extension leg 2, extension leg 3, extension 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)
|
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)
|
initial_motor_angles=initial_motor_angles, reset_duration=0.5)
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
|
|||||||
@@ -87,7 +87,7 @@ class PyBulletSimGymEnv(gym.Env):
|
|||||||
|
|
||||||
|
|
||||||
self._pybullet_client.setAdditionalSearchPath(urdf_root)
|
self._pybullet_client.setAdditionalSearchPath(urdf_root)
|
||||||
self._seed()
|
self.seed()
|
||||||
self.reset()
|
self.reset()
|
||||||
|
|
||||||
observation_high = (
|
observation_high = (
|
||||||
@@ -108,7 +108,7 @@ class PyBulletSimGymEnv(gym.Env):
|
|||||||
def configure(self, args):
|
def configure(self, args):
|
||||||
self._args = args
|
self._args = args
|
||||||
|
|
||||||
def _reset(self):
|
def reset(self):
|
||||||
if self._hard_reset:
|
if self._hard_reset:
|
||||||
self._pybullet_client.resetSimulation()
|
self._pybullet_client.resetSimulation()
|
||||||
|
|
||||||
@@ -130,11 +130,11 @@ class PyBulletSimGymEnv(gym.Env):
|
|||||||
|
|
||||||
return self._get_observation()
|
return self._get_observation()
|
||||||
|
|
||||||
def _seed(self, seed=None):
|
def seed(self, seed=None):
|
||||||
self.np_random, seed = seeding.np_random(seed)
|
self.np_random, seed = seeding.np_random(seed)
|
||||||
return [seed]
|
return [seed]
|
||||||
|
|
||||||
def _step(self, action):
|
def step(self, action):
|
||||||
"""Step forward the simulation, given the action.
|
"""Step forward the simulation, given the action.
|
||||||
|
|
||||||
Args:
|
Args:
|
||||||
@@ -173,7 +173,7 @@ class PyBulletSimGymEnv(gym.Env):
|
|||||||
done = self._termination()
|
done = self._termination()
|
||||||
return np.array(self._get_observation()), reward, done, {}
|
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":
|
if mode != "rgb_array":
|
||||||
return np.array([])
|
return np.array([])
|
||||||
base_pos = [0,0,0]
|
base_pos = [0,0,0]
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
import pybullet
|
import pybullet
|
||||||
import gym, gym.spaces, gym.utils
|
import gym, gym.spaces, gym.utils
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import os, inspect
|
import os, inspect
|
||||||
@@ -22,9 +22,9 @@ class XmlBasedRobot:
|
|||||||
self.robot_body = None
|
self.robot_body = None
|
||||||
|
|
||||||
high = np.ones([action_dim])
|
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])
|
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.model_xml = model_xml
|
||||||
self.robot_name = robot_name
|
self.robot_name = robot_name
|
||||||
@@ -109,8 +109,8 @@ class MJCFBasedRobot(XmlBasedRobot):
|
|||||||
self.model_xml = model_xml
|
self.model_xml = model_xml
|
||||||
self.doneLoading=0
|
self.doneLoading=0
|
||||||
def reset(self, bullet_client):
|
def reset(self, bullet_client):
|
||||||
|
|
||||||
self._p = bullet_client
|
self._p = bullet_client
|
||||||
#print("Created bullet_client with id=", self._p._client)
|
#print("Created bullet_client with id=", self._p._client)
|
||||||
if (self.doneLoading==0):
|
if (self.doneLoading==0):
|
||||||
self.ordered_joints = []
|
self.ordered_joints = []
|
||||||
@@ -151,7 +151,7 @@ class URDFBasedRobot(XmlBasedRobot):
|
|||||||
print(os.path.join(os.path.dirname(__file__), "data", self.model_urdf))
|
print(os.path.join(os.path.dirname(__file__), "data", self.model_urdf))
|
||||||
|
|
||||||
if self.self_collision:
|
if self.self_collision:
|
||||||
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p,
|
self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p,
|
||||||
self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
|
self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
|
||||||
basePosition=self.basePosition,
|
basePosition=self.basePosition,
|
||||||
baseOrientation=self.baseOrientation,
|
baseOrientation=self.baseOrientation,
|
||||||
@@ -280,11 +280,11 @@ class Joint:
|
|||||||
self.bodyIndex = bodyIndex
|
self.bodyIndex = bodyIndex
|
||||||
self.jointIndex = jointIndex
|
self.jointIndex = jointIndex
|
||||||
self.joint_name = joint_name
|
self.joint_name = joint_name
|
||||||
|
|
||||||
jointInfo = self._p.getJointInfo(self.bodies[self.bodyIndex], self.jointIndex)
|
jointInfo = self._p.getJointInfo(self.bodies[self.bodyIndex], self.jointIndex)
|
||||||
self.lowerLimit = jointInfo[8]
|
self.lowerLimit = jointInfo[8]
|
||||||
self.upperLimit = jointInfo[9]
|
self.upperLimit = jointInfo[9]
|
||||||
|
|
||||||
self.power_coeff = 0
|
self.power_coeff = 0
|
||||||
|
|
||||||
def set_state(self, x, vx):
|
def set_state(self, x, vx):
|
||||||
|
|||||||
Reference in New Issue
Block a user