Skip to content

Commit

Permalink
add baylands
Browse files Browse the repository at this point in the history
Signed-off-by: frederik <[email protected]>
  • Loading branch information
frede791 authored and dagar committed Dec 13, 2023
1 parent 751831b commit c00a635
Showing 1 changed file with 109 additions and 0 deletions.
109 changes: 109 additions & 0 deletions worlds/baylands.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
<sdf version='1.9'>
<world name='baylands'>
<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>
<ambient>0.8 0.5 1</ambient>
<grid>false</grid>
</scene>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 100 0 0.75 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.0 0.0 0.0 1</specular>
<intensity>5</intensity>
<attenuation>
<range>100</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<include>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/baylands
</uri>
<name>park</name>
<pose>205 155 -1 0 0 0</pose>
</include>
<include>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Coast Water
</uri>
<pose>0 0 -2 0 0 0
<relative_to>park</relative_to>
</pose>

</include>
</world>
</sdf>

0 comments on commit c00a635

Please sign in to comment.