mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
autotest: fix race condition in EKF type 10
EKF type 10 is always able to give you a position - but the arming checks require you to have a good GPS position, and that's something else again.
This commit is contained in:
parent
cafc5b01f4
commit
c01b26ca62
@ -3886,6 +3886,10 @@ class AutoTest(ABC):
|
||||
if require_absolute:
|
||||
self.wait_gps_sys_status_not_present_or_enabled_and_healthy()
|
||||
armable_time = self.get_sim_time() - start
|
||||
if require_absolute:
|
||||
m = self.poll_home_position()
|
||||
if m is None:
|
||||
raise NotAchievedException("Did not receive a home position")
|
||||
self.progress("Took %u seconds to become armable" % armable_time)
|
||||
self.total_waiting_to_arm_time += armable_time
|
||||
self.waiting_to_arm_count += 1
|
||||
|
Loading…
Reference in New Issue
Block a user