Here’s an example of how to configure SITL and Gazebo so they can run on different machines. In this case we’re running:
- Gazebo on a macOS machine with address
192.168.1.31
- SITL on an Ubuntu VM machine with address
192.168.1.170
We’ll use the iris_with_ardupilot
model from the ardupilot_gazebo
repo.
Configure the Gazebo model
Edit the SDF the ardupilot_gazebo plugin in models/iris_with_ardupilot/model.sdf
to read:
<plugin name="ardupilot_plugin" filename="libArduPilotPlugin.so">
<!-- Port settings for the machine running Gazebo -->
<listen_addr>192.168.1.31</listen_addr>
<fdm_port_in>9002</fdm_port_in>
<!-- Port settings for the machine running SITL -->
<fdm_addr>192.168.1.170</fdm_addr>
<fdm_port_out>9003</fdm_port_out>
<!-- control elements etc... -->
</plugin>
Reinstall the model with:
~/ardupilot_gazebo$ mkdir build && cd build && make -j4 && make install
then launch Gazebo (on 192.168.1.31
) with:
~/ardupilot_gazebo$ gazebo --verbose worlds/iris_arducopter_runway.world
It’s a little confusing as <fdm_addr>
is actually the address of the SITL machine and the flight dynamics in this case is being supplied by Gazebo to SITL.
The ardupilot_plugin
will bind to the socket 192.168.1.31:9002
and listen for messages from SITL. It will attempt to connect to 192.1.168.170:9003
and then send messages to SITL.
Run SITL
On the machine that you’re running SITL (192.168.1.170
) launch a session with:
$ sim_vehicle.py \
-v ArduCopter \
-f gazebo-iris \
--sitl-instance-args="--sim-address=192.168.1.31"
--console \
--map
Note that you must place the additional SITL instance arguments in quotes. You don’t need to specify the ports --sim-port-in-9002
and --sim-port-out=9003
as we are using the defaults.
In the SITL console you should see something like:
Setting SIM_SPEEDUP=1.000000
Starting SITL Gazebo
Bind 127.0.0.1:9003 for SITL in
Setting Gazebo interface to 192.168.1.31:9002
Starting sketch 'ArduCopter'
Starting SITL input
Using Irlock at port : 9005
bind port 5760 for 0
Serial port 0 on TCP port 5760
Waiting for connection ....
Connection on serial port 5760
Loaded defaults from /home/rhys/Code/ardupilot/ardupilot/Tools/autotest/default_params/copter.parm,/home/rhys/Code/ardupilot/ardupilot/Tools/autotest/default_params/gazebo-iris.parm
bind port 5762 for 2
Serial port 2 on TCP port 5762
bind port 5763 for 3
Serial port 3 on TCP port 5763
MKFIFO failed with File exists
MKFIFO failed with File exists
Home: -35.363262 149.165237 alt=584.000000m hdg=353.000000
bus.bus=0 address=0x55
bus.bus=1 address=0x55
bus.bus=0 address=0x38
bus.bus=0 address=0x39
bus.bus=1 address=0x38
bus.bus=1 address=0x39
bus.bus=2 address=0x38
bus.bus=2 address=0x39
bus.bus=3 address=0x38
bus.bus=3 address=0x39
bus.bus=0 address=0x38
bus.bus=0 address=0x39
validate_structures:489: Validating structures
Loaded defaults from /home/rhys/Code/ardupilot/ardupilot/Tools/autotest/default_params/copter.parm,/home/rhys/Code/ardupilot/ardupilot/Tools/autotest/default_params/gazebo-iris.parm
Here SITL is binding to a datagram (udp) socket on the local machine. In the
ArduPilot SITL code the socket is binding to 0.0.0.0:9003
not 127.0.0.1:9003
as reported. That’s important as the socket bound to 0.0.0.0:9003
will listen
to all network interfaces not just the local machine (which is why Gazebo can then
connect to it, whereas it could not connect to the loopback address).