mirror of
https://github.com/Farama-Foundation/Gymnasium.git
synced 2025-08-30 01:50:19 +00:00
* Allows a new RNG to be generated with seed=-1 and updated env_checker to fix bug if environment doesn't use np_random in reset
* Revert "fixed `gym.vector.make` where the checker was being applied in the opposite case than was intended to (#2871)"
This reverts commit 519dfd9117
.
* Remove bad pushed commits
* Fixed spelling in core.py
* Pins pytest to the last py 3.6 version
* Allow Box automatic scalar shape
* Add test box and change default from () to (1,)
* update Box shape inference with more strict checking
* Update the box shape and add check on the custom Box shape
* Removed incorrect shape type and assert shape code
* Update the Box and associated tests
* Remove all folders and files from pyright exclude
* Revert issues
* Push RedTachyon code review
* Add Python Platform
* Remove play from pyright check
* Fixed CI issues
* remove mujoco env type hinting
* Fixed pixel observation test
* Added some new type hints
* Fixed CI errors
* Fixed CI errors
* Remove play.py from exlucde pyright
* Fixed pyright issues
74 lines
2.1 KiB
Python
74 lines
2.1 KiB
Python
import numpy as np
|
|
|
|
from gym import utils
|
|
from gym.envs.mujoco import mujoco_env
|
|
from gym.spaces import Box
|
|
|
|
|
|
class HopperEnv(mujoco_env.MujocoEnv, utils.EzPickle):
|
|
metadata = {
|
|
"render_modes": [
|
|
"human",
|
|
"rgb_array",
|
|
"depth_array",
|
|
"single_rgb_array",
|
|
"single_depth_array",
|
|
],
|
|
"render_fps": 125,
|
|
}
|
|
|
|
def __init__(self, **kwargs):
|
|
observation_space = Box(low=-np.inf, high=np.inf, shape=(11,), dtype=np.float64)
|
|
mujoco_env.MujocoEnv.__init__(
|
|
self,
|
|
"hopper.xml",
|
|
4,
|
|
mujoco_bindings="mujoco_py",
|
|
observation_space=observation_space,
|
|
**kwargs
|
|
)
|
|
utils.EzPickle.__init__(self)
|
|
|
|
def step(self, a):
|
|
posbefore = self.sim.data.qpos[0]
|
|
self.do_simulation(a, self.frame_skip)
|
|
posafter, height, ang = self.sim.data.qpos[0:3]
|
|
|
|
self.renderer.render_step()
|
|
|
|
alive_bonus = 1.0
|
|
reward = (posafter - posbefore) / self.dt
|
|
reward += alive_bonus
|
|
reward -= 1e-3 * np.square(a).sum()
|
|
s = self.state_vector()
|
|
done = not (
|
|
np.isfinite(s).all()
|
|
and (np.abs(s[2:]) < 100).all()
|
|
and (height > 0.7)
|
|
and (abs(ang) < 0.2)
|
|
)
|
|
ob = self._get_obs()
|
|
return ob, reward, done, {}
|
|
|
|
def _get_obs(self):
|
|
return np.concatenate(
|
|
[self.sim.data.qpos.flat[1:], np.clip(self.sim.data.qvel.flat, -10, 10)]
|
|
)
|
|
|
|
def reset_model(self):
|
|
qpos = self.init_qpos + self.np_random.uniform(
|
|
low=-0.005, high=0.005, size=self.model.nq
|
|
)
|
|
qvel = self.init_qvel + self.np_random.uniform(
|
|
low=-0.005, high=0.005, size=self.model.nv
|
|
)
|
|
self.set_state(qpos, qvel)
|
|
return self._get_obs()
|
|
|
|
def viewer_setup(self):
|
|
assert self.viewer is not None
|
|
self.viewer.cam.trackbodyid = 2
|
|
self.viewer.cam.distance = self.model.stat.extent * 0.75
|
|
self.viewer.cam.lookat[2] = 1.15
|
|
self.viewer.cam.elevation = -20
|