mirror of https://github.com/ArduPilot/ardupilot
autotest: allow other prearm failures while waiting for estop prearm
accels inconsistent was popping up in here. We can ignore that - we only care we won't arm because of the estop being active. This will also save a bit of time with the removal of the raw delay-for-10-seconds
This commit is contained in:
parent
ba6d467c9d
commit
ae37d76f2d
|
@ -11665,10 +11665,12 @@ switch value'''
|
||||||
0,
|
0,
|
||||||
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
want_result=mavutil.mavlink.MAV_RESULT_FAILED
|
||||||
)
|
)
|
||||||
self.wait_statustext("PreArm: Motors Emergency Stopped", check_context=True)
|
self.assert_prearm_failure("Motors Emergency Stopped",
|
||||||
|
other_prearm_failures_fatal=False)
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
self.delay_sim_time(10)
|
self.assert_prearm_failure(
|
||||||
self.assert_prearm_failure("Motors Emergency Stopped")
|
"Motors Emergency Stopped",
|
||||||
|
other_prearm_failures_fatal=False)
|
||||||
self.context_pop()
|
self.context_pop()
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue