Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions models/advanced_plane/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<model name='advanced_plane'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<enable_wind>false</enable_wind>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/omnicopter/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<self_collide>false</self_collide>
<static>false</static>
<link name='base_link'>
<enable_wind>true</enable_wind>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/px4vision/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
<self_collide>false</self_collide>
<static>false</static>
<link name='base_link'>
<enable_wind>true</enable_wind>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/quadtailsitter/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<sdf version='1.10'>
<model name='quadtailsitter'>
<link name='base_link'>
<enable_wind>false</enable_wind>
<pose>0 0 0.4 0 0 0</pose>
<inertial>
<pose>0 0 0.05 0 0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/rc_cessna/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<model name='rc_cessna'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<enable_wind>false</enable_wind>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/standard_vtol/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<model name='standard_vtol'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<enable_wind>false</enable_wind>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why disable these?

<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/tiltrotor/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<model name='tiltrotor'>
<pose>0 0 0.246 0 0 0</pose>
<link name='base_link'>
<enable_wind>true</enable_wind>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
Expand Down
1 change: 1 addition & 0 deletions models/x500_base/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
<self_collide>false</self_collide>
<static>false</static>
<link name="base_link">
<enable_wind>true</enable_wind>
<inertial>
<mass>2.0</mass>
<inertia>
Expand Down
39 changes: 37 additions & 2 deletions worlds/windy.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,6 @@
<izz>1</izz>
</inertia>
</inertial>
<enable_wind>true</enable_wind>
</link>
<pose>0 0 0 0 -0 0</pose>
<self_collide>false</self_collide>
Expand All @@ -83,7 +82,7 @@
</spot>
</light>
<wind>
<linear_velocity>5 2 0</linear_velocity>
<linear_velocity>0 0 0</linear_velocity>
</wind>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
Expand All @@ -92,5 +91,41 @@
<longitude_deg> 8.546163739800146</longitude_deg>
<elevation>0</elevation>
</spherical_coordinates>
<!-- Load the plugin for the wind -->
<plugin
filename="gz-sim-wind-effects-system"
name="gz::sim::systems::WindEffects">
<force_approximation_scaling_factor>1</force_approximation_scaling_factor>
<horizontal>
<magnitude>
<time_for_rise>10</time_for_rise>
<sin>
<amplitude_percent>0.05</amplitude_percent>
<period>60</period>
</sin>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.0002</stddev>
</noise>
</magnitude>
<direction>
<time_for_rise>30</time_for_rise>
<sin>
<amplitude>5</amplitude>
<period>20</period>
</sin>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.03</stddev>
</noise>
</direction>
</horizontal>
<vertical>
<noise type="gaussian">
<mean>0</mean>
<stddev>0.03</stddev>
</noise>
</vertical>
</plugin>
</world>
</sdf>