mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Tools: sim_vehicle to only launch one 1455x UDP port
This commit is contained in:
parent
bb80881c10
commit
61b184781a
@ -857,7 +857,7 @@ def start_mavproxy(opts, stuff):
|
||||
|
||||
for i in instances:
|
||||
if not opts.no_extra_ports:
|
||||
ports = [p + 10 * i for p in [14550, 14551]]
|
||||
ports = [14550 + 10 * i]
|
||||
for port in ports:
|
||||
if under_vagrant():
|
||||
# We're running inside of a vagrant guest; forward our
|
||||
|
Loading…
Reference in New Issue
Block a user