Tools: Make default udpout ports scale by instance in sim_vehicle.py

This commit is contained in:
Fnoop 2016-10-09 11:43:13 +01:00 committed by Andrew Tridgell
parent 02f49398be
commit 2c0b687b9d

View File

@ -615,9 +615,11 @@ 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
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:14550"])
for port in [14550, 14551]:
cmd.extend(["--out", "10.0.2.2:" + str(port)])
else:
cmd.extend(["--out", "127.0.0.1:" + str(port)])
if opts.tracker: