Files
Gymnasium/gymnasium/envs/mujoco/humanoid.py

95 lines
2.8 KiB
Python
Raw Normal View History

2016-04-27 08:00:58 -07:00
import numpy as np
2022-09-08 10:10:07 +01:00
from gymnasium import utils
from gymnasium.envs.mujoco import MuJocoPyEnv
from gymnasium.spaces import Box
2016-04-27 08:00:58 -07:00
2021-07-29 02:26:34 +02:00
def mass_center(model, sim):
mass = np.expand_dims(model.body_mass, 1)
xpos = sim.data.xipos
2016-04-27 08:00:58 -07:00
return (np.sum(mass * xpos, 0) / np.sum(mass))[0]
2021-07-29 02:26:34 +02:00
2022-07-06 11:18:03 -04:00
class HumanoidEnv(MuJocoPyEnv, utils.EzPickle):
2022-06-19 21:50:31 +01:00
metadata = {
"render_modes": [
"human",
"rgb_array",
"depth_array",
],
"render_fps": 67,
}
def __init__(self, **kwargs):
observation_space = Box(
low=-np.inf, high=np.inf, shape=(376,), dtype=np.float64
)
2022-07-06 11:18:03 -04:00
MuJocoPyEnv.__init__(
self, "humanoid.xml", 5, observation_space=observation_space, **kwargs
2022-05-24 08:47:51 -04:00
)
utils.EzPickle.__init__(self, **kwargs)
2016-04-27 08:00:58 -07:00
def _get_obs(self):
data = self.sim.data
2021-07-29 02:26:34 +02:00
return np.concatenate(
[
data.qpos.flat[2:],
data.qvel.flat,
data.cinert.flat,
data.cvel.flat,
data.qfrc_actuator.flat,
data.cfrc_ext.flat,
]
)
2016-04-27 08:00:58 -07:00
def step(self, a):
pos_before = mass_center(self.model, self.sim)
2016-04-27 08:00:58 -07:00
self.do_simulation(a, self.frame_skip)
pos_after = mass_center(self.model, self.sim)
Render API (#2671) * add pygame GUI for frozen_lake.py env * add new line at EOF * pre-commit reformat * improve graphics * new images and dynamic window size * darker tile borders and fix ICC profile * pre-commit hook * adjust elf and stool size * Update frozen_lake.py * reformat * fix #2600 * #2600 * add rgb_array support * reformat * test render api change on FrozenLake * add render support for reset on frozenlake * add clock on pygame render * new render api for blackjack * new render api for cliffwalking * new render api for Env class * update reset method, lunar and Env * fix wrapper * fix reset lunar * new render api for box2d envs * new render api for mujoco envs * fix bug * new render api for classic control envs * fix tests * add render_mode None for CartPole * new render api for test fake envs * pre-commit hook * fix FrozenLake * fix FrozenLake * more render_mode to super - frozenlake * remove kwargs from frozen_lake new * pre-commit hook * add deprecated render method * add backwards compatibility * fix test * add _render * move pygame.init() (avoid pygame dependency on init) * fix pygame dependencies * remove collect_render() maintain multi-behaviours .render() * add type hints * fix renderer * don't call .render() with None * improve docstring * add single_rgb_array to all envs * remove None from metadata["render_modes"] * add type hints to test_env_checkers * fix lint * add comments to renderer * add comments to single_depth_array and single_state_pixels * reformat * add deprecation warnings and env.render_mode declaration * fix lint * reformat * fix tests * add docs * fix car racing determinism * remove warning test envs, customizable modes on renderer * remove commments and add todo for env_checker * fix car racing * replace render mode check with assert * update new mujoco * reformat * reformat * change metaclass definition * fix tests * implement mark suggestions (test, docs, sets) * check_render Co-authored-by: J K Terry <jkterry0@gmail.com>
2022-06-08 00:20:56 +02:00
2016-04-27 08:00:58 -07:00
alive_bonus = 5.0
data = self.sim.data
lin_vel_cost = 1.25 * (pos_after - pos_before) / self.dt
quad_ctrl_cost = 0.1 * np.square(data.ctrl).sum()
2021-07-29 02:26:34 +02:00
quad_impact_cost = 0.5e-6 * np.square(data.cfrc_ext).sum()
2016-04-27 08:00:58 -07:00
quad_impact_cost = min(quad_impact_cost, 10)
reward = lin_vel_cost - quad_ctrl_cost - quad_impact_cost + alive_bonus
qpos = self.sim.data.qpos
terminated = bool((qpos[2] < 1.0) or (qpos[2] > 2.0))
if self.render_mode == "human":
self.render()
2021-07-29 02:26:34 +02:00
return (
self._get_obs(),
reward,
terminated,
False,
2021-07-29 02:26:34 +02:00
dict(
reward_linvel=lin_vel_cost,
reward_quadctrl=-quad_ctrl_cost,
reward_alive=alive_bonus,
reward_impact=-quad_impact_cost,
),
)
2016-04-27 08:00:58 -07:00
2016-04-30 22:47:51 -07:00
def reset_model(self):
c = 0.01
self.set_state(
[WIP] add support for seeding environments (#135) * Make environments seedable * Fix monitor bugs - Set monitor_id before setting the infix. This was a bug that would yield incorrect results with multiple monitors. - Remove extra pid from stats recorder filename. This should be purely cosmetic. * Start uploading seeds in episode_batch * Fix _bigint_from_bytes for python3 * Set seed explicitly in random_agent * Pass through seed argument * Also pass through random state to spaces * Pass random state into the observation/action spaces * Make all _seed methods return the list of used seeds * Switch over to np.random where possible * Start hashing seeds, and also seed doom engine * Fixup seeding determinism in many cases * Seed before loading the ROM * Make seeding more Python3 friendly * Make the MuJoCo skipping a bit more forgiving * Remove debugging PDB calls * Make setInt argument into raw bytes * Validate and upload seeds * Skip box2d * Make seeds smaller, and change representation of seeds in upload * Handle long seeds * Fix RandomAgent example to be deterministic * Handle integer types correctly in Python2 and Python3 * Try caching pip * Try adding swap * Add df and free calls * Bump swap * Bump swap size * Try setting overcommit * Try other sysctls * Try fixing overcommit * Try just setting overcommit_memory=1 * Add explanatory comment * Add what's new section to readme * BUG: Mark ElevatorAction-ram-v0 as non-deterministic for now * Document seed * Move nondetermistic check into spec
2016-05-29 09:07:09 -07:00
self.init_qpos + self.np_random.uniform(low=-c, high=c, size=self.model.nq),
2021-07-29 02:26:34 +02:00
self.init_qvel
+ self.np_random.uniform(
low=-c,
high=c,
size=self.model.nv,
),
2016-04-30 22:47:51 -07:00
)
2016-04-27 08:00:58 -07:00
return self._get_obs()
def viewer_setup(self):
assert self.viewer is not None
2016-04-27 08:00:58 -07:00
self.viewer.cam.trackbodyid = 1
self.viewer.cam.distance = self.model.stat.extent * 1.0
self.viewer.cam.lookat[2] = 2.0
2016-04-27 08:00:58 -07:00
self.viewer.cam.elevation = -20