Skip to content

Commit

Permalink
autotest: only check for PitotBlockage once vehicle is loitering
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
peterbarker committed Feb 10, 2024
1 parent e728176 commit 0eb73c1
Showing 1 changed file with 2 additions and 4 deletions.
6 changes: 2 additions & 4 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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'''
Expand Down

0 comments on commit 0eb73c1

Please sign in to comment.