2021-11-05 11:04:04 +01:00
|
|
|
from typing import Tuple, Union
|
|
|
|
|
|
|
|
import numpy as np
|
|
|
|
|
2022-06-30 17:33:05 +02:00
|
|
|
from alr_envs.black_box.raw_interface_wrapper import RawInterfaceWrapper
|
2021-11-05 11:04:04 +01:00
|
|
|
|
|
|
|
|
2022-06-30 14:08:54 +02:00
|
|
|
class MPWrapper(RawInterfaceWrapper):
|
2021-11-05 11:04:04 +01:00
|
|
|
|
|
|
|
@property
|
2022-06-30 14:08:54 +02:00
|
|
|
def context_mask(self) -> np.ndarray:
|
2021-11-05 11:04:04 +01:00
|
|
|
return np.hstack([
|
|
|
|
[False] * 7, # cos
|
|
|
|
[False] * 7, # sin
|
2022-06-02 09:05:38 +02:00
|
|
|
[False] * 7, # joint velocities
|
|
|
|
[False] * 3, # cup_goal_diff_final
|
|
|
|
[False] * 3, # cup_goal_diff_top
|
2022-01-28 19:24:34 +01:00
|
|
|
[True] * 2, # xy position of cup
|
2021-11-05 11:04:04 +01:00
|
|
|
[False] # env steps
|
|
|
|
])
|
|
|
|
|
|
|
|
@property
|
|
|
|
def start_pos(self):
|
|
|
|
return self._start_pos
|
|
|
|
|
|
|
|
@property
|
|
|
|
def current_pos(self) -> Union[float, int, np.ndarray, Tuple]:
|
|
|
|
return self.sim.data.qpos[0:7].copy()
|
|
|
|
|
|
|
|
@property
|
|
|
|
def current_vel(self) -> Union[float, int, np.ndarray, Tuple]:
|
|
|
|
return self.sim.data.qvel[0:7].copy()
|
|
|
|
|
|
|
|
@property
|
|
|
|
def goal_pos(self):
|
|
|
|
raise ValueError("Goal position is not available and has to be learnt based on the environment.")
|
|
|
|
|
|
|
|
@property
|
|
|
|
def dt(self) -> Union[float, int]:
|
|
|
|
return self.env.dt
|