autotest: use wait_statustext rather than mavproxy.expect

This is important when running under Valgrind as the text can be
significantly delayed.  wait_statustext times out in simulation time,
whereas mavproxy.expect has a flat 60s timeout
This commit is contained in:
Peter Barker 2021-02-17 12:53:13 +11:00 committed by Peter Barker
parent c20c4a6308
commit a292fe1b8b
5 changed files with 51 additions and 51 deletions

View File

@ -618,7 +618,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 4)
self.takeoffAndMoveAway()
self.set_parameter('SIM_GPS_DISABLE', 1)
self.mavproxy.expect("SmartRTL deactivated: bad position")
self.wait_statustext("SmartRTL deactivated: bad position", timeout=60)
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
self.delay_sim_time(5)
@ -633,7 +633,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 5)
self.takeoffAndMoveAway()
self.set_parameter('SIM_GPS_DISABLE', 1)
self.mavproxy.expect("SmartRTL deactivated: bad position")
self.wait_statustext("SmartRTL deactivated: bad position", timeout=60)
self.set_parameter('SIM_GPS_DISABLE', 0)
self.wait_ekf_happy()
self.delay_sim_time(5)
@ -718,7 +718,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("SMART_RTL")
self.wait_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.takeoffAndMoveAway()
self.set_heartbeat_rate(0)
@ -733,7 +733,7 @@ class AutoTestCopter(AutoTest):
self.install_message_hook_context(ensure_smartrtl)
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.set_heartbeat_rate(0)
self.wait_statustext("GCS Failsafe")
@ -741,7 +741,7 @@ class AutoTestCopter(AutoTest):
self.end_subtest("GCS failsafe SmartRTL twice")
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.context_pop()
# Trigger telemetry loss with failsafe disabled. Verify no action taken.
@ -763,7 +763,7 @@ class AutoTestCopter(AutoTest):
self.set_heartbeat_rate(0)
self.wait_mode("RTL")
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.change_mode("LOITER")
self.end_subtest("Completed GCS failsafe recovery test")
@ -775,7 +775,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("RTL")
self.wait_rtl_complete()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.end_subtest("Completed GCS failsafe RTL with no options test")
# Trigger telemetry loss with failsafe enabled. Verify failsafe triggers and land completes
@ -786,7 +786,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("LAND")
self.wait_landed_and_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.end_subtest("Completed GCS failsafe land with no options test")
# Trigger telemetry loss with failsafe enabled. Verify failsafe triggers and SmartRTL completes
@ -797,7 +797,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("SMART_RTL")
self.wait_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.end_subtest("Completed GCS failsafe SmartRTL->RTL with no options test")
# Trigger telemetry loss with failsafe enabled. Verify failsafe triggers and SmartRTL completes
@ -808,7 +808,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("SMART_RTL")
self.wait_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.end_subtest("Completed GCS failsafe SmartRTL->Land with no options test")
# Trigger telemetry loss with an invalid failsafe value. Verify failsafe triggers and RTL completes
@ -819,7 +819,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("RTL")
self.wait_rtl_complete()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.end_subtest("Completed GCS failsafe invalid value with no options test")
# Trigger telemetry loss with failsafe enabled to test FS_OPTIONS settings
@ -832,34 +832,34 @@ class AutoTestCopter(AutoTest):
self.takeoffAndMoveAway()
self.progress("Testing continue in pilot controlled modes")
self.set_heartbeat_rate(0)
self.mavproxy.expect("GCS Failsafe - Continuing Pilot Control")
self.wait_statustext("GCS Failsafe - Continuing Pilot Control", timeout=60)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.progress("Testing continue in auto mission")
self.set_parameter('FS_OPTIONS', 2)
self.change_mode("AUTO")
self.delay_sim_time(5)
self.set_heartbeat_rate(0)
self.mavproxy.expect("GCS Failsafe - Continuing Auto Mode")
self.wait_statustext("GCS Failsafe - Continuing Auto Mode", timeout=60)
self.delay_sim_time(5)
self.wait_mode("AUTO")
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.progress("Testing continue landing in land mode")
self.set_parameter('FS_OPTIONS', 8)
self.change_mode("LAND")
self.delay_sim_time(5)
self.set_heartbeat_rate(0)
self.mavproxy.expect("GCS Failsafe - Continuing Landing")
self.wait_statustext("GCS Failsafe - Continuing Landing", timeout=60)
self.delay_sim_time(5)
self.wait_mode("LAND")
self.wait_landed_and_disarmed()
self.set_heartbeat_rate(self.speedup)
self.mavproxy.expect("GCS Failsafe Cleared")
self.wait_statustext("GCS Failsafe Cleared", timeout=60)
self.end_subtest("Completed GCS failsafe with option bits")
self.setGCSfailsafe(0)
@ -903,11 +903,11 @@ class AutoTestCopter(AutoTest):
self.start_subtest("Batt failsafe disabled test")
self.takeoffAndMoveAway()
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_statustext("Battery 1 is low", timeout=60)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_statustext("Battery 1 is critical", timeout=60)
self.delay_sim_time(5)
self.wait_mode("ALT_HOLD")
self.change_mode("RTL")
@ -923,12 +923,12 @@ class AutoTestCopter(AutoTest):
self.set_parameter('BATT_FS_LOW_ACT', 2)
self.set_parameter('BATT_FS_CRT_ACT', 1)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_statustext("Battery 1 is low", timeout=60)
self.delay_sim_time(5)
self.wait_mode("RTL")
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_statustext("Battery 1 is critical", timeout=60)
self.delay_sim_time(5)
self.wait_mode("LAND")
self.wait_landed_and_disarmed()
@ -943,13 +943,13 @@ class AutoTestCopter(AutoTest):
self.set_parameter('BATT_FS_CRT_ACT', 4)
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_statustext("Battery 1 is low", timeout=60)
self.delay_sim_time(5)
self.wait_mode("SMART_RTL")
self.change_mode("LOITER")
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_statustext("Battery 1 is critical", timeout=60)
self.delay_sim_time(5)
self.wait_mode("SMART_RTL")
self.wait_disarmed()
@ -964,7 +964,7 @@ class AutoTestCopter(AutoTest):
self.change_mode("LAND")
self.delay_sim_time(5)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_statustext("Battery 1 is low", timeout=60)
self.delay_sim_time(5)
self.wait_mode("LAND")
self.wait_landed_and_disarmed()
@ -981,7 +981,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('FS_THR_ENABLE', 1)
self.delay_sim_time(5)
self.set_parameter('SIM_BATT_VOLTAGE', 10.0)
self.mavproxy.expect("Battery 1 is critical")
self.wait_statustext("Battery 1 is critical", timeout=60)
self.wait_mode("LAND")
self.delay_sim_time(10)
self.set_parameter("SIM_RC_FAIL", 1)
@ -999,7 +999,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('BATT_FS_LOW_ACT', 5)
self.delay_sim_time(10)
self.set_parameter('SIM_BATT_VOLTAGE', 11.4)
self.mavproxy.expect("Battery 1 is low")
self.wait_statustext("Battery 1 is low", timeout=60)
self.wait_disarmed()
self.end_subtest("Completed terminate failsafe test")
@ -2653,7 +2653,7 @@ class AutoTestCopter(AutoTest):
self.arm_vehicle()
self.change_mode('AUTO')
self.set_rc(3, 1600)
self.mavproxy.expect('BANG')
self.wait_statustext('BANG', timeout=60)
self.disarm_vehicle(force=True)
self.reboot_sitl()
@ -2667,7 +2667,7 @@ class AutoTestCopter(AutoTest):
0,
0,
0)
self.mavproxy.expect('BANG')
self.wait_statustext('BANG', timeout=60)
self.disarm_vehicle(force=True)
self.reboot_sitl()
@ -2677,7 +2677,7 @@ class AutoTestCopter(AutoTest):
self.progress("Test manual triggering")
self.takeoff(20)
self.set_rc(9, 2000)
self.mavproxy.expect('BANG')
self.wait_statustext('BANG', timeout=60)
self.set_rc(9, 1000)
self.disarm_vehicle(force=True)
self.reboot_sitl()
@ -2688,7 +2688,7 @@ class AutoTestCopter(AutoTest):
self.set_rc(9, 1500)
self.set_parameter("SIM_ENGINE_MUL", 0)
self.set_parameter("SIM_ENGINE_FAIL", 1)
self.mavproxy.expect('BANG')
self.wait_statustext('BANG', timeout=60)
self.set_rc(9, 1000)
self.disarm_vehicle(force=True)
self.reboot_sitl()
@ -3561,8 +3561,8 @@ class AutoTestCopter(AutoTest):
self.mavproxy.send('mode auto\n')
self.wait_mode('AUTO')
self.set_rc(3, 1500)
self.mavproxy.expect("Gripper Grabbed")
self.mavproxy.expect("Gripper Released")
self.wait_statustext("Gripper Grabbed", timeout=60)
self.wait_statustext("Gripper Released", timeout=60)
except Exception as e:
self.progress("Exception caught: %s" % (
self.get_exception_stacktrace(e)))
@ -5342,7 +5342,7 @@ class AutoTestCopter(AutoTest):
self.reboot_sitl()
self.set_rc(9, 1000) # remember this is a switch position - stop
self.customise_SITL_commandline(["--uartF=sim:richenpower"])
self.mavproxy.expect("requested state is not RUN")
self.wait_statustext("requested state is not RUN", timeout=60)
self.set_message_rate_hz("GENERATOR_STATUS", 10)
self.drain_mav_unparsed()
@ -5360,9 +5360,9 @@ class AutoTestCopter(AutoTest):
finally:
self.remove_message_hook(my_message_hook)
if "Generator HIGH" not in [x.text for x in messages]:
self.mavproxy.expect("Generator HIGH")
self.wait_statustext("Generator HIGH", timeout=60)
self.set_rc(9, 1000) # remember this is a switch position - stop
self.mavproxy.expect("requested state is not RUN", timeout=200)
self.wait_statustext("requested state is not RUN", timeout=200)
self.set_rc(9, 1500) # remember this is a switch position - idle
self.wait_generator_speed_and_state(3000, 8000, mavutil.mavlink.MAV_GENERATOR_STATUS_FLAG_IDLE)

