Skip to content

Commit db0941b

Browse files
committed
split world and model
1 parent 73cb2ec commit db0941b

File tree

3 files changed

+46
-36
lines changed

3 files changed

+46
-36
lines changed

models/moving_platform/model.config

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<model>
3+
<sdf version="1.9">model.sdf</sdf>
4+
</model>

models/moving_platform/model.sdf

+39
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<sdf version="1.9">
3+
<model name="flat_platform">
4+
<link name="platform_link">
5+
<visual name="platform_visual">
6+
<geometry>
7+
<box>
8+
<size>5 5 0.1</size>
9+
</box>
10+
</geometry>
11+
<material>
12+
<ambient>0.3 0.3 0.3 1</ambient>
13+
<diffuse>0.3 0.3 0.3 1</diffuse>
14+
<specular>0.1 0.1 0.1 1</specular>
15+
</material>
16+
</visual>
17+
<collision name="platform_collision">
18+
<geometry>
19+
<box>
20+
<size>5 5 0.1</size>
21+
</box>
22+
</geometry>
23+
</collision>
24+
<pose>0 0 2 0 0 0</pose>
25+
<inertial>
26+
<mass>10000</mass>
27+
<inertia>
28+
<ixx>10000</ixx>
29+
<iyy>10000</iyy>
30+
<izz>10000</izz>
31+
</inertia>
32+
</inertial>
33+
<sensor name="navsat_sensor" type="navsat">
34+
<always_on>1</always_on>
35+
<update_rate>30</update_rate>
36+
</sensor>
37+
</link>
38+
</model>
39+
</sdf>

worlds/moving_platform.sdf

+3-36
Original file line numberDiff line numberDiff line change
@@ -64,42 +64,9 @@
6464
<pose>0 0 0 0 -0 0</pose>
6565
<self_collide>false</self_collide>
6666
</model>
67-
<model name="flat_platform">
68-
<link name="platform_link">
69-
<visual name="platform_visual">
70-
<geometry>
71-
<box>
72-
<size>5 5 0.1</size>
73-
</box>
74-
</geometry>
75-
<material>
76-
<ambient>0.3 0.3 0.3 1</ambient>
77-
<diffuse>0.3 0.3 0.3 1</diffuse>
78-
<specular>0.1 0.1 0.1 1</specular>
79-
</material>
80-
</visual>
81-
<collision name="platform_collision">
82-
<geometry>
83-
<box>
84-
<size>5 5 0.1</size>
85-
</box>
86-
</geometry>
87-
</collision>
88-
<pose>0 0 2 0 0 0</pose>
89-
<inertial>
90-
<mass>10000</mass>
91-
<inertia>
92-
<ixx>10000</ixx>
93-
<iyy>10000</iyy>
94-
<izz>10000</izz>
95-
</inertia>
96-
</inertial>
97-
<sensor name="navsat_sensor" type="navsat">
98-
<always_on>1</always_on>
99-
<update_rate>30</update_rate>
100-
</sensor>
101-
</link>
102-
</model>
67+
<include>
68+
<uri>model://moving_platform</uri>
69+
</include>
10370
<light name="sunUTC" type="directional">
10471
<pose>0 0 500 0 -0 0</pose>
10572
<cast_shadows>true</cast_shadows>

0 commit comments

Comments
 (0)