Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
59 changes: 59 additions & 0 deletions examples/dave_demo_launch/launch/dave_integrated_world_demo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
<?xml version="1.0"?>
<launch>
<arg name="gui" default="true"/>
<arg name="paused" default="false"/>
<arg name="world_name" default="$(find dave_worlds)/worlds/dave_integrated.world"/>
<arg name="set_timeout" default="false"/>
<arg name="timeout" default="0.0"/>
<arg name="velocity_control" default="true"/>
<arg name="joy_id" default="0"/>

<!-- use Gazebo's empty_world.launch with dave_integrated.world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="false"/>
</include>

<!-- use ned frame north east down -->
<include file="$(find uuv_assistants)/launch/publish_world_ned_frame.launch"/>

<!-- timeout -->
<group if="$(arg set_timeout)">
<include file="$(find uuv_assistants)/launch/set_simulation_timer.launch">
<arg name="timeout" value="$(arg timeout)"/>
</include>
</group>

<!-- rexrov robot with oberon7 arm -->
<include file="$(find rexrov_description)/launch/upload_rexrov_oberon7.launch">
<arg name="namespace" value="rexrov"/>
<arg name="x" value="1007.8"/>
<arg name="y" value="999.8"/>
<arg name="z" value="-93.7"/>
<arg name="yaw" value="3.141592"/>
</include>

<!-- Velocity teleop (UUV stays in position when joystick is not used) -->
<include if="$(arg velocity_control)" file="$(find uuv_control_cascaded_pid)/launch/joy_velocity.launch">
<arg name="uuv_name" value="rexrov" />
<arg name="model_name" value="rexrov" />
<arg name="joy_id" value="$(arg joy_id)"/>
</include>

<!-- joystick control for rexrov and oberon7, no velocity control-->
<include unless="$(arg velocity_control)" file="$(find uuv_control_cascaded_pid)/launch/joy_accel.launch">
<arg name="model_name" value="rexrov"/>
<arg name="joy_id" value="$(arg joy_id)"/>
</include>

<!-- joint control for oberon7 -->
<include file="$(find oberon7_control)/launch/joint_control.launch">
<arg name="uuv_name" value="rexrov"/>
</include>

</launch>
160 changes: 160 additions & 0 deletions models/dave_worlds/worlds/dave_integrated.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,160 @@
<?xml version="1.0" ?>
<!-- Modified for different Gazebo GUI camera angle -->

<sdf version="1.4">
<world name="santorini">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.002</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>500</real_time_update_rate>
</physics>

<!-- Origin placed at the center of the tile -->
<spherical_coordinates>
<latitude_deg>36.408</latitude_deg>
<longitude_deg>25.403</longitude_deg>
</spherical_coordinates>

<!-- Global light source -->
<light type="directional" name="sun1">
<pose>50 0 150 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>false</cast_shadows>
</light>

<!-- Global light source -->
<light type="directional" name="sun_diffuse">
<pose>-50 0 -150 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>false</cast_shadows>
</light>

<!-- Virtual NED frame -->
<include>
<uri>model://ned_frame</uri>
<pose>0 0 0 0 0 0</pose>
</include>

<!-- Santorini -->
<include>
<uri>model://Santorini</uri>
<pose>0 0 0 0 0 0</pose>
</include>

<plugin name="underwater_current_plugin" filename="libdave_ocean_current_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>

<transient_current>
<topic_stratified>stratified_current_velocity</topic_stratified>
<!-- Database tag can accept full path or filename for .csv within the dave_worlds/worlds folder -->
<databasefilePath>transientOceanCurrentDatabase.csv</databasefilePath>
</transient_current>

<!-- transient current database CSV file (North direction value) is used as a depth variation -->
<tidal_oscillation>
<!-- Method 1: databse file https://tidesandcurrents.noaa.gov/noaacurrents/Annual?id=ACT1951_1 -->
<!-- Database tag can accept full path or filename for .csv within the dave_worlds/worlds folder -->
<databasefilePath>ACT1951_1_Annual_2021.csv</databasefilePath>

<!-- Mean direction of the tidal currents -->
<mean_direction>
<ebb>69</ebb>
<flood>255</flood>
</mean_direction>

<!-- Starting time of the simulator in GMT -->
<world_start_time_GMT>
<day>4</day>
<month>3</month>
<year>2021</year>
<hour>15</hour>
<minute>0</minute>
</world_start_time_GMT>
</tidal_oscillation>
</plugin>

<plugin name="sc_interface" filename="libdave_sc_coordinates_interface.so"/>

<!-- Electrical flying lead -->
<include>
<uri>model://plug</uri>
<pose>1005 1000 -94.84 0 -1.5707963267948966 0</pose>
</include>

<model name="platform">
<static>true</static>
<pose>1005 1000 -95 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 0.2</size>
</box>
</geometry>
</collision>

<visual name="visual">
<geometry>
<box>
<size>1 1 0.2</size>
</box>
</geometry>
</visual>
</link>
</model>

<include>
<uri>model://socket_box</uri>
<pose>1000 1000 -99.8 0 0 0</pose>
</include>

<plugin name="vehicle_docked_bay1_exterior" filename="libContainPlugin.so">
<entity>wamv::base_link</entity>
<namespace>vrx/dock_2018/bay_1_external</namespace>
<pose frame="robotx_dock_2018::dock_2018_placard1::placard::link">1000 990 -1.5 0 0 0</pose>
<geometry>
<box>
<size>8 1.5 2</size>
</box>
</geometry>
</plugin>

<gui fullscreen='0'>
<camera name='user_camera'>
<pose frame=''>1012 985 -73 0 0.88 1.8</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>