mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AutoTest: higher copter throttle when in stabilize
This commit is contained in:
parent
022c549339
commit
765fa0e223
@ -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 1420\n')
|
||||
mavproxy.send('rc 3 1450\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 1400\n')
|
||||
mavproxy.send('rc 3 1450\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 1400\n')
|
||||
mavproxy.send('rc 3 1450\n')
|
||||
|
||||
# start copter yawing slowly
|
||||
mavproxy.send('rc 4 1550\n')
|
||||
|
Loading…
Reference in New Issue
Block a user