2020-03-11 14:17:04 -03:00
|
|
|
#!/usr/bin/env python3
|
|
|
|
|
|
|
|
import queue
|
|
|
|
import time
|
|
|
|
import os
|
|
|
|
import atexit
|
|
|
|
import subprocess
|
|
|
|
import threading
|
|
|
|
import errno
|
2020-03-13 06:02:58 -03:00
|
|
|
from typing import Dict, List, TextIO, Optional
|
2020-03-11 14:17:04 -03:00
|
|
|
|
|
|
|
|
|
|
|
class Runner:
|
2020-03-13 06:02:58 -03:00
|
|
|
def __init__(self,
|
|
|
|
log_dir: str,
|
2020-03-16 12:05:12 -03:00
|
|
|
model: str,
|
|
|
|
case: str,
|
2020-03-13 06:02:58 -03:00
|
|
|
verbose: bool):
|
2020-03-11 14:17:04 -03:00
|
|
|
self.name = ""
|
|
|
|
self.cmd = ""
|
2020-03-13 05:18:10 -03:00
|
|
|
self.cwd = ""
|
|
|
|
self.args: List[str]
|
|
|
|
self.env: Dict[str, str]
|
2020-03-16 12:05:12 -03:00
|
|
|
self.model = model
|
|
|
|
self.case = case
|
2020-03-11 14:17:04 -03:00
|
|
|
self.log_filename = ""
|
2020-03-13 06:02:58 -03:00
|
|
|
self.log_fd: TextIO
|
2020-03-11 14:17:04 -03:00
|
|
|
self.verbose = verbose
|
2020-03-13 06:02:58 -03:00
|
|
|
self.output_queue: queue.Queue[str] = queue.Queue()
|
2020-03-11 14:17:04 -03:00
|
|
|
self.start_time = time.time()
|
2020-03-16 12:05:12 -03:00
|
|
|
self.log_dir = log_dir
|
|
|
|
self.log_filename = ""
|
2020-03-11 14:17:04 -03:00
|
|
|
|
2020-03-16 15:26:05 -03:00
|
|
|
def set_log_filename(self, log_filename: str) -> None:
|
|
|
|
self.log_filename = log_filename
|
2020-03-16 12:05:12 -03:00
|
|
|
|
|
|
|
def get_log_filename(self) -> str:
|
|
|
|
return self.log_filename
|
2020-03-11 14:17:04 -03:00
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def start(self) -> None:
|
2020-03-11 14:17:04 -03:00
|
|
|
if self.verbose:
|
|
|
|
print("Running: {}".format(" ".join([self.cmd] + self.args)))
|
|
|
|
|
|
|
|
atexit.register(self.stop)
|
|
|
|
|
2020-03-16 12:05:12 -03:00
|
|
|
if self.verbose:
|
|
|
|
print("Logging to {}".format(self.log_filename))
|
2020-03-11 14:17:04 -03:00
|
|
|
self.log_fd = open(self.log_filename, 'w')
|
|
|
|
|
|
|
|
self.process = subprocess.Popen(
|
|
|
|
[self.cmd] + self.args,
|
|
|
|
cwd=self.cwd,
|
|
|
|
env=self.env,
|
|
|
|
stdout=subprocess.PIPE,
|
|
|
|
stderr=subprocess.STDOUT,
|
|
|
|
universal_newlines=True
|
|
|
|
)
|
|
|
|
|
|
|
|
self.stop_thread = threading.Event()
|
|
|
|
self.thread = threading.Thread(target=self.process_output)
|
|
|
|
self.thread.start()
|
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def process_output(self) -> None:
|
|
|
|
assert self.process.stdout is not None
|
2020-03-11 14:17:04 -03:00
|
|
|
while not self.stop_thread.is_set():
|
|
|
|
line = self.process.stdout.readline()
|
|
|
|
if line == "\n":
|
|
|
|
continue
|
|
|
|
self.output_queue.put(line)
|
|
|
|
self.log_fd.write(line)
|
|
|
|
self.log_fd.flush()
|
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def poll(self) -> Optional[int]:
|
2020-03-11 14:17:04 -03:00
|
|
|
return self.process.poll()
|
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def wait(self, timeout_min: float) -> Optional[int]:
|
2020-03-11 14:17:04 -03:00
|
|
|
try:
|
|
|
|
return self.process.wait(timeout=timeout_min*60)
|
|
|
|
except subprocess.TimeoutExpired:
|
|
|
|
print("Timeout of {} min{} reached, stopping...".
|
|
|
|
format(timeout_min, "s" if timeout_min > 1 else ""))
|
|
|
|
self.stop()
|
|
|
|
print("stopped.")
|
|
|
|
return errno.ETIMEDOUT
|
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def get_output(self) -> Optional[str]:
|
2020-03-11 14:17:04 -03:00
|
|
|
try:
|
2020-03-16 15:26:05 -03:00
|
|
|
return self.output_queue.get(block=True, timeout=0.1)
|
2020-03-11 14:17:04 -03:00
|
|
|
except queue.Empty:
|
|
|
|
return None
|
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def stop(self) -> int:
|
2020-03-11 14:17:04 -03:00
|
|
|
atexit.unregister(self.stop)
|
|
|
|
|
|
|
|
self.stop_thread.set()
|
|
|
|
|
|
|
|
returncode = self.process.poll()
|
|
|
|
if returncode is None:
|
|
|
|
|
|
|
|
if self.verbose:
|
|
|
|
print("Terminating {}".format(self.cmd))
|
|
|
|
self.process.terminate()
|
|
|
|
|
|
|
|
try:
|
|
|
|
returncode = self.process.wait(timeout=1)
|
|
|
|
except subprocess.TimeoutExpired:
|
|
|
|
pass
|
|
|
|
|
|
|
|
if returncode is None:
|
|
|
|
if self.verbose:
|
|
|
|
print("Killing {}".format(self.cmd))
|
|
|
|
self.process.kill()
|
|
|
|
returncode = self.process.poll()
|
|
|
|
|
|
|
|
if self.verbose:
|
|
|
|
print("{} exited with {}".format(
|
|
|
|
self.cmd, self.process.returncode))
|
|
|
|
|
|
|
|
self.thread.join()
|
|
|
|
|
|
|
|
self.log_fd.close()
|
|
|
|
|
|
|
|
return self.process.returncode
|
|
|
|
|
2020-03-13 06:02:58 -03:00
|
|
|
def time_elapsed_s(self) -> float:
|
2020-03-11 14:17:04 -03:00
|
|
|
return time.time() - self.start_time
|
|
|
|
|
|
|
|
|
|
|
|
class Px4Runner(Runner):
|
2020-03-13 05:18:10 -03:00
|
|
|
def __init__(self, workspace_dir: str, log_dir: str,
|
2020-03-16 12:05:12 -03:00
|
|
|
model: str, case: str, speed_factor: float,
|
2020-03-13 05:18:10 -03:00
|
|
|
debugger: str, verbose: bool):
|
2020-03-16 12:05:12 -03:00
|
|
|
super().__init__(log_dir, model, case, verbose)
|
2020-03-11 14:17:04 -03:00
|
|
|
self.name = "px4"
|
|
|
|
self.cmd = workspace_dir + "/build/px4_sitl_default/bin/px4"
|
|
|
|
self.cwd = workspace_dir + "/build/px4_sitl_default/tmp/rootfs"
|
|
|
|
self.args = [
|
|
|
|
workspace_dir + "/ROMFS/px4fmu_common",
|
|
|
|
"-s",
|
|
|
|
"etc/init.d-posix/rcS",
|
|
|
|
"-t",
|
|
|
|
workspace_dir + "/test_data",
|
|
|
|
"-d"
|
|
|
|
]
|
2020-03-13 05:18:10 -03:00
|
|
|
self.env = {"PATH": str(os.environ['PATH']),
|
2020-03-16 12:05:12 -03:00
|
|
|
"PX4_SIM_MODEL": self.model,
|
2020-03-11 14:17:04 -03:00
|
|
|
"PX4_SIM_SPEED_FACTOR": str(speed_factor)}
|
|
|
|
self.debugger = debugger
|
|
|
|
|
|
|
|
if not self.debugger:
|
|
|
|
pass
|
|
|
|
elif self.debugger == "valgrind":
|
|
|
|
self.args = ["--track-origins=yes", "--leak-check=full", "-v",
|
|
|
|
self.cmd] + self.args
|
|
|
|
self.cmd = "valgrind"
|
|
|
|
elif self.debugger == "callgrind":
|
|
|
|
self.args = ["--tool=callgrind", "-v", self.cmd] + self.args
|
|
|
|
self.cmd = "valgrind"
|
|
|
|
elif self.debugger == "gdb":
|
|
|
|
self.args = ["--args", self.cmd] + self.args
|
|
|
|
self.cmd = "gdb"
|
|
|
|
else:
|
|
|
|
print("Using custom debugger " + self.debugger)
|
|
|
|
self.args = [self.cmd] + self.args
|
|
|
|
self.cmd = self.debugger
|
|
|
|
|
|
|
|
|
|
|
|
class GzserverRunner(Runner):
|
2020-03-13 06:02:58 -03:00
|
|
|
def __init__(self,
|
|
|
|
workspace_dir: str,
|
|
|
|
log_dir: str,
|
2020-03-16 12:05:12 -03:00
|
|
|
model: str,
|
|
|
|
case: str,
|
2020-03-13 06:02:58 -03:00
|
|
|
speed_factor: float,
|
|
|
|
verbose: bool):
|
2020-03-16 12:05:12 -03:00
|
|
|
super().__init__(log_dir, model, case, verbose)
|
2020-03-11 14:17:04 -03:00
|
|
|
self.name = "gzserver"
|
2020-03-13 05:18:10 -03:00
|
|
|
self.cwd = workspace_dir
|
2020-03-11 14:17:04 -03:00
|
|
|
self.env = {"PATH": os.environ['PATH'],
|
|
|
|
"HOME": os.environ['HOME'],
|
|
|
|
"GAZEBO_PLUGIN_PATH":
|
|
|
|
workspace_dir + "/build/px4_sitl_default/build_gazebo",
|
|
|
|
"GAZEBO_MODEL_PATH":
|
|
|
|
workspace_dir + "/Tools/sitl_gazebo/models",
|
|
|
|
"PX4_SIM_SPEED_FACTOR": str(speed_factor),
|
2020-03-18 09:31:18 -03:00
|
|
|
"DISPLAY": os.environ['DISPLAY']}
|
|
|
|
self.add_to_env_if_set("PX4_HOME_LAT")
|
|
|
|
self.add_to_env_if_set("PX4_HOME_LON")
|
|
|
|
self.add_to_env_if_set("PX4_HOME_ALT")
|
2020-03-11 14:17:04 -03:00
|
|
|
self.cmd = "gzserver"
|
|
|
|
self.args = ["--verbose",
|
|
|
|
workspace_dir + "/Tools/sitl_gazebo/worlds/" +
|
2020-03-16 12:05:12 -03:00
|
|
|
self.model + ".world"]
|
2020-03-11 14:17:04 -03:00
|
|
|
|
2020-03-18 09:31:18 -03:00
|
|
|
def add_to_env_if_set(self, var: str) -> None:
|
|
|
|
if var in os.environ:
|
|
|
|
self.env[var] = os.environ[var]
|
|
|
|
|
2020-03-11 14:17:04 -03:00
|
|
|
|
|
|
|
class GzclientRunner(Runner):
|
2020-03-13 06:02:58 -03:00
|
|
|
def __init__(self,
|
|
|
|
workspace_dir: str,
|
|
|
|
log_dir: str,
|
2020-03-16 12:05:12 -03:00
|
|
|
model: str,
|
|
|
|
case: str,
|
2020-03-13 06:02:58 -03:00
|
|
|
verbose: bool):
|
2020-03-16 12:05:12 -03:00
|
|
|
super().__init__(log_dir, model, case, verbose)
|
2020-03-11 14:17:04 -03:00
|
|
|
self.name = "gzclient"
|
2020-03-13 05:18:10 -03:00
|
|
|
self.cwd = workspace_dir
|
2020-03-11 14:17:04 -03:00
|
|
|
self.env = {"PATH": os.environ['PATH'],
|
|
|
|
"HOME": os.environ['HOME'],
|
|
|
|
"GAZEBO_MODEL_PATH":
|
|
|
|
workspace_dir + "/Tools/sitl_gazebo/models",
|
|
|
|
"DISPLAY": os.environ['DISPLAY']}
|
|
|
|
self.cmd = "gzclient"
|
|
|
|
self.args = ["--verbose"]
|
|
|
|
|
|
|
|
|
|
|
|
class TestRunner(Runner):
|
2020-03-13 06:02:58 -03:00
|
|
|
def __init__(self,
|
|
|
|
workspace_dir: str,
|
|
|
|
log_dir: str,
|
2020-03-16 12:05:12 -03:00
|
|
|
model: str,
|
|
|
|
case: str,
|
2020-03-13 06:02:58 -03:00
|
|
|
mavlink_connection: str,
|
|
|
|
verbose: bool):
|
2020-03-16 12:05:12 -03:00
|
|
|
super().__init__(log_dir, model, case, verbose)
|
2020-03-11 14:17:04 -03:00
|
|
|
self.name = "test_runner"
|
2020-03-13 05:18:10 -03:00
|
|
|
self.cwd = workspace_dir
|
2020-03-11 14:17:04 -03:00
|
|
|
self.env = {"PATH": os.environ['PATH']}
|
|
|
|
self.cmd = workspace_dir + \
|
|
|
|
"/build/px4_sitl_default/mavsdk_tests/mavsdk_tests"
|
2020-03-16 12:05:12 -03:00
|
|
|
self.args = ["--url", mavlink_connection, case]
|