Skip to content
GitLab
Menu
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
U2IS
aquanaute
Commits
e714f54c
Commit
e714f54c
authored
Jul 07, 2020
by
Ricardo Rico Uribe
Browse files
spawn correct - flotation incorrect
parent
d0abee90
Changes
18
Hide whitespace changes
Inline
Side-by-side
aquanaute_description/launch/description.launch
View file @
e714f54c
<launch>
<arg name="robot_namespace" default="aquanaute"/>
<param name="robot_description" command="cat $(find aquanaute_description)/urdf/aquanaute
.urdf
"/>
<param name="robot_description" command="cat $(find aquanaute_description)/urdf/aquanaute
_description.urdf.xacro
"/>
<!-- send fake joint values -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
...
...
aquanaute_description/urdf/aquanaute
.urdf
→
aquanaute_description/urdf/aquanaute
_description.urdf.xacro
View file @
e714f54c
<?xml version="1.0"?>
<robot
name=
"aquanaute"
>
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
name=
"aquanaute"
>
<material
name=
"blue"
>
<color
rgba=
"0 0 0.8 1"
/>
...
...
@@ -209,7 +209,7 @@
<kd>
100000.0
</kd>
<mu1>
10.0
</mu1>
<mu2>
10.0
</mu2>
<material>
Gazebo/
Grey
</material>
<material>
Gazebo/
Red
</material>
</gazebo>
<gazebo
reference=
"left_hull_link"
>
...
...
@@ -217,7 +217,7 @@
<kd>
100000.0
</kd>
<mu1>
10.0
</mu1>
<mu2>
10.0
</mu2>
<material>
Gazebo/
Grey
</material>
<material>
Gazebo/
Red
</material>
</gazebo>
<gazebo
reference=
"motor_link"
>
...
...
@@ -225,7 +225,7 @@
<kd>
100000.0
</kd>
<mu1>
10.0
</mu1>
<mu2>
10.0
</mu2>
<material>
Gazebo/
Grey
</material>
<material>
Gazebo/
Black
</material>
</gazebo>
<gazebo
reference=
"sensor_frame_link"
>
...
...
@@ -233,35 +233,7 @@
<kd>
100000.0
</kd>
<mu1>
10.0
</mu1>
<mu2>
10.0
</mu2>
<material>
Gazebo/
Grey
</material>
<material>
Gazebo/
White
</material>
</gazebo>
<!--
<joint name="pitch_joint" type="revolute">
<parent link="roll_M1_link"/>
<child link="pitch_M2_link"/>
<origin xyz="0 0 0" rpy="0 -1.5708 0"/>
<limit lower="0" upper="0.44" effort="0.1" velocity="0.005"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="yaw_joint" type="continuous">
<parent link="pitch_M2_link"/>
<child link="yaw_M3_link"/>
<origin xyz="0.01 0 0" rpy="0 1.5708 0"/>
<limit effort="0.1" velocity="0.01"/>
<axis xyz="0 0 1"/>
</joint>
-->
<!-- This is for color and physical properties in Gazebo, color won't work with the material tag in gazebo
only for URDF coloring
<gazebo reference="roll_M1_link">
<kp>1000.0</kp>
<kd>10.0</kd>
<mu1>10.0</mu1>
<mu2>10.0</mu2>
<material>Gazebo/Red</material>
</gazebo>
-->
</robot>
aquanaute_gazebo/CMakeList.txt
deleted
100644 → 0
View file @
d0abee90
cmake_minimum_required(VERSION 2.8.3)
project(aquanaute_gazebo)
find_package(catkin REQUIRED COMPONENTS roslaunch)
catkin_package()
roslaunch_add_file_check(launch)
install(
DIRECTORY launch worlds
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
aquanaute_gazebo/CMakeLists.txt
0 → 100644
View file @
e714f54c
cmake_minimum_required
(
VERSION 2.8.3
)
project
(
aquanaute_gazebo
)
find_package
(
catkin REQUIRED COMPONENTS
aquanaute_description
usv_gazebo_plugins
xacro
)
catkin_package
(
CATKIN_DEPENDS aquanaute_description usv_gazebo_plugins xacro
)
# Generate urdf files from xacro and install
xacro_add_files
(
urdf/aquanaute_gazebo.urdf.xacro
INORDER INSTALL DESTINATION urdf
)
# Install xacro files / macros
install
(
DIRECTORY urdf/
DESTINATION
${
CATKIN_PACKAGE_SHARE_DESTINATION
}
/urdf
)
aquanaute_gazebo/launch/empty_world.launch
deleted
100644 → 0
View file @
d0abee90
<launch>
<arg name="world_name" default="worlds/empty.world"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/> <!-- world_name is wrt GAZEBO_RESOURCE_PATH environment variable -->
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<include file="$(find aquanaute_gazebo)/launch/spawn_aquanaute.launch">
</include>
</launch>
aquanaute_gazebo/launch/lac_world.launch
deleted
100644 → 0
View file @
d0abee90
<launch>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find aquanaute_gazebo)/worlds/lac.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
</launch>
aquanaute_gazebo/launch/spawn_aquanaute.launch
deleted
100644 → 0
View file @
d0abee90
<launch>
<arg name="robot_namespace" default="/"/>
<arg name="x" default="0.0"/>
<arg name="y" default="0.0"/>
<arg name="z" default="0.0"/>
<arg name="yaw" default="0.0"/>
<group ns="$(arg robot_namespace)">
<include file="$(find aquanaute_description)/launch/description.launch" >
<arg name="robot_namespace" value="$(arg robot_namespace)"/>
<!--<arg name="urdf_extras" default="$(arg urdf_extras)"/>-->
</include>
<!-- Spawn robot in gazebo -->
<node name="spawn_husky_model" pkg="gazebo_ros" type="spawn_model"
args="-x $(arg x)
-y $(arg y)
-z $(arg z)
-Y $(arg yaw)
-unpause
-urdf
-param robot_description
-model $(arg robot_namespace)" />
</group>
</launch>
aquanaute_gazebo/package.xml
View file @
e714f54c
<?xml version="1.0"?>
<package>
<package
format=
"2"
>
<name>
aquanaute_gazebo
</name>
<version>
0.4.2
</version>
<description>
Aquanaute Simulator bringup
</description>
<author
email=
"ricardo.rico-uribe@ensta-paris.fr"
>
Ricardo RICO URIBE
</author>
<version>
1.3.0
</version>
<description>
Provides templates and examples for integrating the WAM-V model into gazebo with dynamics, sensors, etc.
</description>
<maintainer
email=
"caguero@osrfoundation.org"
>
Carlos Aguero
</maintainer>
<maintainer
email=
"jriveroo@osrfoundation.org"
>
Jose Luis Rivero
</maintainer>
<license>
Apache 2.0
</license>
<url
type=
"website"
>
http://wiki.ros.org/wamv_gazebo
</url>
<url
type=
"bugtracker"
>
http://github.com/osrf/vrx/issues
</url>
<author
email=
"briansbingham@gmail.com"
>
Brian Bingham
</author>
<author
email=
"caguero@osrfoundation.org"
>
Carlos Aguero
</author>
<buildtool_depend>
catkin
</buildtool_depend>
<build_depend>
roslaunch
</build_depend>
<run_depend>
controller_manager
</run_depend>
<run_depend>
gazebo_plugins
</run_depend>
<run_depend>
gazebo_ros
</run_depend>
<run_depend>
gazebo_ros_control
</run_depend>
<run_depend>
aquanaute_description
</run_depend>
<run_depend>
rostopic
</run_depend>
<export>
</export>
<depend>
gazebo_plugins
</depend>
<depend>
hector_gazebo_plugins
</depend>
<depend>
robot_localization
</depend>
<depend>
usv_gazebo_plugins
</depend>
<depend>
velodyne_gazebo_plugins
</depend>
<depend>
aquanaute_description
</depend>
<depend>
xacro
</depend>
</package>
aquanaute_gazebo/urdf/aquanaute_gazebo.urdf.xacro
0 → 100644
View file @
e714f54c
<?xml version="1.0"?>
<!-- Basic WAM-V with gazebo plugins for dynamics -->
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
name=
"aquanaute"
>
<!-- Include macros for dynamics plugins -->
<xacro:include
filename=
"$(find aquanaute_gazebo)/urdf/macros.xacro"
/>
<!-- Defines the base vehicle -->
<xacro:include
filename=
"$(find aquanaute_description)/urdf/aquanaute_description.urdf.xacro"
/>
<!-- Attach hydrodynamics plugin -->
<xacro:usv_dynamics_gazebo
name=
"aquanaute_dynamics_plugin"
/>
</robot>
aquanaute_gazebo/urdf/aquanaute_gazebo.xacro
0 → 100644
View file @
e714f54c
<?xml version="1.0"?>
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
>
<xacro:macro
name=
"aquanaute_gazebo"
>
<!-- Include macros for dynamics plugins -->
<xacro:include
filename=
"$(find aquanaute_gazebo)/urdf/macros.xacro"
/>
<!-- Defines the base vehicle -->
<xacro:include
filename=
"$(find aquanaute_description)/urdf/aquanaute_description.urdf.xacro"
/>
<!-- Attach hydrodynamics plugin -->
<xacro:usv_dynamics_gazebo
name=
"aquanaute_dynamics_plugin"
/>
</xacro:macro>
</robot>
aquanaute_gazebo/urdf/dynamics/aquanaute_gazebo_dynamics_plugin.xacro
0 → 100644
View file @
e714f54c
<?xml version="1.0"?>
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
>
<xacro:macro
name=
"usv_dynamics_gazebo"
params=
"name"
>
<!--Gazebo Plugin for simulating WAM-V dynamics-->
<gazebo>
<plugin
name=
"usv_dynamics_${name}"
filename=
"libusv_gazebo_dynamics_plugin.so"
>
<bodyName>
base_link
</bodyName>
<!-- Must be same as the ocean model!-->
<waterLevel>
0
</waterLevel>
<waterDensity>
997.8
</waterDensity>
<!-- Added mass -->
<xDotU>
0.0
</xDotU>
<yDotV>
0.0
</yDotV>
<nDotR>
0.0
</nDotR>
<!-- Linear and quadratic drag -->
<xU>
51.3
</xU>
<xUU>
72.4
</xUU>
<yV>
40.0
</yV>
<yVV>
0.0
</yVV>
<zW>
500.0
</zW>
<kP>
50.0
</kP>
<mQ>
50.0
</mQ>
<nR>
400.0
</nR>
<nRR>
0.0
</nRR>
<!-- General dimensions -->
<!--<boatArea>2.2</boatArea>-->
<hullRadius>
0.19
</hullRadius>
<boatWidth>
2
</boatWidth>
<boatLength>
3
</boatLength>
<!-- Length discretization, AKA, "N" -->
<length_n>
10
</length_n>
<!-- Wave model -->
<wave_model>
ocean_waves
</wave_model>
</plugin>
</gazebo>
</xacro:macro>
</robot>
aquanaute_gazebo/urdf/macros.xacro
0 → 100644
View file @
e714f54c
<?xml version="1.0"?>
<!-- Includes all macros in this package so they don't need to be included individualy -->
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
name=
"Aquanaute"
>
<!-- Include dynamics macros -->
<xacro:include
filename=
"$(find aquanaute_gazebo)/urdf/dynamics/aquanaute_gazebo_dynamics_plugin.xacro"
/>
</robot>
aquanaute_gazebo/worlds/empty.world
deleted
100644 → 0
View file @
d0abee90
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file clearpath_playpen.world
\authors Prasenjit Mukherjee <code@clearpathrobotics.com
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<sdf
version=
'1.4'
>
<world
name=
'default'
>
<light
name=
'sun'
type=
'directional'
>
<cast_shadows>
1
</cast_shadows>
<pose>
0 0 10 0 -0 0
</pose>
<diffuse>
0.8 0.8 0.8 1
</diffuse>
<specular>
0.2 0.2 0.2 1
</specular>
<attenuation>
<range>
1000
</range>
<constant>
0.9
</constant>
<linear>
0.01
</linear>
<quadratic>
0.001
</quadratic>
</attenuation>
<direction>
-0.5 0.1 -0.9
</direction>
</light>
<model
name=
'ground_plane'
>
<static>
1
</static>
<link
name=
'link'
>
<collision
name=
'collision'
>
<geometry>
<plane>
<normal>
0 0 1
</normal>
<size>
100 100
</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>
100
</mu>
<mu2>
50
</mu2>
</ode>
</friction>
<bounce/>
<contact>
<ode/>
</contact>
</surface>
<max_contacts>
10
</max_contacts>
</collision>
<visual
name=
'visual'
>
<cast_shadows>
0
</cast_shadows>
<geometry>
<plane>
<normal>
0 0 1
</normal>
<size>
100 100
</size>
</plane>
</geometry>
<material>
<script>
<uri>
file://media/materials/scripts/gazebo.material
</uri>
<name>
Gazebo/Grey
</name>
</script>
</material>
</visual>
<velocity_decay>
<linear>
0
</linear>
<angular>
0
</angular>
</velocity_decay>
<self_collide>
0
</self_collide>
<kinematic>
0
</kinematic>
<gravity>
1
</gravity>
</link>
</model>
<physics
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>
<gravity>
0 0 -9.8
</gravity>
</physics>
<scene>
<ambient>
0.4 0.4 0.4 1
</ambient>
<background>
0.7 0.7 0.7 1
</background>
<shadows>
1
</shadows>
</scene>
<gui
fullscreen=
'0'
>
<camera
name=
'user_camera'
>
<pose>
16.2337 1.23674 17.6497 0 0.923643 -3.08299
</pose>
<view_controller>
orbit
</view_controller>
</camera>
</gui>
</world>
</sdf>
aquanaute_gazebo/worlds/lac.world
deleted
100644 → 0
View file @
d0abee90
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file clearpath_playpen.world
\authors Prasenjit Mukherjee <code@clearpathrobotics.com
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<sdf
version=
'1.4'
>
<world
name=
'default'
>
<light
name=
'sun'
type=
'directional'
>
<cast_shadows>
1
</cast_shadows>
<pose>
0 0 10 0 -0 0
</pose>
<diffuse>
0.8 0.8 0.8 1
</diffuse>
<specular>
0.2 0.2 0.2 1
</specular>
<attenuation>
<range>
1000
</range>
<constant>
0.9
</constant>
<linear>
0.01
</linear>
<quadratic>
0.001
</quadratic>
</attenuation>
<direction>
-0.5 0.1 -0.9
</direction>
</light>
<model
name=
'ground_plane'
>
<static>
1
</static>
<link
name=
'link'
>
<collision
name=
'collision'
>
<geometry>
<plane>
<normal>
0 0 1
</normal>
<size>
100 100
</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>
100
</mu>
<mu2>
50
</mu2>
</ode>
</friction>
<bounce/>
<contact>
<ode/>
</contact>
</surface>
<max_contacts>
10
</max_contacts>
</collision>
<visual
name=
'visual'
>
<cast_shadows>
0
</cast_shadows>
<geometry>
<plane>
<normal>
0 0 1
</normal>
<size>
100 100
</size>
</plane>
</geometry>
<material>
<script>
<uri>
file://media/materials/scripts/gazebo.material
</uri>
<name>
Gazebo/Grey
</name>
</script>
</material>
</visual>
<velocity_decay>
<linear>
0
</linear>
<angular>
0
</angular>
</velocity_decay>
<self_collide>
0
</self_collide>
<kinematic>
0
</kinematic>
<gravity>
1
</gravity>
</link>
</model>
<physics
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>
<gravity>
0 0 -9.8
</gravity>
</physics>
<scene>
<ambient>
0.4 0.4 0.4 1
</ambient>
<background>
0.7 0.7 0.7 1
</background>
<shadows>
1
</shadows>
</scene>
<gui
fullscreen=
'0'
>
<camera
name=
'user_camera'
>
<pose>
16.2337 1.23674 17.6497 0 0.923643 -3.08299
</pose>
<view_controller>
orbit
</view_controller>
</camera>
</gui>
</world>
</sdf>
vrx_gazebo/launch/sandisland.launch
View file @
e714f54c
...
...
@@ -17,7 +17,7 @@
<!-- Initial USV location and attitude-->
<arg
name=
"x"
default=
"0"
/>
<arg
name=
"y"
default=
"0"
/>
<arg
name=
"z"
default=
"
0
"
/>
<arg
name=
"z"
default=
"
2
"
/>
<arg
name=
"P"
default=
"0"
/>
<arg
name=
"R"
default=
"0"
/>
<arg
name=
"Y"
default=
"0"
/>
...
...
@@ -37,9 +37,10 @@
<arg
name=
"extra_gazebo_args"
value=
"$(arg extra_gazebo_args)"
/>
</include>
<!-- Load robot model -->
<!-- Load robot model -->
<arg
name=
"urdf"
default=
"$(find aquanaute_gazebo)/urdf/aquanaute_gazebo.urdf.xacro"
/>
<param
name=
"$(arg namespace)/robot_description"
command=
"
cat
$(find
aquanaute_description)/urdf/aquanaute.
urdf"
/>
command=
"$(find
xacro)/xacro '$(arg
urdf
)'
"
/>
<!-- Spawn model in Gazebo, script depending on non_competition_mode -->
<node
name=
"spawn_model"
pkg=
"gazebo_ros"
type=
"spawn_model"
...
...
vrx_gazebo/worlds/ocean.world.xacro
View file @
e714f54c
...
...
@@ -51,6 +51,5 @@
<!-- World models -->
<xacro:include
filename=
"$(find wave_gazebo)/world_models/ocean_waves/model.xacro"
/>
<xacro:ocean_waves
gain=
"0.6"
/>
</world>
</sdf>
vrx_gazebo/worlds/xacros/usv_wind_plugin.xacro
View file @
e714f54c
...
...
@@ -5,7 +5,7 @@
direction:=270
mean_vel:=0
var_gain:=0
var_time:=
1
var_time:=
0
seed:=''
ros_update_rate:=10
"
>
...
...
wave_gazebo/world_models/ocean_waves/model.xacro
View file @
e714f54c
...
...
@@ -22,83 +22,79 @@
Modified to include wave field model and visual plugins.
-->
<world
xmlns:xacro=
"http://ros.org/wiki/xacro"
>
<xacro:macro
name=
"ocean_waves"
params=
"gain:=0.1 period:=5
direction_x:=1.0 direction_y:=0.0
angle:=0.4"
>
<model
name=
'ocean_waves'
>
<static>
true
</static>
<plugin
name=
"wavefield_plugin"
filename=
"libWavefieldModelPlugin.so"
>
<static>
false
</static>
<update_rate>
30
</update_rate>
<size>
1000 1000
</size>
<cell_count>
50 50
</cell_count>
<wave>
<model>
PMS
</model>
<period>
${period}
</period>
<number>
3
</number>
<scale>
1.5
</scale>
S
<gain>
${gain}
</gain>
<direction>
${direction_x} ${direction_y}
</direction>
<angle>
${angle}
</angle>
<tau>
2.0
</tau>
<amplitude>
0.0
</amplitude>
<!-- No effect for the PMS model -->
<steepness>
0.0
</steepness>
</wave>
</plugin>
<xacro:macro
name=
"ocean_waves"
params=
"gain:=0.0 period:=5 direction_x:=1.0 direction_y:=0.0 angle:=0.4"
>
<model
name=
'ocean_waves'
>
<static>
true
</static>
<plugin
name=
"wavefield_plugin"
filename=
"libWavefieldModelPlugin.so"
>
<static>
false
</static>
<update_rate>
30
</update_rate>
<size>
500 500
</size>
<cell_count>
50 50
</cell_count>
<wave>
<model>
PMS
</model>
<period>
${period}
</period>
<number>
3
</number>
<scale>
1.5
</scale>
<gain>
${gain}
</gain>
<direction>
${direction_x} ${direction_y}
</direction>
<angle>
${angle}
</angle>
<tau>
2.0
</tau>
<amplitude>
0.0
</amplitude>
<!-- No effect for the PMS model -->
<steepness>
0.0
</steepness>
</wave>
</plugin>
<link
name=
"ocean_waves_link"
>
<visual
name=
"ocean_waves_visual"
>
<plugin
name=
"ocean_waves_visual_plugin"
filename=
"libWavefieldVisualPlugin.so"
>
<enableRtt>
true
</enableRtt>
<rttNoise>
0.1
</rttNoise>
<refractOpacity>
0.2
</refractOpacity>
<reflectOpacity>
0.2
</reflectOpacity>
<wave>
<model>
PMS
</model>
<period>
${period}
</period>
<number>
3
</number>
<scale>
1.5
</scale>
<gain>
${gain}
</gain>