From 2802814a6609cdce85d053f5f1d6362571c7cc66 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 15 Jul 2013 13:11:41 +1000 Subject: [PATCH] autotest: cope with slower updating roll in MAVLink for plane need less precision in horizontal roll test --- Tools/autotest/arduplane.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index e9c1b47867..821da6c81e 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -146,11 +146,11 @@ def axial_left_roll(mavproxy, mav, count=1): while count > 0: print("Starting roll") mavproxy.send('rc 1 1000\n') - if not wait_roll(mav, -150, accuracy=20): + if not wait_roll(mav, -150, accuracy=45): return False - if not wait_roll(mav, 150, accuracy=20): + if not wait_roll(mav, 150, accuracy=45): return False - if not wait_roll(mav, 0, accuracy=20): + if not wait_roll(mav, 0, accuracy=45): return False count -= 1