diff --git a/Tools/autotest/ArduCopter.parm b/Tools/autotest/ArduCopter.parm index 3465fc56d2..5e9a2a45be 100644 --- a/Tools/autotest/ArduCopter.parm +++ b/Tools/autotest/ArduCopter.parm @@ -29,12 +29,3 @@ FLTMODE3 2 FLTMODE4 6 FLTMODE5 5 FLTMODE6 0 -NAV_LAT_I 0 -NAV_LON_I 0 -NAV_LAT_P 1 -NAV_LON_P 1 -STB_PIT_P 2 -STB_RLL_P 2 -XTRACK_P 1 -RATE_PIT_P 0.1 -RATE_RLL_P 0.1 diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index a98c8bf337..593ad682fe 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -229,7 +229,7 @@ def land(mavproxy, mav, timeout=60): return False -def fly_mission(mavproxy, mav, filename, timeout=120): +def fly_mission(mavproxy, mav, filename): '''fly a mission from a file''' startloc = current_location(mav) mavproxy.send('wp load %s\n' % filename) @@ -239,7 +239,7 @@ def fly_mission(mavproxy, mav, filename, timeout=120): mavproxy.send('switch 1\n') # auto mode mavproxy.expect('AUTO>') wait_distance(mav, 30, timeout=120) - wait_location(mav, startloc, timeout=300) + wait_location(mav, startloc, timeout=600) def setup_rc(mavproxy): @@ -306,6 +306,7 @@ def fly_ArduCopter(): loiter(mavproxy, mav) land(mavproxy, mav) fly_mission(mavproxy, mav, os.path.join(testdir, "mission1.txt")) + land(mavproxy, mav) disarm_motors(mavproxy) except pexpect.TIMEOUT, e: failed = True