From fd19db8151aaacf5d3d4d396489a3b4aec4679c7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 6 Oct 2024 12:38:37 +1100 Subject: [PATCH] autotest: delay indefinitely if MAVProxy exits this is useful if you are running under GDB and ArduPilot fails early (eg. parameter sanity checks or SITL device configuration issues) --- Tools/autotest/sim_vehicle.py | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index babd1b3cd7936e..19dbbb5ee7cd3a 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -986,6 +986,17 @@ def start_mavproxy(opts, stuff): run_cmd_blocking("Run MavProxy", cmd, env=env) progress("MAVProxy exited") + if opts.gdb: + # in the case that MAVProxy exits (as opposed to being + # killed), restart it if we are running under GDB. This + # allows ArduPilot to stop (eg. via a very early panic call) + # and have you debugging session not be killed. + while True: + progress("Running under GDB; restarting MAVProxy") + run_cmd_blocking("Run MavProxy", cmd, env=env) + progress("MAVProxy exited; sleeping 10") + time.sleep(10) + vehicle_options_string = '|'.join(vinfo.options.keys())