mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
autotest: add test for setting streamrates from files
This commit is contained in:
parent
df7b2982d3
commit
d7f037e548
@ -6924,6 +6924,42 @@ class AutoTestCopter(AutoTest):
|
||||
if not ok:
|
||||
raise NotAchievedException("check_replay failed")
|
||||
|
||||
def DefaultIntervalsFromFiles(self):
|
||||
ex = None
|
||||
intervals_filepath = util.reltopdir("message-intervals-chan0.txt")
|
||||
self.progress("Using filepath (%s)" % intervals_filepath)
|
||||
try:
|
||||
with open(intervals_filepath, "w") as f:
|
||||
f.write("""30 50
|
||||
28 100
|
||||
29 200
|
||||
""")
|
||||
|
||||
# other tests may have explicitly set rates, so wipe parameters:
|
||||
def custom_stream_rate_setter():
|
||||
for stream in mavutil.mavlink.MAV_DATA_STREAM_EXTRA3, mavutil.mavlink.MAV_DATA_STREAM_RC_CHANNELS:
|
||||
self.set_streamrate(5, stream=stream)
|
||||
|
||||
self.customise_SITL_commandline(
|
||||
[],
|
||||
wipe=True,
|
||||
set_streamrate_callback=custom_stream_rate_setter,
|
||||
)
|
||||
|
||||
self.assert_message_rate_hz("ATTITUDE", 20)
|
||||
self.assert_message_rate_hz("SCALED_PRESSURE", 5)
|
||||
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
||||
os.unlink(intervals_filepath)
|
||||
|
||||
self.reboot_sitl()
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
def BaroDrivers(self):
|
||||
sensors = [
|
||||
("MS5611", 2),
|
||||
@ -7919,6 +7955,9 @@ class AutoTestCopter(AutoTest):
|
||||
"Change speed (down) during misison",
|
||||
self.WPNAV_SPEED_DN),
|
||||
|
||||
("DefaultIntervalsFromFiles",
|
||||
"Test setting default mavlink message intervals from files",
|
||||
self.DefaultIntervalsFromFiles),
|
||||
|
||||
Test("GPSTypes",
|
||||
"Test simulated GPS types",
|
||||
|
@ -1676,7 +1676,7 @@ class AutoTest(ABC):
|
||||
self.progress("Calling initialise-after-reboot")
|
||||
self.initialise_after_reboot_sitl()
|
||||
|
||||
def set_streamrate(self, streamrate, timeout=20):
|
||||
def set_streamrate(self, streamrate, timeout=20, stream=mavutil.mavlink.MAV_DATA_STREAM_ALL):
|
||||
'''set MAV_DATA_STREAM_ALL; timeout is wallclock time'''
|
||||
tstart = time.time()
|
||||
while True:
|
||||
@ -1685,7 +1685,7 @@ class AutoTest(ABC):
|
||||
self.mav.mav.request_data_stream_send(
|
||||
1,
|
||||
1,
|
||||
mavutil.mavlink.MAV_DATA_STREAM_ALL,
|
||||
stream,
|
||||
streamrate,
|
||||
1)
|
||||
m = self.mav.recv_match(type='SYSTEM_TIME',
|
||||
@ -2146,7 +2146,12 @@ class AutoTest(ABC):
|
||||
self.set_streamrate(self.sitl_streamrate())
|
||||
self.progress("Reboot complete")
|
||||
|
||||
def customise_SITL_commandline(self, customisations, model=None, defaults_filepath=None, wipe=False):
|
||||
def customise_SITL_commandline(self,
|
||||
customisations,
|
||||
model=None,
|
||||
defaults_filepath=None,
|
||||
wipe=False,
|
||||
set_streamrate_callback=None):
|
||||
'''customisations could be "--uartF=sim:nmea" '''
|
||||
self.contexts[-1].sitl_commandline_customised = True
|
||||
self.stop_SITL()
|
||||
@ -2166,7 +2171,10 @@ class AutoTest(ABC):
|
||||
except IOError:
|
||||
pass
|
||||
break
|
||||
self.set_streamrate(self.sitl_streamrate())
|
||||
if set_streamrate_callback is not None:
|
||||
set_streamrate_callback()
|
||||
else:
|
||||
self.set_streamrate(self.sitl_streamrate())
|
||||
m = self.mav.recv_match(type='RC_CHANNELS', blocking=True, timeout=15)
|
||||
if m is None:
|
||||
raise NotAchievedException("No RC_CHANNELS message after restarting SITL")
|
||||
|
Loading…
Reference in New Issue
Block a user