mirror of https://github.com/ArduPilot/ardupilot
autotest: change wait_waypoint mode check
If we change mode while waiting for waypoints then we are no longer running the mission and should fail
This commit is contained in:
parent
e06c900812
commit
c873524966
|
@ -609,7 +609,7 @@ def fly_gps_glitch_auto_test(mavproxy, mav, timeout=120):
|
||||||
mavproxy.send('param set SIM_GPS_GLITCH_Y 0\n')
|
mavproxy.send('param set SIM_GPS_GLITCH_Y 0\n')
|
||||||
|
|
||||||
# continue with the mission
|
# continue with the mission
|
||||||
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500, mode='AUTO')
|
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500)
|
||||||
|
|
||||||
# wait for arrival back home
|
# wait for arrival back home
|
||||||
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
|
@ -800,7 +800,7 @@ def fly_auto_test(mavproxy, mav):
|
||||||
mavproxy.send('rc 3 1500\n')
|
mavproxy.send('rc 3 1500\n')
|
||||||
|
|
||||||
# fly the mission
|
# fly the mission
|
||||||
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500, mode='AUTO')
|
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500)
|
||||||
|
|
||||||
# set throttle to minimum
|
# set throttle to minimum
|
||||||
mavproxy.send('rc 3 1000\n')
|
mavproxy.send('rc 3 1000\n')
|
||||||
|
@ -834,7 +834,7 @@ def fly_avc_test(mavproxy, mav):
|
||||||
mavproxy.send('rc 3 1500\n')
|
mavproxy.send('rc 3 1500\n')
|
||||||
|
|
||||||
# fly the mission
|
# fly the mission
|
||||||
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500, mode='AUTO')
|
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500)
|
||||||
|
|
||||||
# set throttle to minimum
|
# set throttle to minimum
|
||||||
mavproxy.send('rc 3 1000\n')
|
mavproxy.send('rc 3 1000\n')
|
||||||
|
@ -865,7 +865,7 @@ def fly_mission(mavproxy, mav, height_accuracy=-1, target_altitude=None):
|
||||||
mavproxy.send('wp set 1\n')
|
mavproxy.send('wp set 1\n')
|
||||||
mavproxy.send('switch 4\n') # auto mode
|
mavproxy.send('switch 4\n') # auto mode
|
||||||
wait_mode(mav, 'AUTO')
|
wait_mode(mav, 'AUTO')
|
||||||
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500, mode='AUTO')
|
ret = wait_waypoint(mav, 0, num_wp-1, timeout=500)
|
||||||
expect_msg = "Reached command #%u" % (num_wp-1)
|
expect_msg = "Reached command #%u" % (num_wp-1)
|
||||||
if (ret):
|
if (ret):
|
||||||
mavproxy.expect(expect_msg)
|
mavproxy.expect(expect_msg)
|
||||||
|
|
|
@ -172,12 +172,13 @@ def wait_location(mav, loc, accuracy=5, timeout=30, target_altitude=None, height
|
||||||
print("Failed to attain location")
|
print("Failed to attain location")
|
||||||
return False
|
return False
|
||||||
|
|
||||||
def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, timeout=400, mode=None):
|
def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, timeout=400):
|
||||||
'''wait for waypoint ranges'''
|
'''wait for waypoint ranges'''
|
||||||
tstart = get_sim_time(mav)
|
tstart = get_sim_time(mav)
|
||||||
# this message arrives after we set the current WP
|
# this message arrives after we set the current WP
|
||||||
start_wp = mav.waypoint_current()
|
start_wp = mav.waypoint_current()
|
||||||
current_wp = start_wp
|
current_wp = start_wp
|
||||||
|
mode = mav.flightmode
|
||||||
|
|
||||||
print("\ntest: wait for waypoint ranges start=%u end=%u\n\n" % (wpnum_start, wpnum_end))
|
print("\ntest: wait for waypoint ranges start=%u end=%u\n\n" % (wpnum_start, wpnum_end))
|
||||||
# if start_wp != wpnum_start:
|
# if start_wp != wpnum_start:
|
||||||
|
@ -190,10 +191,10 @@ def wait_waypoint(mav, wpnum_start, wpnum_end, allow_skip=True, max_dist=2, time
|
||||||
wp_dist = m.wp_dist
|
wp_dist = m.wp_dist
|
||||||
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
m = mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
|
|
||||||
# if we exited the required mode, finish
|
# if we changed mode, fail
|
||||||
if mode is not None and mav.flightmode != mode:
|
if mav.flightmode != mode:
|
||||||
print('Exited %s mode' % mode)
|
print('Exited %s mode' % mode)
|
||||||
return True
|
return False
|
||||||
|
|
||||||
print("test: WP %u (wp_dist=%u Alt=%d), current_wp: %u, wpnum_end: %u" % (seq, wp_dist, m.alt, current_wp, wpnum_end))
|
print("test: WP %u (wp_dist=%u Alt=%d), current_wp: %u, wpnum_end: %u" % (seq, wp_dist, m.alt, current_wp, wpnum_end))
|
||||||
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
|
if seq == current_wp+1 or (seq > current_wp+1 and allow_skip):
|
||||||
|
|
Loading…
Reference in New Issue