Skip to content
Permalink
Branch: master
Find file Copy path
Find file Copy path
Fetching contributors…
Cannot retrieve contributors at this time
126 lines (111 sloc) 3.71 KB
<?xml version="1.0" ?>
<!-- Copyright (c) 2016 The UUV Simulator Authors.
All rights reserved.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->
<sdf version="1.4">
<world name="mangalia">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>1.2</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.01 0.01 0.01 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>1</shadows>
</scene>
<!-- Origin of the Mangalia world in GPS coordinates -->
<spherical_coordinates>
<latitude_deg>43.797763</latitude_deg>
<longitude_deg>28.598597</longitude_deg>
</spherical_coordinates>
<!-- Global light source -->
<light type="directional" name="sun1">
<pose>-50 0 -20 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>.1 .1 .1 1</specular>
<direction>0.3 0.3 -1</direction>
<cast_shadows>true</cast_shadows>
</light>
<!-- Global light source -->
<light type="directional" name="sun_diffuse_1">
<pose>0 0 100 0 0 0</pose>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0 0 0 1</specular>
<direction>-0.3 -0.3 -1</direction>
<cast_shadows>true</cast_shadows>
</light>
<light type="directional" name="sun_diffuse_2">
<pose>-2000 50 800 0 0 0</pose>
<diffuse>0.6 0.6 0.6 1</diffuse>
<specular>0 0 0 1</specular>
<direction>-0.3 -0.3 -1</direction>
<cast_shadows>true</cast_shadows>
</light>
<!-- Virtual NED frame -->
<include>
<uri>model://ned_frame</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- Mangalia terrain model -->
<include>
<uri>model://mangalia</uri>
<pose>-572.0074568380 537.7086925743 0 0 0 0</pose>
</include>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose frame=''>34.6042 32.2383 20 0 0.528384 1.41245</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>
You can’t perform that action at this time.