|
|
|
@ -98,6 +98,11 @@ def drive_mission(mavproxy, mav, filename):
@@ -98,6 +98,11 @@ def drive_mission(mavproxy, mav, filename):
|
|
|
|
|
print("Mission OK") |
|
|
|
|
return True |
|
|
|
|
|
|
|
|
|
def do_get_banner(mavproxy, mav): |
|
|
|
|
mavproxy.send("long DO_SEND_BANNER 1\n") |
|
|
|
|
mavproxy.expect("APM:Rover") |
|
|
|
|
return True; |
|
|
|
|
|
|
|
|
|
vinfo = vehicleinfo.VehicleInfo() |
|
|
|
|
|
|
|
|
|
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10): |
|
|
|
@ -202,6 +207,12 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
@@ -202,6 +207,12 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
|
|
|
|
|
# if not drive_RTL(mavproxy, mav): |
|
|
|
|
# print("Failed RTL") |
|
|
|
|
# failed = True |
|
|
|
|
|
|
|
|
|
# do not move this to be the first test. MAVProxy's dedupe |
|
|
|
|
# function may bite you. |
|
|
|
|
print("Getting banner") |
|
|
|
|
if not do_get_banner(mavproxy, mav): |
|
|
|
|
failed = True |
|
|
|
|
except pexpect.TIMEOUT as e: |
|
|
|
|
print("Failed with timeout") |
|
|
|
|
failed = True |
|
|
|
|