Skip to content

Commit

Permalink
autotest: delay indefinitely if MAVProxy exits
Browse files Browse the repository at this point in the history
this is useful if you are running under GDB and ArduPilot fails early (eg. parameter sanity checks or SITL device configuration issues)
  • Loading branch information
peterbarker committed Oct 9, 2024
1 parent f588e9a commit fd19db8
Showing 1 changed file with 11 additions and 0 deletions.
11 changes: 11 additions & 0 deletions Tools/autotest/sim_vehicle.py
Original file line number Diff line number Diff line change
Expand Up @@ -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())

Expand Down

0 comments on commit fd19db8

Please sign in to comment.