-
-
Notifications
You must be signed in to change notification settings - Fork 134
Expand file tree
/
Copy pathreach.py
More file actions
171 lines (130 loc) · 13.7 KB
/
reach.py
File metadata and controls
171 lines (130 loc) · 13.7 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
import os
from gymnasium.utils.ezpickle import EzPickle
from gymnasium_robotics.envs.fetch import MujocoFetchEnv, MujocoPyFetchEnv
# Ensure we get the path separator correct on windows
MODEL_XML_PATH = os.path.join("fetch", "reach.xml")
class MujocoFetchReachEnv(MujocoFetchEnv, EzPickle):
"""
## Description
This environment was introduced in ["Multi-Goal Reinforcement Learning: Challenging Robotics Environments and Request for Research"](https://arxiv.org/abs/1802.09464).
The task in the environment is for a manipulator to move the end effector to a randomly selected position in the robot's workspace. The robot is a 7-DoF [Fetch Mobile Manipulator](https://fetchrobotics.com/) with a two-fingered parallel gripper.
The robot is controlled by small displacements of the gripper in Cartesian coordinates and the inverse kinematics are computed internally by the MuJoCo framework. The task is also continuing which means that the robot has to maintain the end effector's
position for an indefinite period of time.
The control frequency of the robot is of `f = 25 Hz`. This is achieved by applying the same action in 20 subsequent simulator step (with a time step of `dt = 0.002 s`) before returning the control to the robot.
## Action Space
The action space is a `Box(-1.0, 1.0, (4,), float32)`. An action represents the Cartesian displacement dx, dy, and dz of the end effector. In addition to a last action that controls closing and opening of the gripper. This last action is not required since
there is no object to be manipulated, thus its value won't generate any control output.
| Num | Action | Control Min | Control Max | Name (in corresponding XML file) | Joint | Unit |
| --- | ------------------------------------------------------ | ----------- | ----------- | --------------------------------------------------------------- | ----- | ------------ |
| 0 | Displacement of the end effector in the x direction dx | -1 | 1 | robot0:mocap | hinge | position (m) |
| 1 | Displacement of the end effector in the y direction dy | -1 | 1 | robot0:mocap | hinge | position (m) |
| 2 | Displacement of the end effector in the z direction dz | -1 | 1 | robot0:mocap | hinge | position (m) |
| 3 | - | -1 | 1 | - | - | - |
## Observation Space
The observation is a `goal-aware observation space`. It consists of a dictionary with information about the robot's end effector state and goal. The kinematics observations are derived from Mujoco bodies known as [sites](https://mujoco.readthedocs.io/en/latest/XMLreference.html?highlight=site#body-site)
attached to the body of interest, the end effector. Also to take into account the temporal influence of the step time, velocity values are multiplied by the step time dt=number_of_sub_steps*sub_step_time. The dictionary consists of the following 3 keys:
* `observation`: its value is an `ndarray` of shape `(10,)`. It consists of kinematic information of the end effector. The elements of the array correspond to the following:
| Num | Observation | Min | Max | Site Name (in corresponding XML file) | Joint Name (in corresponding XML file) |Joint Type| Unit |
|-----|---------------------------------------------------------------------------------------------------------------------------------------|--------|--------|---------------------------------------|----------------------------------------|----------|--------------------------|
| 0 | End effector x position in global coordinates | -Inf | Inf | robot0:grip |- |- | position (m) |
| 1 | End effector y position in global coordinates | -Inf | Inf | robot0:grip |- |- | position (m) |
| 2 | End effector z position in global coordinates | -Inf | Inf | robot0:grip |- |- | position (m) |
| 3 | Joint displacement of the right gripper finger | -Inf | Inf |- | robot0:r_gripper_finger_joint | hinge | position (m) |
| 4 | Joint displacement of the left gripper finger | -Inf | Inf |- | robot0:l_gripper_finger_joint | hinge | position (m) |
| 5 | End effector linear velocity x direction | -Inf | Inf | robot0:grip |- |- | velocity (m/s) |
| 6 | End effector linear velocity y direction | -Inf | Inf | robot0:grip |- |- | velocity (m/s) |
| 7 | End effector linear velocity z direction | -Inf | Inf | robot0:grip |- |- | velocity (m/s) |
| 8 | Right gripper finger linear velocity | -Inf | Inf |- | robot0:r_gripper_finger_joint | hinge | velocity (m/s) |
| 9 | Left gripper finger linear velocity | -Inf | Inf |- | robot0:l_gripper_finger_joint | hinge | velocity (m/s) |
* `desired_goal`: this key represents the final goal to be achieved. In this environment it is a 3-dimensional `ndarray`, `(3,)`, that consists of the three cartesian coordinates of the desired final end effector position `[x,y,z]`. The elements of the array are the following:
| Num | Observation | Min | Max | Site Name (in corresponding XML file) |Unit |
|-----|---------------------------------------------------------------------------------------------------------------------------------------|--------|--------|---------------------------------------|--------------|
| 0 | Final goal end effector position in the x coordinate | -Inf | Inf | robot0:grip | position (m) |
| 1 | Final goal end effector position in the y coordinate | -Inf | Inf | robot0:grip | position (m) |
| 2 | Final goal end effector position in the z coordinate | -Inf | Inf | robot0:grip | position (m) |
* `achieved_goal`: this key represents the current state of the end effector, as if it would have achieved a goal. This is useful for goal orientated learning algorithms such as those that use [Hindsight Experience Replay](https://arxiv.org/abs/1707.01495) (HER).
The value is an `ndarray` with shape `(3,)`. The elements of the array are the following:
| Num | Observation | Min | Max | Site Name (in corresponding XML file) |Unit |
|-----|---------------------------------------------------------------------------------------------------------------------------------------|--------|--------|---------------------------------------|--------------|
| 0 | Current end effector position in the x coordinate | -Inf | Inf | robot0:grip | position (m) |
| 1 | Current end effector position in the y coordinate | -Inf | Inf | robot0:grip | position (m) |
| 2 | Current end effector position in the z coordinate | -Inf | Inf | robot0:grip | position (m) |
## Rewards
The reward can be initialized as `sparse` or `dense`:
- *sparse*: the returned reward can have two values: `-1` if the end effector hasn't reached its final target position, and `0` if the end effector is in the final target position (the robot is considered to have reached the goal if the Euclidean distance between
the end effector and the goal is lower than 0.05 m).
- *dense*: the returned reward is the negative Euclidean distance between the achieved goal position and the desired goal.
To initialize this environment with one of the mentioned reward functions the type of reward must be specified in the id string when the environment is initialized. For `sparse` reward the id is the default of the environment, `FetchReach-v2`. However, for `dense`
reward the id must be modified to `FetchReachDense-v2` and initialized as follows:
```python
import gymnasium as gym
import gymnasium_robotics
gym.register_envs(gymnasium_robotics)
env = gym.make('FetchReachDense-v2')
```
## Starting State
When the environment is reset the gripper is placed in the following global cartesian coordinates `(x,y,z) = [1.3419 0.7491 0.555] m`, and its orientation in quaternions is `(w,x,y,z) = [1.0, 0.0, 1.0, 0.0]`. The joint positions are computed by inverse kinematics
internally by MuJoCo. The base of the robot will always be fixed at `(x,y,z) = [0.405, 0.48, 0]` in global coordinates.
The gripper's target position is randomly selected by adding an offset to the initial grippers position `(x,y,z)` sampled from a uniform distribution with a range of `[-0.15, 0.15] m`.
## Episode End
The episode will be `truncated` when the duration reaches a total of `max_episode_steps` which by default is set to 50 timesteps.
The episode is never `terminated` since the task is continuing with infinite horizon.
## Arguments
To increase/decrease the maximum number of timesteps before the episode is `truncated` the `max_episode_steps` argument can be set at initialization. The default value is 50. For example, to increase the total number of timesteps to 100 make the environment as follows:
```python
import gymnasium as gym
import gymnasium_robotics
gym.register_envs(gymnasium_robotics)
env = gym.make('FetchReach-v2', max_episode_steps=100)
```
## Version History
* v2: the environment depends on the newest [mujoco python bindings](https://mujoco.readthedocs.io/en/latest/python.html) maintained by the MuJoCo team in Deepmind.
* v1: the environment depends on `mujoco_py` which is no longer maintained.
"""
def __init__(self, reward_type: str = "sparse", **kwargs):
initial_qpos = {
"robot0:slide0": 0.4049,
"robot0:slide1": 0.48,
"robot0:slide2": 0.0,
}
MujocoFetchEnv.__init__(
self,
model_path=MODEL_XML_PATH,
has_object=False,
block_gripper=True,
n_substeps=20,
gripper_extra_height=0.2,
target_in_the_air=True,
target_offset=0.0,
obj_range=0.15,
target_range=0.15,
distance_threshold=0.05,
initial_qpos=initial_qpos,
reward_type=reward_type,
**kwargs,
)
EzPickle.__init__(self, reward_type=reward_type, **kwargs)
class MujocoPyFetchReachEnv(MujocoPyFetchEnv, EzPickle):
def __init__(self, reward_type: str = "sparse", **kwargs):
initial_qpos = {
"robot0:slide0": 0.4049,
"robot0:slide1": 0.48,
"robot0:slide2": 0.0,
}
MujocoPyFetchEnv.__init__(
self,
model_path=MODEL_XML_PATH,
has_object=False,
block_gripper=True,
n_substeps=20,
gripper_extra_height=0.2,
target_in_the_air=True,
target_offset=0.0,
obj_range=0.15,
target_range=0.15,
distance_threshold=0.05,
initial_qpos=initial_qpos,
reward_type=reward_type,
**kwargs,
)
EzPickle.__init__(self, reward_type=reward_type, **kwargs)