mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
autotest: fix arming checks test
waity for accels/gyros to settle
This commit is contained in:
parent
e494c40b61
commit
df06e85450
@ -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")
|
||||
|
@ -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():
|
||||
|
Loading…
Reference in New Issue
Block a user