From 6435e106606092bf4b49e2dad73d94ddd6a44827 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:22:17 +1100 Subject: [PATCH 1/2] autotest: assert_received_message_values gets timeout and check_context --- Tools/autotest/vehicle_test_suite.py | 23 ++++++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 3b71023a03df1..427ebb5bb6103 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -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 @@ -4298,7 +4313,7 @@ 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, @@ -4306,6 +4321,8 @@ def assert_receive_message(self, delay_fn=None, instance=None, check_context=False): + if timeout is None: + timeout = 1 if mav is None: mav = self.mav From 5edb60a7cd9f7e31383ab1d459fd33631e066d1c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:08:47 +1100 Subject: [PATCH 2/2] autotest: tidy testing of SentToComponents --- Tools/autotest/rover.py | 22 +++++++--------------- 1 file changed, 7 insertions(+), 15 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 3f97fd9e2eaca..2da688ab12410 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -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 @@ -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'''