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 Sep 22, 2024
1 parent 4e433af commit ed9ce51
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -10855,10 +10855,18 @@ def SET_MESSAGE_INTERVAL(self):
def MESSAGE_INTERVAL_COMMAND_INT(self):
'''Test MAV_CMD_SET_MESSAGE_INTERVAL works as COMMAND_INT'''
original_rate = round(self.measure_message_rate("VFR_HUD", 20))
self.context_set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int)
self.set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int)
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=eval("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 ed9ce51

Please sign in to comment.