Tools: autotest: fix race conditions in arm_vehicle and disarm_vehicle

This commit is contained in:
Peter Barker 2019-09-09 10:03:21 +10:00 committed by Peter Barker
parent ba3cfbfb54
commit da2e00dd6f
1 changed files with 2 additions and 2 deletions

View File

@ -923,6 +923,7 @@ class AutoTest(ABC):
def arm_vehicle(self, timeout=20):
"""Arm vehicle with mavlink arm message."""
self.progress("Arm motors with MAVLink cmd")
tstart = self.get_sim_time()
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
1, # ARM
0,
@ -932,7 +933,6 @@ class AutoTest(ABC):
0,
0,
timeout=timeout)
tstart = self.get_sim_time()
while self.get_sim_time_cached() - tstart < timeout:
self.wait_heartbeat()
if self.mav.motors_armed():
@ -946,6 +946,7 @@ class AutoTest(ABC):
p2 = 0
if force:
p2 = 21196 # magic force disarm value
tstart = self.get_sim_time()
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
0, # DISARM
p2,
@ -955,7 +956,6 @@ class AutoTest(ABC):
0,
0,
timeout=timeout)
tstart = self.get_sim_time()
while self.get_sim_time_cached() - tstart < timeout:
self.wait_heartbeat()
if not self.mav.motors_armed():