mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Tools: autotest: improve test reliability
Also remove redundant reset code Tools: autotest: drain mav and all pexexpects before running each test Tools: autotest: increase some timeouts for failures when running under GDB Tools: autotest: correct ordering of operations in mount test
This commit is contained in:
parent
aca2115401
commit
28e27b4120
@ -715,6 +715,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
self.progress("chan3=%f want=%f" % (m.chan3_raw, normal_rc_throttle))
|
self.progress("chan3=%f want=%f" % (m.chan3_raw, normal_rc_throttle))
|
||||||
if m.chan3_raw == normal_rc_throttle:
|
if m.chan3_raw == normal_rc_throttle:
|
||||||
break
|
break
|
||||||
|
self.disarm_vehicle()
|
||||||
|
|
||||||
def test_rc_overrides(self):
|
def test_rc_overrides(self):
|
||||||
self.context_push()
|
self.context_push()
|
||||||
|
@ -535,10 +535,6 @@ class AutoTestCopter(AutoTest):
|
|||||||
# wait for LAND mode. If unsuccessful an exception will be raised
|
# wait for LAND mode. If unsuccessful an exception will be raised
|
||||||
self.wait_mode('LAND', timeout=timeout)
|
self.wait_mode('LAND', timeout=timeout)
|
||||||
|
|
||||||
# disable battery failsafe
|
|
||||||
self.set_parameter('BATT_FS_LOW_ACT', 0)
|
|
||||||
self.set_parameter('SIM_BATT_VOLTAGE', 13)
|
|
||||||
|
|
||||||
self.progress("Successfully entered LAND after battery failsafe")
|
self.progress("Successfully entered LAND after battery failsafe")
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
@ -719,20 +715,9 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.progress("Waiting for disarm")
|
self.progress("Waiting for disarm")
|
||||||
self.mav.motors_disarmed_wait()
|
self.mav.motors_disarmed_wait()
|
||||||
self.progress("Reached home OK")
|
self.progress("Reached home OK")
|
||||||
self.change_mode("STABILIZE")
|
|
||||||
self.zero_throttle()
|
self.zero_throttle()
|
||||||
# remove if we ever clear battery failsafe flag on disarm:
|
|
||||||
self.mavproxy.send('arm uncheck all\n')
|
|
||||||
self.arm_vehicle()
|
|
||||||
# remove if we ever clear battery failsafe flag on disarm:
|
|
||||||
self.mavproxy.send('arm check all\n')
|
|
||||||
self.progress("Reached home OK")
|
|
||||||
return
|
return
|
||||||
|
|
||||||
# disable fence, enable avoidance
|
|
||||||
self.set_parameter("FENCE_ENABLE", 0)
|
|
||||||
self.set_parameter("AVOID_ENABLE", 1)
|
|
||||||
|
|
||||||
# give we're testing RTL, doing one here probably doesn't make sense
|
# give we're testing RTL, doing one here probably doesn't make sense
|
||||||
home_distance = self.distance_to_home(use_cached_home=True)
|
home_distance = self.distance_to_home(use_cached_home=True)
|
||||||
raise AutoTestTimeoutException(
|
raise AutoTestTimeoutException(
|
||||||
@ -775,14 +760,6 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
self.zero_throttle()
|
self.zero_throttle()
|
||||||
|
|
||||||
self.mavproxy.send('switch 6\n') # stabilize mode
|
|
||||||
self.wait_mode('STABILIZE')
|
|
||||||
# remove if we ever clear battery failsafe flag on disarm
|
|
||||||
self.mavproxy.send('arm uncheck all\n')
|
|
||||||
self.arm_vehicle()
|
|
||||||
# remove if we ever clear battery failsafe flag on disarm:
|
|
||||||
self.mavproxy.send('arm check all\n')
|
|
||||||
|
|
||||||
def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20):
|
def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20):
|
||||||
"""fly_gps_glitch_loiter_test. Fly south east in loiter and test
|
"""fly_gps_glitch_loiter_test. Fly south east in loiter and test
|
||||||
reaction to gps glitch."""
|
reaction to gps glitch."""
|
||||||
@ -887,7 +864,8 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.progress("GPS glitch test passed!"
|
self.progress("GPS glitch test passed!"
|
||||||
" stayed within %u meters for %u seconds" %
|
" stayed within %u meters for %u seconds" %
|
||||||
(max_distance, timeout))
|
(max_distance, timeout))
|
||||||
self.do_RTL()
|
# re-arming is problematic because the GPS is glitching!
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
# fly_gps_glitch_auto_test - fly mission and test reaction to gps glitch
|
# fly_gps_glitch_auto_test - fly mission and test reaction to gps glitch
|
||||||
def fly_gps_glitch_auto_test(self, timeout=120):
|
def fly_gps_glitch_auto_test(self, timeout=120):
|
||||||
@ -993,6 +971,8 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.show_gps_and_sim_positions(False)
|
self.show_gps_and_sim_positions(False)
|
||||||
|
|
||||||
self.progress("GPS Glitch test Auto completed: passed!")
|
self.progress("GPS Glitch test Auto completed: passed!")
|
||||||
|
# re-arming is problematic because the GPS is glitching!
|
||||||
|
self.reboot_sitl()
|
||||||
|
|
||||||
# fly_simple - assumes the simple bearing is initialised to be
|
# fly_simple - assumes the simple bearing is initialised to be
|
||||||
# directly north flies a box with 100m west, 15 seconds north,
|
# directly north flies a box with 100m west, 15 seconds north,
|
||||||
@ -1039,9 +1019,6 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.mav.recv_match(type='VFR_HUD', blocking=True)
|
self.mav.recv_match(type='VFR_HUD', blocking=True)
|
||||||
self.set_rc(2, 1500)
|
self.set_rc(2, 1500)
|
||||||
|
|
||||||
# restore to default
|
|
||||||
self.set_parameter("SIMPLE", 0)
|
|
||||||
|
|
||||||
# hover in place
|
# hover in place
|
||||||
self.hover()
|
self.hover()
|
||||||
|
|
||||||
@ -1499,7 +1476,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
if gpi.lat != 0:
|
if gpi.lat != 0:
|
||||||
break
|
break
|
||||||
|
|
||||||
if self.get_sim_time_cached() - tstart > 10:
|
if self.get_sim_time_cached() - tstart > 20:
|
||||||
raise AutoTestTimeoutException("Did not get non-zero lat")
|
raise AutoTestTimeoutException("Did not get non-zero lat")
|
||||||
|
|
||||||
self.takeoff()
|
self.takeoff()
|
||||||
@ -2258,7 +2235,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
delta_ef = pos - dest
|
delta_ef = pos - dest
|
||||||
dist = math.sqrt(delta_ef.x * delta_ef.x + delta_ef.y * delta_ef.y)
|
dist = math.sqrt(delta_ef.x * delta_ef.x + delta_ef.y * delta_ef.y)
|
||||||
self.progress("dist=%f" % (dist,))
|
self.progress("dist=%f" % (dist,))
|
||||||
if dist < 0.1:
|
if dist < 1:
|
||||||
break
|
break
|
||||||
delta_bf = self.earth_to_body(delta_ef)
|
delta_bf = self.earth_to_body(delta_ef)
|
||||||
angle_x = math.atan2(delta_bf.x, delta_bf.z)
|
angle_x = math.atan2(delta_bf.x, delta_bf.z)
|
||||||
@ -2422,7 +2399,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.run_cmd_do_set_mode("ACRO")
|
self.run_cmd_do_set_mode("ACRO")
|
||||||
self.mav.motors_disarmed_wait()
|
self.mav.motors_disarmed_wait()
|
||||||
|
|
||||||
def test_mount_pitch(self, despitch, despitch_tolerance, timeout=5):
|
def test_mount_pitch(self, despitch, despitch_tolerance, timeout=10):
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
if self.get_sim_time_cached() - tstart > timeout:
|
if self.get_sim_time_cached() - tstart > timeout:
|
||||||
@ -2512,7 +2489,6 @@ class AutoTestCopter(AutoTest):
|
|||||||
raise NotAchievedException("Mount stabilising when not requested")
|
raise NotAchievedException("Mount stabilising when not requested")
|
||||||
|
|
||||||
self.progress("Enable pitch stabilization using MOUNT_CONFIGURE")
|
self.progress("Enable pitch stabilization using MOUNT_CONFIGURE")
|
||||||
self.do_pitch(despitch)
|
|
||||||
self.mav.mav.mount_configure_send(
|
self.mav.mav.mount_configure_send(
|
||||||
1, # target system
|
1, # target system
|
||||||
1, # target component
|
1, # target component
|
||||||
@ -2521,6 +2497,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
1, # stab-pitch
|
1, # stab-pitch
|
||||||
0)
|
0)
|
||||||
|
|
||||||
|
self.do_pitch(despitch)
|
||||||
self.test_mount_pitch(-despitch, 1)
|
self.test_mount_pitch(-despitch, 1)
|
||||||
|
|
||||||
self.progress("Disable pitch using MAV_CMD_DO_MOUNT_CONFIGURE")
|
self.progress("Disable pitch using MAV_CMD_DO_MOUNT_CONFIGURE")
|
||||||
|
@ -371,12 +371,15 @@ class AutoTest(ABC):
|
|||||||
global expect_list
|
global expect_list
|
||||||
expect_list.extend(list_to_add)
|
expect_list.extend(list_to_add)
|
||||||
|
|
||||||
def idle_hook(self, mav):
|
def drain_all_pexpects(self):
|
||||||
"""Called when waiting for a mavlink message."""
|
|
||||||
global expect_list
|
global expect_list
|
||||||
for p in expect_list:
|
for p in expect_list:
|
||||||
util.pexpect_drain(p)
|
util.pexpect_drain(p)
|
||||||
|
|
||||||
|
def idle_hook(self, mav):
|
||||||
|
"""Called when waiting for a mavlink message."""
|
||||||
|
self.drain_all_pexpects()
|
||||||
|
|
||||||
def message_hook(self, mav, msg):
|
def message_hook(self, mav, msg):
|
||||||
"""Called as each mavlink msg is received."""
|
"""Called as each mavlink msg is received."""
|
||||||
self.idle_hook(mav)
|
self.idle_hook(mav)
|
||||||
@ -1650,8 +1653,10 @@ class AutoTest(ABC):
|
|||||||
self.mav.idle_hooks.append(self.idle_hook)
|
self.mav.idle_hooks.append(self.idle_hook)
|
||||||
|
|
||||||
def check_sitl_reset(self):
|
def check_sitl_reset(self):
|
||||||
|
self.wait_heartbeat()
|
||||||
if self.armed():
|
if self.armed():
|
||||||
self.forced_post_test_sitl_reboots += 1
|
self.forced_post_test_sitl_reboots += 1
|
||||||
|
self.progress("Force-resetting SITL")
|
||||||
self.reboot_sitl() # that'll learn it
|
self.reboot_sitl() # that'll learn it
|
||||||
|
|
||||||
def show_test_timings_key_sorter(self, t):
|
def show_test_timings_key_sorter(self, t):
|
||||||
@ -1684,6 +1689,9 @@ class AutoTest(ABC):
|
|||||||
try:
|
try:
|
||||||
self.check_rc_defaults()
|
self.check_rc_defaults()
|
||||||
self.change_mode(self.default_mode())
|
self.change_mode(self.default_mode())
|
||||||
|
self.drain_mav()
|
||||||
|
self.drain_all_pexpects()
|
||||||
|
|
||||||
test_function()
|
test_function()
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
self.test_timings[desc] = time.time() - start_time
|
self.test_timings[desc] = time.time() - start_time
|
||||||
@ -1735,7 +1743,7 @@ class AutoTest(ABC):
|
|||||||
old = self.mav.messages.get("HOME_POSITION", None)
|
old = self.mav.messages.get("HOME_POSITION", None)
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
if self.get_sim_time() - tstart > 30:
|
if self.get_sim_time_cached() - tstart > 30:
|
||||||
raise NotAchievedException("Failed to poll home position")
|
raise NotAchievedException("Failed to poll home position")
|
||||||
if not quiet:
|
if not quiet:
|
||||||
self.progress("Sending MAV_CMD_GET_HOME_POSITION")
|
self.progress("Sending MAV_CMD_GET_HOME_POSITION")
|
||||||
|
Loading…
Reference in New Issue
Block a user