autotest: poll_message limits polled message to system it was requested from

This commit is contained in:
Peter Barker 2023-10-19 20:51:20 +11:00 committed by Peter Barker
parent f3271ce0a6
commit 5e929e1b39
1 changed files with 9 additions and 2 deletions

View File

@ -10987,13 +10987,17 @@ Also, ignores heartbeats not from our target system'''
mav=mav,
)
def poll_message(self, message_id, timeout=10, quiet=False, mav=None):
def poll_message(self, message_id, timeout=10, quiet=False, mav=None, target_sysid=None, target_compid=None):
if mav is None:
mav = self.mav
if target_sysid is None:
target_sysid = self.sysid_thismav()
if target_compid is None:
target_compid = 1
if isinstance(message_id, str):
message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id)
tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work
self.send_poll_message(message_id, quiet=quiet, mav=mav)
self.send_poll_message(message_id, quiet=quiet, mav=mav, target_sysid=target_sysid, target_compid=target_compid)
self.run_cmd_get_ack(
mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
mavutil.mavlink.MAV_RESULT_ACCEPTED,
@ -11012,6 +11016,9 @@ Also, ignores heartbeats not from our target system'''
continue
if m.id != message_id:
continue
if (m.get_srcSystem() != target_sysid or
m.get_srcComponent() != target_compid):
continue
return m
def get_messages_frame(self, msg_names):