From 817efe9b6d548d21972e869917d1b8bc0a1e5c68 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Jan 2017 16:53:13 +1100 Subject: [PATCH] Tools: expect message for EKF readiness rather than sleeping This solves a problem for me when running Valgrind as 30s was not sufficient --- Tools/autotest/apmrover2.py | 7 +++++-- Tools/autotest/arducopter.py | 10 ++++++---- Tools/autotest/arduplane.py | 6 ++++-- 3 files changed, 15 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 5a430a5508..99478fde4d 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -18,9 +18,12 @@ HOME = mavutil.location(40.071374969556928, -105.22978898137808, 1583.702759, 24 homeloc = None -def arm_rover(mavproxy, mav): +def wait_ready_to_arm(mavproxy): # wait for EKF and GPS checks to pass - wait_seconds(mav, 30) + mavproxy.expect('IMU0 is using GPS') + +def arm_rover(mavproxy, mav): + wait_ready_to_arm(mavproxy); mavproxy.send('arm throttle\n') mavproxy.expect('ARMED') diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b45e59012d..8da4f24ae8 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -29,6 +29,10 @@ num_wp = 0 speedup_default = 10 +def wait_ready_to_arm(mavproxy): + # wait for EKF and GPS checks to pass + mavproxy.expect('IMU0 is using GPS') + def hover(mavproxy, mav, hover_throttle=1500): mavproxy.send('rc 3 %u\n' % hover_throttle) return True @@ -1027,8 +1031,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal setup_rc(mavproxy) homeloc = mav.location() - # wait for EKF and GPS checks to pass - wait_seconds(mav, 30) + wait_ready_to_arm(mavproxy) # Arm print("# Arm motors") @@ -1378,8 +1381,7 @@ def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals print("Lowering rotor speed") mavproxy.send('rc 8 1000\n') - # wait for EKF and GPS checks to pass - wait_seconds(mav, 30) + wait_ready_to_arm(mavproxy) # Arm print("# Arm motors") diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 1c454ee269..0ff955a337 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -19,12 +19,14 @@ WIND = "0,180,0.2" # speed,direction,variance homeloc = None +def wait_ready_to_arm(mavproxy): + # wait for EKF and GPS checks to pass + mavproxy.expect('IMU0 is using GPS') def takeoff(mavproxy, mav): """Takeoff get to 30m altitude.""" - # wait for EKF and GPS checks to pass - wait_seconds(mav, 30) + wait_ready_to_arm(mavproxy) mavproxy.send('arm throttle\n') mavproxy.expect('ARMED')