Ardupilot SITL + gazebo on different computers

I followed the SITL+gazebo tutorial (http://ardupilot.org/dev/docs/using-gazebo-simulator-with-sitl.html) using the plugin (https://github.com/SwiftGust/ardupilot_gazebo) and I was able to run SITL + gazebo in the same computer.

However, I want to be able to run SITL in one computer and gazebo in another one, is it possible to pass the address of the gazebo computer as a parameter when starting sim_veichle.py?

Hi,

I have been struggling with the same issue over a week by now. According to the source, it seems that in libraries/AP_HAL_SITL/SITL_cmdline.cpp is the place where SITL is started. And at line 91, its clearly stated that simulator address can be specified as a command-line argument. According to my knowledge, this must be the address of Gazebo host. Now the thing is that this SITL is started via sim_vehicle.py somehow I guess, and I haven’t found a way yet how to pass that sim_address to SITIL via sim_vehicle. Pull request for this feature (https://github.com/ArduPilot/ardupilot/pull/5346/files) also did not give much light about it. Only changes in sim_vehicle.py are new frame types. Might it be that it comes somehow from model definition?

Now at gazebo side. There also should be this functionality implemented by this pull request: https://bitbucket.org/osrf/gazebo/pull-requests/2451/ardupilot-make-ardupilot-address/diff
If I’m not mistaken, it should allow specifying fdm_addr via model sdf configuration. I gave it a try, but when gazebo starts up, then UI still displays fdm_address as localhost. So I have to dig little deeper in that. Might be that my model configurations are somehow mixed up.

Anyway, it would be nice if someone can share some light in that matter.

Note, I’m not much familiar with either c++ nor ardupilot logic, so statements above are just assumptions made by searching through the source code.


Kpihus

@kpihus Re passing the address of the other computer running gazebo, you’ll have to use the -A arg in sim_vehicle.py to pass the next argument to the SITL instance.

$ sim_vehicle.py --help
 -A SITL_INSTANCE_ARGS, --sitl-instance-args=SITL_INSTANCE_ARGS
                        pass arguments to SITL instance

The arguments of the SITL instance are here - https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_SITL/SITL_cmdline.cpp#L62

The one for address is --sim-address
Therefore, something like

sim_vehicle.py ... -A --sim-address=127.0.0.1

Change 127.0.0.1 to the correct address of the other machine
Not sure about how to change it from the Gazebo side

Hope this helps!
Rajat

Hi, @rajat2004 thankyou for that. I’ll give it a try asap.
Allready fixed gazebo side, i was editing wrong model file :slight_smile:

Still not good enogh. As i understand i have to specify frametype as gazebo-iris with -f flag. But in this case, it cant connect to mavproxy. At least it keeps waiting heartbeat from tcp:127.0.0.1:5760.
If i choos frame type as X for example, then it seems to work fine, but of course it does not open gazebo connection.
Any ideas?

Ok, i get it, it needs gazebo connection i order to start mavproxy, right? Seems that i have still some issues there.

EDIT:

I have a feeling that something is still wrong.
SITL starts with messages:

Set parameter SIM_SPEEDUP to 1.000000
Starting SITL Gazebo
Bind 127.0.0.1:9003 for SITL in
Setting Gazebo interface to 172.16.66.1:9002 
Starting sketch 'ArduCopter'
Starting SITL input

Now that Bind 127.0.0.1:9003 for SITL in Is that correct? I presume it should listen on machines external address, in my case on 172.16.66.100 ?

It’s old post but, somebody solve this issue ?

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).

Thank you very much for help.

For anyone trying to do this with multiple SITL instances, each instance in a different computer you need the --sim-port-in and --sim-port-out but they are inverted with respect to the gazebo model.

Hi Loki2020
I’m stuck. Can you help me? I applied instructions above. First of all there is no such a folder as […]/iris_with_ardupilot in swiftgust repo.
I see “link 1 down” message on the Mavproxy white-theme console. What I did: Tried to make SITL and gazebo_plugin run in the same computer:
1 - on gazebo computer (192.168.1.36) modify …/iris_with_standoffs_demo/model.sdf as described above
2 - Reinstall and Launch gazebo as described above
3- Run SITL : sim_vehicle.py
-v ArduCopter
-f gazebo-iris
–sitl-instance-args=“–sim-address=192.168.1.36”
–console
–map