diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py
index ff773cd0de7d197ea660c369f70192f4a23bacaf..100418cfb1438b9a7b2fe519c661e0e0d1d8f835 100644
--- a/Tools/autotest/arducopter.py
+++ b/Tools/autotest/arducopter.py
@@ -160,7 +160,7 @@ def fly_square(mavproxy, mav, side=50, timeout=120):
     save_wp(mavproxy, mav)
 
     # switch back to stabilize mode
-    mavproxy.send('rc 3 1450\n')
+    mavproxy.send('rc 3 1430\n')
     mavproxy.send('switch 6\n')
     wait_mode(mav, 'STABILIZE')
 
@@ -615,7 +615,7 @@ def fly_simple(mavproxy, mav, side=50, timeout=120):
     # switch to stabilize mode
     mavproxy.send('switch 6\n')
     wait_mode(mav, 'STABILIZE')
-    mavproxy.send('rc 3 1450\n')
+    mavproxy.send('rc 3 1430\n')
 
     # fly south 50m
     print("# Flying south %u meters" % side)
@@ -680,7 +680,7 @@ def fly_super_simple(mavproxy, mav, timeout=45):
     # switch to stabilize mode
     mavproxy.send('switch 6\n')
     wait_mode(mav, 'STABILIZE')
-    mavproxy.send('rc 3 1450\n')
+    mavproxy.send('rc 3 1430\n')
 
     # start copter yawing slowly
     mavproxy.send('rc 4 1550\n')