mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavsdk_tests: update to be able to fetch rtps builds as well
This commit is contained in:
parent
9312c772f1
commit
9894598b63
@ -52,6 +52,9 @@ def main() -> NoReturn:
|
||||
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("--build-dir", type=str,
|
||||
default='build/px4_sitl_default/',
|
||||
help="relative path where the built files are stored")
|
||||
args = parser.parse_args()
|
||||
|
||||
with open(args.config_file) as json_file:
|
||||
@ -62,7 +65,7 @@ def main() -> NoReturn:
|
||||
.format(config["mode"]))
|
||||
sys.exit(1)
|
||||
|
||||
if not is_everything_ready(config):
|
||||
if not is_everything_ready(config, args.build_dir):
|
||||
sys.exit(1)
|
||||
|
||||
if args.verbose:
|
||||
@ -80,7 +83,8 @@ def main() -> NoReturn:
|
||||
args.log_dir,
|
||||
args.gui,
|
||||
args.verbose,
|
||||
args.upload
|
||||
args.upload,
|
||||
args.build_dir
|
||||
)
|
||||
signal.signal(signal.SIGINT, tester.sigint_handler)
|
||||
|
||||
@ -94,7 +98,7 @@ def is_running(process_name: str) -> bool:
|
||||
return False
|
||||
|
||||
|
||||
def is_everything_ready(config: Dict[str, str]) -> bool:
|
||||
def is_everything_ready(config: Dict[str, str], build_dir: str) -> bool:
|
||||
result = True
|
||||
|
||||
if config['mode'] == 'sitl':
|
||||
@ -102,10 +106,11 @@ def is_everything_ready(config: Dict[str, str]) -> bool:
|
||||
print("px4 process already running\n"
|
||||
"run `killall px4` and try again")
|
||||
result = False
|
||||
if not os.path.isfile('build/px4_sitl_default/bin/px4'):
|
||||
if not os.path.isfile(os.path.join(build_dir, 'bin/px4')):
|
||||
print("PX4 SITL is not built\n"
|
||||
"run `DONT_RUN=1 "
|
||||
"make px4_sitl gazebo mavsdk_tests`")
|
||||
"make px4_sitl gazebo mavsdk_tests` or "
|
||||
"`DONT_RUN=1 make px4_sitl_rtps gazebo mavsdk_tests`")
|
||||
result = False
|
||||
if config['simulator'] == 'gazebo':
|
||||
if is_running('gzserver'):
|
||||
@ -117,10 +122,12 @@ def is_everything_ready(config: Dict[str, str]) -> bool:
|
||||
"run `killall gzclient` and try again")
|
||||
result = False
|
||||
|
||||
if not os.path.isfile('build/px4_sitl_default/mavsdk_tests/mavsdk_tests'):
|
||||
if not os.path.isfile(os.path.join(build_dir,
|
||||
'mavsdk_tests/mavsdk_tests')):
|
||||
print("Test runner is not built\n"
|
||||
"run `DONT_RUN=1 "
|
||||
"make px4_sitl gazebo mavsdk_tests`")
|
||||
"make px4_sitl gazebo mavsdk_tests` or "
|
||||
"`DONT_RUN=1 make px4_sitl_rtps gazebo mavsdk_tests`")
|
||||
result = False
|
||||
|
||||
return result
|
||||
@ -138,8 +145,10 @@ class Tester:
|
||||
log_dir: str,
|
||||
gui: bool,
|
||||
verbose: bool,
|
||||
upload: bool):
|
||||
upload: bool,
|
||||
build_dir: str):
|
||||
self.config = config
|
||||
self.build_dir = build_dir
|
||||
self.active_runners: List[ph.Runner]
|
||||
self.iterations = iterations
|
||||
self.abort_early = abort_early
|
||||
@ -153,30 +162,20 @@ class Tester:
|
||||
self.start_time = datetime.datetime.now()
|
||||
self.log_fd: Any[TextIO] = None
|
||||
|
||||
@classmethod
|
||||
def determine_tests(cls,
|
||||
tests: List[Dict[str, Any]],
|
||||
model: str,
|
||||
case: str) -> List[Dict[str, Any]]:
|
||||
for test in tests:
|
||||
test['selected'] = (model == 'all' or model == test['model'])
|
||||
test['cases'] = dict.fromkeys(
|
||||
cls.query_test_cases(test['test_filter']))
|
||||
for key in test['cases'].keys():
|
||||
test['cases'][key] = {
|
||||
'selected': (test['selected'] and
|
||||
(case == 'all' or
|
||||
cls.wildcard_match(case, key)))}
|
||||
|
||||
return tests
|
||||
|
||||
@staticmethod
|
||||
def wildcard_match(pattern: str, potential_match: str) -> bool:
|
||||
return fnmatch.fnmatchcase(potential_match, pattern)
|
||||
|
||||
@staticmethod
|
||||
def query_test_cases(filter: str) -> List[str]:
|
||||
cmd = os.getcwd() + "/build/px4_sitl_default/mavsdk_tests/mavsdk_tests"
|
||||
def plural_s(n_items: int) -> str:
|
||||
if n_items > 1:
|
||||
return "s"
|
||||
else:
|
||||
return ""
|
||||
|
||||
@staticmethod
|
||||
def query_test_cases(build_dir: str, filter: str) -> List[str]:
|
||||
cmd = os.path.join(build_dir, 'mavsdk_tests/mavsdk_tests')
|
||||
args = ["--list-test-names-only", filter]
|
||||
p = subprocess.Popen(
|
||||
[cmd] + args,
|
||||
@ -187,12 +186,20 @@ class Tester:
|
||||
cases = str(p.stdout.read().decode("utf-8")).strip().split('\n')
|
||||
return cases
|
||||
|
||||
@staticmethod
|
||||
def plural_s(n_items: int) -> str:
|
||||
if n_items > 1:
|
||||
return "s"
|
||||
else:
|
||||
return ""
|
||||
def determine_tests(self,
|
||||
tests: List[Dict[str, Any]],
|
||||
model: str,
|
||||
case: str) -> List[Dict[str, Any]]:
|
||||
for test in tests:
|
||||
test['selected'] = (model == 'all' or model == test['model'])
|
||||
test['cases'] = dict.fromkeys(
|
||||
self.query_test_cases(self.build_dir, test['test_filter']))
|
||||
for key in test['cases'].keys():
|
||||
test['cases'][key] = {
|
||||
'selected': (test['selected'] and
|
||||
(case == 'all' or
|
||||
self.wildcard_match(case, key)))}
|
||||
return tests
|
||||
|
||||
def run(self) -> bool:
|
||||
self.show_plans()
|
||||
@ -392,6 +399,7 @@ class Tester:
|
||||
test: Dict[str, Any],
|
||||
case: str) -> None:
|
||||
self.active_runners = []
|
||||
|
||||
if self.config['mode'] == 'sitl':
|
||||
px4_runner = ph.Px4Runner(
|
||||
os.getcwd(),
|
||||
@ -400,7 +408,8 @@ class Tester:
|
||||
case,
|
||||
self.get_max_speed_factor(test),
|
||||
self.debugger,
|
||||
self.verbose)
|
||||
self.verbose,
|
||||
self.build_dir)
|
||||
self.active_runners.append(px4_runner)
|
||||
|
||||
if self.config['simulator'] == 'gazebo':
|
||||
@ -410,7 +419,8 @@ class Tester:
|
||||
test['vehicle'],
|
||||
case,
|
||||
self.get_max_speed_factor(test),
|
||||
self.verbose)
|
||||
self.verbose,
|
||||
self.build_dir)
|
||||
self.active_runners.append(gzserver_runner)
|
||||
|
||||
gzmodelspawn_runner = ph.GzmodelspawnRunner(
|
||||
@ -418,7 +428,8 @@ class Tester:
|
||||
log_dir,
|
||||
test['vehicle'],
|
||||
case,
|
||||
self.verbose)
|
||||
self.verbose,
|
||||
self.build_dir)
|
||||
self.active_runners.append(gzmodelspawn_runner)
|
||||
|
||||
if self.gui:
|
||||
@ -437,7 +448,8 @@ class Tester:
|
||||
case,
|
||||
self.config['mavlink_connection'],
|
||||
self.speed_factor,
|
||||
self.verbose)
|
||||
self.verbose,
|
||||
self.build_dir)
|
||||
self.active_runners.append(mavsdk_tests_runner)
|
||||
|
||||
abort = False
|
||||
@ -490,9 +502,9 @@ class Tester:
|
||||
for line in log.splitlines():
|
||||
found = line.find(match)
|
||||
if found != -1:
|
||||
return os.getcwd() \
|
||||
+ "/build/px4_sitl_default/tmp_mavsdk_tests/rootfs/" \
|
||||
+ line[found+len(match):]
|
||||
return os.path.join(os.getcwd(), self.build_dir,
|
||||
"tmp_mavsdk_tests/rootfs",
|
||||
line[found+len(match):])
|
||||
return None
|
||||
|
||||
def upload_log(self, ulog_path: Optional[str],
|
||||
|
||||
@ -146,18 +146,18 @@ class Runner:
|
||||
class Px4Runner(Runner):
|
||||
def __init__(self, workspace_dir: str, log_dir: str,
|
||||
model: str, case: str, speed_factor: float,
|
||||
debugger: str, verbose: bool):
|
||||
debugger: str, verbose: bool, build_dir: str):
|
||||
super().__init__(log_dir, model, case, verbose)
|
||||
self.name = "px4"
|
||||
self.cmd = workspace_dir + "/build/px4_sitl_default/bin/px4"
|
||||
self.cwd = workspace_dir + \
|
||||
"/build/px4_sitl_default/tmp_mavsdk_tests/rootfs"
|
||||
self.cmd = os.path.join(workspace_dir, build_dir, "bin/px4")
|
||||
self.cwd = os.path.join(workspace_dir, build_dir,
|
||||
"tmp_mavsdk_tests/rootfs")
|
||||
self.args = [
|
||||
workspace_dir + "/build/px4_sitl_default/etc",
|
||||
os.path.join(workspace_dir, build_dir, "etc"),
|
||||
"-s",
|
||||
"etc/init.d-posix/rcS",
|
||||
"-t",
|
||||
workspace_dir + "/test_data",
|
||||
os.path.join(workspace_dir, "test_data"),
|
||||
"-d"
|
||||
]
|
||||
self.env["PX4_SIM_MODEL"] = self.model
|
||||
@ -214,14 +214,15 @@ class GzserverRunner(Runner):
|
||||
model: str,
|
||||
case: str,
|
||||
speed_factor: float,
|
||||
verbose: bool):
|
||||
verbose: bool,
|
||||
build_dir: str):
|
||||
super().__init__(log_dir, model, case, verbose)
|
||||
self.name = "gzserver"
|
||||
self.cwd = workspace_dir
|
||||
self.env["GAZEBO_PLUGIN_PATH"] = \
|
||||
workspace_dir + "/build/px4_sitl_default/build_gazebo"
|
||||
os.path.join(workspace_dir, build_dir, "build_gazebo")
|
||||
self.env["GAZEBO_MODEL_PATH"] = \
|
||||
workspace_dir + "/Tools/sitl_gazebo/models"
|
||||
os.path.join(workspace_dir, "Tools/sitl_gazebo/models")
|
||||
self.env["PX4_SIM_SPEED_FACTOR"] = str(speed_factor)
|
||||
self.cmd = "stdbuf"
|
||||
self.args = ["-o0", "-e0", "gzserver", "--verbose",
|
||||
@ -251,28 +252,29 @@ class GzmodelspawnRunner(Runner):
|
||||
log_dir: str,
|
||||
model: str,
|
||||
case: str,
|
||||
verbose: bool):
|
||||
verbose: bool,
|
||||
build_dir: str):
|
||||
super().__init__(log_dir, model, case, verbose)
|
||||
self.name = "gzmodelspawn"
|
||||
self.cwd = workspace_dir
|
||||
self.env["GAZEBO_PLUGIN_PATH"] = \
|
||||
workspace_dir + "/build/px4_sitl_default/build_gazebo"
|
||||
os.path.join(workspace_dir, build_dir, "build_gazebo")
|
||||
self.env["GAZEBO_MODEL_PATH"] = \
|
||||
workspace_dir + "/Tools/sitl_gazebo/models"
|
||||
os.path.join(workspace_dir, "Tools/sitl_gazebo/models")
|
||||
self.cmd = "gz"
|
||||
|
||||
if os.path.isfile(workspace_dir +
|
||||
"/Tools/sitl_gazebo/models/" +
|
||||
self.model + "/" + self.model + ".sdf"):
|
||||
model_path = workspace_dir + \
|
||||
"/Tools/sitl_gazebo/models/" + \
|
||||
self.model + "/" + self.model + ".sdf"
|
||||
elif os.path.isfile(workspace_dir +
|
||||
"/Tools/sitl_gazebo/models/" +
|
||||
self.model + "/" + self.model + "-gen.sdf"):
|
||||
model_path = workspace_dir + \
|
||||
"/Tools/sitl_gazebo/models/" + \
|
||||
self.model + "/" + self.model + "-gen.sdf"
|
||||
if os.path.isfile(os.path.join(workspace_dir,
|
||||
"Tools/sitl_gazebo/models",
|
||||
self.model, self.model + ".sdf")):
|
||||
model_path = os.path.join(workspace_dir,
|
||||
"Tools/sitl_gazebo/models",
|
||||
self.model, self.model + ".sdf")
|
||||
elif os.path.isfile(os.path.join(workspace_dir,
|
||||
"Tools/sitl_gazebo/models",
|
||||
self.model, self.model + "-gen.sdf")):
|
||||
model_path = os.path.join(workspace_dir,
|
||||
"Tools/sitl_gazebo/models",
|
||||
self.model, self.model + "-gen.sdf")
|
||||
else:
|
||||
raise Exception("Model not found")
|
||||
|
||||
@ -322,7 +324,8 @@ class GzclientRunner(Runner):
|
||||
self.name = "gzclient"
|
||||
self.cwd = workspace_dir
|
||||
self.env = dict(os.environ, **{
|
||||
"GAZEBO_MODEL_PATH": workspace_dir + "/Tools/sitl_gazebo/models"})
|
||||
"GAZEBO_MODEL_PATH": os.path.join(workspace_dir,
|
||||
"Tools/sitl_gazebo/models")})
|
||||
self.cmd = "gzclient"
|
||||
self.args = ["--verbose"]
|
||||
|
||||
@ -335,12 +338,13 @@ class TestRunner(Runner):
|
||||
case: str,
|
||||
mavlink_connection: str,
|
||||
speed_factor: float,
|
||||
verbose: bool):
|
||||
verbose: bool,
|
||||
build_dir: str):
|
||||
super().__init__(log_dir, model, case, verbose)
|
||||
self.name = "mavsdk_tests"
|
||||
self.cwd = workspace_dir
|
||||
self.cmd = workspace_dir + \
|
||||
"/build/px4_sitl_default/mavsdk_tests/mavsdk_tests"
|
||||
self.cmd = os.path.join(workspace_dir, build_dir,
|
||||
"mavsdk_tests/mavsdk_tests")
|
||||
self.args = ["--url", mavlink_connection,
|
||||
"--speed-factor", str(speed_factor),
|
||||
case]
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user