Leeps Claude Opus 4.6 (1M context) commited on
Commit
376295f
·
1 Parent(s): 9c05e86

Simplify drone env: remove trees, static camera, close target

Browse files

- Remove all 25 tree bodies from XML
- Static overhead camera (mode=fixed, height 15, fovy 70)
- Target placed 2-4m from spawn instead of 5-10m
- Remove obstacle_distances from observations
- Reward: +0.1 if drone moves closer, 0.0 otherwise
- Default render 512x512
- Collision check: ground only (no trees)

Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>

server/drone_forest.xml CHANGED
@@ -16,8 +16,6 @@
16
  <material name="drone_body_mat" rgba="0.2 0.2 0.2 1"/>
17
  <material name="drone_arm_mat" rgba="0.4 0.4 0.4 1"/>
18
  <material name="rotor_mat" rgba="0.1 0.1 0.8 1"/>
19
- <material name="trunk_mat" rgba="0.45 0.3 0.15 1"/>
20
- <material name="canopy_mat" rgba="0.1 0.5 0.1 0.8"/>
21
  <material name="target_mat" rgba="1.0 0.0 0.0 0.6"/>
22
  </asset>
23
 
@@ -65,166 +63,14 @@
65
  </body>
66
 
67
  <!-- Target (visual only) -->
68
- <body name="target" pos="5 5 1.5">
69
  <geom name="target_geom" type="sphere" size="0.3" material="target_mat"
70
  contype="0" conaffinity="0"/>
71
  </body>
72
 
