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.
This commit is contained in:
Peter Barker 2024-02-10 12:43:46 +11:00 committed by Peter Barker
parent e728176d4e
commit 0eb73c1db2

View File

@ -2131,9 +2131,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
"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 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
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'''