Skip to content

Commit

Permalink
Tools: Add test for SET_MESSAGE_INTERVAL limiting
Browse files Browse the repository at this point in the history
  • Loading branch information
stephendade committed Oct 1, 2024
1 parent 533b045 commit 013d1f4
Showing 1 changed file with 8 additions and 0 deletions.
8 changes: 8 additions & 0 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -10866,6 +10866,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')
Expand Down

0 comments on commit 013d1f4

Please sign in to comment.