73
- <!-- 25 tree bodies - positions set at runtime via Python -->
74
- <body name="tree_0" pos="3 2 0">
75
- <geom name="trunk_0" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
76
- material="trunk_mat" contype="1" conaffinity="1"/>
77
- <geom name="canopy_0" type="sphere" size="0.6" pos="0 0 3.2"
78
- material="canopy_mat" contype="0" conaffinity="0"/>
79
- </body>
80
- <body name="tree_1" pos="5 -3 0">
81
- <geom name="trunk_1" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
82
- material="trunk_mat" contype="1" conaffinity="1"/>
83
- <geom name="canopy_1" type="sphere" size="0.6" pos="0 0 3.2"
84
- material="canopy_mat" contype="0" conaffinity="0"/>
85
- </body>
86
- <body name="tree_2" pos="-4 4 0">
87
- <geom name="trunk_2" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
88
- material="trunk_mat" contype="1" conaffinity="1"/>
89
- <geom name="canopy_2" type="sphere" size="0.6" pos="0 0 3.2"
90
- material="canopy_mat" contype="0" conaffinity="0"/>
91
- </body>
92
- <body name="tree_3" pos="7 1 0">
93
- <geom name="trunk_3" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
94
- material="trunk_mat" contype="1" conaffinity="1"/>
95
- <geom name="canopy_3" type="sphere" size="0.6" pos="0 0 3.2"
96
- material="canopy_mat" contype="0" conaffinity="0"/>
97
- </body>
98
- <body name="tree_4" pos="-2 -5 0">
99
- <geom name="trunk_4" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
100
- material="trunk_mat" contype="1" conaffinity="1"/>
101
- <geom name="canopy_4" type="sphere" size="0.6" pos="0 0 3.2"
102
- material="canopy_mat" contype="0" conaffinity="0"/>
103
- </body>
104
- <body name="tree_5" pos="1 6 0">
105
- <geom name="trunk_5" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
106
- material="trunk_mat" contype="1" conaffinity="1"/>
107
- <geom name="canopy_5" type="sphere" size="0.6" pos="0 0 3.2"
108
- material="canopy_mat" contype="0" conaffinity="0"/>
109
- </body>
110
- <body name="tree_6" pos="-6 -1 0">
111
- <geom name="trunk_6" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
112
- material="trunk_mat" contype="1" conaffinity="1"/>
113
- <geom name="canopy_6" type="sphere" size="0.6" pos="0 0 3.2"
114
- material="canopy_mat" contype="0" conaffinity="0"/>
115
- </body>
116
- <body name="tree_7" pos="4 -6 0">
117
- <geom name="trunk_7" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
118
- material="trunk_mat" contype="1" conaffinity="1"/>
119
- <geom name="canopy_7" type="sphere" size="0.6" pos="0 0 3.2"
120
- material="canopy_mat" contype="0" conaffinity="0"/>
121
- </body>
122
- <body name="tree_8" pos="-3 3 0">
123
- <geom name="trunk_8" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
124
- material="trunk_mat" contype="1" conaffinity="1"/>
125
- <geom name="canopy_8" type="sphere" size="0.6" pos="0 0 3.2"
126
- material="canopy_mat" contype="0" conaffinity="0"/>
127
- </body>
128
- <body name="tree_9" pos="6 4 0">
129
- <geom name="trunk_9" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
130
- material="trunk_mat" contype="1" conaffinity="1"/>
131
- <geom name="canopy_9" type="sphere" size="0.6" pos="0 0 3.2"
132
- material="canopy_mat" contype="0" conaffinity="0"/>
133
- </body>
134
- <body name="tree_10" pos="-5 -4 0">
135
- <geom name="trunk_10" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
136
- material="trunk_mat" contype="1" conaffinity="1"/>
137
- <geom name="canopy_10" type="sphere" size="0.6" pos="0 0 3.2"
138
- material="canopy_mat" contype="0" conaffinity="0"/>
139
- </body>
140
- <body name="tree_11" pos="2 -2 0">
141
- <geom name="trunk_11" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
142
- material="trunk_mat" contype="1" conaffinity="1"/>
143
- <geom name="canopy_11" type="sphere" size="0.6" pos="0 0 3.2"
144
- material="canopy_mat" contype="0" conaffinity="0"/>
145
- </body>
146
- <body name="tree_12" pos="-1 7 0">
147
- <geom name="trunk_12" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
148
- material="trunk_mat" contype="1" conaffinity="1"/>
149
- <geom name="canopy_12" type="sphere" size="0.6" pos="0 0 3.2"
150
- material="canopy_mat" contype="0" conaffinity="0"/>
151
- </body>
152
- <body name="tree_13" pos="8 -2 0">
153
- <geom name="trunk_13" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
154
- material="trunk_mat" contype="1" conaffinity="1"/>
155
- <geom name="canopy_13" type="sphere" size="0.6" pos="0 0 3.2"
156
- material="canopy_mat" contype="0" conaffinity="0"/>
157
- </body>
158
- <body name="tree_14" pos="-7 5 0">
159
- <geom name="trunk_14" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
160
- material="trunk_mat" contype="1" conaffinity="1"/>
161
- <geom name="canopy_14" type="sphere" size="0.6" pos="0 0 3.2"
162
- material="canopy_mat" contype="0" conaffinity="0"/>
163
- </body>
164
- <body name="tree_15" pos="3 7 0">
165
- <geom name="trunk_15" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
166
- material="trunk_mat" contype="1" conaffinity="1"/>
167
- <geom name="canopy_15" type="sphere" size="0.6" pos="0 0 3.2"
168
- material="canopy_mat" contype="0" conaffinity="0"/>
169
- </body>
170
- <body name="tree_16" pos="-4 -7 0">
171
- <geom name="trunk_16" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
172
- material="trunk_mat" contype="1" conaffinity="1"/>
173
- <geom name="canopy_16" type="sphere" size="0.6" pos="0 0 3.2"
174
- material="canopy_mat" contype="0" conaffinity="0"/>
175
- </body>
176
- <body name="tree_17" pos="7 -5 0">
177
- <geom name="trunk_17" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
178
- material="trunk_mat" contype="1" conaffinity="1"/>
179
- <geom name="canopy_17" type="sphere" size="0.6" pos="0 0 3.2"
180
- material="canopy_mat" contype="0" conaffinity="0"/>
181
- </body>
182
- <body name="tree_18" pos="-8 0 0">
183
- <geom name="trunk_18" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
184
- material="trunk_mat" contype="1" conaffinity="1"/>
185
- <geom name="canopy_18" type="sphere" size="0.6" pos="0 0 3.2"
186
- material="canopy_mat" contype="0" conaffinity="0"/>
187
- </body>
188
- <body name="tree_19" pos="0 -8 0">
189
- <geom name="trunk_19" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
190
- material="trunk_mat" contype="1" conaffinity="1"/>
191
- <geom name="canopy_19" type="sphere" size="0.6" pos="0 0 3.2"
192
- material="canopy_mat" contype="0" conaffinity="0"/>
193
- </body>
194
- <body name="tree_20" pos="5 8 0">
195
- <geom name="trunk_20" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
196
- material="trunk_mat" contype="1" conaffinity="1"/>
197
- <geom name="canopy_20" type="sphere" size="0.6" pos="0 0 3.2"
198
- material="canopy_mat" contype="0" conaffinity="0"/>
199
- </body>
200
- <body name="tree_21" pos="-6 6 0">
201
- <geom name="trunk_21" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
202
- material="trunk_mat" contype="1" conaffinity="1"/>
203
- <geom name="canopy_21" type="sphere" size="0.6" pos="0 0 3.2"
204
- material="canopy_mat" contype="0" conaffinity="0"/>
205
- </body>
206
- <body name="tree_22" pos="8 3 0">
207
- <geom name="trunk_22" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
208
- material="trunk_mat" contype="1" conaffinity="1"/>
209
- <geom name="canopy_22" type="sphere" size="0.6" pos="0 0 3.2"
210
- material="canopy_mat" contype="0" conaffinity="0"/>
211
- </body>
212
- <body name="tree_23" pos="-2 8 0">
213
- <geom name="trunk_23" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
214
- material="trunk_mat" contype="1" conaffinity="1"/>
215
- <geom name="canopy_23" type="sphere" size="0.6" pos="0 0 3.2"
216
- material="canopy_mat" contype="0" conaffinity="0"/>
217
- </body>
218
- <body name="tree_24" pos="1 -4 0">
219
- <geom name="trunk_24" type="cylinder" size="0.15 1.5" pos="0 0 1.5"
220
- material="trunk_mat" contype="1" conaffinity="1"/>
221
- <geom name="canopy_24" type="sphere" size="0.6" pos="0 0 3.2"
222
- material="canopy_mat" contype="0" conaffinity="0"/>
223
- </body>
224
-
225
- <!-- Overhead tracking camera -->
226
- <camera name="tracking" pos="0 0 25" xyaxes="1 0 0 0 1 0" mode="trackcom"
227
- fovy="60"/>
228
  </worldbody>