View File

@ -538,7 +538,7 @@ class AutoTestPlane(AutoTest):
self.change_mode('AUTO')
self.wait_waypoint(1, num_wp, max_dist=60)
self.wait_groundspeed(0, 0.5, timeout=mission_timeout)
self.mavproxy.expect("Auto disarmed")
self.wait_statustext("Auto disarmed", timeout=60)
self.progress("Mission OK")
def fly_do_reposition(self):
@ -1018,9 +1018,9 @@ class AutoTestPlane(AutoTest):
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
self.mavproxy.expect("Gripper Grabbed")
self.mavproxy.expect("Gripper Released")
self.mavproxy.expect("Auto disarmed")
self.wait_statustext("Gripper Grabbed", timeout=60)
self.wait_statustext("Gripper Released", timeout=60)
self.wait_statustext("Auto disarmed", timeout=60)
except Exception as e:
self.progress("Exception caught:")
self.progress(self.get_exception_stacktrace(e))
@ -1275,7 +1275,7 @@ class AutoTestPlane(AutoTest):
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
self.mavproxy.expect("BANG")
self.wait_statustext("BANG", timeout=60)
self.disarm_vehicle(force=True)
self.reboot_sitl()
@ -1294,7 +1294,7 @@ class AutoTestPlane(AutoTest):
self.progress("Diving")
self.set_rc(2, 2000)
self.mavproxy.expect("BANG")
self.wait_statustext("BANG", timeout=60)
self.disarm_vehicle(force=True)
self.reboot_sitl()
@ -1513,7 +1513,7 @@ class AutoTestPlane(AutoTest):
raise NotAchievedException("Did not receive GLOBAL_POSITION_INT message")
if abs(rf.distance - gpi.relative_alt/1000.0) > 3:
raise NotAchievedException("rangefinder alt (%s) disagrees with global-position-int.relative_alt (%s)" % (rf.distance, gpi.relative_alt/1000.0))
self.mavproxy.expect("Auto disarmed")
self.wait_statustext("Auto disarmed", timeout=60)
self.progress("Ensure RFND messages in log")
if not self.current_onboard_log_contains_message("RFND"):

