From f0a292e53eaf52b2a72e339644bc97fc814b21c7 Mon Sep 17 00:00:00 2001 From: Henning Wiedemann Date: Tue, 13 Feb 2024 15:36:25 +0100 Subject: [PATCH] Fix model_testing.py Relates to #336 --- phobos/ci/model_testing.py | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/phobos/ci/model_testing.py b/phobos/ci/model_testing.py index 9b399f12..675bfbf7 100644 --- a/phobos/ci/model_testing.py +++ b/phobos/ci/model_testing.py @@ -25,15 +25,15 @@ def __init__(self, new_model, compare_model=None): self.old_hyrodyn = None self.new_hml_test = get_load_report(self.new.robot.xmlfile, self.new.robot.submechanisms_file) self.new_sm_hml_test = [] - if len([x for x in self.new.robot.submodel_defs if not x["name"].startswith("#submech#")]) > 0: + if len([x for name, x in self.new.robot.submodel_defs.items() if not name.startswith("#submech#")]) > 0: sm_path = os.path.join(self.new.exportdir, "submodels") - for au in self.new.robot.submodel_defs: - if au["name"].startswith("#submech#"): + for name, au in self.new.robot.submodel_defs.items(): + if name.startswith("#submech#"): continue self.new_sm_hml_test += [{ - "name": au["name"], - "urdf": os.path.join(sm_path, au["name"], "urdf", au["name"] + ".urdf"), - "submech": os.path.normpath(os.path.join(sm_path, au["name"], "smurf", au["name"] + "_submechanisms.yml")) + "name": name, + "urdf": os.path.join(sm_path, name, "urdf", name + ".urdf"), + "submech": os.path.normpath(os.path.join(sm_path, name, "smurf", name + "_submechanisms.yml")) }] self.new_sm_hml_test[-1]["report"] = get_load_report( self.new_sm_hml_test[-1]["urdf"], @@ -267,10 +267,12 @@ def test_compare_amount_joints(self): return len(self.new.robot.joints) == len(self.old.joints) def test_load_in_pybullet(self): - if not PYBULLET_AVAILABLE: log.warning('Pybullet not present') return True + from ..defs import check_pybullet_available + if not check_pybullet_available(): try: + import pybullet as pb client = pb.connect(pb.DIRECT) pb.loadURDF(os.path.join(self.new.robot.xmlfile), physicsClientId=client) pb.disconnect(client)