autotest: use context to get AUTOPILOT_VERSION

... avoid race condition in modern ways
This commit is contained in:
Peter Barker 2024-12-15 11:47:40 +11:00
parent 016853f8c7
commit 0b4cee84a3

View File

@ -6890,19 +6890,14 @@ class TestSuite(ABC):
raise NotAchievedException("AutoPilot has feature %s (when it shouln't)" % (name,))
def get_autopilot_capabilities(self):
# Cannot use run_cmd otherwise the respond is lost during the wait for ACK
self.mav.mav.command_long_send(self.sysid_thismav(),
1,
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
0, # confirmation
1, # 1: Request autopilot version
0,
0,
0,
0,
0,
0)
m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10)
self.context_push()
self.context_collect('AUTOPILOT_VERSION')
self.run_cmd(
mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
p1=1, # 1: Request autopilot version
)
m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10, check_context=True)
self.context_pop()
return m.capabilities
def decode_flight_sw_version(self, flight_sw_version: int):