autotest: get Valgrind closer-to-working

This gets us past the reboot problem for the most part, where Valgrind doesn't like you exec'ing
This commit is contained in:
Peter Barker 2020-11-10 12:45:58 +11:00 committed by Andrew Tridgell
parent 0db8745320
commit 58bdae1b52
2 changed files with 26 additions and 10 deletions

View File

@ -901,7 +901,7 @@ class AutoTestCopter(AutoTest):
self.change_mode("RTL")
self.wait_rtl_complete()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.reboot_sitl_mavproxy()
self.reboot_sitl()
self.end_subtest("Completed Batt failsafe disabled test")
# TWO STAGE BATTERY FAILSAFE: Trigger low battery condition, then critical battery condition. Verify RTL and Land actions complete.
@ -921,7 +921,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("LAND")
self.wait_landed_and_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.reboot_sitl_mavproxy()
self.reboot_sitl()
self.end_subtest("Completed two stage battery failsafe test with RTL and Land")
# TWO STAGE BATTERY FAILSAFE: Trigger low battery condition, then critical battery condition. Verify both SmartRTL actions complete
@ -942,7 +942,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("SMART_RTL")
self.wait_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.reboot_sitl_mavproxy()
self.reboot_sitl()
self.end_subtest("Completed two stage battery failsafe test with SmartRTL")
# Trigger low battery condition in land mode with FS_OPTIONS set to allow land mode to continue. Verify landing completes uninterupted.
@ -957,7 +957,7 @@ class AutoTestCopter(AutoTest):
self.wait_mode("LAND")
self.wait_landed_and_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.reboot_sitl_mavproxy()
self.reboot_sitl()
self.end_subtest("Completed battery failsafe with FS_OPTIONS set to continue landing")
# Trigger a critical battery condition, which triggers a land mode failsafe. Trigger an RC failure. Verify the RC failsafe is prevented from stopping the low battery landing.
@ -978,7 +978,7 @@ class AutoTestCopter(AutoTest):
self.wait_landed_and_disarmed()
self.set_parameter('SIM_BATT_VOLTAGE', 12.5)
self.set_parameter("SIM_RC_FAIL", 0)
self.reboot_sitl_mavproxy()
self.reboot_sitl()
self.end_subtest("Completed battery failsafe critical landing")
# Trigger low battery condition with failsafe set to terminate. Copter will disarm and crash.

View File

@ -1345,12 +1345,24 @@ class AutoTest(ABC):
0,
0)
def reboot_check_valgrind_log(self):
valgrind_log = util.valgrind_log_filepath(binary=self.binary,
model=self.frame)
if os.path.getsize(valgrind_log) > 0:
backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))
shutil.move(valgrind_log, backup_valgrind_log)
def reboot_sitl_mav(self, required_bootcount=None):
"""Reboot SITL instance using mavlink and wait for it to reconnect."""
old_bootcount = self.get_parameter('STAT_BOOTCNT')
# ardupilot SITL may actually NAK the reboot; replace with
# run_cmd when we don't do that.
self.send_reboot_command()
if self.valgrind:
self.reboot_check_valgrind_log()
self.stop_SITL()
self.start_SITL(wipe=False)
else:
self.send_reboot_command()
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
def send_cmd_enter_cpu_lockup(self):
@ -1893,11 +1905,15 @@ class AutoTest(ABC):
valgrind_log = util.valgrind_log_filepath(binary=self.binary,
model=self.frame)
if os.path.exists(valgrind_log):
files = glob.glob("*" + valgrind_log)
for valgrind_log in files:
os.chmod(valgrind_log, 0o644)
shutil.copy(valgrind_log,
self.buildlogs_path("%s-valgrind.log" %
self.log_name()))
if os.path.getsize(valgrind_log) > 0:
target = self.buildlogs_path("%s-%s" % (
self.log_name(),
os.path.basename(valgrind_log)))
self.progress("Valgrind log: moving %s to %s" % (valgrind_log, target))
shutil.move(valgrind_log, target)
def start_test(self, description):
self.progress("##################################################################################")