mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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
ae37d76f2d
commit
9f2aef4c97
@ -6071,8 +6071,9 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
})
|
})
|
||||||
self.set_rc(9, 2000)
|
self.set_rc(9, 2000)
|
||||||
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
Block a user