From 324d9f3c7d393c8dc59739226d833d7e86e5e950 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 28 Aug 2017 10:57:59 +1000 Subject: [PATCH] Tools: apmrover2.py: add a test for MAV_CMD_DO_GET_BANNER --- Tools/autotest/apmrover2.py | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 42073e54eb..c123bdf9d4 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -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 # 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