From 0eb73c1db2a9b9401f5a37c9368a5bf861921e7e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 10 Feb 2024 12:43:46 +1100 Subject: [PATCH] autotest: only check for PitotBlockage once vehicle is loitering vehicle should be a in a steady state before we make the ratio change to synthesise a pitot blockage. Otherwise, changes to the shape of the takeoff will affect the heuristics used to detect pitot blockage. --- Tools/autotest/arduplane.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index ce476165310b4..636575f57cb31 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2131,9 +2131,7 @@ def PitotBlockage(self): "SIM_WIND_DIR": 0, "ARSPD_WIND_MAX": 15, }) - self.change_mode("TAKEOFF") - self.wait_ready_to_arm() - self.arm_vehicle() + self.takeoff(alt=50, mode='TAKEOFF') # simulate the effect of a blocked pitot tube self.set_parameter("ARSPD_RATIO", 0.1) self.delay_sim_time(10) @@ -2156,7 +2154,7 @@ def PitotBlockage(self): self.progress("Sensor Re-Enabled") else: raise NotAchievedException("Airspeed Sensor Not Re-Enabled") - self.disarm_vehicle(force=True) + self.fly_home_land_and_disarm() def AIRSPEED_AUTOCAL(self): '''Test AIRSPEED_AUTOCAL'''