autotest: add test for setting multiple messages to same rate

This commit is contained in:
Peter Barker 2021-08-30 15:39:39 +10:00 committed by Peter Barker
parent 591c7d55c7
commit b9d62e7ff2
1 changed files with 38 additions and 5 deletions

View File

@ -7850,6 +7850,43 @@ Also, ignores heartbeats not from our target system'''
raise NotAchievedException("Expected ACCEPTED for reading message interval")
def test_set_message_interval(self):
self.start_subtest('Basic tests')
self.test_set_message_interval_basic()
self.start_subtest('Many-message tests')
self.test_set_message_interval_many()
def test_set_message_interval_many(self):
messages = [
'CAMERA_FEEDBACK',
'RAW_IMU',
'ATTITUDE',
]
ex = None
try:
rate = 5
for message in messages:
self.set_message_rate_hz(message, rate)
for message in messages:
self.assert_message_rate_hz(message, rate)
except Exception as e:
self.print_exception_caught(e)
ex = e
# reset message rates to default:
for message in messages:
self.set_message_rate_hz(message, -1)
if ex is not None:
raise ex
def assert_message_rate_hz(self, message, want_rate, sample_period=20):
self.drain_mav()
rate = round(self.get_message_rate(message, sample_period))
self.progress("%s: Want=%u got=%u" % (message, want_rate, rate))
if rate != want_rate:
raise NotAchievedException("Did not get expected rate (want=%u got=%u" % (want_rate, rate))
def test_set_message_interval_basic(self):
self.victim_message = 'VFR_HUD'
self.victim_message_id = mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD
ex = None
@ -7871,11 +7908,7 @@ Also, ignores heartbeats not from our target system'''
for want_rate in range(5, 14):
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK,
want_rate)
self.drain_mav()
rate = round(self.get_message_rate("CAMERA_FEEDBACK", 20))
self.progress("Want=%u got=%u" % (want_rate, rate))
if rate != want_rate:
raise NotAchievedException("Did not get expected rate (want=%u got=%u" % (want_rate, rate))
self.assert_message_rate_hz('CAMERA_FEEDBACK', want_rate)
self.progress("try at the main loop rate")
# have to reset the speedup as MAVProxy can't keep up otherwise