From 717c04d507c7f6bcc7373b49ba688fb9b7b7a377 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 May 2015 18:13:55 +1000 Subject: [PATCH] autotest: fly CopterAVC mission as a helicopter this ensures heli gets basic testing --- Tools/autotest/arducopter.py | 23 ++++++++++++++++------- Tools/autotest/autotest.py | 5 +++++ 2 files changed, 21 insertions(+), 7 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 32a1ef105c..bc9ccaad81 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1260,20 +1260,20 @@ def fly_CopterAVC(viewerip=None, map=False): util.build_SIL('ArduCopter', target=TARGET) home = "%f,%f,%u,%u" % (AVCHOME.lat, AVCHOME.lng, AVCHOME.alt, AVCHOME.heading) - sil = util.start_SIL('ArduCopter', wipe=True, model='+', home=home, speedup=speedup_default) - mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter') + sil = util.start_SIL('ArduCopter', wipe=True, model='heli', home=home, speedup=speedup_default) + mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550') mavproxy.expect('Received [0-9]+ parameters') # setup test parameters - mavproxy.send("param load %s/copter_AVC2013_params.parm\n" % testdir) + mavproxy.send("param load %s/Helicopter.parm\n" % testdir) mavproxy.expect('Loaded [0-9]+ parameters') # reboot with new parameters util.pexpect_close(mavproxy) util.pexpect_close(sil) - sil = util.start_SIL('ArduCopter', model='+', home=home, speedup=speedup_default) - options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5' + sil = util.start_SIL('ArduCopter', model='heli', home=home, speedup=speedup_default) + options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5' if viewerip: options += ' --out=%s:14550' % viewerip if map: @@ -1323,8 +1323,11 @@ def fly_CopterAVC(viewerip=None, map=False): setup_rc(mavproxy) homeloc = mav.location() - # wait 10sec to allow EKF to settle - wait_seconds(mav, 10) + print("Lowering rotor speed") + mavproxy.send('rc 8 1000\n') + + # wait 20sec to allow EKF to settle + wait_seconds(mav, 20) # Arm print("# Arm motors") @@ -1333,6 +1336,9 @@ def fly_CopterAVC(viewerip=None, map=False): print(failed_test_msg) failed = True + print("Raising rotor speed") + mavproxy.send('rc 8 2000\n') + print("# Fly AVC mission") if not fly_avc_test(mavproxy, mav): failed_test_msg = "fly_avc_test failed" @@ -1341,6 +1347,9 @@ def fly_CopterAVC(viewerip=None, map=False): else: print("Flew AVC mission OK") + print("Lowering rotor speed") + mavproxy.send('rc 8 1000\n') + #mission includes disarm at end so should be ok to download logs now if not log_download(mavproxy, mav, util.reltopdir("../buildlogs/CopterAVC-log.bin")): failed_test_msg = "log_download failed" diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index acb1dca502..261db30bae 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -163,6 +163,8 @@ steps = [ 'build.ArduCopter', 'defaults.ArduCopter', 'fly.ArduCopter', + + 'build.Helicopter', 'fly.CopterAVC', 'convertgpx', @@ -204,6 +206,9 @@ def run_step(step): if step == 'build.ArduCopter': return util.build_SIL('ArduCopter', j=opts.j) + if step == 'build.Helicopter': + return util.build_SIL('ArduCopter', target='sitl-heli', j=opts.j) + if step == 'defaults.ArduPlane': return get_default_params('ArduPlane')