diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 833c69ad11..8a57666b80 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -879,6 +879,21 @@ class AutoTestPlane(AutoTest): raise NotAchievedException("Receiver not healthy") self.change_mode('MANUAL') + self.progress("Ensure long failsafe can trigger when short failsafe disabled") + self.context_push() + ex = None + try: + self.set_parameter("FS_SHORT_ACTN", 3) # 3 means disabled + self.set_parameter("SIM_RC_FAIL", 1) + self.wait_statustext("Long event on") + except Exception as e: + self.progress("Exception caught:") + self.progress(self.get_exception_stacktrace(e)) + ex = e + self.context_pop() + if ex is not None: + raise ex + def test_gripper_mission(self): self.context_push() ex = None diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 60dd04297d..3399e018ba 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -1909,7 +1909,10 @@ class AutoTest(ABC): return raise AutoTestTimeoutException("Failed to get EKF.flags=%u disabled" % not_required_value) - def wait_text(self, text, timeout=20, the_function=None): + def wait_text(self, *args, **kwargs): + self.wait_statustext(*args, **kwargs) + + def wait_statustext(self, text, timeout=20, the_function=None): """Wait a specific STATUS_TEXT.""" self.progress("Waiting for text : %s" % text.lower()) tstart = self.get_sim_time()