Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tools: Use a single MAVProxy instance in sim_vehicle #15728

Closed
wants to merge 2 commits into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
54 changes: 24 additions & 30 deletions Tools/autotest/sim_vehicle.py
Expand Up @@ -722,6 +722,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
Expand Down Expand Up @@ -802,36 +824,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())
Expand Down