diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 13ee95ab6d..1eea64d996 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -307,9 +307,14 @@ def fly_throttle_failsafe(mavproxy, mav, side=60, timeout=180): # switch back to stabilize mavproxy.send('switch 2\n') # land mode wait_mode(mav, 'LAND') + print("Waiting for disarm") + mav.motors_disarmed_wait() + print("Reached failsafe home OK") mavproxy.send('switch 6\n') # stabilize mode wait_mode(mav, 'STABILIZE') - print("Reached failsafe home OK") + if not arm_motors(mavproxy, mav): + print("Failed to re-arm") + return False return True print("Failed to land on failsafe RTL - timed out after %u seconds" % timeout) # reduce throttle