From 2c0b687b9d8a96fb34ef7d4c874ce03ee71dea37 Mon Sep 17 00:00:00 2001 From: Fnoop Date: Sun, 9 Oct 2016 11:43:13 +0100 Subject: [PATCH] Tools: Make default udpout ports scale by instance in sim_vehicle.py --- Tools/autotest/sim_vehicle.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index b940c034b5..edfa86ce6c 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -615,10 +615,12 @@ def start_mavproxy(opts, stuff): cmd.extend(["--sitl", simout_port]) # If running inside of a vagrant guest, then we probably want to forward our mavlink out to the containing host OS - if getpass.getuser() == "vagrant": - cmd.extend(["--out", "10.0.2.2:14550"]) - for port in [14550, 14551]: - cmd.extend(["--out", "127.0.0.1:" + str(port)]) + ports = [p + 10 * cmd_opts.instance for p in [14550,14551]] + for port in ports: + if getpass.getuser() == "vagrant": + cmd.extend(["--out", "10.0.2.2:" + str(port)]) + else: + cmd.extend(["--out", "127.0.0.1:" + str(port)]) if opts.tracker: cmd.extend(["--load-module", "tracker"])