From 705c6e1a8347fbf24343b4f47f413dc6861d4cc6 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Mon, 4 Jul 2022 18:53:52 +1000 Subject: [PATCH] Tools: Add partial unblockage to pitot blockage test --- Tools/autotest/arduplane.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index f55629fdff..ecb4ede11e 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1742,7 +1742,14 @@ class AutoTestPlane(AutoTest): else: raise NotAchievedException("Airspeed Sensor Not Disabled") self.delay_sim_time(20) - # simulate the effect of blockage clearing + # simulate the effect of blockage partially clearing + self.set_parameter("ARSPD_RATIO",1.0) + self.delay_sim_time(60) + if (self.get_parameter("ARSPD_USE") == 0): + self.progress("Faulty Sensor Remains Disabled") + else: + raise NotAchievedException("Fault Sensor Re-Enabled") + # simulate the effect of blockage fully clearing self.set_parameter("ARSPD_RATIO",2.0) self.delay_sim_time(60) if (self.get_parameter("ARSPD_USE") == 1):