-
Notifications
You must be signed in to change notification settings - Fork 198
wave_params_tutorial
McCarrin, Michael (CIV) edited this page Jul 31, 2023
·
3 revisions
- Parameters for the wavefield are broadcast to the
/vrx/wavefield/parameters
topic by a Publisher plugin attached to the world. - An instance of the wavefield plugin, which reads from this topic, must be attached to all objects affected by the wavefield.
- Open
vrx/vrx_gz/worlds/sydney_regatta.sdf
and edit the values for direction, gain, period and steepness listed in the publisher plugin message:<!-- The wave field --> <plugin filename="libPublisherPlugin.so" name="vrx::PublisherPlugin"> <message type="gz.msgs.Param" topic="/vrx/wavefield/parameters" every="2.0"> params { key: "direction" value { type: DOUBLE double_value: 0.0 } } params { key: "gain" value { type: DOUBLE double_value: 0.3 } } params { key: "period" value { type: DOUBLE double_value: 6.0 } } params { key: "steepness" value { type: DOUBLE double_value: 0.0 } } </message> </plugin>
For example, try changing the gain to 0.8.
Recompile your workspace:
cd <VRX_WS>
colcon build --merge-install
Launch the simulation:
ros2 launch vrx_gz competition.launch.py world:=sydney_regatta
You should observe your WAM-V slowly moving due to the wind and bigger waves impacting the WAM-V.
Back: Adjusting Wind Parameters | Top: VRX Tutorials | Next: Adjusting Fog Parameters |
---|