mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Tools: autotest: disarm rover before downloading logs
This commit is contained in:
parent
5b70b688cb
commit
05ea121d0c
@ -32,6 +32,14 @@ def arm_rover(mavproxy, mav):
|
|||||||
return True
|
return True
|
||||||
|
|
||||||
|
|
||||||
|
def disarm_rover(mavproxy, mav):
|
||||||
|
mavproxy.send('disarm\n')
|
||||||
|
mavproxy.expect('DISARMED')
|
||||||
|
|
||||||
|
print("ROVER DISARMED")
|
||||||
|
return True
|
||||||
|
|
||||||
|
|
||||||
def drive_left_circuit(mavproxy, mav):
|
def drive_left_circuit(mavproxy, mav):
|
||||||
"""Drive a left circuit, 50m on a side."""
|
"""Drive a left circuit, 50m on a side."""
|
||||||
mavproxy.send('switch 6\n')
|
mavproxy.send('switch 6\n')
|
||||||
@ -172,6 +180,9 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
|
|||||||
if not drive_mission(mavproxy, mav, os.path.join(testdir, "rover1.txt")):
|
if not drive_mission(mavproxy, mav, os.path.join(testdir, "rover1.txt")):
|
||||||
print("Failed mission")
|
print("Failed mission")
|
||||||
failed = True
|
failed = True
|
||||||
|
if not disarm_rover(mavproxy, mav):
|
||||||
|
print("Failed to DISARM")
|
||||||
|
failed = True
|
||||||
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/APMrover2-log.bin")):
|
if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/APMrover2-log.bin")):
|
||||||
print("Failed log download")
|
print("Failed log download")
|
||||||
failed = True
|
failed = True
|
||||||
|
Loading…
Reference in New Issue
Block a user