229
 
230
  <!-- Site-based thrust actuators: force applied in site-local z (tilts with drone) -->
 
16
  <material name="drone_body_mat" rgba="0.2 0.2 0.2 1"/>
17
  <material name="drone_arm_mat" rgba="0.4 0.4 0.4 1"/>
18
  <material name="rotor_mat" rgba="0.1 0.1 0.8 1"/>
 
 
19
  <material name="target_mat" rgba="1.0 0.0 0.0 0.6"/>
20
  </asset>
21
 
 
63
  </body>
64
 
65
  <!-- Target (visual only) -->
66
+ <body name="target" pos="3 0 1.5">
67
  <geom name="target_geom" type="sphere" size="0.3" material="target_mat"
68
  contype="0" conaffinity="0"/>
69
  </body>
70
 
71
+ <!-- Static overhead camera (does not track drone) -->
72
+ <camera name="tracking" pos="0 0 15" xyaxes="1 0 0 0 1 0" mode="fixed"
73
+ fovy="70"/>
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
74
  </worldbody>
75
 
76
  <!-- Site-based thrust actuators: force applied in site-local z (tilts with drone) -->
server/drone_forest_environment.py CHANGED
@@ -1,7 +1,7 @@
1
  """
2
- Drone Forest Navigation Environment.
3
 
4
- A quadrotor drone navigates through a forest of columns (trees) to reach a target.
5
  The RL policy commands velocity (forward/left/up/turn) while a built-in PD flight
6
  controller handles low-level motor mixing.
7
  """
@@ -52,14 +52,12 @@ except ImportError:
52
  # ---------------------------------------------------------------------------
53
  # Constants
54
  # ---------------------------------------------------------------------------
55
- NUM_TREES = 25
56
  ARENA_HALF = 10.0 # arena is 20x20 m
57
  MAX_ALTITUDE = 8.0
58
  MIN_ALTITUDE = 0.1
59
  TARGET_RADIUS = 0.5 # success if within this distance
