mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
autotest: terminate FTP session after transfering files
race condition starting the second MAVProxy if the first session isn't terminated
This commit is contained in:
parent
b3e4306b70
commit
87eb703bc1
@ -12288,11 +12288,15 @@ switch value'''
|
||||
try:
|
||||
mavproxy.send("module load ftp\n")
|
||||
mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])
|
||||
mavproxy.send("ftp set debug 1\n") # so we get the "Terminated session" message
|
||||
mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name))
|
||||
mavproxy.expect("Getting")
|
||||
self.delay_sim_time(2)
|
||||
mavproxy.send("ftp status\n")
|
||||
mavproxy.expect("No transfer in progress")
|
||||
# terminate the connection, or it may still be in progress the next time an FTP is attempted:
|
||||
mavproxy.send("ftp cancel\n")
|
||||
mavproxy.expect("Terminated session")
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
Loading…
Reference in New Issue
Block a user