2022-01-26 16:02:42 -05:00
|
|
|
__credits__ = ["Rushiv Arora"]
|
|
|
|
|
2019-02-25 15:12:06 -08:00
|
|
|
import numpy as np
|
|
|
|
|
2022-03-31 12:50:38 -07:00
|
|
|
from gym import utils
|
2022-07-06 11:18:03 -04:00
|
|
|
from gym.envs.mujoco import MuJocoPyEnv
|
2022-06-30 10:59:59 -04:00
|
|
|
from gym.spaces import Box
|
2019-02-25 15:12:06 -08:00
|
|
|
|
|
|
|
DEFAULT_CAMERA_CONFIG = {}
|
|
|
|
|
|
|
|
|
2022-07-06 11:18:03 -04:00
|
|
|
class SwimmerEnv(MuJocoPyEnv, utils.EzPickle):
|
2022-06-19 21:50:31 +01:00
|
|
|
metadata = {
|
|
|
|
"render_modes": [
|
|
|
|
"human",
|
|
|
|
"rgb_array",
|
|
|
|
"depth_array",
|
|
|
|
"single_rgb_array",
|
|
|
|
"single_depth_array",
|
|
|
|
],
|
|
|
|
"render_fps": 25,
|
|
|
|
}
|
|
|
|
|
2021-07-29 02:26:34 +02:00
|
|
|
def __init__(
|
|
|
|
self,
|
|
|
|
xml_file="swimmer.xml",
|
|
|
|
forward_reward_weight=1.0,
|
|
|
|
ctrl_cost_weight=1e-4,
|
|
|
|
reset_noise_scale=0.1,
|
|
|
|
exclude_current_positions_from_observation=True,
|
2022-06-16 18:29:50 +02:00
|
|
|
**kwargs
|
2021-07-29 02:26:34 +02:00
|
|
|
):
|
2019-02-25 15:12:06 -08:00
|
|
|
utils.EzPickle.__init__(**locals())
|
|
|
|
|
|
|
|
self._forward_reward_weight = forward_reward_weight
|
|
|
|
self._ctrl_cost_weight = ctrl_cost_weight
|
|
|
|
|
|
|
|
self._reset_noise_scale = reset_noise_scale
|
|
|
|
|
2021-07-29 15:39:42 -04:00
|
|
|
self._exclude_current_positions_from_observation = (
|
|
|
|
exclude_current_positions_from_observation
|
|
|
|
)
|
2019-02-25 15:12:06 -08:00
|
|
|
|
2022-06-30 10:59:59 -04:00
|
|
|
if exclude_current_positions_from_observation:
|
|
|
|
observation_space = Box(
|
|
|
|
low=-np.inf, high=np.inf, shape=(8,), dtype=np.float64
|
|
|
|
)
|
|
|
|
else:
|
|
|
|
observation_space = Box(
|
|
|
|
low=-np.inf, high=np.inf, shape=(10,), dtype=np.float64
|
|
|
|
)
|
|
|
|
|
2022-07-06 11:18:03 -04:00
|
|
|
MuJocoPyEnv.__init__(
|
|
|
|
self, xml_file, 4, observation_space=observation_space, **kwargs
|
2022-06-08 00:20:56 +02:00
|
|
|
)
|
2019-02-25 15:12:06 -08:00
|
|
|
|
|
|
|
def control_cost(self, action):
|
|
|
|
control_cost = self._ctrl_cost_weight * np.sum(np.square(action))
|
|
|
|
return control_cost
|
|
|
|
|
|
|
|
def step(self, action):
|
|
|
|
xy_position_before = self.sim.data.qpos[0:2].copy()
|
|
|
|
self.do_simulation(action, self.frame_skip)
|
|
|
|
xy_position_after = self.sim.data.qpos[0:2].copy()
|
|
|
|
|
2022-06-08 00:20:56 +02:00
|
|
|
self.renderer.render_step()
|
|
|
|
|
2019-02-25 15:12:06 -08:00
|
|
|
xy_velocity = (xy_position_after - xy_position_before) / self.dt
|
|
|
|
x_velocity, y_velocity = xy_velocity
|
|
|
|
|
|
|
|
forward_reward = self._forward_reward_weight * x_velocity
|
|
|
|
ctrl_cost = self.control_cost(action)
|
|
|
|
|
|
|
|
observation = self._get_obs()
|
|
|
|
reward = forward_reward - ctrl_cost
|
|
|
|
done = False
|
|
|
|
info = {
|
2021-07-29 02:26:34 +02:00
|
|
|
"reward_fwd": forward_reward,
|
|
|
|
"reward_ctrl": -ctrl_cost,
|
|
|
|
"x_position": xy_position_after[0],
|
|
|
|
"y_position": xy_position_after[1],
|
|
|
|
"distance_from_origin": np.linalg.norm(xy_position_after, ord=2),
|
|
|
|
"x_velocity": x_velocity,
|
|
|
|
"y_velocity": y_velocity,
|
|
|
|
"forward_reward": forward_reward,
|
2019-02-25 15:12:06 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
return observation, reward, done, info
|
|
|
|
|
|
|
|
def _get_obs(self):
|
|
|
|
position = self.sim.data.qpos.flat.copy()
|
|
|
|
velocity = self.sim.data.qvel.flat.copy()
|
|
|
|
|
|
|
|
if self._exclude_current_positions_from_observation:
|
|
|
|
position = position[2:]
|
|
|
|
|
|
|
|
observation = np.concatenate([position, velocity]).ravel()
|
|
|
|
return observation
|
|
|
|
|
|
|
|
def reset_model(self):
|
|
|
|
noise_low = -self._reset_noise_scale
|
|
|
|
noise_high = self._reset_noise_scale
|
|
|
|
|
2021-07-29 15:39:42 -04:00
|
|
|
qpos = self.init_qpos + self.np_random.uniform(
|
|
|
|
low=noise_low, high=noise_high, size=self.model.nq
|
|
|
|
)
|
|
|
|
qvel = self.init_qvel + self.np_random.uniform(
|
|
|
|
low=noise_low, high=noise_high, size=self.model.nv
|
|
|
|
)
|
2019-02-25 15:12:06 -08:00
|
|
|
|
|
|
|
self.set_state(qpos, qvel)
|
|
|
|
|
|
|
|
observation = self._get_obs()
|
|
|
|
return observation
|
|
|
|
|
|
|
|
def viewer_setup(self):
|
2022-07-04 18:19:25 +01:00
|
|
|
assert self.viewer is not None
|
2019-02-25 15:12:06 -08:00
|
|
|
for key, value in DEFAULT_CAMERA_CONFIG.items():
|
|
|
|
if isinstance(value, np.ndarray):
|
|
|
|
getattr(self.viewer.cam, key)[:] = value
|
|
|
|
else:
|
|
|
|
setattr(self.viewer.cam, key, value)
|