autotest: ensure vehicle is armed before issuing takeoff command

sending the arm command isn't sufficient if there are other arming problems.

Caught a test failing when throttle was found to be high - I think the rc(3, 1700) was managing to have effect before we processed the arm command because of the way the input queues to ArduPilot SITL work
This commit is contained in:
Peter Barker 2022-12-27 09:10:45 +11:00 committed by Peter Barker
parent 89ecd8fb17
commit a71911c19f

View File

@ -1130,8 +1130,7 @@ class AutoTestCopter(AutoTest):
self.wait_ready_to_arm()
self.context_push()
self.context_collect('STATUSTEXT')
self.send_mavlink_arm_command()
self.mav.recv_match(blocking=True, timeout=1)
self.arm_vehicle()
if user_takeoff:
self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 10)
else: