mavsdk_tests: output less verbose unless needed

This commit is contained in:
Julian Oes 2020-03-06 18:48:14 +01:00 committed by Nuno Marques
parent 0989e90b4a
commit 911cdc8774
1 changed files with 43 additions and 33 deletions

View File

@ -13,27 +13,31 @@ import signal
class Runner: class Runner:
def __init__(self, log_dir): def __init__(self, log_dir, verbose):
self.cmd = "" self.cmd = ""
self.cwd = None self.cwd = None
self.args = [] self.args = []
self.env = {} self.env = {}
self.log_prefix = "" self.log_prefix = ""
self.log_dir = log_dir self.log_dir = log_dir
self.verbose = verbose
def start(self, config): def start(self, config):
if self.verbose:
print("Running: {}".format(" ".join([self.cmd] + self.args)))
atexit.register(self.stop)
if self.log_dir: if self.log_dir:
f = open(self.log_dir + os.path.sep + f = open(
"log-{}-{}-{}-{}.log".format( self.log_dir + os.path.sep + "log-{}-{}-{}-{}.log".format(
self.log_prefix, self.log_prefix, config['model'], config['test_filter'],
config['model'], datetime.datetime.now().strftime("%Y-%m-%dT%H-%M-%SZ")),
config['test_filter'], 'w')
datetime.datetime.now().strftime("%Y-%m-%dT%H-%M-%SZ")
), 'w')
else: else:
f = None f = None
print("Running: {}".format(" ".join([self.cmd] + self.args))) # TODO: pipe stdout through when set to verbose
self.process = subprocess.Popen( self.process = subprocess.Popen(
[self.cmd] + self.args, [self.cmd] + self.args,
@ -43,8 +47,6 @@ class Runner:
stderr=f stderr=f
) )
atexit.register(self.stop)
def wait(self, timeout_min): def wait(self, timeout_min):
try: try:
return self.process.wait(timeout=timeout_min*60) return self.process.wait(timeout=timeout_min*60)
@ -62,6 +64,7 @@ class Runner:
if returncode is not None: if returncode is not None:
return returncode return returncode
if self.verbose:
print("Sending SIGINT to {}".format(self.process.pid)) print("Sending SIGINT to {}".format(self.process.pid))
self.process.send_signal(signal.SIGINT) self.process.send_signal(signal.SIGINT)
try: try:
@ -69,6 +72,7 @@ class Runner:
except subprocess.TimeoutExpired: except subprocess.TimeoutExpired:
pass pass
if self.verbose:
print("Terminating {}".format(self.process.pid)) print("Terminating {}".format(self.process.pid))
self.process.terminate() self.process.terminate()
@ -77,14 +81,20 @@ class Runner:
except subprocess.TimeoutExpired: except subprocess.TimeoutExpired:
pass pass
if self.verbose:
print("Killing {}".format(self.process.pid)) print("Killing {}".format(self.process.pid))
self.process.kill() self.process.kill()
if self.verbose:
print("{} exited with {}".format(
self.command, self.process.returncode))
return self.process.returncode return self.process.returncode
class Px4Runner(Runner): class Px4Runner(Runner):
def __init__(self, model, workspace_dir, log_dir, speed_factor, debugger): def __init__(self, model, workspace_dir, log_dir, speed_factor, debugger,
super().__init__(log_dir) verbose):
super().__init__(log_dir, verbose)
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"
self.args = [ self.args = [
@ -119,8 +129,8 @@ class Px4Runner(Runner):
class GzserverRunner(Runner): class GzserverRunner(Runner):
def __init__(self, model, workspace_dir, log_dir, speed_factor): def __init__(self, model, workspace_dir, log_dir, speed_factor, verbose):
super().__init__(log_dir) super().__init__(log_dir, verbose)
self.env = {"PATH": os.environ['PATH'], self.env = {"PATH": os.environ['PATH'],
"HOME": os.environ['HOME'], "HOME": os.environ['HOME'],
"GAZEBO_PLUGIN_PATH": "GAZEBO_PLUGIN_PATH":
@ -137,8 +147,8 @@ class GzserverRunner(Runner):
class GzclientRunner(Runner): class GzclientRunner(Runner):
def __init__(self, workspace_dir, log_dir): def __init__(self, workspace_dir, log_dir, verbose):
super().__init__(log_dir) super().__init__(log_dir, verbose)
self.env = {"PATH": os.environ['PATH'], self.env = {"PATH": os.environ['PATH'],
"HOME": os.environ['HOME'], "HOME": os.environ['HOME'],
# "GAZEBO_PLUGIN_PATH": # "GAZEBO_PLUGIN_PATH":
@ -153,8 +163,8 @@ class GzclientRunner(Runner):
class TestRunner(Runner): class TestRunner(Runner):
def __init__(self, workspace_dir, log_dir, config, test, def __init__(self, workspace_dir, log_dir, config, test,
mavlink_connection): mavlink_connection, verbose):
super().__init__(log_dir) super().__init__(log_dir, verbose)
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"
@ -179,6 +189,8 @@ def main():
help="Specify which model to run") help="Specify which model to run")
parser.add_argument("--debugger", default="", parser.add_argument("--debugger", default="",
help="valgrind callgrind gdb lldb") help="valgrind callgrind gdb lldb")
parser.add_argument("--verbose", default=False, action='store_true',
help="Enable more verbose output")
parser.add_argument("config_file", help="JSON config file to use") parser.add_argument("config_file", help="JSON config file to use")
args = parser.parse_args() args = parser.parse_args()
@ -193,6 +205,8 @@ def main():
if not is_everything_ready(config): if not is_everything_ready(config):
sys.exit(1) sys.exit(1)
if args.verbose:
print("Creating directory: {}".format(args.log_dir))
os.makedirs(args.log_dir, exist_ok=True) os.makedirs(args.log_dir, exist_ok=True)
run(args, config) run(args, config)
@ -319,21 +333,22 @@ def run_test(test, group, args, config):
if config['mode'] == 'sitl': if config['mode'] == 'sitl':
px4_runner = Px4Runner( px4_runner = Px4Runner(
group['model'], os.getcwd(), args.log_dir, speed_factor, group['model'], os.getcwd(), args.log_dir, speed_factor,
args.debugger) args.debugger, args.verbose)
px4_runner.start(group) px4_runner.start(group)
if config['simulator'] == 'gazebo': if config['simulator'] == 'gazebo':
gzserver_runner = GzserverRunner( gzserver_runner = GzserverRunner(
group['model'], os.getcwd(), args.log_dir, speed_factor) group['model'], os.getcwd(), args.log_dir, speed_factor,
args.verbose)
gzserver_runner.start(group) gzserver_runner.start(group)
if args.gui: if args.gui:
gzclient_runner = GzclientRunner( gzclient_runner = GzclientRunner(
os.getcwd(), args.log_dir) os.getcwd(), args.log_dir, args.verbose)
gzclient_runner.start(group) gzclient_runner.start(group)
test_runner = TestRunner(os.getcwd(), args.log_dir, group, test, test_runner = TestRunner(os.getcwd(), args.log_dir, group, test,
config['mavlink_connection']) config['mavlink_connection'], args.verbose)
test_runner.start(group) test_runner.start(group)
returncode = test_runner.wait(group['timeout_min']) returncode = test_runner.wait(group['timeout_min'])
@ -342,14 +357,9 @@ def run_test(test, group, args, config):
if config['mode'] == 'sitl': if config['mode'] == 'sitl':
if config['simulator'] == 'gazebo': if config['simulator'] == 'gazebo':
if args.gui: if args.gui:
returncode = gzclient_runner.stop() gzclient_runner.stop()
print("gzclient exited with {}".format(returncode)) gzserver_runner.stop()
returncode = gzserver_runner.stop()
print("gzserver exited with {}".format(returncode))
px4_runner.stop() px4_runner.stop()
print("px4 exited with {}".format(returncode))
return is_success return is_success