From a6d49b4ee297e4796cc348d15a8dc0c30fb5ba62 Mon Sep 17 00:00:00 2001 From: Stephen Dade Date: Fri, 20 Sep 2024 21:08:33 +1000 Subject: [PATCH] Tools: Add test for SET_MESSAGE_INTERVAL limiting --- Tools/autotest/vehicle_test_suite.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index c70d7a3bddbf0f..beaa63a6e5467b 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -10859,6 +10859,14 @@ def MESSAGE_INTERVAL_COMMAND_INT(self): if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1: raise NotAchievedException("Did not set rate") + # Try setting a rate well beyond SCHED_LOOP_RATE + self.run_cmd( + mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, + p1=mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD, + p2=self.rate_to_interval_us(800), + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + ) + self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT") # 148 is AUTOPILOT_VERSION: self.context_collect('AUTOPILOT_VERSION')