mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
autotest: assert_received_message_values gets timeout and check_context
This commit is contained in:
parent
d33facd884
commit
a53d583963
@ -3895,10 +3895,25 @@ class TestSuite(ABC):
|
||||
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
|
||||
|
||||
@ -4298,7 +4313,7 @@ class TestSuite(ABC):
|
||||
|
||||
def assert_receive_message(self,
|
||||
type,
|
||||
timeout=1,
|
||||
timeout=None,
|
||||
verbose=False,
|
||||
very_verbose=False,
|
||||
mav=None,
|
||||
@ -4306,6 +4321,8 @@ class TestSuite(ABC):
|
||||
delay_fn=None,
|
||||
instance=None,
|
||||
check_context=False):
|
||||
if timeout is None:
|
||||
timeout = 1
|
||||
if mav is None:
|
||||
mav = self.mav
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user