mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
autotest: drain mav before attempting disarm
If the queue of messages for us to parse is very long then we can time out before managing to parse them all and find the disarm!
This commit is contained in:
parent
03c68f991c
commit
d2cf0939a5
@ -1088,6 +1088,7 @@ class AutoTest(ABC):
|
|||||||
def disarm_vehicle(self, timeout=60, force=False):
|
def disarm_vehicle(self, timeout=60, force=False):
|
||||||
"""Disarm vehicle with mavlink disarm message."""
|
"""Disarm vehicle with mavlink disarm message."""
|
||||||
self.progress("Disarm motors with MAVLink cmd")
|
self.progress("Disarm motors with MAVLink cmd")
|
||||||
|
self.drain_mav_unparsed()
|
||||||
p2 = 0
|
p2 = 0
|
||||||
if force:
|
if force:
|
||||||
p2 = 21196 # magic force disarm value
|
p2 = 21196 # magic force disarm value
|
||||||
|
Loading…
Reference in New Issue
Block a user