autotest: fix arming checks test

waity for accels/gyros to settle
This commit is contained in:
Peter Barker 2023-02-22 22:29:51 +11:00 committed by Peter Barker
parent e494c40b61
commit df06e85450
2 changed files with 2 additions and 0 deletions

View File

@ -6444,6 +6444,7 @@ class AutoTestCopter(AutoTest):
"EK3_SRC1_VELXY": 0,
})
self.reboot_sitl()
self.delay_sim_time(30) # wait for accels/gyros to settle
# check for expected EKF flags
ahrs_ekf_type = self.get_parameter("AHRS_EKF_TYPE")

View File

@ -9340,6 +9340,7 @@ Also, ignores heartbeats not from our target system'''
def ArmFeatures(self):
'''Arm features'''
# TEST ARMING/DISARM
self.delay_sim_time(12) # wait for gyros/accels to be happy
if self.get_parameter("ARMING_CHECK") != 1.0 and not self.is_sub():
raise ValueError("Arming check should be 1")
if not self.is_sub() and not self.is_tracker():