View File

@ -276,8 +276,8 @@ class AutoTestSub(AutoTest):
self.wait_ready_to_arm()
self.arm_vehicle()
self.change_mode('AUTO')
self.mavproxy.expect("Gripper Grabbed")
self.mavproxy.expect("Gripper Released")
self.wait_statustext("Gripper Grabbed", timeout=60)
self.wait_statustext("Gripper Released", timeout=60)
except Exception as e:
self.progress("Exception caught: %s" % (
self.get_exception_stacktrace(e)))

View File

@ -5863,7 +5863,7 @@ Also, ignores heartbeats not from our target system'''
self.mavproxy_load_module("sitl_calibration")
self.mavproxy_load_module("calibration")
self.mavproxy_load_module("relay")
self.mavproxy.expect("is using GPS")
self.wait_statustext("is using GPS", timeout=60)
self.mavproxy.send("accelcalsimple\n")
self.mavproxy.expect("Calibrated")
# disable it to not interfert with calibration acceptation

View File

@ -396,7 +396,7 @@ class AutoTestRover(AutoTest):
self.arm_vehicle()
self.change_mode('AUTO')
self.wait_waypoint(1, 4, max_dist=5)
self.mavproxy.expect("Mission Complete")
self.wait_statustext("Mission Complete", timeout=600)
self.disarm_vehicle()
self.progress("Mission OK")
@ -405,9 +405,9 @@ class AutoTestRover(AutoTest):
self.change_mode('AUTO')
self.wait_ready_to_arm()
self.arm_vehicle()
self.mavproxy.expect("Gripper Grabbed")
self.mavproxy.expect("Gripper Released")
self.mavproxy.expect("Mission Complete")
self.wait_statustext("Gripper Grabbed", timeout=60)
self.wait_statustext("Gripper Released", timeout=60)
self.wait_statustext("Mission Complete", timeout=60)
self.disarm_vehicle()
def do_get_banner(self):
@ -550,7 +550,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
(m.wp_dist, wp_dist_min,))
# wait for mission to complete
self.mavproxy.expect("Mission Complete")
self.wait_statustext("Mission Complete", timeout=60)
# the EKF doesn't pull us down to 0 speed:
self.wait_groundspeed(0, 0.5, timeout=600)
@ -586,7 +586,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.set_rc(3, 1550)
self.wait_distance_to_home(25, 100000, timeout=60)
self.change_mode("RTL")
self.mavproxy.expect("APM: Reached destination")
self.wait_statustext("Reached destination", timeout=60)
# now enable avoidance and make sure we can't:
self.set_rc(10, 2000)
self.change_mode("ACRO")