From c1405bddb30ab92518dec387889aa8931d015bd0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Aug 2012 11:44:57 +1000 Subject: [PATCH] APM-autotest: fixed inside loop test pitch 80 may not be reached due to granularity of the MAVLink logging --- Tools/autotest/arduplane.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 1f33112c44..aeb76e5a5a 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -179,7 +179,7 @@ def inside_loop(mavproxy, mav, count=1): while count > 0: print("Starting loop") mavproxy.send('rc 2 1000\n') - if not wait_pitch(mav, 80, accuracy=20): + if not wait_pitch(mav, -60, accuracy=20): return False if not wait_pitch(mav, 0, accuracy=20): return False @@ -228,7 +228,7 @@ def fly_ArduPlane(viewerip=None): ''' global homeloc - options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5' + options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip