Tools: Use a single MAVProxy instance in sim_vehicle

With the implementation of the 'alllinks' command in MAVProxy, and the
exposure of the SYSID parameter this becomes feasible

        Tools: Fix mcast handling
This commit is contained in:
Arash Negahdar 2020-10-28 14:09:16 -04:00 committed by Tom Pittenger
parent 49af90a70e
commit d065515b2a
1 changed files with 24 additions and 30 deletions

View File

@ -735,6 +735,28 @@ def start_mavproxy(opts, stuff):
else:
cmd.append("mavproxy.py")
if opts.mcast:
cmd.extend(["--master", "mcast:"])
for i in instances:
if not opts.no_extra_ports:
ports = [p + 10 * i for p in [14550, 14551]]
for port in ports:
if os.path.isfile("/ardupilot.vagrant"):
# We're running inside of a vagrant guest; forward our
# mavlink out to the containing host OS
cmd.extend(["--out", "10.0.2.2:" + str(port)])
else:
cmd.extend(["--out", "127.0.0.1:" + str(port)])
if not opts.mcast:
if opts.udp:
cmd.extend(["--master", ":" + str(5760 + 10 * i)])
else:
cmd.extend(["--master", "tcp:127.0.0.1:" + str(5760 + 10 * i)])
if stuff["sitl-port"] and not opts.no_rcin:
cmd.extend(["--sitl", "127.0.0.1:" + str(5501 + 10 * i)])
if opts.tracker:
cmd.extend(["--load-module", "tracker"])
global tracker_uarta
@ -815,36 +837,8 @@ def start_mavproxy(opts, stuff):
if old is not None:
env['PYTHONPATH'] += os.path.pathsep + old
old_dir = os.getcwd()
for i, i_dir in zip(instances, instance_dir):
c = []
if not opts.no_extra_ports:
ports = [p + 10 * i for p in [14550, 14551]]
for port in ports:
if os.path.isfile("/ardupilot.vagrant"):
# We're running inside of a vagrant guest; forward our
# mavlink out to the containing host OS
c.extend(["--out", "10.0.2.2:" + str(port)])
else:
c.extend(["--out", "127.0.0.1:" + str(port)])
if True:
if opts.mcast:
c.extend(["--master", "mcast:"])
elif opts.udp:
c.extend(["--master", ":" + str(5760 + 10 * i)])
else:
c.extend(["--master", "tcp:127.0.0.1:" + str(5760 + 10 * i)])
if stuff["sitl-port"] and not opts.no_rcin:
c.extend(["--sitl", "127.0.0.1:" + str(5501 + 10 * i)])
os.chdir(i_dir)
if i == instances[-1]:
run_cmd_blocking("Run MavProxy", cmd + c, env=env)
else:
run_in_terminal_window("Run MavProxy", cmd + c, env=env)
os.chdir(old_dir)
run_cmd_blocking("Run MavProxy", cmd, env=env)
progress("MAVProxy exited")
vehicle_options_string = '|'.join(vinfo.options.keys())