mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
autotest: Increase startup wait time to allow EKF and GPS checks to pass
This commit is contained in:
parent
aaab250f13
commit
e0d87bf529
@ -14,8 +14,8 @@ HOME=mavutil.location(40.071374969556928,-105.22978898137808,1583.702759,246)
|
||||
homeloc = None
|
||||
|
||||
def arm_rover(mavproxy, mav):
|
||||
# wait for EKF to settle
|
||||
wait_seconds(mav, 15)
|
||||
# wait for EKF and GPS checks to pass
|
||||
wait_seconds(mav, 30)
|
||||
|
||||
mavproxy.send('arm throttle\n')
|
||||
mavproxy.expect('ARMED')
|
||||
|
@ -987,8 +987,8 @@ def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
setup_rc(mavproxy)
|
||||
homeloc = mav.location()
|
||||
|
||||
# wait 10sec to allow EKF to settle
|
||||
wait_seconds(mav, 10)
|
||||
# wait for EKF and GPS checks to pass
|
||||
wait_seconds(mav, 30)
|
||||
|
||||
# Arm
|
||||
print("# Arm motors")
|
||||
@ -1340,8 +1340,8 @@ def fly_CopterAVC(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
print("Lowering rotor speed")
|
||||
mavproxy.send('rc 8 1000\n')
|
||||
|
||||
# wait 20sec to allow EKF to settle
|
||||
wait_seconds(mav, 20)
|
||||
# wait for EKF and GPS checks to pass
|
||||
wait_seconds(mav, 30)
|
||||
|
||||
# Arm
|
||||
print("# Arm motors")
|
||||
|
@ -17,8 +17,8 @@ homeloc = None
|
||||
def takeoff(mavproxy, mav):
|
||||
'''takeoff get to 30m altitude'''
|
||||
|
||||
# wait for EKF to settle
|
||||
wait_seconds(mav, 15)
|
||||
# wait for EKF and GPS checks to pass
|
||||
wait_seconds(mav, 30)
|
||||
|
||||
mavproxy.send('arm throttle\n')
|
||||
mavproxy.expect('ARMED')
|
||||
|
@ -101,8 +101,8 @@ def fly_QuadPlane(binary, viewerip=None, map=False, valgrind=False, gdb=False):
|
||||
homeloc = mav.location()
|
||||
print("Home location: %s" % homeloc)
|
||||
|
||||
# wait for EKF to settle
|
||||
wait_seconds(mav, 15)
|
||||
# wait for EKF and GPS checks to pass
|
||||
wait_seconds(mav, 30)
|
||||
|
||||
mavproxy.send('arm throttle\n')
|
||||
mavproxy.expect('ARMED')
|
||||
|
Loading…
Reference in New Issue
Block a user