Skip to content

Commit

Permalink
autotest: reboot after any context in which a reboot was done
Browse files Browse the repository at this point in the history
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
  • Loading branch information
peterbarker committed Jul 9, 2024
1 parent 0cf357e commit 69c76a9
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 18 deletions.
33 changes: 22 additions & 11 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -2421,8 +2421,8 @@ def OpticalFlowLimits(self):
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
Expand Down Expand Up @@ -2503,8 +2503,8 @@ def OpticalFlowCalibration(self):
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:
Expand Down Expand Up @@ -5640,10 +5640,11 @@ def Mount(self):
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:
Expand Down Expand Up @@ -7149,8 +7150,8 @@ def PrecisionLoiterCompanion(self):
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")

Expand Down Expand Up @@ -7415,9 +7416,9 @@ def AC_Avoidance_Proximity(self):
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):
Expand Down Expand Up @@ -7567,8 +7568,8 @@ def shove(a, b):
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
Expand Down Expand Up @@ -9227,9 +9228,10 @@ def test_replay_bit(self, bit):

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")
Expand Down Expand Up @@ -10398,9 +10400,10 @@ def Sprayer(self):

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")
Expand Down Expand Up @@ -11344,7 +11347,10 @@ def check_altitude(mav, m):

self.delay_sim_time(1500)

self.disarm_vehicle(force=True)

self.context_pop()

self.reboot_sitl(force=True)

def GuidedForceArm(self):
Expand Down Expand Up @@ -11410,6 +11416,8 @@ def check_altitude(mav, m):

self.delay_sim_time(1500)

self.disarm_vehicle(force=True)

self.context_pop()
self.reboot_sitl(force=True)

Expand Down Expand Up @@ -11507,16 +11515,19 @@ def GripperReleaseOnThrustLoss(self):
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,
"FLIGHT_OPTIONS": 4,
})

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):
Expand Down
3 changes: 2 additions & 1 deletion Tools/autotest/helicopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -729,9 +729,10 @@ def check_airspeeds(mav, m):
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()

Expand Down
8 changes: 4 additions & 4 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -334,8 +334,8 @@ def Sprayer(self):
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
Expand Down Expand Up @@ -578,9 +578,9 @@ def AC_Avoidance(self):
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
Expand Down Expand Up @@ -1133,8 +1133,8 @@ def RCOverrides(self):
self.print_exception_caught(e)
ex = e

self.context_pop()
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()

if ex is not None:
Expand Down Expand Up @@ -1223,8 +1223,8 @@ def MANUAL_CONTROL(self):
self.print_exception_caught(e)
ex = e

self.context_pop()
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()

if ex is not None:
Expand Down
16 changes: 14 additions & 2 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -2223,7 +2224,12 @@ def send_cmd_enter_cpu_lockup(self):
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")
Expand All @@ -2232,6 +2238,8 @@ def reboot_sitl(self, required_bootcount=None, force=False, check_position=True)
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."""
Expand Down Expand Up @@ -6290,6 +6298,9 @@ def context_pop(self, process_interaction_allowed=True, hooks_already_removed=Fa
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={}):
Expand Down Expand Up @@ -10070,7 +10081,6 @@ def DataFlashOverMAVLink(self):
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:
Expand All @@ -10090,6 +10100,8 @@ def DataFlashOverMAVLink(self):

self.mavproxy_unload_module(mavproxy, 'log')

self.context_pop()

self.stop_mavproxy(mavproxy)
self.reboot_sitl()
if ex is not None:
Expand Down

0 comments on commit 69c76a9

Please sign in to comment.