diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 4d891f54e9..f5fae73122 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -14,8 +14,8 @@ HOME=mavutil.location(40.071374969556928,-105.22978898137808,1583.702759,246) homeloc = None def arm_rover(mavproxy, mav): - # wait for EKF to settle - wait_seconds(mav, 15) + # wait for EKF and GPS checks to pass + wait_seconds(mav, 30) mavproxy.send('arm throttle\n') mavproxy.expect('ARMED') diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index a0c43db654..fde91083a1 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -987,8 +987,8 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False): setup_rc(mavproxy) homeloc = mav.location() - # wait 10sec to allow EKF to settle - wait_seconds(mav, 10) + # wait for EKF and GPS checks to pass + wait_seconds(mav, 30) # Arm print("# Arm motors") @@ -1340,8 +1340,8 @@ def fly_CopterAVC(binary, viewerip=None, map=False, valgrind=False, gdb=False): print("Lowering rotor speed") mavproxy.send('rc 8 1000\n') - # wait 20sec to allow EKF to settle - wait_seconds(mav, 20) + # wait for EKF and GPS checks to pass + wait_seconds(mav, 30) # Arm print("# Arm motors") diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index cc80ec9a6f..e977e4ad37 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -17,8 +17,8 @@ homeloc = None def takeoff(mavproxy, mav): '''takeoff get to 30m altitude''' - # wait for EKF to settle - wait_seconds(mav, 15) + # wait for EKF and GPS checks to pass + wait_seconds(mav, 30) mavproxy.send('arm throttle\n') mavproxy.expect('ARMED') diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 982c8757fb..ed86347d75 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -101,8 +101,8 @@ def fly_QuadPlane(binary, viewerip=None, map=False, valgrind=False, gdb=False): homeloc = mav.location() print("Home location: %s" % homeloc) - # wait for EKF to settle - wait_seconds(mav, 15) + # wait for EKF and GPS checks to pass + wait_seconds(mav, 30) mavproxy.send('arm throttle\n') mavproxy.expect('ARMED')