mirror of https://github.com/ArduPilot/ardupilot
Fixed Loiter Timeout bug, added more wind by default.
This commit is contained in:
parent
a9e1e9a8db
commit
986b42a45b
|
@ -57,7 +57,7 @@ def takeoff(mavproxy, mav, alt_min = 30):
|
||||||
print("TAKEOFF COMPLETE")
|
print("TAKEOFF COMPLETE")
|
||||||
return True
|
return True
|
||||||
|
|
||||||
def loiter(mavproxy, mav, holdtime=20, maxaltchange=10, timeout=60):
|
def loiter(mavproxy, mav, holdtime=60, maxaltchange=20):
|
||||||
'''hold loiter position'''
|
'''hold loiter position'''
|
||||||
mavproxy.send('switch 5\n') # loiter mode
|
mavproxy.send('switch 5\n') # loiter mode
|
||||||
wait_mode(mav, 'LOITER')
|
wait_mode(mav, 'LOITER')
|
||||||
|
@ -67,7 +67,7 @@ def loiter(mavproxy, mav, holdtime=20, maxaltchange=10, timeout=60):
|
||||||
tstart = time.time()
|
tstart = time.time()
|
||||||
tholdstart = time.time()
|
tholdstart = time.time()
|
||||||
print("Holding loiter at %u meters for %u seconds" % (start_altitude, holdtime))
|
print("Holding loiter at %u meters for %u seconds" % (start_altitude, holdtime))
|
||||||
while time.time() < tstart + timeout:
|
while time.time() < tstart + holdtime:
|
||||||
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
pos = current_location(mav)
|
pos = current_location(mav)
|
||||||
delta = get_distance(start, pos)
|
delta = get_distance(start, pos)
|
||||||
|
@ -282,7 +282,7 @@ def fly_ArduCopter(viewerip=None):
|
||||||
|
|
||||||
simquad_cmd = util.reltopdir('Tools/autotest/pysim/sim_quad.py') + ' --rate=400 --home=%f,%f,%u,%u' % (
|
simquad_cmd = util.reltopdir('Tools/autotest/pysim/sim_quad.py') + ' --rate=400 --home=%f,%f,%u,%u' % (
|
||||||
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||||
simquad_cmd += ' --wind=2,90,0.2'
|
simquad_cmd += ' --wind=6,45,.3'
|
||||||
if viewerip:
|
if viewerip:
|
||||||
simquad_cmd += ' --fgout=%s:5503' % viewerip
|
simquad_cmd += ' --fgout=%s:5503' % viewerip
|
||||||
|
|
||||||
|
@ -358,9 +358,9 @@ def fly_ArduCopter(viewerip=None):
|
||||||
print("takeoff failed")
|
print("takeoff failed")
|
||||||
failed = True
|
failed = True
|
||||||
|
|
||||||
# Loiter for 10 seconds
|
# Loiter for 30 seconds
|
||||||
print("# Loiter for 30 seconds")
|
print("# Loiter for 30 seconds")
|
||||||
if not loiter(mavproxy, mav, 10):
|
if not loiter(mavproxy, mav, 30):
|
||||||
print("loiter failed")
|
print("loiter failed")
|
||||||
failed = True
|
failed = True
|
||||||
|
|
||||||
|
@ -462,9 +462,3 @@ def fly_ArduCopter(viewerip=None):
|
||||||
return False
|
return False
|
||||||
return True
|
return True
|
||||||
|
|
||||||
#Fly a circle for 60 seconds
|
|
||||||
#print("# Fly a Circle")
|
|
||||||
#if not circle(mavproxy, mav):
|
|
||||||
# print("circle failed")
|
|
||||||
# failed = True
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue