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
84 lines
2.4 KiB
Python
84 lines
2.4 KiB
Python
import numpy as np
|
|
|
|
from gym import utils
|
|
from gym.envs.mujoco import mujoco_env
|
|
from gym.spaces import Box
|
|
|
|
|
|
class AntEnv(mujoco_env.MujocoEnv, utils.EzPickle):
|
|
metadata = {
|
|
"render_modes": [
|
|
"human",
|
|
"rgb_array",
|
|
"depth_array",
|
|
"single_rgb_array",
|
|
"single_depth_array",
|
|
],
|
|
"render_fps": 20,
|
|
}
|
|
|
|
def __init__(self, **kwargs):
|
|
observation_space = Box(
|
|
low=-np.inf, high=np.inf, shape=(111,), dtype=np.float64
|
|
)
|
|
mujoco_env.MujocoEnv.__init__(
|
|
self,
|
|
"ant.xml",
|
|
5,
|
|
mujoco_bindings="mujoco_py",
|
|
observation_space=observation_space,
|
|
**kwargs
|
|
)
|
|
utils.EzPickle.__init__(self)
|
|
|
|
def step(self, a):
|
|
xposbefore = self.get_body_com("torso")[0]
|
|
self.do_simulation(a, self.frame_skip)
|
|
xposafter = self.get_body_com("torso")[0]
|
|
|
|
self.renderer.render_step()
|
|
|
|
forward_reward = (xposafter - xposbefore) / self.dt
|
|
ctrl_cost = 0.5 * np.square(a).sum()
|
|
contact_cost = (
|
|
0.5 * 1e-3 * np.sum(np.square(np.clip(self.sim.data.cfrc_ext, -1, 1)))
|
|
)
|
|
survive_reward = 1.0
|
|
reward = forward_reward - ctrl_cost - contact_cost + survive_reward
|
|
state = self.state_vector()
|
|
notdone = np.isfinite(state).all() and state[2] >= 0.2 and state[2] <= 1.0
|
|
done = not notdone
|
|
ob = self._get_obs()
|
|
return (
|
|
ob,
|
|
reward,
|
|
done,
|
|
dict(
|
|
reward_forward=forward_reward,
|
|
reward_ctrl=-ctrl_cost,
|
|
reward_contact=-contact_cost,
|
|
reward_survive=survive_reward,
|
|
),
|
|
)
|
|
|
|
def _get_obs(self):
|
|
return np.concatenate(
|
|
[
|
|
self.sim.data.qpos.flat[2:],
|
|
self.sim.data.qvel.flat,
|
|
np.clip(self.sim.data.cfrc_ext, -1, 1).flat,
|
|
]
|
|
)
|
|
|
|
def reset_model(self):
|
|
qpos = self.init_qpos + self.np_random.uniform(
|
|
size=self.model.nq, low=-0.1, high=0.1
|
|
)
|
|
qvel = self.init_qvel + self.np_random.standard_normal(self.model.nv) * 0.1
|
|
self.set_state(qpos, qvel)
|
|
return self._get_obs()
|
|
|
|
def viewer_setup(self):
|
|
assert self.viewer is not None
|
|
self.viewer.cam.distance = self.model.stat.extent * 0.5
|