mirror of https://github.com/ArduPilot/ardupilot
Tools: correct copter's fly_throttle_failsafe failure case
This commit is contained in:
parent
13894506f4
commit
0334cc1c88
|
@ -281,13 +281,12 @@ def fly_throttle_failsafe(mavproxy, mav, side=60, timeout=180):
|
|||
mavproxy.send('switch 6\n')
|
||||
wait_mode(mav, 'STABILIZE')
|
||||
hover(mavproxy, mav)
|
||||
failed = False
|
||||
|
||||
# fly east 60 meters
|
||||
print("# Going forward %u meters" % side)
|
||||
mavproxy.send('rc 2 1350\n')
|
||||
if not wait_distance(mav, side, 5, 60):
|
||||
failed = True
|
||||
return False
|
||||
mavproxy.send('rc 2 1500\n')
|
||||
|
||||
# pull throttle low
|
||||
|
|
Loading…
Reference in New Issue