mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
e728176d4e
commit
0eb73c1db2
@ -2131,9 +2131,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||||||
"SIM_WIND_DIR": 0,
|
"SIM_WIND_DIR": 0,
|
||||||
"ARSPD_WIND_MAX": 15,
|
"ARSPD_WIND_MAX": 15,
|
||||||
})
|
})
|
||||||
self.change_mode("TAKEOFF")
|
self.takeoff(alt=50, mode='TAKEOFF')
|
||||||
self.wait_ready_to_arm()
|
|
||||||
self.arm_vehicle()
|
|
||||||
# simulate the effect of a blocked pitot tube
|
# simulate the effect of a blocked pitot tube
|
||||||
self.set_parameter("ARSPD_RATIO", 0.1)
|
self.set_parameter("ARSPD_RATIO", 0.1)
|
||||||
self.delay_sim_time(10)
|
self.delay_sim_time(10)
|
||||||
@ -2156,7 +2154,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||||||
self.progress("Sensor Re-Enabled")
|
self.progress("Sensor Re-Enabled")
|
||||||
else:
|
else:
|
||||||
raise NotAchievedException("Airspeed Sensor Not Re-Enabled")
|
raise NotAchievedException("Airspeed Sensor Not Re-Enabled")
|
||||||
self.disarm_vehicle(force=True)
|
self.fly_home_land_and_disarm()
|
||||||
|
|
||||||
def AIRSPEED_AUTOCAL(self):
|
def AIRSPEED_AUTOCAL(self):
|
||||||
'''Test AIRSPEED_AUTOCAL'''
|
'''Test AIRSPEED_AUTOCAL'''
|
||||||
|
Loading…
Reference in New Issue
Block a user