|
| 1 | +<?xml version="1.0" ?> |
| 2 | +<!-- Copyright (c) 2016 The UUV Simulator Authors. |
| 3 | + All rights reserved. |
| 4 | +
|
| 5 | + Licensed under the Apache License, Version 2.0 (the "License"); |
| 6 | + you may not use this file except in compliance with the License. |
| 7 | + You may obtain a copy of the License at |
| 8 | +
|
| 9 | + http://www.apache.org/licenses/LICENSE-2.0 |
| 10 | +
|
| 11 | + Unless required by applicable law or agreed to in writing, software |
| 12 | + distributed under the License is distributed on an "AS IS" BASIS, |
| 13 | + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 14 | + See the License for the specific language governing permissions and |
| 15 | + limitations under the License. |
| 16 | +--> |
| 17 | +<!-- Modified for different Gazebo GUI camera angle --> |
| 18 | + |
| 19 | +<sdf version="1.4"> |
| 20 | + <world name="oceans_waves"> |
| 21 | + <physics name="default_physics" default="true" type="ode"> |
| 22 | + <max_step_size>0.002</max_step_size> |
| 23 | + <real_time_factor>1</real_time_factor> |
| 24 | + <real_time_update_rate>500</real_time_update_rate> |
| 25 | + </physics> |
| 26 | + <scene> |
| 27 | + <ambient>0.01 0.01 0.01 1.0</ambient> |
| 28 | + <sky> |
| 29 | + <clouds> |
| 30 | + <speed>12</speed> |
| 31 | + </clouds> |
| 32 | + </sky> |
| 33 | + <shadows>1</shadows> |
| 34 | + </scene> |
| 35 | + |
| 36 | + <!-- Origin placed somewhere in the middle of the North Sea --> |
| 37 | + <spherical_coordinates> |
| 38 | + <latitude_deg>56.71897669633431</latitude_deg> |
| 39 | + <longitude_deg>3.515625</longitude_deg> |
| 40 | + </spherical_coordinates> |
| 41 | + |
| 42 | + <!-- Global light source --> |
| 43 | + <light type="directional" name="sun1"> |
| 44 | + <pose>50 0 150 0 0 0</pose> |
| 45 | + <diffuse>1 1 1 1</diffuse> |
| 46 | + <specular>.1 .1 .1 1</specular> |
| 47 | + <direction>0.3 0.3 -1</direction> |
| 48 | + <cast_shadows>false</cast_shadows> |
| 49 | + </light> |
| 50 | + |
| 51 | + <!-- Global light source --> |
| 52 | + <light type="directional" name="sun_diffuse"> |
| 53 | + <pose>-50 0 -150 0 0 0</pose> |
| 54 | + <diffuse>0.6 0.6 0.6 1</diffuse> |
| 55 | + <specular>0 0 0 1</specular> |
| 56 | + <direction>-0.3 -0.3 -1</direction> |
| 57 | + <cast_shadows>false</cast_shadows> |
| 58 | + </light> |
| 59 | + |
| 60 | + <light type="directional" name="sun_diffuse_1"> |
| 61 | + <pose>-100 500 -20 0 0 0</pose> |
| 62 | + <diffuse>0.8 0.8 0.8 1</diffuse> |
| 63 | + <specular>1 1 1 1</specular> |
| 64 | + <direction>-1 -1 0</direction> |
| 65 | + <cast_shadows>false</cast_shadows> |
| 66 | + </light> |
| 67 | + |
| 68 | + <light type="directional" name="sun_diffuse_2"> |
| 69 | + <pose>100 50 20 0 0 0</pose> |
| 70 | + <diffuse>0.6 0.6 0.6 1</diffuse> |
| 71 | + <specular>0 0 0 1</specular> |
| 72 | + <direction>-0.3 -0.3 -1</direction> |
| 73 | + <cast_shadows>false</cast_shadows> |
| 74 | + </light> |
| 75 | + |
| 76 | + <light type="directional" name="sun_diffuse_3"> |
| 77 | + <pose>-150 -130 50 0 0 0</pose> |
| 78 | + <diffuse>0.6 0.6 0.6 1</diffuse> |
| 79 | + <specular>0.2 0.2 0.2 1</specular> |
| 80 | + <direction>0.5 0.5 -1</direction> |
| 81 | + <cast_shadows>false</cast_shadows> |
| 82 | + </light> |
| 83 | + |
| 84 | + <light type="directional" name="sun_diffuse_4"> |
| 85 | + <pose>20 0 -90 0 0 0</pose> |
| 86 | + <diffuse>0.9 0.9 0.9 1</diffuse> |
| 87 | + <specular>0.2 0.2 0.2 1</specular> |
| 88 | + <direction>-1 0 0</direction> |
| 89 | + <cast_shadows>false</cast_shadows> |
| 90 | + </light> |
| 91 | + |
| 92 | + <light type="directional" name="sun_diffuse_5"> |
| 93 | + <pose>10 0 -80 0 0 0</pose> |
| 94 | + <diffuse>0.9 0.9 0.9 1</diffuse> |
| 95 | + <specular>0.2 0.2 0.2 1</specular> |
| 96 | + <direction>-1 0 -1</direction> |
| 97 | + <cast_shadows>false</cast_shadows> |
| 98 | + </light> |
| 99 | + |
| 100 | + <!-- Virtual NED frame --> |
| 101 | + <include> |
| 102 | + <uri>model://ned_frame</uri> |
| 103 | + <pose>0 0 0 0 0 0</pose> |
| 104 | + </include> |
| 105 | + |
| 106 | + <!-- Bounding box with sea surface --> |
| 107 | + <include> |
| 108 | + <uri>model://ocean</uri> |
| 109 | + <pose>0 0 0 0 0 0</pose> |
| 110 | + </include> |
| 111 | + |
| 112 | + <plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so"> |
| 113 | + <namespace>hydrodynamics</namespace> |
| 114 | + <constant_current> |
| 115 | + <topic>current_velocity</topic> |
| 116 | + <velocity> |
| 117 | + <mean>0</mean> |
| 118 | + <min>0</min> |
| 119 | + <max>5</max> |
| 120 | + <mu>0.0</mu> |
| 121 | + <noiseAmp>0.0</noiseAmp> |
| 122 | + </velocity> |
| 123 | + |
| 124 | + <horizontal_angle> |
| 125 | + <mean>0</mean> |
| 126 | + <min>-3.141592653589793238</min> |
| 127 | + <max>3.141592653589793238</max> |
| 128 | + <mu>0.0</mu> |
| 129 | + <noiseAmp>0.0</noiseAmp> |
| 130 | + </horizontal_angle> |
| 131 | + |
| 132 | + <vertical_angle> |
| 133 | + <mean>0</mean> |
| 134 | + <min>-3.141592653589793238</min> |
| 135 | + <max>3.141592653589793238</max> |
| 136 | + <mu>0.0</mu> |
| 137 | + <noiseAmp>0.0</noiseAmp> |
| 138 | + </vertical_angle> |
| 139 | + </constant_current> |
| 140 | + </plugin> |
| 141 | + |
| 142 | + <plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/> |
| 143 | + |
| 144 | + <include> |
| 145 | + <uri>model://socket_box</uri> |
| 146 | + <pose>0 0 -99.8 0 0 0</pose> |
| 147 | + </include> |
| 148 | + |
| 149 | + <!-- <include> |
| 150 | + <uri>model://bop_panel_with_socket</uri> |
| 151 | + <pose>0 0 -99.5 0 0 0</pose> |
| 152 | + </include> --> |
| 153 | + |
| 154 | + <include> |
| 155 | + <uri>model://plug</uri> |
| 156 | + <pose>5 0 -94.5 1.57079632679 0 -1.57079632679</pose> |
| 157 | + <!-- <pose>0.525207 0.978282 -97.2 1.57079632679 0 -1.57079632679</pose> --> |
| 158 | + </include> |
| 159 | + |
| 160 | + <model name="platform"> |
| 161 | + <static>true</static> |
| 162 | + <pose>5 0 -95 0 0 0</pose> |
| 163 | + <link name="link"> |
| 164 | + <collision name="collision"> |
| 165 | + <geometry> |
| 166 | + <box> |
| 167 | + <size>1 1 0.2</size> |
| 168 | + </box> |
| 169 | + </geometry> |
| 170 | + </collision> |
| 171 | + |
| 172 | + <visual name="visual"> |
| 173 | + <geometry> |
| 174 | + <box> |
| 175 | + <size>1 1 0.2</size> |
| 176 | + </box> |
| 177 | + </geometry> |
| 178 | + </visual> |
| 179 | + </link> |
| 180 | + </model> |
| 181 | + |
| 182 | + <plugin name="vehicle_docked_bay1_exterior" filename="libContainPlugin.so"> |
| 183 | + <entity>wamv::base_link</entity> |
| 184 | + <namespace>vrx/dock_2018/bay_1_external</namespace> |
| 185 | + <pose frame="robotx_dock_2018::dock_2018_placard1::placard::link">0 -10 -1.5 0 0 0</pose> |
| 186 | + <geometry> |
| 187 | + <box> |
| 188 | + <size>8 1.5 2</size> |
| 189 | + </box> |
| 190 | + </geometry> |
| 191 | + </plugin> |
| 192 | + |
| 193 | + <plugin name="uuv_mating_plugin" filename="libuuv_mating_plugin.so"> |
| 194 | + <rollAlignmentTolerence>0.3</rollAlignmentTolerence> |
| 195 | + <pitchAlignmentTolerence>0.3</pitchAlignmentTolerence> |
| 196 | + <yawAlignmentTolerence>0.3</yawAlignmentTolerence> |
| 197 | + <zAlignmentTolerence>0.5</zAlignmentTolerence> |
| 198 | + </plugin> |
| 199 | + |
| 200 | + |
| 201 | + <gui fullscreen='0'> |
| 202 | + <camera name='user_camera'> |
| 203 | + <pose frame=''>9.0 -8.0 -87.0 0.0 0.7 2.2</pose> |
| 204 | + <view_controller>orbit</view_controller> |
| 205 | + <projection_type>perspective</projection_type> |
| 206 | + </camera> |
| 207 | + </gui> |
| 208 | + </world> |
| 209 | +</sdf> |
0 commit comments