autotest: reboot after any context in which a reboot was done

this makes the assumption that any reboot done within a SITL was because some parameter changes only take effect after a reboot.

... so after we have reverted the parameters, reboot again to make the reverted parameter values take effect
This commit is contained in:
Peter Barker 2024-07-08 12:33:30 +10:00 committed by Peter Barker
parent 0cf357eb51
commit 69c76a96d3
4 changed files with 42 additions and 18 deletions

View File

@ -2421,8 +2421,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
ex = e
self.set_rc(2, 1500)
self.context_pop()
self.reboot_sitl(force=True)
self.context_pop()
if ex is not None:
raise ex
@ -2503,8 +2503,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.print_exception_caught(e)
ex = e
self.context_pop()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
if ex is not None:
@ -5640,10 +5640,11 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.print_exception_caught(e)
ex = e
self.context_pop()
self.mav.mav.srcSystem = old_srcSystem
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl() # to handle MNT1_TYPE changing
if ex is not None:
@ -7149,8 +7150,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.print_exception_caught(e)
ex = e
self.context_pop()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
self.progress("All done")
@ -7415,9 +7416,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.assert_current_onboard_log_contains_message("PRX")
self.assert_current_onboard_log_contains_message("PRXR")
self.context_pop()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
def ProximitySensors(self):
@ -7567,8 +7568,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e
self.context_pop()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex
@ -9227,9 +9228,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.run_replay(current_log_filepath)
replay_log_filepath = self.current_onboard_log_filepath()
self.context_pop()
replay_log_filepath = self.current_onboard_log_filepath()
self.progress("Replay log path: %s" % str(replay_log_filepath))
check_replay = util.load_local_module("Tools/Replay/check_replay.py")
@ -10398,9 +10400,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.wait_servo_channel_value(pump_ch, pump_ch_min)
self.disarm_vehicle(force=True)
self.context_pop()
self.disarm_vehicle(force=True)
self.reboot_sitl()
self.progress("Sprayer OK")
@ -11344,7 +11347,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.delay_sim_time(1500)
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl(force=True)
def GuidedForceArm(self):
@ -11410,6 +11416,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.delay_sim_time(1500)
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl(force=True)
@ -11507,6 +11515,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.reboot_sitl()
self.takeoff(30, mode='LOITER')
self.context_push()
self.context_collect('STATUSTEXT')
self.set_parameters({
"SIM_ENGINE_FAIL": 1,
"SIM_ENGINE_MUL": 0.5,
@ -11514,9 +11524,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
})
self.wait_statustext("Gripper Load Released", timeout=60)
self.context_pop()
self.do_RTL()
self.context_pop()
self.reboot_sitl()
def assert_home_position_not_set(self):

View File

@ -729,9 +729,10 @@ class AutoTestHelicopter(AutoTestCopter):
raise NotAchievedException("Never saw an airspeed1")
if airspeed[1] is None:
raise NotAchievedException("Never saw an airspeed2")
self.context_pop()
if not self.current_onboard_log_contains_message("ARSP"):
raise NotAchievedException("Expected ARSP log message")
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()

View File

@ -334,8 +334,8 @@ class AutoTestRover(vehicle_test_suite.TestSuite):
except Exception as e:
self.print_exception_caught(e)
ex = e
self.context_pop()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
if ex:
raise ex
@ -578,9 +578,9 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
except Exception as e:
self.print_exception_caught(e)
ex = e
self.disarm_vehicle(force=True)
self.context_pop()
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
self.disarm_vehicle(force=True)
self.reboot_sitl()
if ex:
raise ex
@ -1133,8 +1133,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.print_exception_caught(e)
ex = e
self.context_pop()
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()
if ex is not None:
@ -1223,8 +1223,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.print_exception_caught(e)
ex = e
self.context_pop()
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()
if ex is not None:

View File

@ -205,6 +205,7 @@ class Context(object):
def __init__(self):
self.parameters = []
self.sitl_commandline_customised = False
self.reboot_sitl_was_done = False
self.message_hooks = []
self.collections = {}
self.heartbeat_interval_ms = 1000
@ -2223,7 +2224,12 @@ class TestSuite(ABC):
0,
0)
def reboot_sitl(self, required_bootcount=None, force=False, check_position=True):
def reboot_sitl(self,
required_bootcount=None,
force=False,
check_position=True,
mark_context=True,
):
"""Reboot SITL instance and wait for it to reconnect."""
if self.armed() and not force:
raise NotAchievedException("Reboot attempted while armed")
@ -2232,6 +2238,8 @@ class TestSuite(ABC):
self.do_heartbeats(force=True)
if check_position and self.frame != 'sailboat': # sailboats drift with wind!
self.assert_simstate_location_is_at_startup_location()
if mark_context:
self.context_get().reboot_sitl_was_done = True
def reboot_sitl_mavproxy(self, required_bootcount=None):
"""Reboot SITL instance using MAVProxy and wait for it to reconnect."""
@ -6290,6 +6298,9 @@ class TestSuite(ABC):
f.close()
self.start_SITL(wipe=False)
self.set_streamrate(self.sitl_streamrate())
elif dead.reboot_sitl_was_done:
self.progress("Doing implicit context-pop reboot")
self.reboot_sitl(mark_context=False)
# the following method is broken under Python2; can't **build_opts
# def context_start_custom_binary(self, extra_defines={}):
@ -10070,7 +10081,6 @@ Also, ignores heartbeats not from our target system'''
self.print_exception_caught(e)
self.disarm_vehicle()
ex = e
self.context_pop()
self.mavproxy_unload_module(mavproxy, 'dataflash_logger')
# the following things won't work - but they shouldn't die either:
@ -10090,6 +10100,8 @@ Also, ignores heartbeats not from our target system'''
self.mavproxy_unload_module(mavproxy, 'log')
self.context_pop()
self.stop_mavproxy(mavproxy)
self.reboot_sitl()
if ex is not None: