From a60fe8f0f34764e01b3a4f67f0904cba672f411c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 10 Mar 2024 15:00:55 +1100 Subject: [PATCH] autotest: remove special-case-for-reboot for Sub we now instantiate AP_Stats so the boot count is available --- Tools/autotest/ardusub.py | 41 --------------------------------------- 1 file changed, 41 deletions(-) diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 44beefaed3e0b..fff37aeed3394 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -10,7 +10,6 @@ from __future__ import print_function import os import sys -import time from pymavlink import mavutil @@ -480,39 +479,6 @@ def SET_POSITION_TARGET_GLOBAL_INT(self): self.change_mode('MANUAL') self.disarm_vehicle() - def reboot_sitl(self): - """Reboot SITL instance and wait it to reconnect.""" - # our battery is reset to full on reboot. So reduce it to 10% - # and wait for it to go above 50. - self.run_cmd( - mavutil.mavlink.MAV_CMD_BATTERY_RESET, - p1=65535, # battery mask - p2=10, # percentage - ) - self.run_cmd_reboot() - tstart = time.time() - while True: - if time.time() - tstart > 30: - raise NotAchievedException("Did not detect reboot") - # ask for the message: - batt = None - try: - self.send_cmd( - mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, - p1=mavutil.mavlink.MAVLINK_MSG_ID_BATTERY_STATUS, - ) - batt = self.mav.recv_match(type='BATTERY_STATUS', - blocking=True, - timeout=1) - except ConnectionResetError: - pass - self.progress("Battery: %s" % str(batt)) - if batt is None: - continue - if batt.battery_remaining > 50: - break - self.initialise_after_reboot_sitl() - def DoubleCircle(self): '''Test entering circle twice''' self.change_mode('CIRCLE') @@ -527,13 +493,6 @@ def default_parameter_list(self): ret["FS_GCS_ENABLE"] = 0 # FIXME return ret - def disabled_tests(self): - ret = super(AutoTestSub, self).disabled_tests() - ret.update({ - "ConfigErrorLoop": "Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247", # noqa - }) - return ret - def MAV_CMD_NAV_LOITER_UNLIM(self): '''test handling of MAV_CMD_NAV_LOITER_UNLIM received via mavlink''' for cmd in self.run_cmd, self.run_cmd_int: