Files
Gymnasium/gym/envs/mujoco/ant.py

58 lines
1.8 KiB
Python
Raw Normal View History

2016-04-27 08:00:58 -07:00
import numpy as np
2016-04-27 08:00:58 -07:00
from gym import utils
from gym.envs.mujoco import mujoco_env
2021-07-29 02:26:34 +02:00
2016-04-27 08:00:58 -07:00
class AntEnv(mujoco_env.MujocoEnv, utils.EzPickle):
def __init__(self):
2021-07-29 02:26:34 +02:00
mujoco_env.MujocoEnv.__init__(self, "ant.xml", 5)
2016-04-27 08:00:58 -07:00
utils.EzPickle.__init__(self)
def step(self, a):
2016-04-27 08:00:58 -07:00
xposbefore = self.get_body_com("torso")[0]
self.do_simulation(a, self.frame_skip)
xposafter = self.get_body_com("torso")[0]
2021-07-29 02:26:34 +02:00
forward_reward = (xposafter - xposbefore) / self.dt
ctrl_cost = 0.5 * np.square(a).sum()
2021-07-29 15:39:42 -04:00
contact_cost = (
0.5 * 1e-3 * np.sum(np.square(np.clip(self.sim.data.cfrc_ext, -1, 1)))
)
2016-04-27 08:00:58 -07:00
survive_reward = 1.0
reward = forward_reward - ctrl_cost - contact_cost + survive_reward
2016-04-30 22:47:51 -07:00
state = self.state_vector()
2021-07-29 02:26:34 +02:00
notdone = np.isfinite(state).all() and state[2] >= 0.2 and state[2] <= 1.0
2016-04-27 08:00:58 -07:00
done = not notdone
ob = self._get_obs()
2021-07-29 02:26:34 +02:00
return (
ob,
reward,
done,
dict(
reward_forward=forward_reward,
reward_ctrl=-ctrl_cost,
reward_contact=-contact_cost,
reward_survive=survive_reward,
),
)
2016-04-27 08:00:58 -07:00
def _get_obs(self):
2021-07-29 02:26:34 +02:00
return np.concatenate(
[
self.sim.data.qpos.flat[2:],
self.sim.data.qvel.flat,
np.clip(self.sim.data.cfrc_ext, -1, 1).flat,
]
)
2016-04-27 08:00:58 -07:00
2016-04-30 22:47:51 -07:00
def reset_model(self):
2021-07-29 15:39:42 -04:00
qpos = self.init_qpos + self.np_random.uniform(
size=self.model.nq, low=-0.1, high=0.1
)
Seeding update (#2422) * Ditch most of the seeding.py and replace np_random with the numpy default_rng. Let's see if tests pass * Updated a bunch of RNG calls from the RandomState API to Generator API * black; didn't expect that, did ya? * Undo a typo * blaaack * More typo fixes * Fixed setting/getting state in multidiscrete spaces * Fix typo, fix a test to work with the new sampling * Correctly (?) pass the randomly generated seed if np_random is called with None as seed * Convert the Discrete sample to a python int (as opposed to np.int64) * Remove some redundant imports * First version of the compatibility layer for old-style RNG. Mainly to trigger tests. * Removed redundant f-strings * Style fixes, removing unused imports * Try to make tests pass by removing atari from the dockerfile * Try to make tests pass by removing atari from the setup * Try to make tests pass by removing atari from the setup * Try to make tests pass by removing atari from the setup * First attempt at deprecating `env.seed` and supporting `env.reset(seed=seed)` instead. Tests should hopefully pass but throw up a million warnings. * black; didn't expect that, didya? * Rename the reset parameter in VecEnvs back to `seed` * Updated tests to use the new seeding method * Removed a bunch of old `seed` calls. Fixed a bug in AsyncVectorEnv * Stop Discrete envs from doing part of the setup (and using the randomness) in init (as opposed to reset) * Add explicit seed to wrappers reset * Remove an accidental return * Re-add some legacy functions with a warning. * Use deprecation instead of regular warnings for the newly deprecated methods/functions
2021-12-08 22:14:15 +01:00
qvel = self.init_qvel + self.np_random.standard_normal(self.model.nv) * 0.1
2016-04-30 22:47:51 -07:00
self.set_state(qpos, qvel)
2016-04-27 08:00:58 -07:00
return self._get_obs()
def viewer_setup(self):
self.viewer.cam.distance = self.model.stat.extent * 0.5