mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: autotest: fix initial mode switch position race
Solves a race condition where an initial setting of mode via mavlink could be overwritten by the vehicle polling the RC channels and changing mode based on the new positions. This will require each vehicle to specify the mode expected without an RC inputs present and the expected mode once the RC defaults have been installed. These two modes will need to be different to eliminate the race condition.
This commit is contained in:
parent
d4a05c8ada
commit
e6bfbe5f07
@ -2411,6 +2411,12 @@ class AutoTestCopter(AutoTest):
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def initial_mode(self):
|
||||
return "STABILIZE"
|
||||
|
||||
def initial_mode_switch_mode(self):
|
||||
return "AUTO"
|
||||
|
||||
def default_mode(self):
|
||||
return "STABILIZE"
|
||||
|
||||
|
@ -1964,6 +1964,33 @@ class AutoTest(ABC):
|
||||
# def test_mission(self, filename):
|
||||
# pass
|
||||
|
||||
def initial_mode(self):
|
||||
'''return mode vehicle should start in with no RC inputs set'''
|
||||
return None
|
||||
|
||||
def initial_mode_switch_mode(self):
|
||||
'''return mode vehicle should start in with default RC inputs set'''
|
||||
return None
|
||||
|
||||
def wait_for_initial_mode(self):
|
||||
'''wait until we get a heartbeat with an expected initial mode (the
|
||||
one specified in the vehicle constructor)'''
|
||||
want = self.initial_mode()
|
||||
if want is None:
|
||||
return
|
||||
self.progress("Waiting for initial mode %s" % want)
|
||||
self.wait_mode(want)
|
||||
|
||||
def wait_for_mode_switch_poll(self):
|
||||
'''look for a transition from boot-up-mode (e.g. the flightmode
|
||||
specificied in Copter's constructor) to the one specified by the mode
|
||||
switch value'''
|
||||
want = self.initial_mode_switch_mode()
|
||||
if want is None:
|
||||
return
|
||||
self.progress("Waiting for mode-switch mode %s" % want)
|
||||
self.wait_mode(want)
|
||||
|
||||
def run_tests(self, tests):
|
||||
"""Autotest vehicle in SITL."""
|
||||
self.check_test_syntax(test_file=os.path.realpath(__file__))
|
||||
@ -1976,8 +2003,10 @@ class AutoTest(ABC):
|
||||
self.progress("Waiting for a heartbeat with mavlink protocol %s"
|
||||
% self.mav.WIRE_PROTOCOL_VERSION)
|
||||
self.wait_heartbeat()
|
||||
self.wait_for_initial_mode()
|
||||
self.progress("Setting up RC parameters")
|
||||
self.set_rc_default()
|
||||
self.wait_for_mode_switch_poll()
|
||||
|
||||
for test in tests:
|
||||
(name, desc, func) = test
|
||||
|
Loading…
Reference in New Issue
Block a user