60
- TREE_MIN_SPACING = 1.5 # min distance between tree centres
61
- SPAWN_CLEAR_RADIUS = 2.0 # keep trees away from spawn
62
- TARGET_MIN_DIST = 5.0 # target at least this far from spawn
63
  MAX_STEPS = 1000
64
  PHYSICS_DT = 0.002
65
  CONTROL_DT = 0.02 # 50 Hz control
@@ -85,7 +83,7 @@ XML_PATH = str(Path(__file__).parent / "drone_forest.xml")
85
 
86
 
87
  class DroneForestEnvironment(Environment):
88
- """Drone navigates a randomised forest of columns to reach a target."""
89
 
90
  SUPPORTS_CONCURRENT_SESSIONS = True
91
 
@@ -98,15 +96,14 @@ class DroneForestEnvironment(Environment):
98
  self._model = None
99
  self._data = None
100
  self._render_height = render_height or int(
101
- os.environ.get("DMCONTROL_RENDER_HEIGHT", "480")
102
  )
103
  self._render_width = render_width or int(
104
- os.environ.get("DMCONTROL_RENDER_WIDTH", "640")
105
  )
106
  self._include_pixels = False
107
  self._step_count = 0
108
  self._prev_dist = None
109
- self._tree_positions: List[np.ndarray] = []
110
  self._target_pos = np.zeros(3)
111
  self._done = False
112
  self._rng = np.random.RandomState()
@@ -135,14 +132,6 @@ class DroneForestEnvironment(Environment):
135
  self._target_body_id = mujoco.mj_name2id(
136
  self._model, mujoco.mjtObj.mjOBJ_BODY, "target"
137
  )
138
- self._tree_body_ids = [
139
- mujoco.mj_name2id(self._model, mujoco.mjtObj.mjOBJ_BODY, f"tree_{i}")
140
- for i in range(NUM_TREES)
141
- ]
142
- self._trunk_geom_ids = [
143
- mujoco.mj_name2id(self._model, mujoco.mjtObj.mjOBJ_GEOM, f"trunk_{i}")
144
- for i in range(NUM_TREES)
145
- ]
146
  self._drone_body_geom_id = mujoco.mj_name2id(
147
  self._model, mujoco.mjtObj.mjOBJ_GEOM, "drone_body"
148
  )
@@ -164,62 +153,22 @@ class DroneForestEnvironment(Environment):
164
  "orientation": {"shape": [3], "dtype": "float64"},
165
  "angular_velocity": {"shape": [3], "dtype": "float64"},
166
  "target_relative": {"shape": [3], "dtype": "float64"},
167
- "obstacle_distances": {"shape": [8], "dtype": "float64"},
168
  }
169
  self._state.physics_timestep = PHYSICS_DT
170
  self._state.control_timestep = CONTROL_DT
171
 
172
  # ------------------------------------------------------------------
173
- # Forest randomisation
174
  # ------------------------------------------------------------------
175
- def _randomise_forest(self):
176
- """Place trees and target using rejection sampling."""
177
  import mujoco
178
 
179
- positions = []
180
- attempts = 0
181
- while len(positions) < NUM_TREES and attempts < 5000:
182
- x = self._rng.uniform(-ARENA_HALF + 1, ARENA_HALF - 1)
183
- y = self._rng.uniform(-ARENA_HALF + 1, ARENA_HALF - 1)
184
- # Keep clear of spawn
185
- if np.sqrt(x ** 2 + y ** 2) < SPAWN_CLEAR_RADIUS:
186
- attempts += 1
187
- continue
188
- # Min spacing from existing trees
189
- ok = True
190
- for p in positions:
191
- if np.sqrt((x - p[0]) ** 2 + (y - p[1]) ** 2) < TREE_MIN_SPACING:
192
- ok = False
193
- break
194
- if ok:
195
- positions.append(np.array([x, y]))
196
- attempts += 1
197
-
198
- # Pad with far-away positions if we didn't get enough
199
- while len(positions) < NUM_TREES:
200
- positions.append(np.array([100.0, 100.0]))
201
-
202
- self._tree_positions = positions
203
-
204
- # Set tree body positions in the model
205
- for i, pos in enumerate(positions):
206
- body_id = self._tree_body_ids[i]
207
- self._model.body_pos[body_id] = [pos[0], pos[1], 0.0]
208
-
209
- # Place target: at least TARGET_MIN_DIST from origin, away from trees
210
- for _ in range(1000):
211
- angle = self._rng.uniform(0, 2 * np.pi)
212
- dist = self._rng.uniform(TARGET_MIN_DIST, ARENA_HALF - 2)
213
- tx, ty = dist * np.cos(angle), dist * np.sin(angle)
214
- tz = self._rng.uniform(1.0, 3.0)
215
- # Check clearance from trees
216
- clear = True
217
- for p in positions[:NUM_TREES]:
218
- if np.sqrt((tx - p[0]) ** 2 + (ty - p[1]) ** 2) < 1.5:
219
- clear = False
220
- break
221
- if clear:
222
- break
223
 
