autotest: adjust CAN test for lack of MAVProxy

This commit is contained in:
Peter Barker 2021-03-16 17:48:22 +11:00 committed by Peter Barker
parent 6c67e191d4
commit 42eec13f5e

View File

@ -2161,8 +2161,19 @@ class AutoTestCopter(AutoTest):
if case[3] != int(gps2_det_text.split('-')[1]):
raise NotAchievedException("Failed ordering for requested CASE:", case)
if len(case[4]):
self.mavproxy.send('arm throttle\n')
self.mavproxy.expect(case[4])
self.context_collect('STATUSTEXT')
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
1, # ARM
0,
0,
0,
0,
0,
0,
timeout=10,
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.wait_statustext(case[4], check_context=True)
self.context_stop_collecting('STATUSTEXT')
self.progress("############################### All GPS Order Cases Tests Passed")
self.context_pop()
self.fly_auto_test()