From 445ee8673441f1997c2f28bb14ba2bdb31eb3fbf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 20 Nov 2021 10:38:13 +1100 Subject: [PATCH] autotest: tidy resetting of parameters after battery failsafe test --- Tools/autotest/arducopter.py | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 183cf5f1e0..6a77ec167c 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -901,10 +901,10 @@ class AutoTestCopter(AutoTest): self.setGCSfailsafe(0) self.set_parameter('FS_OPTIONS', 0) self.progress("All GCS failsafe tests complete") - self.reboot_sitl() # Tests all actions and logic behind the battery failsafe def fly_battery_failsafe(self, timeout=300): + self.context_push() ex = None try: self.test_battery_failsafe(timeout=timeout) @@ -912,14 +912,7 @@ class AutoTestCopter(AutoTest): self.print_exception_caught(e) self.disarm_vehicle(force=True) ex = e - - self.set_parameters({ - 'BATT_LOW_VOLT': 0, - 'BATT_CRT_VOLT': 0, - 'BATT_FS_LOW_ACT': 0, - 'BATT_FS_CRT_ACT': 0, - 'FS_OPTIONS': 0, - }) + self.context_pop() self.reboot_sitl() if ex is not None: