Tools: Add partial unblockage to pitot blockage test
This commit is contained in:
parent
2a31cd7ca0
commit
86cb341173
@ -1742,7 +1742,14 @@ class AutoTestPlane(AutoTest):
|
|||||||
else:
|
else:
|
||||||
raise NotAchievedException("Airspeed Sensor Not Disabled")
|
raise NotAchievedException("Airspeed Sensor Not Disabled")
|
||||||
self.delay_sim_time(20)
|
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.set_parameter("ARSPD_RATIO",2.0)
|
||||||
self.delay_sim_time(60)
|
self.delay_sim_time(60)
|
||||||
if (self.get_parameter("ARSPD_USE") == 1):
|
if (self.get_parameter("ARSPD_USE") == 1):
|
||||||
|
Loading…
Reference in New Issue
Block a user