Tools: Add test for SET_MESSAGE_INTERVAL limiting

This commit is contained in:
Stephen Dade 2024-09-20 21:08:33 +10:00 committed by Peter Barker
parent 9a563e222f
commit 9042e7de1a
1 changed files with 8 additions and 0 deletions

View File

@ -10866,6 +10866,14 @@ Also, ignores heartbeats not from our target system'''
if abs(original_rate*2 - round(self.get_message_rate_hz("VFR_HUD", run_cmd=self.run_cmd_int))) > 1: 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") 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") self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT")
# 148 is AUTOPILOT_VERSION: # 148 is AUTOPILOT_VERSION:
self.context_collect('AUTOPILOT_VERSION') self.context_collect('AUTOPILOT_VERSION')