AutoTest: reduce copter throttle when in stabilize

Simulated copter is flying too high and causing the land to timeout
This commit is contained in:
Randy Mackay 2015-01-14 12:41:18 +09:00
parent c40c3632bb
commit 2a7f78a2cd

View File

@ -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')