From 4ff6f603b2f0e2eb21ee221e5bf2b890b8db990e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 3 Sep 2024 18:45:35 +1000 Subject: [PATCH] autotest: add --enable-fgview option --- Tools/autotest/autotest.py | 4 ++++ Tools/autotest/pysim/util.py | 4 ++-- Tools/autotest/vehicle_test_suite.py | 3 +++ 3 files changed, 9 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index d11c11ff0e..74f08297f1 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -516,6 +516,7 @@ def run_step(step): "reset_after_every_test": opts.reset_after_every_test, "build_opts": copy.copy(build_opts), "generate_junit": opts.junit, + "enable_fgview": opts.enable_fgview, } if opts.speedup is not None: fly_opts["speedup"] = opts.speedup @@ -862,6 +863,9 @@ if __name__ == "__main__": parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to') + parser.add_option("--enable-fgview", + action='store_true', + help="Enable FlightGear output") parser.add_option("--map", action='store_true', default=False, diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index 1830e8f82a..2c84afe8da 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -428,7 +428,7 @@ def start_SITL(binary, disable_breakpoints=False, customisations=[], lldb=False, - enable_fgview_output=False, + enable_fgview=False, supplementary=False, stdout_prefix=None): @@ -534,7 +534,7 @@ def start_SITL(binary, cmd.extend(['--unhide-groups']) # somewhere for MAVProxy to connect to: cmd.append('--serial1=tcp:2') - if enable_fgview_output: + if enable_fgview: cmd.append("--enable-fgview") if len(defaults): diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 7b44dc3aca..8ac22b6ede 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -1865,6 +1865,7 @@ class TestSuite(ABC): num_aux_imus=0, dronecan_tests=False, generate_junit=False, + enable_fgview=False, build_opts={}): self.start_time = time.time() @@ -1931,6 +1932,7 @@ class TestSuite(ABC): self.last_heartbeat_time_wc_s = 0 self.in_drain_mav = False self.tlog = None + self.enable_fgview = enable_fgview self.rc_thread = None self.rc_thread_should_quit = False @@ -9100,6 +9102,7 @@ Also, ignores heartbeats not from our target system''' "valgrind": self.valgrind, "callgrind": self.callgrind, "wipe": True, + "enable_fgview": self.enable_fgview, } start_sitl_args.update(**sitl_args) if ("defaults_filepath" not in start_sitl_args or