-
Notifications
You must be signed in to change notification settings - Fork 196
wind_params_tutorial
McCarrin, Michael (CIV) edited this page Jul 31, 2023
·
3 revisions
- The wind can be characterized by a direction and mean velocity.
- In the current implementation of VRX, the wind only affects the WAM-V.
- The windage coefficients used for the WAM-V are based on the FAU report(Station-keeping control of an unmanned surface vehicle exposed to current and wind disturbances)[https://doi.org/10.1016/j.oceaneng.2016.09.037].
Open vrx/vrx_gz/worlds/sydney_regatta.sdf
and edit the values given in the wind plugin element:
<!-- Load the plugin for the wind -->
<plugin
filename="libUSVWind.so"
name="vrx::USVWind">
<wind_obj>
<name>wamv</name>
<link_name>wamv/base_link</link_name>
<coeff_vector>.5 .5 .33</coeff_vector>
</wind_obj>
<!-- Wind -->
<wind_direction>240</wind_direction>
<!-- in degrees -->
<wind_mean_velocity>0.0</wind_mean_velocity>
<var_wind_gain_constants>0</var_wind_gain_constants>
<var_wind_time_constants>2</var_wind_time_constants>
<random_seed>10</random_seed>
<!-- set to zero/empty to randomize -->
<update_rate>10</update_rate>
<topic_wind_speed>/vrx/debug/wind/speed</topic_wind_speed>
<topic_wind_direction>/vrx/debug/wind/direction</topic_wind_direction>
</plugin>
For example, try changing wind_mean_velocity
to 5 (m/s) and wind_direction
to 180 (degrees).
Recompile your workspace:
cd <VRX_WS>
GZ_VERSION=garden colcon build --merge-install
Launch the simulation:
ros2 launch vrx_gz competition.launch.py world:=sydney_regatta
In a separate terminal, source the workspace and echo the wind direction topic to confirm the change:
. install/setup.bash
ros2 topic echo /vrx/debug/wind/direction
To see the effect on wind speed, press CTRL+C to terminate the echo command and run:
ros2 topic echo /vrx/debug/wind/speed
You should see a series of wind velocity values varying around a mean of 5 m/s.
Back: Env Params Overview | Top: VRX Tutorials | Next: Adjusting Wave Parameters |
---|