autotest: add --enable-fgview option

This commit is contained in:
Peter Barker 2024-09-03 18:45:35 +10:00 committed by Randy Mackay
parent 2a371077e3
commit 4ff6f603b2
3 changed files with 9 additions and 2 deletions

View File

@ -516,6 +516,7 @@ def run_step(step):
"reset_after_every_test": opts.reset_after_every_test, "reset_after_every_test": opts.reset_after_every_test,
"build_opts": copy.copy(build_opts), "build_opts": copy.copy(build_opts),
"generate_junit": opts.junit, "generate_junit": opts.junit,
"enable_fgview": opts.enable_fgview,
} }
if opts.speedup is not None: if opts.speedup is not None:
fly_opts["speedup"] = opts.speedup fly_opts["speedup"] = opts.speedup
@ -862,6 +863,9 @@ if __name__ == "__main__":
parser.add_option("--viewerip", parser.add_option("--viewerip",
default=None, default=None,
help='IP address to send MAVLink and fg packets to') 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", parser.add_option("--map",
action='store_true', action='store_true',
default=False, default=False,

View File

@ -428,7 +428,7 @@ def start_SITL(binary,
disable_breakpoints=False, disable_breakpoints=False,
customisations=[], customisations=[],
lldb=False, lldb=False,
enable_fgview_output=False, enable_fgview=False,
supplementary=False, supplementary=False,
stdout_prefix=None): stdout_prefix=None):
@ -534,7 +534,7 @@ def start_SITL(binary,
cmd.extend(['--unhide-groups']) cmd.extend(['--unhide-groups'])
# somewhere for MAVProxy to connect to: # somewhere for MAVProxy to connect to:
cmd.append('--serial1=tcp:2') cmd.append('--serial1=tcp:2')
if enable_fgview_output: if enable_fgview:
cmd.append("--enable-fgview") cmd.append("--enable-fgview")
if len(defaults): if len(defaults):

View File

@ -1865,6 +1865,7 @@ class TestSuite(ABC):
num_aux_imus=0, num_aux_imus=0,
dronecan_tests=False, dronecan_tests=False,
generate_junit=False, generate_junit=False,
enable_fgview=False,
build_opts={}): build_opts={}):
self.start_time = time.time() self.start_time = time.time()
@ -1931,6 +1932,7 @@ class TestSuite(ABC):
self.last_heartbeat_time_wc_s = 0 self.last_heartbeat_time_wc_s = 0
self.in_drain_mav = False self.in_drain_mav = False
self.tlog = None self.tlog = None
self.enable_fgview = enable_fgview
self.rc_thread = None self.rc_thread = None
self.rc_thread_should_quit = False self.rc_thread_should_quit = False
@ -9100,6 +9102,7 @@ Also, ignores heartbeats not from our target system'''
"valgrind": self.valgrind, "valgrind": self.valgrind,
"callgrind": self.callgrind, "callgrind": self.callgrind,
"wipe": True, "wipe": True,
"enable_fgview": self.enable_fgview,
} }
start_sitl_args.update(**sitl_args) start_sitl_args.update(**sitl_args)
if ("defaults_filepath" not in start_sitl_args or if ("defaults_filepath" not in start_sitl_args or