Skip to content

Commit 9163e73

Browse files
WALLS: remove walls below groundplane (#60)
1 parent 9fb8484 commit 9163e73

File tree

1 file changed

+40
-52
lines changed

1 file changed

+40
-52
lines changed

worlds/walls.sdf

+40-52
Original file line numberDiff line numberDiff line change
@@ -155,18 +155,6 @@
155155
<model name="ground_plane">
156156
<static>true</static>
157157
<link name="link">
158-
<inertial>
159-
<inertia>
160-
<ixx>0.16666</ixx>
161-
<ixy>0</ixy>
162-
<ixz>0</ixz>
163-
<iyy>0.16666</iyy>
164-
<iyz>0</iyz>
165-
<izz>0.16666</izz>
166-
</inertia>
167-
<mass>10</mass>
168-
<pose>0 0 0 0 0 0</pose>
169-
</inertial>
170158
<collision name="collision">
171159
<geometry>
172160
<plane>
@@ -213,21 +201,47 @@
213201
<pose>0 0 0 0 -0 0</pose>
214202
<self_collide>false</self_collide>
215203
</model>
204+
<light name="sunUTC" type="directional">
205+
<pose>0 0 500 0 -0 0</pose>
206+
<cast_shadows>true</cast_shadows>
207+
<intensity>1</intensity>
208+
<direction>0.001 0.625 -0.78</direction>
209+
<diffuse>0.904 0.904 0.904 1</diffuse>
210+
<specular>0.271 0.271 0.271 1</specular>
211+
<attenuation>
212+
<range>2000</range>
213+
<linear>0</linear>
214+
<constant>1</constant>
215+
<quadratic>0</quadratic>
216+
</attenuation>
217+
<spot>
218+
<inner_angle>0</inner_angle>
219+
<outer_angle>0</outer_angle>
220+
<falloff>0</falloff>
221+
</spot>
222+
</light>
223+
<spherical_coordinates>
224+
<surface_model>EARTH_WGS84</surface_model>
225+
<world_frame_orientation>ENU</world_frame_orientation>
226+
<latitude_deg>47.397971057728974</latitude_deg>
227+
<longitude_deg> 8.546163739800146</longitude_deg>
228+
<elevation>0</elevation>
229+
</spherical_coordinates>
216230
<model name="box1">
217-
<pose>5 0 0 0 0 0</pose>
231+
<pose>5 0 7.5 0 0 0</pose>
218232
<static>true</static>
219233
<link name="link1">
220234
<collision name="collision">
221235
<geometry>
222236
<box>
223-
<size>1 20 30</size>
237+
<size>1 20 15</size>
224238
</box>
225239
</geometry>
226240
</collision>
227241
<visual name="visual">
228242
<geometry>
229243
<box>
230-
<size>1 20 30</size>
244+
<size>1 20 15</size>
231245
</box>
232246
</geometry>
233247
<material>
@@ -240,19 +254,19 @@
240254
</model>
241255
<model name="box2">
242256
<static>true</static>
243-
<pose>-3 5 0 0 0 0</pose>
257+
<pose>-3 5 7.5 0 0 0</pose>
244258
<link name="link2">
245259
<collision name="collision">
246260
<geometry>
247261
<box>
248-
<size>10 1 30</size>
262+
<size>10 1 15</size>
249263
</box>
250264
</geometry>
251265
</collision>
252266
<visual name="visual">
253267
<geometry>
254268
<box>
255-
<size>10 1 30</size>
269+
<size>10 1 15</size>
256270
</box>
257271
</geometry>
258272
<material>
@@ -265,19 +279,19 @@
265279
</model>
266280
<model name="box3">
267281
<static>true</static>
268-
<pose>13 -10 0 0 0 0</pose>
269-
<link name="link2">
282+
<pose>13 -10 7.5 0 0 0</pose>
283+
<link name="link3">
270284
<collision name="collision">
271285
<geometry>
272286
<box>
273-
<size>17 1 30</size>
287+
<size>17 1 15</size>
274288
</box>
275289
</geometry>
276290
</collision>
277291
<visual name="visual">
278292
<geometry>
279293
<box>
280-
<size>17 1 30</size>
294+
<size>17 1 15</size>
281295
</box>
282296
</geometry>
283297
<material>
@@ -289,20 +303,20 @@
289303
</link>
290304
</model>
291305
<model name="box4">
292-
<pose>12 0 0 0 0 0</pose>
306+
<pose>12 0 7.5 0 0 0</pose>
293307
<static>true</static>
294-
<link name="link1">
308+
<link name="link4">
295309
<collision name="collision">
296310
<geometry>
297311
<box>
298-
<size>1 20 30</size>
312+
<size>1 20 15</size>
299313
</box>
300314
</geometry>
301315
</collision>
302316
<visual name="visual">
303317
<geometry>
304318
<box>
305-
<size>1 20 30</size>
319+
<size>1 20 15</size>
306320
</box>
307321
</geometry>
308322
<material>
@@ -313,31 +327,5 @@
313327
</visual>
314328
</link>
315329
</model>
316-
<light name="sunUTC" type="directional">
317-
<pose>0 0 500 0 -0 0</pose>
318-
<cast_shadows>true</cast_shadows>
319-
<intensity>1</intensity>
320-
<direction>0.001 0.625 -0.78</direction>
321-
<diffuse>0.904 0.904 0.904 1</diffuse>
322-
<specular>0.271 0.271 0.271 1</specular>
323-
<attenuation>
324-
<range>2000</range>
325-
<linear>0</linear>
326-
<constant>1</constant>
327-
<quadratic>0</quadratic>
328-
</attenuation>
329-
<spot>
330-
<inner_angle>0</inner_angle>
331-
<outer_angle>0</outer_angle>
332-
<falloff>0</falloff>
333-
</spot>
334-
</light>
335-
<spherical_coordinates>
336-
<surface_model>EARTH_WGS84</surface_model>
337-
<world_frame_orientation>ENU</world_frame_orientation>
338-
<latitude_deg>47.397971057728974</latitude_deg>
339-
<longitude_deg> 8.546163739800146</longitude_deg>
340-
<elevation>0</elevation>
341-
</spherical_coordinates>
342330
</world>
343331
</sdf>

0 commit comments

Comments
 (0)