Browse Source

mavsdk_tests: improve log file folder structure

sbg
Julian Oes 5 years ago committed by Nuno Marques
parent
commit
814d79cb32
  1. 78
      test/mavsdk_tests/mavsdk_test_runner.py
  2. 55
      test/mavsdk_tests/process_helper.py

78
test/mavsdk_tests/mavsdk_test_runner.py

@ -1,7 +1,9 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
import argparse import argparse
import datetime
import json import json
import math
import os import os
import psutil # type: ignore import psutil # type: ignore
import signal import signal
@ -126,6 +128,7 @@ class Tester:
self.log_dir = log_dir self.log_dir = log_dir
self.gui = gui self.gui = gui
self.verbose = verbose self.verbose = verbose
self.start_time = datetime.datetime.now()
@classmethod @classmethod
def determine_tests(cls, tests: List[Dict[str, Any]], model: str) \ def determine_tests(cls, tests: List[Dict[str, Any]], model: str) \
@ -194,7 +197,6 @@ class Tester:
print() print()
def prepare_for_results(self) -> None: def prepare_for_results(self) -> None:
# prepare dict entry for results
for test in self.tests: for test in self.tests:
if not test['selected']: if not test['selected']:
continue continue
@ -207,14 +209,13 @@ class Tester:
print("%%% Test iteration: {} / {}". print("%%% Test iteration: {} / {}".
format(iteration + 1, self.iterations)) format(iteration + 1, self.iterations))
success = self.run_iteration() success = self.run_iteration(iteration)
if not success: if not success:
if self.abort_early: if self.abort_early:
break break
def run_iteration(self) -> bool: def run_iteration(self, iteration: int) -> bool:
iteration_success = True iteration_success = True
for test in self.tests: for test in self.tests:
if not test['selected']: if not test['selected']:
continue continue
@ -226,7 +227,15 @@ class Tester:
for i, case in enumerate(test['cases']): for i, case in enumerate(test['cases']):
print("--> Test case {} of {}: '{}' running ...". print("--> Test case {} of {}: '{}' running ...".
format(i+1, len(test['cases']), case)) format(i+1, len(test['cases']), case))
was_success = self.run_test_case(test, case)
log_dir = self.get_log_dir(iteration, test['model'], case)
if self.verbose:
print("creating log directory: {}"
.format(log_dir))
os.makedirs(log_dir, exist_ok=True)
was_success = self.run_test_case(test, case, log_dir)
if was_success: if was_success:
print(colorize( print(colorize(
"--- Test case {} of {}: '{}' succeeded." "--- Test case {} of {}: '{}' succeeded."
@ -247,7 +256,23 @@ class Tester:
return iteration_success return iteration_success
def run_test_case(self, test: Dict[str, Any], case: str) -> bool: def get_log_dir(self, iteration: int, model: str, case: str) -> str:
date_and_time = self.start_time.strftime("%Y-%m-%dT%H-%M-%SZ")
foldername = os.path.join(self.log_dir, date_and_time)
if self.iterations > 1:
# Use as many zeros in foldername as required.
digits = math.floor(math.log10(self.iterations)) + 1
foldername = os.path.join(foldername,
str(iteration + 1).zfill(digits))
foldername = os.path.join(foldername, model)
foldername = os.path.join(foldername, case.replace(" ", "_"))
return foldername
def run_test_case(self, test: Dict[str, Any],
case: str, logfile_path: str) -> bool:
self.active_runners = [] self.active_runners = []
speed_factor = self.speed_factor speed_factor = self.speed_factor
@ -257,8 +282,9 @@ class Tester:
if self.config['mode'] == 'sitl': if self.config['mode'] == 'sitl':
px4_runner = ph.Px4Runner( px4_runner = ph.Px4Runner(
os.getcwd(), os.getcwd(),
self.log_dir, logfile_path,
test, test['model'],
case,
speed_factor, speed_factor,
self.debugger, self.debugger,
self.verbose) self.verbose)
@ -268,8 +294,9 @@ class Tester:
if self.config['simulator'] == 'gazebo': if self.config['simulator'] == 'gazebo':
gzserver_runner = ph.GzserverRunner( gzserver_runner = ph.GzserverRunner(
os.getcwd(), os.getcwd(),
self.log_dir, logfile_path,
test, test['model'],
case,
self.speed_factor, self.speed_factor,
self.verbose) self.verbose)
gzserver_runner.start() gzserver_runner.start()
@ -278,16 +305,17 @@ class Tester:
if self.gui: if self.gui:
gzclient_runner = ph.GzclientRunner( gzclient_runner = ph.GzclientRunner(
os.getcwd(), os.getcwd(),
self.log_dir, logfile_path,
test, test['model'],
case,
self.verbose) self.verbose)
gzclient_runner.start() gzclient_runner.start()
self.active_runners.append(gzclient_runner) self.active_runners.append(gzclient_runner)
test_runner = ph.TestRunner( test_runner = ph.TestRunner(
os.getcwd(), os.getcwd(),
self.log_dir, logfile_path,
test, test['model'],
case, case,
self.config['mavlink_connection'], self.config['mavlink_connection'],
self.verbose) self.verbose)
@ -315,18 +343,26 @@ class Tester:
for runner in self.active_runners: for runner in self.active_runners:
runner.stop() runner.stop()
test['cases'][case]['results'].append(is_success) result = {'success': is_success,
'logfiles': [runner.get_log_filename()
for runner in self.active_runners]}
test['cases'][case]['results'].append(result)
if not is_success:
# TODO: print error and logfiles
pass
return is_success return is_success
def show_detailed_results(self) -> None: def show_detailed_results(self) -> None:
print() print()
print(colorize("Results:", color.BOLD)) print(colorize("Results:", color.BOLD))
for test in self.tests: for test in self.tests:
if not test['selected']: if not test['selected']:
print(colorize(colorize(" - {} (not selected)". print(colorize(colorize(
format(test['model']), color.BOLD), color.GRAY)) " - {} (not selected)".
format(test['model']), color.BOLD), color.GRAY))
continue continue
else: else:
print(colorize(" - {}:".format(test['model']), color.BOLD)) print(colorize(" - {}:".format(test['model']), color.BOLD))
@ -334,8 +370,10 @@ class Tester:
for name, case in test['cases'].items(): for name, case in test['cases'].items():
print(" - '{}': ".format(name), end="") print(" - '{}': ".format(name), end="")
n_succeeded = case['results'].count(True) n_succeeded = [result['success']
n_failed = case['results'].count(False) for result in case['results']].count(True)
n_failed = [result['success']
for result in case['results']].count(False)
n_cancelled = self.iterations - len(case['results']) n_cancelled = self.iterations - len(case['results'])
notes = [ notes = [

55
test/mavsdk_tests/process_helper.py

@ -3,7 +3,6 @@
import queue import queue
import time import time
import os import os
import datetime
import atexit import atexit
import subprocess import subprocess
import threading import threading
@ -15,29 +14,30 @@ from typing import Dict, List, TextIO, Optional
class Runner: class Runner:
def __init__(self, def __init__(self,
log_dir: str, log_dir: str,
config: Dict[str, str], model: str,
case: str,
verbose: bool): verbose: bool):
self.name = "" self.name = ""
self.cmd = "" self.cmd = ""
self.cwd = "" self.cwd = ""
self.args: List[str] self.args: List[str]
self.env: Dict[str, str] self.env: Dict[str, str]
self.log_dir = log_dir self.model = model
self.config = config self.case = case
self.log_filename = "" self.log_filename = ""
self.log_fd: TextIO self.log_fd: TextIO
self.verbose = verbose self.verbose = verbose
self.output_queue: queue.Queue[str] = queue.Queue() self.output_queue: queue.Queue[str] = queue.Queue()
self.start_time = time.time() self.start_time = time.time()
self.log_dir = log_dir
self.log_filename = ""
def create_log_filename(self, model: str, test_filter: str) -> str: def set_log_filename(self) -> None:
return self.log_dir + os.path.sep + \ self.log_filename = self.log_dir + os.path.sep + \
"log-{}-{}-{}-{}.log".format( "log-{}.log".format(self.name)
self.name,
model, def get_log_filename(self) -> str:
test_filter, return self.log_filename
datetime.datetime.now().strftime("%Y-%m-%dT%H-%M-%SZ"))
# TODO: improve logfilename, create folder, create merged log.
def start(self) -> None: def start(self) -> None:
if self.verbose: if self.verbose:
@ -45,8 +45,9 @@ class Runner:
atexit.register(self.stop) atexit.register(self.stop)
self.log_filename = self.create_log_filename( self.set_log_filename()
self.config['model'], self.config['test_filter']) if self.verbose:
print("Logging to {}".format(self.log_filename))
self.log_fd = open(self.log_filename, 'w') self.log_fd = open(self.log_filename, 'w')
self.process = subprocess.Popen( self.process = subprocess.Popen(
@ -138,9 +139,9 @@ class Runner:
class Px4Runner(Runner): class Px4Runner(Runner):
def __init__(self, workspace_dir: str, log_dir: str, def __init__(self, workspace_dir: str, log_dir: str,
config: Dict[str, str], speed_factor: float, model: str, case: str, speed_factor: float,
debugger: str, verbose: bool): debugger: str, verbose: bool):
super().__init__(log_dir, config, verbose) super().__init__(log_dir, model, case, verbose)
self.name = "px4" self.name = "px4"
self.cmd = workspace_dir + "/build/px4_sitl_default/bin/px4" self.cmd = workspace_dir + "/build/px4_sitl_default/bin/px4"
self.cwd = workspace_dir + "/build/px4_sitl_default/tmp/rootfs" self.cwd = workspace_dir + "/build/px4_sitl_default/tmp/rootfs"
@ -153,7 +154,7 @@ class Px4Runner(Runner):
"-d" "-d"
] ]
self.env = {"PATH": str(os.environ['PATH']), self.env = {"PATH": str(os.environ['PATH']),
"PX4_SIM_MODEL": str(config['model']), "PX4_SIM_MODEL": self.model,
"PX4_SIM_SPEED_FACTOR": str(speed_factor)} "PX4_SIM_SPEED_FACTOR": str(speed_factor)}
self.debugger = debugger self.debugger = debugger
@ -179,10 +180,11 @@ class GzserverRunner(Runner):
def __init__(self, def __init__(self,
workspace_dir: str, workspace_dir: str,
log_dir: str, log_dir: str,
config: Dict[str, str], model: str,
case: str,
speed_factor: float, speed_factor: float,
verbose: bool): verbose: bool):
super().__init__(log_dir, config, verbose) super().__init__(log_dir, model, case, verbose)
self.name = "gzserver" self.name = "gzserver"
self.cwd = workspace_dir self.cwd = workspace_dir
self.env = {"PATH": os.environ['PATH'], self.env = {"PATH": os.environ['PATH'],
@ -196,16 +198,17 @@ class GzserverRunner(Runner):
self.cmd = "gzserver" self.cmd = "gzserver"
self.args = ["--verbose", self.args = ["--verbose",
workspace_dir + "/Tools/sitl_gazebo/worlds/" + workspace_dir + "/Tools/sitl_gazebo/worlds/" +
config['model'] + ".world"] self.model + ".world"]
class GzclientRunner(Runner): class GzclientRunner(Runner):
def __init__(self, def __init__(self,
workspace_dir: str, workspace_dir: str,
log_dir: str, log_dir: str,
config: Dict[str, str], model: str,
case: str,
verbose: bool): verbose: bool):
super().__init__(log_dir, config, verbose) super().__init__(log_dir, model, case, verbose)
self.name = "gzclient" self.name = "gzclient"
self.cwd = workspace_dir self.cwd = workspace_dir
self.env = {"PATH": os.environ['PATH'], self.env = {"PATH": os.environ['PATH'],
@ -223,14 +226,14 @@ class TestRunner(Runner):
def __init__(self, def __init__(self,
workspace_dir: str, workspace_dir: str,
log_dir: str, log_dir: str,
config: Dict[str, str], model: str,
test: str, case: str,
mavlink_connection: str, mavlink_connection: str,
verbose: bool): verbose: bool):
super().__init__(log_dir, config, verbose) super().__init__(log_dir, model, case, verbose)
self.name = "test_runner" self.name = "test_runner"
self.cwd = workspace_dir self.cwd = workspace_dir
self.env = {"PATH": os.environ['PATH']} self.env = {"PATH": os.environ['PATH']}
self.cmd = workspace_dir + \ self.cmd = workspace_dir + \
"/build/px4_sitl_default/mavsdk_tests/mavsdk_tests" "/build/px4_sitl_default/mavsdk_tests/mavsdk_tests"
self.args = ["--url", mavlink_connection, test] self.args = ["--url", mavlink_connection, case]

Loading…
Cancel
Save