224
  self._target_pos = np.array([tx, ty, tz])
225
  self._model.body_pos[self._target_body_id] = self._target_pos.copy()
@@ -319,33 +268,19 @@ class DroneForestEnvironment(Environment):
319
 
320
  target_rel = self._target_pos - pos
321
 
322
- # 8 nearest obstacle distances (XY plane, from drone position)
323
- dists = []
324
- for tp in self._tree_positions:
325
- dx = tp[0] - pos[0]
326
- dy = tp[1] - pos[1]
327
- dists.append(np.sqrt(dx ** 2 + dy ** 2))
328
- dists.sort()
329
- obstacle_distances = dists[:8]
330
- # Pad if fewer than 8
331
- while len(obstacle_distances) < 8:
332
- obstacle_distances.append(50.0)
333
-
334
  return {
335
  "position": pos.tolist(),
336
  "velocity": vel.tolist(),
337
  "orientation": [float(roll), float(pitch), float(yaw)],
338
  "angular_velocity": ang_vel.tolist(),
339
  "target_relative": target_rel.tolist(),
340
- "obstacle_distances": obstacle_distances,
341
  }
342
 
343
  # ------------------------------------------------------------------
344
  # Collision detection
345
  # ------------------------------------------------------------------
346
  def _check_collisions(self) -> bool:
347
- """Return True if drone collides with any tree trunk or ground."""
348
- import mujoco
349
  for i in range(self._data.ncon):
350
  contact = self._data.contact[i]
351
  g1, g2 = contact.geom1, contact.geom2
@@ -353,7 +288,7 @@ class DroneForestEnvironment(Environment):
353
  if self._drone_body_geom_id not in pair:
354
  continue
355
  other = (pair - {self._drone_body_geom_id}).pop()
356
- if other == self._ground_geom_id or other in self._trunk_geom_ids:
357
  return True
358
  return False
359
 
@@ -364,14 +299,11 @@ class DroneForestEnvironment(Environment):
364
  dist = np.linalg.norm(self._target_pos - pos)
365
  reward = 0.0
366
 
367
- # Shaping: reward for getting closer
368
- if self._prev_dist is not None:
369
- reward += 1.0 * (self._prev_dist - dist)
370
  self._prev_dist = dist
371
 
372
- # Time pressure
373
- reward -= 0.01
374
-
375
  return float(reward)
376
 
377
  # ------------------------------------------------------------------
@@ -422,8 +354,8 @@ class DroneForestEnvironment(Environment):
422
  # Reset data to defaults
423
  mujoco.mj_resetData(self._model, self._data)
424
 
425
- # Randomise forest layout
426
- self._randomise_forest()
427
 
428
  # Place drone at origin, altitude 1.5
429
  self._data.qpos[:3] = [0.0, 0.0, 1.5]
 
1
  """
2
+ Drone Navigation Environment (simplified — no trees).
3
 
4
+ A quadrotor drone flies to a nearby target in an open arena.
5
  The RL policy commands velocity (forward/left/up/turn) while a built-in PD flight
6
  controller handles low-level motor mixing.
7
  """
 
52
  # ---------------------------------------------------------------------------
53
  # Constants
54
  # ---------------------------------------------------------------------------
 
55
  ARENA_HALF = 10.0 # arena is 20x20 m
56
  MAX_ALTITUDE = 8.0
57
  MIN_ALTITUDE = 0.1
58
  TARGET_RADIUS = 0.5 # success if within this distance
