mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
Tools: apmrover2.py: add a test for MAV_CMD_DO_GET_BANNER
This commit is contained in:
parent
1928dcb784
commit
324d9f3c7d
@ -98,6 +98,11 @@ def drive_mission(mavproxy, mav, filename):
|
|||||||
print("Mission OK")
|
print("Mission OK")
|
||||||
return True
|
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()
|
vinfo = vehicleinfo.VehicleInfo()
|
||||||
|
|
||||||
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10):
|
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):
|
# if not drive_RTL(mavproxy, mav):
|
||||||
# print("Failed RTL")
|
# print("Failed RTL")
|
||||||
# failed = True
|
# 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:
|
except pexpect.TIMEOUT as e:
|
||||||
print("Failed with timeout")
|
print("Failed with timeout")
|
||||||
failed = True
|
failed = True
|
||||||
|
Loading…
Reference in New Issue
Block a user