Skip to content

Commit 2d3611e

Browse files
author
henrykotze
committed
Example added for Lighter-than-air envelope
Signed-off-by: henrykotze <henry@flycloudline.com>
1 parent f0a55b0 commit 2d3611e

File tree

3 files changed

+78
-1
lines changed

3 files changed

+78
-1
lines changed
+78
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.6">
3+
<world name="blimp">
4+
5+
<physics name="1ms" type="ode">
6+
<max_step_size>0.001</max_step_size>
7+
<!-- Zero to run as fast as possible -->
8+
<real_time_factor>1</real_time_factor>
9+
</physics>
10+
11+
<gravity>0 0 -9.81</gravity>
12+
13+
<plugin
14+
filename="ignition-gazebo-physics-system"
15+
name="gz::sim::systems::Physics">
16+
</plugin>
17+
<plugin
18+
filename="gz-sim-user-commands-system"
19+
name="gz::sim::systems::UserCommands">
20+
</plugin>
21+
<plugin
22+
filename="gz-sim-scene-broadcaster-system"
23+
name="gz::sim::systems::SceneBroadcaster">
24+
</plugin>
25+
26+
<plugin
27+
filename="gz-sim-buoyancy-system"
28+
name="gz::sim::systems::Buoyancy">
29+
<uniform_fluid_density>1.097</uniform_fluid_density>
30+
</plugin>
31+
32+
<light type="directional" name="sun">
33+
<cast_shadows>true</cast_shadows>
34+
<pose>0 0 10 0 0 0</pose>
35+
<diffuse>1 1 1 1</diffuse>
36+
<specular>0.5 0.5 0.5 1</specular>
37+
<attenuation>
38+
<range>1000</range>
39+
<constant>0.9</constant>
40+
<linear>0.01</linear>
41+
<quadratic>0.001</quadratic>
42+
</attenuation>
43+
<direction>-0.5 0.1 -0.9</direction>
44+
</light>
45+
46+
<model name="ground_plane">
47+
<static>true</static>
48+
<link name="link">
49+
<collision name="collision">
50+
<geometry>
51+
<plane>
52+
<normal>0 0 1</normal>
53+
<size>100 100</size>
54+
</plane>
55+
</geometry>
56+
</collision>
57+
<visual name="visual">
58+
<geometry>
59+
<plane>
60+
<normal>0 0 1</normal>
61+
<size>100 100</size>
62+
</plane>
63+
</geometry>
64+
<material>
65+
<ambient>0.8 0.8 0.8 1</ambient>
66+
<diffuse>0.8 0.8 0.8 1</diffuse>
67+
<specular>0.8 0.8 0.8 1</specular>
68+
</material>
69+
</visual>
70+
</link>
71+
</model>
72+
<include>
73+
<uri>
74+
https://fuel.gazebosim.org/1.0/hkotze/models/airship
75+
</uri>
76+
</include>
77+
</world>
78+
</sdf>

test/worlds/CMakeLists.txt

-1
Original file line numberDiff line numberDiff line change
@@ -6,4 +6,3 @@ configure_file (environmental_data.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/envi
66

77
configure_file (environmental_sensor.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/environmental_sensor.sdf)
88
configure_file (hydrodynamics.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/hydrodynamics.sdf)
9-
configure_file (lighter_than_air_dynamics.sdf.in ${PROJECT_BINARY_DIR}/test/worlds/lighter_than_air_dynamics.sdf)

0 commit comments

Comments
 (0)