Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

autotest: assert_received_message_values gets timeout and check_context #25420

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 7 additions & 15 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -5619,6 +5619,9 @@ def SendToComponents(self):
0,
0,
0)

self.context_collect('COMMAND_LONG')

self.progress("Sending control message")
self.mav.mav.digicam_control_send(
1, # target_system
Expand All @@ -5634,21 +5637,10 @@ def SendToComponents(self):
)
self.mav.mav.srcSystem = old_srcSystem

self.progress("Expecting a command long")
tstart = self.get_sim_time_cached()
while True:
now = self.get_sim_time_cached()
if now - tstart > 2:
raise NotAchievedException("Did not receive digicam_control message")
m = self.mav.recv_match(type='COMMAND_LONG', blocking=True, timeout=0.1)
self.progress("Message: %s" % str(m))
if m is None:
continue
if m.command != mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL:
raise NotAchievedException("Did not get correct command")
if m.param6 != 17:
raise NotAchievedException("Did not get correct command_id")
break
self.assert_received_message_field_values('COMMAND_LONG', {
'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL,
'param6': 17,
}, timeout=2, check_context=True)

def SkidSteer(self):
'''Check skid-steering'''
Expand Down
23 changes: 20 additions & 3 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -3895,10 +3895,25 @@ def assert_cached_message_field_values(self, message, fieldvalues, verbose=True,
self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)
return m

def assert_received_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None, poll=False): # noqa
def assert_received_message_field_values(self,
message,
fieldvalues,
verbose=True,
very_verbose=False,
epsilon=None,
poll=False,
timeout=None,
check_context=False,
):
if poll:
self.poll_message(message)
m = self.assert_receive_message(message, verbose=verbose, very_verbose=very_verbose)
m = self.assert_receive_message(
message,
verbose=verbose,
very_verbose=very_verbose,
timeout=timeout,
check_context=check_context
)
self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon)
return m

Expand Down Expand Up @@ -4298,14 +4313,16 @@ def assert_not_receive_message(self, message, timeout=1, mav=None, condition=Non

def assert_receive_message(self,
type,
timeout=1,
timeout=None,
verbose=False,
very_verbose=False,
mav=None,
condition=None,
delay_fn=None,
instance=None,
check_context=False):
if timeout is None:
timeout = 1
if mav is None:
mav = self.mav

Expand Down