add windy default world (#22273)

* add windy default world

* Rename windy_default.sdf to windy.sdf

* rename windy.sdf world

---------

Co-authored-by: frederik <frederik@auterion.com>
This commit is contained in:
Frederik Markus 2023-11-01 09:35:37 +01:00 committed by GitHub
parent 1089079a32
commit d6dbf38a1b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
1 changed files with 151 additions and 0 deletions

View File

@ -0,0 +1,151 @@
<sdf version='1.9'>
<world name='windy'>
<physics type="ode">
<max_step_size>0.004</max_step_size>
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
<plugin name='gz::sim::systems::AirPressure' filename='gz-sim-air-pressure-system'/>
<plugin name='gz::sim::systems::ApplyLinkWrench' filename='gz-sim-apply-link-wrench-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen='false'>
<plugin name='3D View' filename='GzScene3D'>
<gz-gui>
<title>3D View</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='string' key='state'>docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.5984631152222222 0.5984631152222222 0.5984631152222222</ambient_light>
<background_color>0.8984631152222222 0.8984631152222222 0.8984631152222222</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
<plugin name='World control' filename='WorldControl'>
<gz-gui>
<title>World control</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
<property type='double' key='height'>72</property>
<property type='double' key='width'>121</property>
<property type='double' key='z'>1</property>
<property type='string' key='state'>floating</property>
<anchors target='3D View'>
<line own='left' target='left'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name='World stats' filename='WorldStats'>
<gz-gui>
<title>World stats</title>
<property type='bool' key='showTitleBar'>0</property>
<property type='bool' key='resizable'>0</property>
<property type='double' key='height'>110</property>
<property type='double' key='width'>290</property>
<property type='double' key='z'>1</property>
<property type='string' key='state'>floating</property>
<anchors target='3D View'>
<line own='right' target='right'/>
<line own='bottom' target='bottom'/>
</anchors>
</gz-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>
<iterations>1</iterations>
</plugin>
<plugin name='Entity tree' filename='EntityTree'/>
</gui>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<scene>
<grid>false</grid>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>true</shadows>
</scene>
<model name='ground_plane'>
<static>true</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1 1</size>
</plane>
</geometry>
<surface>
<friction>
<ode/>
</friction>
<bounce/>
<contact/>
</surface>
</collision>
<visual name='visual'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<enable_wind>true</enable_wind>
</link>
<pose>0 0 0 0 -0 0</pose>
<self_collide>false</self_collide>
</model>
<light name='sunUTC' type='directional'>
<pose>0 0 500 0 -0 0</pose>
<cast_shadows>true</cast_shadows>
<intensity>1</intensity>
<direction>0.001 0.625 -0.78</direction>
<diffuse>0.904 0.904 0.904 1</diffuse>
<specular>0.271 0.271 0.271 1</specular>
<attenuation>
<range>2000</range>
<linear>0</linear>
<constant>1</constant>
<quadratic>0</quadratic>
</attenuation>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<wind>
<linear_velocity>10 10 10</linear_velocity>
</wind>
</world>
</sdf>