mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for PerfInfo tasks.txt info
This commit is contained in:
parent
ad32f8d6d2
commit
75b9a3ff77
|
@ -7500,6 +7500,18 @@ class AutoTestCopter(AutoTest):
|
|||
self.FETtecESC_btw_mask_checks()
|
||||
self.FETtecESC_flight()
|
||||
|
||||
def PerfInfo(self):
|
||||
self.set_parameter('SCHED_OPTIONS', 1) # enable gathering
|
||||
content = self.fetch_file_via_ftp("@SYS/tasks.txt")
|
||||
self.progress("Got content (%s)" % str(content))
|
||||
if "fast_loop" not in content:
|
||||
raise NotAchievedException("Did not find fast_loop in content")
|
||||
|
||||
lines = content.split("\n")
|
||||
|
||||
if not lines[0].startswith("TasksV1"):
|
||||
raise NotAchievedException("Expected TasksV1 as first line first not (%s)" % lines[0])
|
||||
|
||||
def tests1a(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/common.py
|
||||
|
@ -7959,6 +7971,10 @@ class AutoTestCopter(AutoTest):
|
|||
"Test Callisto",
|
||||
self.test_callisto),
|
||||
|
||||
Test("PerfInfo",
|
||||
"Test Scheduler PerfInfo output",
|
||||
self.PerfInfo),
|
||||
|
||||
Test("Replay",
|
||||
"Test Replay",
|
||||
self.test_replay),
|
||||
|
|
|
@ -24,6 +24,7 @@ import numpy
|
|||
import socket
|
||||
import struct
|
||||
import random
|
||||
import tempfile
|
||||
import threading
|
||||
import enum
|
||||
|
||||
|
@ -10927,6 +10928,30 @@ switch value'''
|
|||
if abs(new_gpi_alt2 - m.alt) > 100:
|
||||
raise NotAchievedException("Failover not detected")
|
||||
|
||||
def fetch_file_via_ftp(self, path):
|
||||
'''returns the content of the FTP'able file at path'''
|
||||
mavproxy = self.start_mavproxy()
|
||||
ex = None
|
||||
tmpfile = tempfile.NamedTemporaryFile(mode='r', delete=False)
|
||||
try:
|
||||
mavproxy.send("module load ftp\n")
|
||||
mavproxy.expect(["Loaded module ftp", "module ftp already loaded"])
|
||||
mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name))
|
||||
mavproxy.expect("Getting")
|
||||
self.delay_sim_time(2)
|
||||
mavproxy.send("ftp status\n")
|
||||
mavproxy.expect("No transfer in progress")
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
|
||||
self.stop_mavproxy(mavproxy)
|
||||
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
return tmpfile.read()
|
||||
|
||||
def MAVFTP(self):
|
||||
'''ensure MAVProxy can do MAVFTP to ardupilot'''
|
||||
mavproxy = self.start_mavproxy()
|
||||
|
|
Loading…
Reference in New Issue