Skip to content

Commit

Permalink
Refactoring (#98)
Browse files Browse the repository at this point in the history
---------

Co-authored-by: Heiko Carrasco <[email protected]>
  • Loading branch information
fdamken and miterion authored Oct 29, 2023
1 parent 93055bb commit 2477928
Show file tree
Hide file tree
Showing 19 changed files with 355 additions and 314 deletions.
5 changes: 2 additions & 3 deletions .github/.pre-commit-config.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
repos:
- repo: https://github.com/pycqa/isort
rev: 5.8.0
rev: 5.12.0
hooks:
- id: isort
name: isort (python)
Expand All @@ -11,7 +11,6 @@ repos:
name: isort (pyi)
types: [pyi]
- repo: https://github.com/psf/black
rev: 20.8b1
rev: 23.10.0
hooks:
- id: black
language_version: python3.7
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -93,3 +93,6 @@ MUJOCO_LOG.*
### sbi-logs
Pyrado/sbi-logs/
Pyrado/tests/sbi-logs/

### pre-commit local/symlink
.pre-commit-config.yaml
3 changes: 0 additions & 3 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,6 @@
[submodule "thirdParty/catch2"]
path = thirdParty/catch2
url = https://github.com/catchorg/Catch2.git
[submodule "thirdParty/mujoco-py"]
path = thirdParty/mujoco-py
url = https://github.com/openai/mujoco-py.git
[submodule "thirdParty/RenderPipeline"]
path = thirdParty/RenderPipeline
url = https://github.com/famura/RenderPipeline.git
Expand Down
1 change: 1 addition & 0 deletions .python-version
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
3.7
329 changes: 171 additions & 158 deletions Pyrado/pyrado/algorithms/meta/spdr.py

Large diffs are not rendered by default.

48 changes: 48 additions & 0 deletions Pyrado/pyrado/domain_randomization/domain_parameter.py
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,43 @@ def make_broadening(
clip_up=clip_up,
)

@staticmethod
def from_domain_randomizer(domain_randomizer, *, target_cov_factor=1.0, init_cov_factor=1 / 100):
"""
Creates a self-paced domain parameter having the same initial and target mean and target variance given by the domain randomizer's variance (scaled by `target_cov_factor`). The initial variance is also given by the domain randomizer's variance (scaled by `init_cov_factor`).
:param domain_randomizer: randomizer to grab the data from
:param target_cov_factor: scaling of the randomizer's variance to get the target variance; defaults to `1`
:param init_cov_factor: scaling of the randomizer's variance to get the init variance; defaults to `1/100`
:return: the self-paced domain parameter
"""
name = []
target_mean = []
target_cov_flat = []
init_mean = []
init_cov_flat = []
for domain_param in domain_randomizer.domain_params:
if not isinstance(domain_param, NormalDomainParam):
raise pyrado.TypeErr(
given=domain_param,
expected_type=NormalDomainParam,
msg="each domain_param must be a NormalDomainParam",
)
name.append(domain_param.name)
target_mean.append(domain_param.mean)
target_cov_flat.append(target_cov_factor * domain_param.std**2)
init_mean.append(domain_param.mean)
init_cov_flat.append(init_cov_factor * domain_param.std**2)
return SelfPacedDomainParam(
name=name,
target_mean=to.tensor(target_mean),
target_cov_flat=to.tensor(target_cov_flat),
init_mean=to.tensor(init_mean),
init_cov_flat=to.tensor(init_cov_flat),
clip_lo=-pyrado.inf,
clip_up=+pyrado.inf,
)

@property
def target_distr(self) -> MultivariateNormal:
"""Get the target distribution."""
Expand All @@ -413,6 +450,17 @@ def context_cov(self) -> to.Tensor:
"""Get the current covariance matrix."""
return self.context_cov_chol @ self.context_cov_chol.T

def info(self) -> dict:
return {
"name": self.name,
"target_mean": self.target_mean,
"target_cov_chol": self.target_cov_chol,
"init_mean": self.init_mean,
"init_cov_chol": self.init_cov_chol,
"clip_lo": self.clip_lo,
"clip_up": self.clip_up,
}

def adapt(self, domain_distr_param: str, domain_distr_param_value: to.Tensor):
"""
Update this domain parameter.
Expand Down
29 changes: 1 addition & 28 deletions Pyrado/pyrado/environments/mujoco/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,35 +26,8 @@
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import os

import pyrado
from pyrado.utils.input_output import print_cbt


try:
import mujoco_py
except (ImportError, Exception):
# The ImportError is raised if mujoco-py is simply not installed
# The Exception catches the case that you have everything installed properly but your IDE does not set the
# LD_LIBRARY_PATH correctly (happens for PyCharm & CLion). To check this, try to run your script from the terminal.
ld_library_path = os.environ.get("LD_LIBRARY_PATH")
ld_preload = os.environ.get("LD_PRELOAD")
print_cbt(
"You are trying to use are MuJoCo-based environment, but the required mujoco_py module can not be imported.\n"
"Try adding\n"
"export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/home/$USER/.mujoco/mujoco200/bin\n"
"export LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libGLEW.so\n"
"to your shell's rc-file.\n"
"The current values of the environment variables are:\n"
f"LD_LIBRARY_PATH={ld_library_path}\n"
f"LD_PRELOAD={ld_preload}"
"If you are using PyCharm or CLion, also add the environment variables above to your run configurations. "
"Note that the IDE will not resolve $USER for some reason, so enter the user name directly, "
"or run it from your terminal.\n\n"
"Here comes the mujoco-py error message:\n\n",
"r",
)
pyrado.mujoco_loaded = False
else:
pyrado.mujoco_loaded = True
pyrado.mujoco_loaded = True
54 changes: 17 additions & 37 deletions Pyrado/pyrado/environments/mujoco/base.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,10 @@
from math import floor
from typing import Optional

import mujoco_py
import mujoco
import mujoco.viewer
import numpy as np
from init_args_serializer import Serializable
from mujoco_py.generated.const import RND_FOG

import pyrado
from pyrado.environments.sim_base import SimEnv
Expand Down Expand Up @@ -87,7 +87,7 @@ def __init__(
xml_model_temp = file_raw.read()
xml_model_temp = self._adapt_model_file(xml_model_temp, self.domain_param)
# Create a dummy model to extract the solver's time step size
model_tmp = mujoco_py.load_model_from_xml(xml_model_temp)
model_tmp = mujoco.MjModel.from_xml_path(xml_model_temp)
frame_skip = dt / model_tmp.opt.timestep
if frame_skip.is_integer():
self.frame_skip = int(frame_skip)
Expand All @@ -112,8 +112,8 @@ def __init__(
super().__init__(dt=self.model.opt.timestep * self.frame_skip, max_steps=max_steps)

# Memorize the initial states of the model from the xml (for fixed init space or later reset)
self.init_qpos = self.sim.data.qpos.copy()
self.init_qvel = self.sim.data.qvel.copy()
self.init_qpos = self.data.qpos.copy()
self.init_qvel = self.data.qvel.copy()

# Initialize space (to be overwritten in constructor of subclasses)
self._init_space = None
Expand Down Expand Up @@ -177,13 +177,7 @@ def domain_param(self, domain_param: dict):
# Update MuJoCo model
self._create_mujoco_model()

if self.viewer is not None:
# If the viewer already exists and we reset the domain parameters, we must also recreate the viewer since
# it references to the simulation object which get's reconstructed during _create_mujoco_model()
import glfw

glfw.destroy_window(self.viewer.window)
self.viewer = None
self.viewer = None

# Update task
self._task = self._create_task(self.task_args)
Expand All @@ -202,7 +196,7 @@ def _adapt_model_file(self, xml_model: str, domain_param: dict) -> str:
:return: adapted model file where the placeholders are filled with numerical values
"""
# The mesh dir is not resolved when later passed as a string, thus we do it manually
xml_model = xml_model.replace(f"[ASSETS_DIR]", pyrado.MUJOCO_ASSETS_DIR)
xml_model = xml_model.replace("[ASSETS_DIR]", pyrado.MUJOCO_ASSETS_DIR)

# Replace all occurrences of the domain parameter placeholder with its value
for key, value in domain_param.items():
Expand Down Expand Up @@ -230,14 +224,14 @@ def _create_mujoco_model(self):
xml_model = self._adapt_model_file(xml_model, self.domain_param)

# Create MuJoCo model from parsed XML file
self.model = mujoco_py.load_model_from_xml(xml_model)
self.sim = mujoco_py.MjSim(self.model, nsubsteps=self.frame_skip)
self.model = mujoco.MjModel.from_xml_string(xml_model)
self.data = mujoco.MjData(self.model)

def configure_viewer(self):
"""Configure the camera when the viewer is initialized. You need to set `self.camera_config` before."""
# Render a fog around the scene by default
if self.camera_config.pop("render_fog", True):
self.viewer.scn.flags[RND_FOG] = 1
self.viewer.scn.flags[mujoco.mjtRndFlag.mjRND_FOG] = 1

# Parse all other options
for key, value in self.camera_config.items():
Expand Down Expand Up @@ -274,25 +268,18 @@ def reset(self, init_state: np.ndarray = None, domain_param: dict = None) -> np.
self._task.reset(env_spec=self.spec, init_state=init_state.copy())

# Reset MuJoCo simulation model (only reset the joint configuration)
self.sim.reset()
old_state = self.sim.get_state()
mujoco.mj_resetData(self.model, self.data)
old_state = self.data
nq = self.model.nq
nv = self.model.nv
if not init_state[:nq].shape == old_state.qpos.shape: # check joint positions dimension
raise pyrado.ShapeErr(given=init_state[:nq], expected_match=old_state.qpos)
# Exclude everything that is appended to the state (at the end), e.g. the ball position for WAMBallInCupSim
if not init_state[nq : nq + nv].shape == old_state.qvel.shape: # check joint velocities dimension
raise pyrado.ShapeErr(given=init_state[nq : nq + nv], expected_match=old_state.qvel)
new_state = mujoco_py.MjSimState(
# Exclude everything that is appended to the state (at the end), e.g. the ball position for WAMBallInCupSim
old_state.time,
init_state[:nq],
init_state[nq : nq + nv],
old_state.act,
old_state.udd_state,
)
self.sim.set_state(new_state)
self.sim.forward()
self.data.qpos[:] = np.copy(init_state[:nq])
self.data.qvel[:] = np.copy(init_state[nq : nq + nv])
mujoco.mj_forward(self.model, self.data)

# Return an observation
return self.observe(self.state)
Expand Down Expand Up @@ -342,14 +329,7 @@ def render(self, mode: RenderMode = RenderMode(), render_step: int = 1):
if mode.video:
if self.viewer is None:
# Create viewer if not existent (see 'human' mode of OpenAI Gym's MujocoEnv)
self.viewer = mujoco_py.MjViewer(self.sim)

# Adjust window size and position to custom values
import glfw

glfw.make_context_current(self.viewer.window)
glfw.set_window_size(self.viewer.window, 1280, 720)
glfw.set_window_pos(self.viewer.window, 50, 50)
self.viewer = mujoco.viewer.launch_passive(self.model, self.data)

self.configure_viewer()
self.viewer.render()
self.viewer.sync()
13 changes: 6 additions & 7 deletions Pyrado/pyrado/environments/mujoco/openai_ant.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
import os.path as osp
from typing import Optional

import mujoco
import numpy as np
from init_args_serializer import Serializable

Expand Down Expand Up @@ -98,9 +99,7 @@ def __init__(

@property
def state_space(self) -> Space:
state_shape = np.concatenate(
[self.sim.data.qpos.flat, self.sim.data.qvel.flat, self.sim.data.cfrc_ext.flat]
).shape
state_shape = np.concatenate([self.data.qpos.flat, self.data.qvel.flat, self.data.cfrc_ext.flat]).shape
return BoxSpace(-pyrado.inf, pyrado.inf, shape=state_shape)

@property
Expand Down Expand Up @@ -148,11 +147,11 @@ def contact_forces(self):
return contact_forces

def _mujoco_step(self, act: np.ndarray) -> dict:
self.sim.data.ctrl[:] = act
self.sim.step()
self.data.ctrl[:] = act
mujoco.mj_step(self.model, self.data)

pos = self.sim.data.qpos.flat.copy()
vel = self.sim.data.qvel.flat.copy()
pos = self.data.qpos.flat.copy()
vel = self.data.qvel.flat.copy()
cfrc_ext = self.contact_forces.flat.copy()

self.state = np.concatenate([pos, vel, cfrc_ext])
Expand Down
11 changes: 6 additions & 5 deletions Pyrado/pyrado/environments/mujoco/openai_half_cheetah.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
import os.path as osp
from typing import Optional

import mujoco
import numpy as np
from init_args_serializer import Serializable

Expand Down Expand Up @@ -91,7 +92,7 @@ def __init__(

@property
def state_space(self) -> Space:
state_shape = np.concatenate([self.sim.data.qpos, self.sim.data.qvel]).shape
state_shape = np.concatenate([self.data.qpos, self.data.qvel]).shape
return BoxSpace(-pyrado.inf, pyrado.inf, shape=state_shape)

@property
Expand Down Expand Up @@ -123,11 +124,11 @@ def _create_task(self, task_args: dict) -> Task:
return GoallessTask(self.spec, ForwardVelocityRewFcn(self._dt, idx_fwd=0, **task_args))

def _mujoco_step(self, act: np.ndarray) -> dict:
self.sim.data.ctrl[:] = act
self.sim.step()
self.data.ctrl[:] = act
mujoco.mj_step(self.model, self.data)

pos = self.sim.data.qpos.copy()
vel = self.sim.data.qvel.copy()
pos = self.data.qpos.copy()
vel = self.data.qvel.copy()
self.state = np.concatenate([pos, vel])

return dict()
Expand Down
9 changes: 5 additions & 4 deletions Pyrado/pyrado/environments/mujoco/openai_hopper.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
import os.path as osp
from typing import Optional

import mujoco
import numpy as np
from init_args_serializer import Serializable

Expand Down Expand Up @@ -141,11 +142,11 @@ def _create_task(self, task_args: dict) -> Task:
return GoallessTask(self.spec, rew_fcn)

def _mujoco_step(self, act: np.ndarray) -> dict:
self.sim.data.ctrl[:] = act
self.sim.step()
self.data.ctrl[:] = act
mujoco.mj_step(self.model, self.data)

pos = self.sim.data.qpos.copy()
vel = self.sim.data.qvel.copy()
pos = self.data.qpos.copy()
vel = self.data.qvel.copy()
self.state = np.concatenate([pos, vel])

return dict()
Expand Down
Loading

0 comments on commit 2477928

Please sign in to comment.