forked from Archive/PX4-Autopilot
mavsdk_tests: wait for gz to run for model spawn
This commit is contained in:
parent
b1d3b95ebf
commit
29c102b205
|
@ -381,12 +381,19 @@ class Tester:
|
||||||
self.verbose)
|
self.verbose)
|
||||||
self.active_runners.append(gzserver_runner)
|
self.active_runners.append(gzserver_runner)
|
||||||
|
|
||||||
|
waitforgz_runner = ph.WaitforgzRunner(
|
||||||
|
os.getcwd(),
|
||||||
|
log_dir,
|
||||||
|
test['model'],
|
||||||
|
case,
|
||||||
|
self.verbose)
|
||||||
|
self.active_runners.append(waitforgz_runner)
|
||||||
|
|
||||||
gzmodelspawn_runner = ph.GzmodelspawnRunner(
|
gzmodelspawn_runner = ph.GzmodelspawnRunner(
|
||||||
os.getcwd(),
|
os.getcwd(),
|
||||||
log_dir,
|
log_dir,
|
||||||
test['model'],
|
test['model'],
|
||||||
case,
|
case,
|
||||||
self.get_max_speed_factor(test),
|
|
||||||
self.verbose)
|
self.verbose)
|
||||||
self.active_runners.append(gzmodelspawn_runner)
|
self.active_runners.append(gzmodelspawn_runner)
|
||||||
|
|
||||||
|
|
|
@ -6,6 +6,7 @@ import os
|
||||||
import atexit
|
import atexit
|
||||||
import subprocess
|
import subprocess
|
||||||
import threading
|
import threading
|
||||||
|
import pathlib
|
||||||
import errno
|
import errno
|
||||||
from typing import Dict, List, TextIO, Optional
|
from typing import Dict, List, TextIO, Optional
|
||||||
|
|
||||||
|
@ -30,6 +31,7 @@ class Runner:
|
||||||
self.start_time = time.time()
|
self.start_time = time.time()
|
||||||
self.log_dir = log_dir
|
self.log_dir = log_dir
|
||||||
self.log_filename = ""
|
self.log_filename = ""
|
||||||
|
self.wait_until_complete = False
|
||||||
|
|
||||||
def set_log_filename(self, log_filename: str) -> None:
|
def set_log_filename(self, log_filename: str) -> None:
|
||||||
self.log_filename = log_filename
|
self.log_filename = log_filename
|
||||||
|
@ -59,6 +61,9 @@ class Runner:
|
||||||
self.stop_thread = threading.Event()
|
self.stop_thread = threading.Event()
|
||||||
self.thread = threading.Thread(target=self.process_output)
|
self.thread = threading.Thread(target=self.process_output)
|
||||||
self.thread.start()
|
self.thread.start()
|
||||||
|
if self.wait_until_complete:
|
||||||
|
if self.wait(1.0) != 0:
|
||||||
|
raise TimeoutError("Command not completed")
|
||||||
|
|
||||||
def process_output(self) -> None:
|
def process_output(self) -> None:
|
||||||
assert self.process.stdout is not None
|
assert self.process.stdout is not None
|
||||||
|
@ -197,13 +202,30 @@ class GzserverRunner(Runner):
|
||||||
self.env[var] = os.environ[var]
|
self.env[var] = os.environ[var]
|
||||||
|
|
||||||
|
|
||||||
|
class WaitforgzRunner(Runner):
|
||||||
|
def __init__(self,
|
||||||
|
workspace_dir: str,
|
||||||
|
log_dir: str,
|
||||||
|
model: str,
|
||||||
|
case: str,
|
||||||
|
verbose: bool):
|
||||||
|
super().__init__(log_dir, model, case, verbose)
|
||||||
|
self.name = "waitforgz"
|
||||||
|
self.cwd = workspace_dir
|
||||||
|
self.env = {"PATH": os.environ['PATH'],
|
||||||
|
"HOME": os.environ['HOME']}
|
||||||
|
script_dir = pathlib.Path(__file__).parent.absolute()
|
||||||
|
self.cmd = os.path.join(script_dir, "waitforgz.sh")
|
||||||
|
self.args = []
|
||||||
|
self.wait_until_complete = True
|
||||||
|
|
||||||
|
|
||||||
class GzmodelspawnRunner(Runner):
|
class GzmodelspawnRunner(Runner):
|
||||||
def __init__(self,
|
def __init__(self,
|
||||||
workspace_dir: str,
|
workspace_dir: str,
|
||||||
log_dir: str,
|
log_dir: str,
|
||||||
model: str,
|
model: str,
|
||||||
case: str,
|
case: str,
|
||||||
speed_factor: float,
|
|
||||||
verbose: bool):
|
verbose: bool):
|
||||||
super().__init__(log_dir, model, case, verbose)
|
super().__init__(log_dir, model, case, verbose)
|
||||||
self.name = "gzmodelspawn"
|
self.name = "gzmodelspawn"
|
||||||
|
@ -214,21 +236,14 @@ class GzmodelspawnRunner(Runner):
|
||||||
workspace_dir + "/build/px4_sitl_default/build_gazebo",
|
workspace_dir + "/build/px4_sitl_default/build_gazebo",
|
||||||
"GAZEBO_MODEL_PATH":
|
"GAZEBO_MODEL_PATH":
|
||||||
workspace_dir + "/Tools/sitl_gazebo/models",
|
workspace_dir + "/Tools/sitl_gazebo/models",
|
||||||
"PX4_SIM_SPEED_FACTOR": str(speed_factor),
|
|
||||||
"DISPLAY": os.environ['DISPLAY']}
|
"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")
|
|
||||||
self.cmd = "gz"
|
self.cmd = "gz"
|
||||||
self.args = ["model", "--spawn-file", workspace_dir +
|
self.args = ["model", "--spawn-file", workspace_dir +
|
||||||
"/Tools/sitl_gazebo/models/" +
|
"/Tools/sitl_gazebo/models/" +
|
||||||
self.model + "/" + self.model + ".sdf",
|
self.model + "/" + self.model + ".sdf",
|
||||||
"--model-name", self.model,
|
"--model-name", self.model,
|
||||||
"-x", "1.01", "-y", "0.98", "-z", "0.83"]
|
"-x", "1.01", "-y", "0.98", "-z", "0.83"]
|
||||||
|
self.wait_until_complete = True
|
||||||
def add_to_env_if_set(self, var: str) -> None:
|
|
||||||
if var in os.environ:
|
|
||||||
self.env[var] = os.environ[var]
|
|
||||||
|
|
||||||
|
|
||||||
class GzclientRunner(Runner):
|
class GzclientRunner(Runner):
|
||||||
|
|
|
@ -0,0 +1,7 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
while gz stats -d 0 2>&1 | grep "An instance of Gazebo is not running."; do
|
||||||
|
echo "Still running"
|
||||||
|
done
|
||||||
|
|
||||||
|
echo "done"
|
Loading…
Reference in New Issue