59
+ TARGET_MIN_DIST = 2.0 # target at least this far from spawn
60
+ TARGET_MAX_DIST = 4.0 # target at most this far from spawn
 
61
  MAX_STEPS = 1000
62
  PHYSICS_DT = 0.002
63
  CONTROL_DT = 0.02 # 50 Hz control
 
83
 
84
 
85
  class DroneForestEnvironment(Environment):
86
+ """Drone navigates to a nearby target in an open arena."""
87
 
88
  SUPPORTS_CONCURRENT_SESSIONS = True
89
 
 
96
  self._model = None
97
  self._data = None
98
  self._render_height = render_height or int(
99
+ os.environ.get("DMCONTROL_RENDER_HEIGHT", "512")
100
  )
101
  self._render_width = render_width or int(
102
+ os.environ.get("DMCONTROL_RENDER_WIDTH", "512")
103
  )
104
  self._include_pixels = False
105
  self._step_count = 0
106
  self._prev_dist = None
 
107
  self._target_pos = np.zeros(3)
108
  self._done = False
109
  self._rng = np.random.RandomState()
 
132
  self._target_body_id = mujoco.mj_name2id(
133
  self._model, mujoco.mjtObj.mjOBJ_BODY, "target"
134
  )
 
 
 
 
 
 
 
 
135
  self._drone_body_geom_id = mujoco.mj_name2id(
136
  self._model, mujoco.mjtObj.mjOBJ_GEOM, "drone_body"
137
  )
 
153
  "orientation": {"shape": [3], "dtype": "float64"},
154
  "angular_velocity": {"shape": [3], "dtype": "float64"},
155
  "target_relative": {"shape": [3], "dtype": "float64"},
 
156
  }
157
  self._state.physics_timestep = PHYSICS_DT
158
  self._state.control_timestep = CONTROL_DT
159
 
160
  # ------------------------------------------------------------------
161
+ # Target placement
162
  # ------------------------------------------------------------------
163
+ def _place_target(self):
164
+ """Place target close to spawn (2-4m away)."""
165
  import mujoco
166
 
167
+ angle = self._rng.uniform(0, 2 * np.pi)
168
+ dist = self._rng.uniform(TARGET_MIN_DIST, TARGET_MAX_DIST)
169
+ tx = dist * np.cos(angle)
170
+ ty = dist * np.sin(angle)
171
+ tz = self._rng.uniform(1.0, 2.5)
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
172
 
173
  self._target_pos = np.array([tx, ty, tz])
174
  self._model.body_pos[self._target_body_id] = self._target_pos.copy()
 
268
 
269
  target_rel = self._target_pos - pos
270
 
 
 
 
 
 
 
 
 
 
 
 
 
271
  return {
272
  "position": pos.tolist(),
273
  "velocity": vel.tolist(),
274
  "orientation": [float(roll), float(pitch), float(yaw)],
275
  "angular_velocity": ang_vel.tolist(),
276
  "target_relative": target_rel.tolist(),
 
277
  }
278
 
279
  # ------------------------------------------------------------------
280
  # Collision detection
281
  # ------------------------------------------------------------------
282
  def _check_collisions(self) -> bool:
283
+ """Return True if drone collides with ground."""
 
284
  for i in range(self._data.ncon):
285
  contact = self._data.contact[i]
286
  g1, g2 = contact.geom1, contact.geom2
 
288
  if self._drone_body_geom_id not in pair:
289
  continue
290
  other = (pair - {self._drone_body_geom_id}).pop()
291
+ if other == self._ground_geom_id:
292
  return True
293
  return False
294
 
 
299
  dist = np.linalg.norm(self._target_pos - pos)
300
  reward = 0.0
301
 
302
+ # +0.1 if drone moved closer to target this step, 0.0 otherwise
303
+ if self._prev_dist is not None and dist < self._prev_dist:
304
+ reward = 0.1
305
  self._prev_dist = dist
306
 
 
 
 
307
  return float(reward)
308
 
309
  # ------------------------------------------------------------------
 
354
  # Reset data to defaults
355
  mujoco.mj_resetData(self._model, self._data)
356
 
357
+ # Place target nearby
358
+ self._place_target()
359
 
360
  # Place drone at origin, altitude 1.5
361
  self._data.qpos[:3] = [0.0, 0.0, 1.5]