Optimising the sim for a low end system
I mentioned that my system is slow and the first modification I needed to make was to tame the bits that use a lot of processing power.
NOTE1:When running the gazebo gui, the “realtimeness” of the running simulation is shown as a percentage in the lower right corner of the sim display. Ideally this should be 100% but with default settings on my system it is around 15%, which is unworkable.
NOTE2: Even if you have a fast system, I would recommend applying the following modifications, at least to make a calm sea. The waves make a lovely sim, but we need simplicity to start with!
NOTE3: If you have a fast system , you may not need to do this, but I have a hunch that some settings such as PID constants may be heavily dependant on the physics update rate, so it would probably be worth making these mods to start with to follow this tutorial.
Customising the sim
To make changes to most anything in Gazebo involves modifying xml files. To know more about the format see http://sdformat.org/.
First a quick look at the real file structure which is hidden somewhat by the environment variables and gazebo search algorithm.
The 3 important files are as follows:
The catamaran_waves gazebo sim is in ~/ApGzCatSim/SITL_Models/Gazebo/worlds/catamaran_waves.sdf
The catamaran model definition for the catamaran_waves sim is in ~/ApGzCatSim/SITL_Models/Gazebo/models/catamaran/model.sdf
The waves model definition for the sim is in ~/ApGzCatSim/asv_wave_sim/gz-waves-models/world_models/waves/model.sdf
Calming the sea
To calm the sea, the recommendation from Rhys, the asv_wave_sim author, was to modify the waves/model.sdf file. Generally modifying source files willy-nilly is not recommended, however here we don’t really have a choice. So to change the sea conditions to flat water, we will need to make use of git to checkout a new asv_wave_sim branch for the modified versions.
Prior to creating the new branch, we need to check the status of the repo, to see the effects of the library build:
$< cd ~/ApGzCatSim/asv_wave_sim
$< git status
It should throw up some artefacts of the asv_wave_sim build namely the build, install and log directories, which we want git to ignore.
Open the ~/ApGzCatSim/asv_wave_sim/.git/info/exclude file in an editor ( or do it from the command line if you are a whizz kid!)
and add the various build dirs to the exclude file:
~/ApGzCatSim/asv_wave_sim/.git/info/exclude-------------------
#...
build/
install/
log/
#...
-------------------------------------------------
Save and close the file and redo the status check. Git should now indicate the branch is clean, so let us create and checkout the new branch.
$< cd ~/ApGzCatSim/asv_wave_sim
$< git checkout -b flat-water
Now modify the waves/model.sdf file with the new settings:
The required mods are in the “gz::sim::systems::WavesModel” plugin definition.
Change the cell_count value to 4 and the wind_speed value to 0.
NOTE: There are 2 places in the waves/model.sdf file where these values have to be changed, else the mods won’t work!
~/ApGzCatSim/asv_wave_sim/gz-waves-models/world_models/waves/model.sdf---------------
\...
<model name="waves">
\...
<plugin
filename="gz-waves1-waves-model-system"
name="gz::sim::systems::WavesModel">
\...
<wave>
\...
<cell_count>4</cell_count>
<wind_speed>0.0</wind_speed>
\...
</wave>
</plugin>
\...
<link name="base_link">
<visual name="visual">
\...
<plugin
filename="gz-waves1-waves-model-system"
name="gz::sim::systems::WavesModel">
\...
<wave>
\...
<cell_count>4</cell_count>
<wind_speed>0.0</wind_speed>
\...
</wave>
</plugin>
</visual>
</link>
</model>
\...
------------------------------------------------------------------------------
Slowing the Physics update rate
The other modification I needed to make to get acceptable performance on my system was to lower the simulation update rate.
This time the relevant file is in SITL_Models in catamaran_waves.sdf
Again prior to modifying the update rate we should create a new branch.
$< cd ~/ApGzCatSim/SITL_Models
$< git status
The repo should be in a clean state so we can go ahead and create and checkout a new branch
$< git checkout -b physics_update_200Hz
Now find the physics definition in catamaran_waves.sdf and change the physics name to “5ms” and the max_step_size to 0.005, which will change the update rate from 1kHz to 200Hz.
~/ApGzCatSim/SITL_Models/Gazebo/worlds/catamaran_waves.sdf ------------
<sdf version="1.7">
<world name="waves">
<physics name="5ms" type="ignored">
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
</physics>
\...
---------------------
Save and close catamaran_waves.sdf and run the gazebo sim again. With the above modifications my system gave a realtimeness percentage of 90%, so, much better and workable.
OK so, running the sim we have a catamaran sitting on a now calm sea, with no wind, as shown below:

