mirror of https://github.com/ArduPilot/ardupilot
autotest: change loiter heading accuracy to 10
This commit is contained in:
parent
b3c9cdb353
commit
8b7fc364f9
|
@ -65,7 +65,7 @@ def fly_left_circuit(mavproxy, mav):
|
||||||
# hard left
|
# hard left
|
||||||
print("Starting turn %u" % i)
|
print("Starting turn %u" % i)
|
||||||
mavproxy.send('rc 1 1000\n')
|
mavproxy.send('rc 1 1000\n')
|
||||||
if not wait_heading(mav, 270 - (90*i)):
|
if not wait_heading(mav, 270 - (90*i), accuracy=10):
|
||||||
return False
|
return False
|
||||||
mavproxy.send('rc 1 1500\n')
|
mavproxy.send('rc 1 1500\n')
|
||||||
print("Starting leg %u" % i)
|
print("Starting leg %u" % i)
|
||||||
|
@ -93,9 +93,9 @@ def fly_LOITER(mavproxy, mav, num_circles=4):
|
||||||
mavproxy.send('loiter\n')
|
mavproxy.send('loiter\n')
|
||||||
wait_mode(mav, 'LOITER')
|
wait_mode(mav, 'LOITER')
|
||||||
while num_circles > 0:
|
while num_circles > 0:
|
||||||
if not wait_heading(mav, 0):
|
if not wait_heading(mav, 0, accuracy=10):
|
||||||
return False
|
return False
|
||||||
if not wait_heading(mav, 180):
|
if not wait_heading(mav, 180, accuracy=10):
|
||||||
return False
|
return False
|
||||||
num_circles -= 1
|
num_circles -= 1
|
||||||
print("Loiter %u circles left" % num_circles)
|
print("Loiter %u circles left" % num_circles)
|
||||||
|
@ -320,6 +320,7 @@ def fly_ArduPlane(viewerip=None):
|
||||||
print("Failed mission")
|
print("Failed mission")
|
||||||
failed = True
|
failed = True
|
||||||
except pexpect.TIMEOUT, e:
|
except pexpect.TIMEOUT, e:
|
||||||
|
print("Failed with timeout")
|
||||||
failed = True
|
failed = True
|
||||||
|
|
||||||
mav.close()
|
mav.close()
|
||||||
|
|
Loading…
Reference in New Issue