mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: Make default udpout ports scale by instance in sim_vehicle.py
This commit is contained in:
parent
02f49398be
commit
2c0b687b9d
@ -615,10 +615,12 @@ def start_mavproxy(opts, stuff):
|
|||||||
cmd.extend(["--sitl", simout_port])
|
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 running inside of a vagrant guest, then we probably want to forward our mavlink out to the containing host OS
|
||||||
if getpass.getuser() == "vagrant":
|
ports = [p + 10 * cmd_opts.instance for p in [14550,14551]]
|
||||||
cmd.extend(["--out", "10.0.2.2:14550"])
|
for port in ports:
|
||||||
for port in [14550, 14551]:
|
if getpass.getuser() == "vagrant":
|
||||||
cmd.extend(["--out", "127.0.0.1:" + str(port)])
|
cmd.extend(["--out", "10.0.2.2:" + str(port)])
|
||||||
|
else:
|
||||||
|
cmd.extend(["--out", "127.0.0.1:" + str(port)])
|
||||||
|
|
||||||
if opts.tracker:
|
if opts.tracker:
|
||||||
cmd.extend(["--load-module", "tracker"])
|
cmd.extend(["--load-module", "tracker"])
|
||||||
|
Loading…
Reference in New Issue
Block a user