To add some wind we can use Gazebo’s distributed messaging system.
Write another bash script called 4wind.sh:
\4wind.sh--------------------
#!/usr/bin/env bash
gz topic -t /wind -m gz.msgs.Vector3d -p "x:0, y:-4, z:0"
-------------------------------------
Save it in ApGzCatSim and make it executable.
In order to run wind in the sim, Open a fresh terminal, cd to ApGzCatSim, then tab open another terminal from the menu bar, which should now start in ApGzCatsim directory.
TIP: I find it best to put terminal down in the bottom right corner of the display and size it quite small and select “always on top” mode to keep it visible while gazebo is running.
Run ./gz_cat.sh
in one terminal, and once the sim is running, switch to the other terminal and run ./4wind.sh
.
You should now see the cat being blown by the wind, though it will probably end up going backwards, sideways, anyway but forwards.
TIP: You can run the sim in Follow mode. When the sim starts, right click on the catamaran and select follow.

NOTE: There is presumably a way to start in follow mode, but I didn’t find what it is. Unfortunately you have to start the sim, set up follow mode, only then can you adjust it.
I prefer to follow close behind the catamaran. Write another bash script called follow.sh
follow.sh--------------------------------
#!/usr/bin/env bash
gz service -s /gui/follow/offset --reqtype gz.msgs.Vector3d\
--reptype gz.msgs.Boolean --timeout 2000 --req "x: -1, y: 0, z:0.3"
-------------------------------------------------------------
Run follow.sh once you have set up following the cat in the sim.
Hooking up Ardupilot SITL
Modify the ardupilot sitl invocation ap-cat.sh to use the json SITL model, and to set a suitable watery location. The one here is just off the Mumbles in Wales, UK.
~/ApGzCatSim/ap_cat.sh------------------------------------------
#...
python3 ../Tools/autotest/sim_vehicle.py -D -v Rover\
--console --map rover --model JSON\
--custom-location='51.566151,-4.034345,10.0,-135'
#...
-------------------------------------------------
To invoke the setup, start a fresh terminal, cd to ApGzCatSim and open 3 terminals (You can usually tab these off a terminal menu bar to keep them tidy)
In first terminal run Gazebo:
$< ./gz-cat.sh
Once the sim is running , follow previous notes to select follow and run follow.sh in 3rd terminal.
In the second terminal run Ardupilot SITL with MavProxy:
$< ./ap-cat.sh
(The ardupilot sitl may rebuild the software if it thinks it is stale). Anyway ultimately you should end up with the ardupilot mavproxy console and the map.
NOTE1: The 3rd terminal is used to send Gazebo messages, such as the follow and wind messages in the scripts we wrote previously.
NOTE2: All these windows can be unwieldy. I tend to move the map up to top right of the display and select “always on top in the menu bar”, similar for the triple terminal in bottom right.
Wait for the MavProxy console to show that the AHRS is stable, signified by the green AHRS text, and then invoke ‘arm throttle’. Once armed, minimise the console. The main display should then be clear to observe the sim.
In the Ardupilot SITL terminal try moving the rudders. rc 1 1000
is full left, rc 1 2000
is full right. You should see the rudders moving in the sim.
You could try adding some wind too. ./4wind.sh
You can also try moving the mainsheet, using rc 3 . Unfortunately you will probably find that the boat is very hard to get working. It weather cocks into wind and then stops. You can get it moving a little by wiggling the rudders, but it is very hard to get out of irons. You can also try changing the wind direction, which may help you. Anyway it is very hard to sail by the keyboard, so we need to make some serious modifications, but that will have to wait until next time!