Gazebo worlds
AUV underwater world¶
This scenario launches the auv_underwater_world.world
and is an empty underwater world that can be used to run vehicles that include fins and the FinPlugin
from uuv_gazebo_plugins
or FinROSPlugin
from uuv_gazebo_ros_plugins
To launch Gazebo with this scenario run
roslaunch uuv_gazebo_worlds auv_underwater_world.launch
The ODE physics engine is setup to enable spawning multiple AUVs as shown in the snippet below.
<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>
This scenario also starts the underwater current to generate 3D current velocity topics as geometry_msgs/Twist
messages and the spherical coordinate transform server to provide services for transformation from ENU or NED to and from spherical coordinates.
Empty underwater world¶
The empty_underwater.world
the underwater current to generate 3D current velocity topics as geometry_msgs/Twist
messages and the spherical coordinate transform server to provide services for transformation from ENU or NED to and from spherical coordinates. It is an empty underwater space using the ocean_box
model.
To launch Gazebo with this scenario run
roslaunch uuv_gazebo_worlds empty_underwater_world.launch
Herkules ship wreck¶
The Herkules ship wreck scenario contains a Gazebo model reconstruction of the M\S Herkules with a blue fog to emulate the visibility undewater.
To launch Gazebo with this scenario run
roslaunch uuv_gazebo_worlds herkules_ship_wreck.launch
Lake¶
Lake with some variations in topography.
To launch Gazebo with this scenario run
roslaunch uuv_gazebo_worlds lake.launch
Coast of Mangalia, Romania¶
This scenario was used for the demonstrations of the second demonstration on the EU-Project SWARMs at Mangalia, Romania.
It contains an approximated model of the seabed around the missions area with the origin set to (43.797763, 28.598597)
.
To start this scenario, run
roslaunch uuv_gazebo_worlds mangalia.launch
Munkholmen, Norway¶
Located close to the location of the third and final demonstration of the EU-Project SWARMs in Trondheim, Norway, the Munkholmen islet is modelled here approximate topography of the seabed and the M\S Herkules ship wreck.
To start this scenario, run
roslaunch uuv_gazebo_worlds munkholmen.launch
Warning
By adding blue fog to this scenario, the fog cannot be limited to only the underwater region. The fog will cover the whole scenario.
Ocean waves world¶
This scenario inclues a sea surface running the ocean
model waves shader
to animate the waves during the simulation.
Warning
The waves are only a visual feature. The wave load will not be applied to surface or underwater vehicles.
To start this scenario, run
roslaunch uuv_gazebo_worlds ocean_waves.launch
Subsea BOP panel¶
The scenario used in the simulated manipulation demonstration for the EU-Project SWARMs in Trondheim, Norway.
It contains moving valves and April tags used for assistance positioning the manipulator end-effector.
To run this scenario, run
roslaunch uuv_gazebo_worlds subsea_bop_panel.launch