Skip to content

Commit

Permalink
autotest: understand verbose and very_vrbose for wait_message_field_v…
Browse files Browse the repository at this point in the history
…alues
  • Loading branch information
peterbarker committed Nov 11, 2023
1 parent 2f9bfb6 commit 0143bf2
Showing 1 changed file with 17 additions and 3 deletions.
20 changes: 17 additions & 3 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -3915,16 +3915,30 @@ def assert_received_message_field_values(self,
return m

# FIXME: try to use wait_and_maintain here?
def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=None, instance=None, minimum_duration=None):
def wait_message_field_values(self,
message,
fieldvalues,
timeout=10,
epsilon=None,
instance=None,
minimum_duration=None,
verbose=False,
very_verbose=False,
):

tstart = self.get_sim_time_cached()
pass_start = None
while True:
now = self.get_sim_time_cached()
if now - tstart > timeout:
raise NotAchievedException("Field never reached values")
m = self.assert_receive_message(message, instance=instance)
if self.message_has_field_values(m, fieldvalues, epsilon=epsilon):
m = self.assert_receive_message(
message,
instance=instance,
verbose=verbose,
very_verbose=very_verbose,
)
if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose):
if minimum_duration is not None:
if pass_start is None:
pass_start = now
Expand Down

0 comments on commit 0143bf2

Please sign in to comment.