From 3031a95893a8fa372520263bec6597ef9e4a0f41 Mon Sep 17 00:00:00 2001 From: Junjia Liu Date: Mon, 14 Oct 2024 18:01:56 +0800 Subject: [PATCH] =?UTF-8?q?=F0=9F=90=9B=20Fix=20some=20bugs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../example_HumanoidASE_ViewMotion.py | 5 +- .../example_HumanoidHOTU_RofuncRL.py | 10 +- .../example_HumanoidPhysHOI_RofuncRL.py | 2 +- .../IsaacLab_RofuncRL/example_isaaclab_env.py | 105 + .../robolab/example_coordinate_transform.py | 13 +- examples/robolab/example_forward_dynamics.py | 72 + .../robolab/example_forward_kinematics.py | 58 +- .../robolab/example_inverse_kinematics.py | 19 +- examples/robolab/example_jacobain.py | 26 + examples/robolab/example_rdf.py | 94 - examples/robolab/example_rdf_bbo_planning.py | 110 - examples/simulator/example_robot_play.py | 12 +- rofunc/__init__.py | 19 +- rofunc/devices/emg/export.py | 5 +- rofunc/learning/RofuncRL/models/utils.py | 3 + .../RofuncRL/state_encoders/graph_encoders.py | 5 +- rofunc/learning/RofuncRL/tasks/__init__.py | 24 +- .../RofuncRL/tasks/utils/env_loaders.py | 204 +- rofunc/learning/RofuncRL/trainers/__init__.py | 4 +- .../learning/RofuncRL/trainers/ppo_trainer.py | 3 +- rofunc/learning/__init__.py | 1 - rofunc/learning/utils/env_wrappers.py | 104 +- rofunc/simulator/assets/mjcf/bruce/bruce.xml | 2 +- .../assets/mjcf/hotu/hotu_humanoid.xml | 4 +- rofunc/simulator/utils/dae2stl.py | 4 +- rofunc/simulator/utils/get_inertia.py | 2 +- rofunc/utils/oslab/path.py | 6 +- rofunc/utils/robolab/formatter/mjcf.py | 174 ++ .../robolab/formatter/mjcf_parser/__init__.py | 18 + .../formatter/mjcf_parser/attribute.py | 572 ++++ .../formatter/mjcf_parser/attribute_test.py | 497 +++ .../robolab/formatter/mjcf_parser/base.py | 279 ++ .../mjcf_parser/code_for_debugging_test.py | 82 + .../formatter/mjcf_parser/constants.py | 83 + .../robolab/formatter/mjcf_parser/copier.py | 71 + .../formatter/mjcf_parser/copier_test.py | 85 + .../formatter/mjcf_parser/debugging.py | 368 +++ .../formatter/mjcf_parser/debugging_test.py | 177 ++ .../robolab/formatter/mjcf_parser/element.py | 1414 +++++++++ .../formatter/mjcf_parser/element_test.py | 1073 +++++++ .../mjcf_parser/export_with_assets.py | 62 + .../mjcf_parser/export_with_assets_as_zip.py | 67 + .../export_with_assets_as_zip_test.py | 95 + .../mjcf_parser/export_with_assets_test.py | 113 + .../utils/robolab/formatter/mjcf_parser/io.py | 35 + .../robolab/formatter/mjcf_parser/mjcf.py | 152 + .../formatter/mjcf_parser/namescope.py | 215 ++ .../robolab/formatter/mjcf_parser/parser.py | 228 ++ .../robolab/formatter/mjcf_parser/physics.py | 668 +++++ .../formatter/mjcf_parser/physics_test.py | 641 ++++ .../robolab/formatter/mjcf_parser/schema.py | 265 ++ .../robolab/formatter/mjcf_parser/schema.xml | 2669 +++++++++++++++++ .../robolab/formatter/mjcf_parser/skin.py | 99 + .../formatter/mjcf_parser/skin_test.py | 45 + .../mjcf_parser/test_assets/arena.xml | 35 + .../test_assets/attribute_test_schema.xml | 100 + .../mjcf_parser/test_assets/included.xml | 10 + .../included_with_invalid_filenames.xml | 10 + .../mjcf_parser/test_assets/lego_brick.xml | 34 + .../mjcf_parser/test_assets/meshes/cube.msh | Bin 0 -> 880 bytes .../mjcf_parser/test_assets/meshes/cube.stl | Bin 0 -> 684 bytes .../test_assets/meshes/more_meshes/cube.stl | Bin 0 -> 684 bytes .../test_assets/model_with_assetdir.xml | 19 + .../test_assets/model_with_assets.xml | 19 + .../test_assets/model_with_include.xml | 11 + .../model_with_invalid_filenames.xml | 11 + .../model_with_nameless_assets.xml | 14 + .../test_assets/model_with_separators.xml | 19 + .../mjcf_parser/test_assets/robot_arm.xml | 200 ++ .../test_assets/skins/test_skin.skn | Bin 0 -> 472672 bytes .../mjcf_parser/test_assets/test_model.xml | 49 + .../test_assets/textures/deepmind.png | Bin 0 -> 2976 bytes .../formatter/mjcf_parser/traversal_utils.py | 81 + .../mjcf_parser/traversal_utils_test.py | 218 ++ .../robolab/formatter/mjcf_parser/util.py | 60 + .../mjcf_parser/xml_validation_test.py | 67 + rofunc/utils/robolab/formatter/sdf.py | 108 + rofunc/utils/robolab/formatter/urdf.py | 137 + .../robolab/formatter/urdf_parser/__init__.py | 1 + .../robolab/formatter/urdf_parser/sdf.py | 310 ++ .../robolab/formatter/urdf_parser/urdf.py | 592 ++++ .../urdf_parser/xml_reflection/__init__.py | 1 + .../urdf_parser/xml_reflection/basics.py | 91 + .../urdf_parser/xml_reflection/core.py | 680 +++++ rofunc/utils/robolab/kinematics/__init__.py | 2 +- rofunc/utils/robolab/kinematics/fk.py | 13 +- rofunc/utils/robolab/kinematics/ik.py | 47 +- .../utils/robolab/kinematics/kinpy_utils.py | 3 +- .../kinematics/pytorch_kinematics_utils.py | 112 +- .../utils/robolab/kinematics/robot_class.py | 337 ++- setup.py | 5 +- 91 files changed, 14072 insertions(+), 487 deletions(-) create mode 100644 examples/learning_rl/IsaacLab_RofuncRL/example_isaaclab_env.py create mode 100644 examples/robolab/example_forward_dynamics.py create mode 100644 examples/robolab/example_jacobain.py delete mode 100644 examples/robolab/example_rdf.py delete mode 100644 examples/robolab/example_rdf_bbo_planning.py create mode 100644 rofunc/utils/robolab/formatter/mjcf.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/__init__.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/attribute.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/attribute_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/base.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/code_for_debugging_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/constants.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/copier.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/copier_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/debugging.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/debugging_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/element.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/element_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/export_with_assets.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/export_with_assets_as_zip.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/export_with_assets_as_zip_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/export_with_assets_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/io.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/mjcf.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/namescope.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/parser.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/physics.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/physics_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/schema.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/schema.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/skin.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/skin_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/arena.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/attribute_test_schema.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included_with_invalid_filenames.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/lego_brick.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/cube.msh create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/cube.stl create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/more_meshes/cube.stl create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assetdir.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assets.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_include.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_invalid_filenames.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_nameless_assets.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_separators.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/robot_arm.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/skins/test_skin.skn create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/test_model.xml create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/test_assets/textures/deepmind.png create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/traversal_utils.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/traversal_utils_test.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/util.py create mode 100644 rofunc/utils/robolab/formatter/mjcf_parser/xml_validation_test.py create mode 100644 rofunc/utils/robolab/formatter/sdf.py create mode 100644 rofunc/utils/robolab/formatter/urdf.py create mode 100644 rofunc/utils/robolab/formatter/urdf_parser/__init__.py create mode 100644 rofunc/utils/robolab/formatter/urdf_parser/sdf.py create mode 100644 rofunc/utils/robolab/formatter/urdf_parser/urdf.py create mode 100644 rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/__init__.py create mode 100644 rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/basics.py create mode 100644 rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/core.py diff --git a/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidASE_ViewMotion.py b/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidASE_ViewMotion.py index ab7e48357..d5d8376a1 100644 --- a/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidASE_ViewMotion.py +++ b/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidASE_ViewMotion.py @@ -8,7 +8,8 @@ import isaacgym import argparse -from rofunc.config.utils import omegaconf_to_dict, get_config, load_view_motion_config +import rofunc as rf +from rofunc.config.utils import omegaconf_to_dict, get_config from rofunc.learning.RofuncRL.tasks import Tasks from rofunc.learning.RofuncRL.trainers import Trainers @@ -63,7 +64,7 @@ def inference(custom_args): # Available types of motion file path: # 1. test data provided by rofunc: `examples/data/amp/*.npy` # 2. custom motion file with absolute path - parser.add_argument("--motion_file", type=str, default="/home/ubuntu/Github/HOTU/hotu/data/hotu/010_amp.npy") + parser.add_argument("--motion_file", type=str, default=rf.oslab.get_rofunc_path('../examples/data/amp/amp_humanoid_backflip.npy')) custom_args = parser.parse_args() inference(custom_args) diff --git a/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidHOTU_RofuncRL.py b/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidHOTU_RofuncRL.py index 9abecd33e..ff58ce6b3 100644 --- a/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidHOTU_RofuncRL.py +++ b/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidHOTU_RofuncRL.py @@ -136,16 +136,16 @@ def inference(custom_args): parser.add_argument("--debug", type=str, default="False") parser.add_argument("--headless", type=str, default="True") parser.add_argument("--inference", action="store_false", help="turn to inference mode while adding this argument") - parser.add_argument("--ckpt_path", type=str, default="/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUBruce_24-05-28_13-51-39-584325_body_amp5/checkpoints/best_ckpt.pth") + parser.add_argument("--ckpt_path", type=str, default="../examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUBruce_24-05-28_13-51-39-584325_body_amp5/checkpoints/best_ckpt.pth") # HOTU - # parser.add_argument("--llc_ckpt_path", type=str, default="/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUHumanoidWQbhandNew_24-05-26_21-16-24-361269_body_amp5/checkpoints/best_ckpt.pth") + # parser.add_argument("--llc_ckpt_path", type=str, default="../examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUHumanoidWQbhandNew_24-05-26_21-16-24-361269_body_amp5/checkpoints/best_ckpt.pth") # ZJU - # parser.add_argument("--llc_ckpt_path", type=str, default="/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUZJUHumanoidWQbhandNew_24-05-26_18-57-20-244370_body_amp5/checkpoints/best_ckpt.pth") + # parser.add_argument("--llc_ckpt_path", type=str, default="../examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUZJUHumanoidWQbhandNew_24-05-26_18-57-20-244370_body_amp5/checkpoints/best_ckpt.pth") # H1 - # parser.add_argument("--llc_ckpt_path", type=str, default="/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUH1WQbhandNew_24-05-27_16-59-15-598225_body_amp5/checkpoints/best_ckpt.pth") + # parser.add_argument("--llc_ckpt_path", type=str, default="../examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUH1WQbhandNew_24-05-27_16-59-15-598225_body_amp5/checkpoints/best_ckpt.pth") # Bruce - parser.add_argument("--llc_ckpt_path", type=str, default="/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUBruce_24-05-28_13-51-39-584325_body_amp5/checkpoints/best_ckpt.pth") + parser.add_argument("--llc_ckpt_path", type=str, default="../examples/learning_rl/IsaacGym_RofuncRL/saved_runs/RofuncRL_HOTUTrainer_HumanoidHOTUGetup_HOTUBruce_24-05-28_13-51-39-584325_body_amp5/checkpoints/best_ckpt.pth") custom_args = parser.parse_args() diff --git a/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidPhysHOI_RofuncRL.py b/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidPhysHOI_RofuncRL.py index 2eb5873c8..96c8d153f 100644 --- a/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidPhysHOI_RofuncRL.py +++ b/examples/learning_rl/IsaacGym_RofuncRL/example_HumanoidPhysHOI_RofuncRL.py @@ -103,7 +103,7 @@ def inference(custom_args): parser.add_argument("--rl_device", type=int, default=1) parser.add_argument("--headless", type=str, default="True") parser.add_argument("--inference", action="store_true", help="turn to inference mode while adding this argument") - parser.add_argument("--ckpt_path", type=str, default="/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/learning_rl/IsaacGym_RofuncRL/runs/RofuncRL_PhysHOITrainer_HumanoidPhysHOI_24-04-23_18-21-03-579079/checkpoints/best_ckpt.pth") + parser.add_argument("--ckpt_path", type=str, default="../examples/learning_rl/IsaacGym_RofuncRL/runs/RofuncRL_PhysHOITrainer_HumanoidPhysHOI_24-04-23_18-21-03-579079/checkpoints/best_ckpt.pth") parser.add_argument("--debug", type=str, default="False") custom_args = parser.parse_args() diff --git a/examples/learning_rl/IsaacLab_RofuncRL/example_isaaclab_env.py b/examples/learning_rl/IsaacLab_RofuncRL/example_isaaclab_env.py new file mode 100644 index 000000000..e93e468a6 --- /dev/null +++ b/examples/learning_rl/IsaacLab_RofuncRL/example_isaaclab_env.py @@ -0,0 +1,105 @@ +""" +Ant (RofuncRL) +=========================== + +Ant RL using RofuncRL +""" + +import sys,os + +sys.path.append("/home/ubuntu/Github/Rofunc") + +import argparse + +from rofunc.config.utils import omegaconf_to_dict, get_config +from rofunc.learning.RofuncRL.tasks import Tasks +from rofunc.learning.RofuncRL.trainers import Trainers +from rofunc.learning.pre_trained_models.download import model_zoo +from rofunc.learning.utils.utils import set_seed +from rofunc.learning.RofuncRL.tasks.utils.env_loaders import load_isaaclab_env +from rofunc.learning.utils.env_wrappers import wrap_env + + +def train(custom_args): + # Config task and trainer parameters for Isaac Gym environments + custom_args.num_envs = 64 if custom_args.agent.upper() in ["SAC", "TD3"] else custom_args.num_envs + + args_overrides = ["task={}".format(custom_args.task), + "train={}{}RofuncRL".format(custom_args.task, custom_args.agent.upper()), + "device_id={}".format(custom_args.sim_device), + "rl_device=cuda:{}".format(custom_args.rl_device), + "headless={}".format(custom_args.headless), + "num_envs={}".format(custom_args.num_envs)] + cfg = get_config('./learning/rl', 'config', args=args_overrides) + cfg_dict = omegaconf_to_dict(cfg.task) + + set_seed(cfg.train.Trainer.seed) + + # Instantiate the Isaac Gym environment + env = load_isaaclab_env(task_name="Isaac-Cartpole-v0", headless=True, num_envs=custom_args.num_envs) + + # Instantiate the RL trainer + trainer = Trainers().trainer_map[custom_args.agent](cfg=cfg, + env=env, + device=cfg.rl_device, + env_name=custom_args.task) + + # Start training + trainer.train() + + +def inference(custom_args): + # Config task and trainer parameters for Isaac Gym environments + args_overrides = ["task={}".format(custom_args.task), + "train={}{}RofuncRL".format(custom_args.task, custom_args.agent.upper()), + "device_id={}".format(custom_args.sim_device), + "rl_device=cuda:{}".format(custom_args.rl_device), + "headless={}".format(False), + "num_envs={}".format(16)] + cfg = get_config('./learning/rl', 'config', args=args_overrides) + cfg_dict = omegaconf_to_dict(cfg.task) + + set_seed(cfg.train.Trainer.seed) + + # Instantiate the Isaac Gym environment + infer_env = Tasks().task_map[custom_args.task](cfg=cfg_dict, + rl_device=cfg.rl_device, + sim_device=f'cuda:{cfg.device_id}', + graphics_device_id=cfg.device_id, + headless=cfg.headless, + virtual_screen_capture=cfg.capture_video, # TODO: check + force_render=cfg.force_render) + + # Instantiate the RL trainer + trainer = Trainers().trainer_map[custom_args.agent](cfg=cfg, + env=infer_env, + device=cfg.rl_device, + env_name=custom_args.task, + inference=True) + # load checkpoint + if custom_args.ckpt_path is None: + custom_args.ckpt_path = model_zoo(name="AntRofuncRLPPO.pth") + trainer.agent.load_ckpt(custom_args.ckpt_path) + + # Start inference + trainer.inference() + + +if __name__ == '__main__': + gpu_id = 0 + + parser = argparse.ArgumentParser() + parser.add_argument("--task", type=str, default="Cartpole") + parser.add_argument("--agent", type=str, default="ppo") # Available agents: ppo, sac, td3, a2c + parser.add_argument("--num_envs", type=int, default=4096) + parser.add_argument("--sim_device", type=int, default=0) + parser.add_argument("--rl_device", type=int, default=gpu_id) + parser.add_argument("--headless", type=str, default="True") + parser.add_argument("--inference", action="store_true", help="turn to inference mode while adding this argument") + parser.add_argument("--ckpt_path", type=str, default=None) + custom_args = parser.parse_args() + + if not custom_args.inference: + train(custom_args) + else: + inference(custom_args) diff --git a/examples/robolab/example_coordinate_transform.py b/examples/robolab/example_coordinate_transform.py index 9d141c2cc..a5ab2091b 100644 --- a/examples/robolab/example_coordinate_transform.py +++ b/examples/robolab/example_coordinate_transform.py @@ -7,6 +7,7 @@ import rofunc as rf +# Quaternion convert quat = [0.234, 0.23, 0.4, 1.3] mat = rf.robolab.convert_ori_format(quat, "quat", "mat") @@ -28,7 +29,7 @@ # [-0.2098, 0.4048, 0.8900, 1.0000], # [ 0.0000, 0.0000, 0.0000, 1.0000]]]) - +# Rotation matrix convert rot = [[0.7825, -0.4763, 0.4011], [0.5862, 0.7806, -0.2168], [-0.2098, 0.4048, 0.8900]] @@ -44,7 +45,7 @@ # [Rofunc:INFO] Quaternion: tensor([[0.1673, 0.1644, 0.2859, 0.9291]]) # [Rofunc:INFO] Euler angles: tensor([[0.4269, 0.2114, 0.6429]]) - +# Euler convert euler = [0.4268, 0.2114, 0.6430] quat = rf.robolab.convert_ori_format(euler, "euler", "quat") mat = rf.robolab.convert_ori_format(euler, "euler", "mat") @@ -57,3 +58,11 @@ # tensor([[[ 0.7825, -0.4763, 0.4011], # [ 0.5863, 0.7806, -0.2168], # [-0.2098, 0.4047, 0.8900]]]) + +# Quaternion multiplication +quat1 = [[-0.436865, 0.49775, 0.054428, 0.747283], [0, 0, 1, 0]] +quat2 = [0.707, 0, 0, 0.707] +quat3 = rf.robolab.quat_multiply(quat1, quat2) +rf.logger.beauty_print(f"Result: {rf.robolab.check_quat_tensor(quat3)}") +# [Rofunc:INFO] Result: tensor([[ 0.2195, 0.3904, -0.3135, 0.8373], +# [ 0.0000, 0.7071, 0.7071, 0.0000]]) diff --git a/examples/robolab/example_forward_dynamics.py b/examples/robolab/example_forward_dynamics.py new file mode 100644 index 000000000..8baef5cc7 --- /dev/null +++ b/examples/robolab/example_forward_dynamics.py @@ -0,0 +1,72 @@ +""" +FD from models +======================== + +Forward dynamics from URDF or MuJoCo XML files. +""" + +import pprint +import math + +import rofunc as rf + +rf.logger.beauty_print("########## Forward kinematics from URDF or MuJoCo XML files with RobotModel class ##########") +rf.logger.beauty_print("---------- Forward kinematics for Franka Panda using URDF file ----------") +model_path = "../../rofunc/simulator/assets/urdf/franka_description/robots/franka_panda.urdf" + +joint_value = [[0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0, 0.0, 0.0], + [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0, 0.0, 0.0]] +export_link = "panda_hand" + +# # Build the robot model with kinpy +# # Deprecated: kinpy is not supported anymore, just for checking the results!!!! Please use pytorch_kinematics instead. +# robot = rf.robolab.RobotModel(model_path, solve_engine="kinpy", verbose=False) +# # Show the robot chain and joint names, can also be done by verbose=True +# robot.show_chain() +# # Get the forward kinematics of export_link +# pos, rot, ret = robot.get_fk(joint_value, export_link) +# +# # Convert the orientation representation and print the results +# rot = rf.robolab.convert_quat_order(rot, "wxyz", "xyzw") +# rf.logger.beauty_print(f"Position of {export_link}: {pos}") +# rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") +# pprint.pprint(ret, width=1) + +# Try the same thing with pytorch_kinematics +robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=False) +pos, rot, ret = robot.get_fk(joint_value, export_link) +rf.logger.beauty_print(f"Position of {export_link}: {pos}") +rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") +pprint.pprint(ret, width=1) + +# rf.logger.beauty_print("---------- Forward kinematics for Bruce Humanoid Robot using MJCF file ----------") +model_path = "../../rofunc/simulator/assets/mjcf/bruce/bruce.xml" +joint_value = [0.0 for _ in range(16)] + +export_link = "elbow_pitch_link_r" + +# # Build the robot model with pytorch_kinematics, kinpy is not supported for MJCF files +robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=True) +# Get the forward kinematics of export_link +pos, rot, ret = robot.get_fk(joint_value, export_link) +# +# # Print the results +# rf.logger.beauty_print(f"Position of {export_link}: {pos}") +# rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") +# pprint.pprint(ret, width=1) + + +model_path = "../../rofunc/simulator/assets/mjcf/hotu/hotu_humanoid.xml" +joint_value = [0.1 for _ in range(34)] + +export_link = "left_hand_link_2" + +# # Build the robot model with pytorch_kinematics, kinpy is not supported for MJCF files +robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=True) +# Get the forward kinematics of export_link +pos, rot, ret = robot.get_fk(joint_value, export_link) + +# # Print the results +rf.logger.beauty_print(f"Position of {export_link}: {pos}") +rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") +pprint.pprint(ret, width=1) diff --git a/examples/robolab/example_forward_kinematics.py b/examples/robolab/example_forward_kinematics.py index 7cbadefd7..a788ebf30 100644 --- a/examples/robolab/example_forward_kinematics.py +++ b/examples/robolab/example_forward_kinematics.py @@ -11,36 +11,36 @@ import rofunc as rf -# rf.logger.beauty_print("########## Forward kinematics from URDF or MuJoCo XML files with RobotModel class ##########") -# rf.logger.beauty_print("---------- Forward kinematics for Franka Panda using URDF file ----------") -# model_path = "../../rofunc/simulator/assets/urdf/franka_description/robots/franka_panda.urdf" -# -# joint_value = [[0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0, 0.0, 0.0], -# [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0, 0.0, 0.0]] -# export_link = "panda_hand" -# -# # # Build the robot model with kinpy -# # # Deprecated: kinpy is not supported anymore, just for checking the results!!!! Please use pytorch_kinematics instead. -# # robot = rf.robolab.RobotModel(model_path, solve_engine="kinpy", verbose=False) -# # # Show the robot chain and joint names, can also be done by verbose=True -# # robot.show_chain() -# # # Get the forward kinematics of export_link -# # pos, rot, ret = robot.get_fk(joint_value, export_link) -# # -# # # Convert the orientation representation and print the results -# # rot = rf.robolab.convert_quat_order(rot, "wxyz", "xyzw") -# # rf.logger.beauty_print(f"Position of {export_link}: {pos}") -# # rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") -# # pprint.pprint(ret, width=1) -# -# # Try the same thing with pytorch_kinematics -# robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=False) +rf.logger.beauty_print("########## Forward kinematics from URDF or MuJoCo XML files with RobotModel class ##########") +rf.logger.beauty_print("---------- Forward kinematics for Franka Panda using URDF file ----------") +model_path = "../../rofunc/simulator/assets/urdf/franka_description/robots/franka_panda.urdf" + +joint_value = [[0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0, 0.0, 0.0], + [0.0, -math.pi / 4.0, 0.0, math.pi / 2.0, 0.0, math.pi / 4.0, 0.0, 0.0, 0.0]] +export_link = "panda_hand" + +# # Build the robot model with kinpy +# # Deprecated: kinpy is not supported anymore, just for checking the results!!!! Please use pytorch_kinematics instead. +# robot = rf.robolab.RobotModel(model_path, solve_engine="kinpy", verbose=False) +# # Show the robot chain and joint names, can also be done by verbose=True +# robot.show_chain() +# # Get the forward kinematics of export_link # pos, rot, ret = robot.get_fk(joint_value, export_link) +# +# # Convert the orientation representation and print the results +# rot = rf.robolab.convert_quat_order(rot, "wxyz", "xyzw") # rf.logger.beauty_print(f"Position of {export_link}: {pos}") # rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") # pprint.pprint(ret, width=1) -# -# rf.logger.beauty_print("---------- Forward kinematics for Bruce Humanoid Robot using MJCF file ----------") + +# Try the same thing with pytorch_kinematics +robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=False) +pos, rot, ret = robot.get_fk(joint_value, export_link) +rf.logger.beauty_print(f"Position of {export_link}: {pos}") +rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") +pprint.pprint(ret, width=1) + +rf.logger.beauty_print("---------- Forward kinematics for Bruce Humanoid Robot using MJCF file ----------") model_path = "../../rofunc/simulator/assets/mjcf/bruce/bruce.xml" joint_value = [0.0 for _ in range(16)] @@ -56,13 +56,11 @@ # rf.logger.beauty_print(f"Rotation of {export_link}: {rot}") # pprint.pprint(ret, width=1) - - - +rf.logger.beauty_print("---------- Forward kinematics for United Digital Human (UDH) using MJCF file ----------") model_path = "../../rofunc/simulator/assets/mjcf/hotu/hotu_humanoid.xml" joint_value = [0.1 for _ in range(34)] -export_link = "left_hand_link_2" +export_link = "left_hand_2" # # Build the robot model with pytorch_kinematics, kinpy is not supported for MJCF files robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=True) diff --git a/examples/robolab/example_inverse_kinematics.py b/examples/robolab/example_inverse_kinematics.py index dccc895d7..690d80004 100644 --- a/examples/robolab/example_inverse_kinematics.py +++ b/examples/robolab/example_inverse_kinematics.py @@ -5,18 +5,21 @@ Inverse kinematics from URDF or MuJoCo XML files. """ -import pprint - -import math -import torch import rofunc as rf rf.logger.beauty_print("########## Inverse kinematics from URDF or MuJoCo XML files with RobotModel class ##########") rf.logger.beauty_print("---------- Inverse kinematics for Franka Panda using URDF file ----------") -model_path = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/rofunc/simulator/assets/urdf/franka_description/robots/franka_panda.urdf" +model_path = "../../rofunc/simulator/assets/urdf/franka_description/robots/franka_panda.urdf" ee_pose = [0, 0, 0, 0, 0, 0, 1] -export_link = "panda_hand_frame" -robot = rf.robolab.RobotModel(model_path, solve_engine="kinpy", verbose=True) +export_link = "panda_hand" +robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=True) + +# Get ik solution ret = robot.get_ik(ee_pose, export_link) -print(ret) +print(ret.solutions) + +# Get ik solution near the current configuration +cur_configs = [[-1.7613, 2.7469, -3.5611, -3.8847, 2.7940, 1.9055, 1.9879]] +ret = robot.get_ik(ee_pose, export_link, cur_configs=cur_configs) +print(ret.solutions) diff --git a/examples/robolab/example_jacobain.py b/examples/robolab/example_jacobain.py new file mode 100644 index 000000000..8ad595205 --- /dev/null +++ b/examples/robolab/example_jacobain.py @@ -0,0 +1,26 @@ +""" +Jacobian from models +======================== + +Jacobian from URDF or MuJoCo XML files. +""" + +import rofunc as rf + +rf.logger.beauty_print("########## Jacobian from URDF or MuJoCo XML files with RobotModel class ##########") +model_path = "../../rofunc/simulator/assets/mjcf/bruce/bruce.xml" +joint_value = [0.1 for _ in range(16)] + +export_link = "elbow_pitch_link_r" + +# # Build the robot model with pytorch_kinematics, kinpy is not supported for MJCF files +robot = rf.robolab.RobotModel(model_path, solve_engine="pytorch_kinematics", verbose=True) + +# Get the jacobian of export_link +J = robot.get_jacobian(joint_value, export_link) +print(J) + +# Get the jacobian at a point offset from the export_link +point = [0.1, 0.1, 0.1] +J = robot.get_jacobian(joint_value, export_link, locations=point) +print(J) diff --git a/examples/robolab/example_rdf.py b/examples/robolab/example_rdf.py deleted file mode 100644 index 726c1bdf8..000000000 --- a/examples/robolab/example_rdf.py +++ /dev/null @@ -1,94 +0,0 @@ -""" -Robot distance field (RDF) -======================== - -This example demonstrates how to use the RDF class to train a Bernstein Polynomial model for the robot distance field -from URDF/MJCF files and visualize the reconstructed whole body. -""" - -import argparse -import os -import time - -import numpy as np -import torch - -import rofunc as rf - - -def rdf_from_robot_model(args): - rdf_bp = rf.robolab.rdf.RDF(args) - - # train Bernstein Polynomial model - if args.train: - rdf_bp.train() - - # load trained model - rdf_model_path = os.path.join(args.robot_asset_root, 'rdf/BP', f'BP_{args.n_func}.pt') - rdf_model = torch.load(rdf_model_path) - - # visualize the Bernstein Polynomial model for each robot link - rdf_bp.create_surface_mesh(rdf_model, nbData=128, vis=False, save_mesh_name=f'BP_{args.n_func}') - - joint_max = rdf_bp.robot.joint_limit_max - joint_min = rdf_bp.robot.joint_limit_min - num_joint = rdf_bp.robot.num_joint - # joint_value = torch.rand(num_joint).to(args.device) * (joint_max - joint_min) + joint_min - joint_value = torch.zeros(num_joint).to(args.device) - - trans_dict = rdf_bp.robot.get_trans_dict(joint_value) - # visualize the Bernstein Polynomial model for the whole body - rdf_bp.visualize_reconstructed_whole_body(rdf_model, trans_dict, tag=f'BP_{args.n_func}') - - # run RDF - x = torch.rand(10, 3).to(args.device) * 2.0 - 1.0 - joint_value = torch.rand(100, rdf_bp.robot.num_joint).to(args.device).float() - base_trans = torch.from_numpy(np.identity(4)).to(args.device).reshape(-1, 4, 4).expand(len(joint_value), 4, - 4).float().to(args.device) - - start_time = time.time() - sdf, gradient = rdf_bp.get_whole_body_sdf_batch(x, joint_value, rdf_model, base_trans=base_trans, - use_derivative=True) - print('Time cost:', time.time() - start_time) - print('sdf:', sdf.shape, 'gradient:', gradient.shape) - - start_time = time.time() - sdf, joint_grad = rdf_bp.get_whole_body_sdf_with_joints_grad_batch(x, joint_value, rdf_model, base_trans=base_trans) - print('Time cost:', time.time() - start_time) - print('sdf:', sdf.shape, 'joint gradient:', joint_grad.shape) - - # visualize the 2D & 3D SDF with gradient - # joint_value = torch.zeros(num_joint).to(args.device).reshape((-1, num_joint)) - - joint_value = (torch.rand(num_joint).to(args.device).reshape((-1, num_joint))*0.5 * (joint_max - joint_min) + joint_min) - rf.robolab.rdf.plot_2D_panda_sdf(joint_value, rdf_bp, nbData=80, model=rdf_model, device=args.device) - rf.robolab.rdf.plot_3D_panda_with_gradient(joint_value, rdf_bp, model=rdf_model, device=args.device) - - -if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument('--device', default='cuda', type=str) - parser.add_argument('--domain_max', default=1.0, type=float) - parser.add_argument('--domain_min', default=-1.0, type=float) - parser.add_argument('--n_func', default=8, type=int) - parser.add_argument('--train_epoch', default=200, type=int) - parser.add_argument('--train', action='store_true') - parser.add_argument('--save_mesh_dict', action='store_false') - parser.add_argument('--sampled_points', action='store_false') - parser.add_argument('--parallel', action='store_false') - # parser.add_argument('--robot_asset_root', default="../../rofunc/simulator/assets/urdf/alicia", type=str) - # parser.add_argument('--robot_asset_name', default="Alicia_0624.xml", type=str) - # parser.add_argument('--robot_asset_root', default="../../rofunc/simulator/assets/urdf/franka_description", type=str) - # parser.add_argument('--robot_asset_name', default="robots/franka_panda.urdf", type=str) - parser.add_argument('--robot_asset_root', default="../../rofunc/simulator/assets/mjcf/bruce", type=str) - parser.add_argument('--robot_asset_name', default="bruce.xml", type=str) - # parser.add_argument('--robot_asset_root', default="../../rofunc/simulator/assets/mjcf/hotu", type=str) - # parser.add_argument('--robot_asset_name', default="hotu_humanoid.xml", type=str) - parser.add_argument('--rdf_model_path', default=None) - parser.add_argument('--joint_conf_path', default=None) - parser.add_argument('--sampled_points_dir', default=None, type=str) - args = parser.parse_args() - args.rdf_model_path = f"{args.robot_asset_root}/rdf/BP/BP_{args.n_func}.pt" - args.joint_conf_path = f"{args.robot_asset_root}/rdf/BP/joint_conf.pt" - - rdf_from_robot_model(args) diff --git a/examples/robolab/example_rdf_bbo_planning.py b/examples/robolab/example_rdf_bbo_planning.py deleted file mode 100644 index c90e456b4..000000000 --- a/examples/robolab/example_rdf_bbo_planning.py +++ /dev/null @@ -1,110 +0,0 @@ -""" -Bimanual box carrying using Robot distance field (RDF) -======================== - -This example plans the contacts of a bimanual box carrying task via optimization based on RDF. -""" -import argparse - -import numpy as np -import torch -import trimesh - -import rofunc as rf - - -def box_carrying_contact_rdf(args): - box_size = np.array([0.18, 0.1, 0.16]) - box_pos = np.array([0.7934301890820722, 0.0, 0.3646743147850761]) - box_rotation = np.array([[0, 1.57, 0], - [-1.57, 0, 0], - [0, 0, 1]]) - - rdf_model = torch.load(args.rdf_model_path) - bbo_planner = rf.robolab.rdf.BBOPlanner(args, rdf_model, box_size, box_pos, box_rotation) - num_joint = bbo_planner.rdf_bp.robot.num_joint - - # contact points - contact_points = bbo_planner.contact_points - p_l, p_r, n_l, n_r = contact_points[0], contact_points[1], contact_points[2], contact_points[3] - - # initial joint value - joint_max = bbo_planner.rdf_bp.robot.joint_limit_max - joint_min = bbo_planner.rdf_bp.robot.joint_limit_min - mid_l = torch.rand(num_joint).to(args.device) * (joint_max - joint_min) + joint_min - mid_r = torch.rand(num_joint).to(args.device) * (joint_max - joint_min) + joint_min - - # planning for both arm - base_pose_l = torch.from_numpy(np.identity(4)).to(args.device).reshape(-1, 4, 4).float() - base_pose_r = torch.from_numpy(np.identity(4)).to(args.device).reshape(-1, 4, 4).float() - base_pose_l[0] = rf.robolab.homo_matrix_from_quat_tensor([-0.436865, 0.49775, 0.054428, 0.747283], - [0.396519, 0.07, 0.644388])[0].to(args.device) - base_pose_r[0] = rf.robolab.homo_matrix_from_quat_tensor([0.436865, 0.49775, -0.054428, 0.747283], - [0.396519, -0.07, 0.644388])[0].to(args.device) - # base_pose_l[0, :3, 3] = torch.tensor([0.4, 0.3, 0]).to(args.device) - # base_pose_r[0, :3, 3] = torch.tensor([0.4, -0.3, 0]).to(args.device) - - joint_value_left = bbo_planner.optimizer(p_l, n_l, mid_l, base_trans=base_pose_l, batch=64) - joint_value_right = bbo_planner.optimizer(p_r, n_r, mid_r, base_trans=base_pose_r, batch=64) - joint_conf = { - 'joint_value_left': joint_value_left, - 'joint_value_right': joint_value_right - } - torch.save(joint_conf, args.joint_conf_path) - - # load planned joint conf - data = torch.load(args.joint_conf_path) - joint_value_left = data['joint_value_left'] - joint_value_right = data['joint_value_right'] - print('joint_value_left', joint_value_left.shape, 'joint_value_right', joint_value_right.shape) - - # visualize planning results - scene = trimesh.Scene() - pc1 = trimesh.PointCloud(bbo_planner.object_internal_points.detach().cpu().numpy(), colors=[0, 255, 0]) - pc2 = trimesh.PointCloud(p_l.detach().cpu().numpy(), colors=[255, 0, 0]) - pc3 = trimesh.PointCloud(p_r.detach().cpu().numpy(), colors=[255, 0, 0]) - scene.add_geometry([pc1, pc2, pc3]) - scene.add_geometry(bbo_planner.object_mesh) - - # visualize the final joint configuration - for t_l, t_r in zip(joint_value_left, joint_value_right): - print('t left:', t_l) - robot_l = bbo_planner.rdf_bp.robot.get_forward_robot_mesh(t_l.reshape(-1, num_joint), base_pose_l)[0] - robot_l = np.sum(robot_l) - robot_l.visual.face_colors = [150, 150, 200, 200] - scene.add_geometry(robot_l, node_name='robot_l') - - print('t right:', t_r) - robot_r = bbo_planner.rdf_bp.robot.get_forward_robot_mesh(t_r.reshape(-1, num_joint), base_pose_r)[0] - robot_r = np.sum(robot_r) - robot_r.visual.face_colors = [150, 200, 150, 200] - scene.add_geometry(robot_r, node_name='robot_r') - scene.show() - - scene.delete_geometry('robot_l') - scene.delete_geometry('robot_r') - - -if __name__ == '__main__': - parser = argparse.ArgumentParser() - parser.add_argument('--device', default='cuda', type=str) - parser.add_argument('--domain_max', default=1.0, type=float) - parser.add_argument('--domain_min', default=-1.0, type=float) - parser.add_argument('--n_func', default=8, type=int) - parser.add_argument('--train_epoch', default=200, type=int) - parser.add_argument('--train', action='store_true') - parser.add_argument('--save_mesh_dict', action='store_false') - parser.add_argument('--load_sampled_points', action='store_false') - parser.add_argument('--parallel', action='store_true') - parser.add_argument('--robot_asset_root', default="../../rofunc/simulator/assets/urdf/alicia", type=str) - parser.add_argument('--robot_asset_name', default="Alicia_0624.xml", type=str) - # parser.add_argument('--robot_asset_root', default="../../rofunc/simulator/assets/urdf/franka_description", type=str) - # parser.add_argument('--robot_asset_name', default="robots/franka_panda.urdf", type=str) - parser.add_argument('--rdf_model_path', default=None) - parser.add_argument('--joint_conf_path', default=None) - parser.add_argument('--sampled_points_dir', default=None, type=str) - args = parser.parse_args() - args.rdf_model_path = f"{args.robot_asset_root}/rdf/BP/BP_{args.n_func}.pt" - args.joint_conf_path = f"{args.robot_asset_root}/rdf/BP/joint_conf.pt" - - box_carrying_contact_rdf(args) diff --git a/examples/simulator/example_robot_play.py b/examples/simulator/example_robot_play.py index 7a434ac27..a142e9fd2 100644 --- a/examples/simulator/example_robot_play.py +++ b/examples/simulator/example_robot_play.py @@ -13,7 +13,7 @@ def hotu_random(): - file = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2hotu.npy" + file = "../examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2hotu.npy" motion = SkeletonMotion.from_file(file) body_links = {"right_hand": gymapi.AXIS_ALL, "left_hand": gymapi.AXIS_ALL, "right_foot": gymapi.AXIS_ROTATION, "left_foot": gymapi.AXIS_ROTATION, @@ -90,7 +90,7 @@ def hotu_random(): def h1_random(): - file = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2h1.npy" + file = "../examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2h1.npy" motion = SkeletonMotion.from_file(file) body_links = {"torso_link": gymapi.AXIS_ALL, "right_elbow_link": gymapi.AXIS_ROTATION, "left_elbow_link": gymapi.AXIS_ROTATION, @@ -172,7 +172,7 @@ def h1_random(): def zju_random(): - file = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2zju.npy" + file = "../examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2zju.npy" motion = SkeletonMotion.from_file(file) body_links = {"pelvis": gymapi.AXIS_ROTATION, "FOREARM_R": gymapi.AXIS_ROTATION, "FOREARM_L": gymapi.AXIS_ROTATION, @@ -254,7 +254,7 @@ def zju_random(): def walker_random(): - file = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2walker.npy" + file = "../examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2walker.npy" motion = SkeletonMotion.from_file(file) body_links = {"torso": gymapi.AXIS_ROTATION, "right_limb_l4": gymapi.AXIS_ROTATION, "left_limb_l4": gymapi.AXIS_ROTATION, @@ -304,7 +304,7 @@ def walker_random(): def bruce_random(): - file = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2bruce.npy" + file = "../examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2bruce.npy" motion = SkeletonMotion.from_file(file) body_links = { "hand_l": gymapi.AXIS_TRANSLATION, "hand_r": gymapi.AXIS_TRANSLATION, @@ -354,7 +354,7 @@ def bruce_random(): def curi_random(): - file = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2curi.npy" + file = "../examples/data/hotu2/20240509/Ramdom (good)_Take 2024-05-09 04.49.16 PM_optitrack2curi.npy" motion = SkeletonMotion.from_file(file) body_links = { # "torso_base2": gymapi.AXIS_ROTATION, "root": gymapi.AXIS_ROTATION, diff --git a/rofunc/__init__.py b/rofunc/__init__.py index 4f8426414..eb30dabb4 100644 --- a/rofunc/__init__.py +++ b/rofunc/__init__.py @@ -10,19 +10,20 @@ warnings.filterwarnings("ignore", category=DeprecationWarning) warnings.simplefilter('ignore', DeprecationWarning) -try: - import pbdlib -except ImportError: - print("pbdlib is not installed. Install it automatically...") - pip.main( - ['install', 'https://github.com/Skylark0924/Rofunc/releases/download/v0.0.2.3/pbdlib-0.1-py3-none-any.whl']) +# try: +# import pbdlib +# except ImportError: +# print("pbdlib is not installed. Install it automatically...") +# pip.main( +# ['install', 'https://github.com/Skylark0924/Rofunc/releases/download/v0.0.2.3/pbdlib-0.1-py3-none-any.whl']) from .devices import zed, xsens, optitrack, mmodal, emg from . import simulator as sim -from .learning import ml, RofuncIL, RofuncRL -from .planning_control import lqt, lqr +# from .learning import ml +from .learning import RofuncIL, RofuncRL +# from .planning_control import lqt, lqr from .utils import visualab, robolab, logger, oslab from .utils.datalab import primitive, data_generator from . import config -from .learning.ml import tpgmm, gmr, tpgmr +# from .learning.ml import tpgmm, gmr, tpgmr diff --git a/rofunc/devices/emg/export.py b/rofunc/devices/emg/export.py index 2b0e1d8c0..913ad830d 100644 --- a/rofunc/devices/emg/export.py +++ b/rofunc/devices/emg/export.py @@ -1,5 +1,4 @@ import matplotlib.pyplot as plt -import neurokit2 as nk import numpy as np SAMPING_RATE = 2000 @@ -19,6 +18,8 @@ def process_one_channel(data, sampling_rate, k): data_mvc: Calculate the Maximum Voluntary Contraction (MVC) of the EMG signals data_abs: Take the absolute value of the EMG signals """ + import neurokit2 as nk + data_filter = [] for i in range(0, len(data) - k + 1, k): data_new = data[i] @@ -50,6 +51,8 @@ def process_all_channels(data, n, sampling_rate, k): DATA_MVC: Calculate the Maximum Voluntary Contraction (MVC) of the EMG signals DATA_ABS: Take the absolute value of the EMG signals """ + import neurokit2 as nk + DATA_FILTER = [] DATA_CLEAN = [] DATA_MVC = [] diff --git a/rofunc/learning/RofuncRL/models/utils.py b/rofunc/learning/RofuncRL/models/utils.py index 97f2241fc..8eeec9f37 100644 --- a/rofunc/learning/RofuncRL/models/utils.py +++ b/rofunc/learning/RofuncRL/models/utils.py @@ -13,6 +13,7 @@ # limitations under the License. from typing import Union, List +from collections.abc import Mapping import gym import gymnasium @@ -143,6 +144,8 @@ def get_space_dim(space): dim = 0 for i in range(len(space)): dim += get_space_dim(space[i]) + elif isinstance(space, Mapping): + dim = get_space_dim(space["policy"]) elif isinstance(space, gym.Space) or isinstance(space, gymnasium.Space): dim = space.shape if isinstance(dim, tuple) and len(dim) == 1: diff --git a/rofunc/learning/RofuncRL/state_encoders/graph_encoders.py b/rofunc/learning/RofuncRL/state_encoders/graph_encoders.py index 488884428..0ce8cca51 100644 --- a/rofunc/learning/RofuncRL/state_encoders/graph_encoders.py +++ b/rofunc/learning/RofuncRL/state_encoders/graph_encoders.py @@ -12,7 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import dgl.nn.pytorch as dglnn import torch.nn as nn from .base_encoders import BaseEncoder @@ -20,6 +19,8 @@ class HomoGraphEncoder(BaseEncoder): def __init__(self, in_dim, hidden_dim): + import dgl.nn.pytorch as dglnn + super(HomoGraphEncoder, self).__init__(hidden_dim) # init_ = lambda m: init(m, nn.init.orthogonal_, lambda x: nn.init. # constant_(x, 0), nn.init.calculate_gain('relu')) @@ -35,6 +36,8 @@ def __init__(self, in_dim, hidden_dim): self.linear = nn.Sequential(nn.Linear(hidden_dim, hidden_dim), nn.ReLU()) def forward(self, g, inputs): + import torch.nn.functional as F + import dgl # 应用图卷积和激活函数 h = self.conv1(g, inputs) h = h.view(-1, h.size(1) * h.size(2)) diff --git a/rofunc/learning/RofuncRL/tasks/__init__.py b/rofunc/learning/RofuncRL/tasks/__init__.py index fa7728663..cf2e639cc 100644 --- a/rofunc/learning/RofuncRL/tasks/__init__.py +++ b/rofunc/learning/RofuncRL/tasks/__init__.py @@ -22,12 +22,12 @@ def __init__(self, env_type="isaacgym"): from .isaacgymenv.physhoi.humanoid_physhoi import HumanoidPhysHOITask # from .isaacgymenv.physhoi.physhoi import PhysHOI_BallPlay # from .isaacgymenv.hotu.humanoid_hotu import HumanoidHOTUTask - from .isaacgymenv.hotu.humanoid_hotu_getup import HumanoidHOTUGetupTask - from .isaacgymenv.hotu.humanoid_hotu_perturb import HumanoidHOTUPerturbTask - from .isaacgymenv.hotu.humanoid_view_motion import HumanoidHOTUViewMotionTask - from .isaacgymenv.hotu.humanoid_hotu_heading import HumanoidHOTUHeadingTask - from .isaacgymenv.hotu.humanoid_hotu_location import HumanoidHOTULocationTask - from .isaacgymenv.hotu.humanoid_hotu_style import HumanoidHOTUStyleTask + # from .isaacgymenv.hotu.humanoid_hotu_getup import HumanoidHOTUGetupTask + # from .isaacgymenv.hotu.humanoid_hotu_perturb import HumanoidHOTUPerturbTask + # from .isaacgymenv.hotu.humanoid_view_motion import HumanoidHOTUViewMotionTask + # from .isaacgymenv.hotu.humanoid_hotu_heading import HumanoidHOTUHeadingTask + # from .isaacgymenv.hotu.humanoid_hotu_location import HumanoidHOTULocationTask + # from .isaacgymenv.hotu.humanoid_hotu_style import HumanoidHOTUStyleTask from .isaacgymenv.hands.shadow_hand_block_stack import ShadowHandBlockStackTask from .isaacgymenv.hands.shadow_hand_bottle_cap import ShadowHandBottleCapTask @@ -76,12 +76,12 @@ def __init__(self, env_type="isaacgym"): "HumanoidASEViewMotion": HumanoidASEViewMotionTask, "HumanoidPhysHOI": HumanoidPhysHOITask, # "HumanoidPhysHOI": PhysHOI_BallPlay, - "HumanoidHOTUGetup": HumanoidHOTUGetupTask, - "HumanoidHOTUPerturb": HumanoidHOTUPerturbTask, - "HumanoidHOTUViewMotion": HumanoidHOTUViewMotionTask, - "HumanoidHOTUHeading": HumanoidHOTUHeadingTask, - "HumanoidHOTULocation": HumanoidHOTULocationTask, - "HumanoidHOTUStyle": HumanoidHOTUStyleTask, + # "HumanoidHOTUGetup": HumanoidHOTUGetupTask, + # "HumanoidHOTUPerturb": HumanoidHOTUPerturbTask, + # "HumanoidHOTUViewMotion": HumanoidHOTUViewMotionTask, + # "HumanoidHOTUHeading": HumanoidHOTUHeadingTask, + # "HumanoidHOTULocation": HumanoidHOTULocationTask, + # "HumanoidHOTUStyle": HumanoidHOTUStyleTask, "BiShadowHandOver": ShadowHandOverTask, "BiShadowHandBlockStack": ShadowHandBlockStackTask, diff --git a/rofunc/learning/RofuncRL/tasks/utils/env_loaders.py b/rofunc/learning/RofuncRL/tasks/utils/env_loaders.py index 00cf2adfc..482affaf4 100644 --- a/rofunc/learning/RofuncRL/tasks/utils/env_loaders.py +++ b/rofunc/learning/RofuncRL/tasks/utils/env_loaders.py @@ -1,12 +1,17 @@ import os -import sys import queue +import sys from contextlib import contextmanager +from typing import Optional, Sequence + +from rofunc.utils.logger.beauty_logger import beauty_print __all__ = ["load_isaacgym_env_preview2", "load_isaacgym_env_preview3", "load_isaacgym_env_preview4", - "load_omniverse_isaacgym_env"] + "load_omniverse_isaacgym_env", + "load_isaac_orbit_env", + "load_isaaclab_env"] @contextmanager @@ -25,6 +30,7 @@ def cwd(new_path: str) -> None: finally: os.chdir(current_path) + def _omegaconf_to_dict(config) -> dict: """Convert OmegaConf config to dict @@ -42,6 +48,7 @@ def _omegaconf_to_dict(config) -> dict: d[k] = _omegaconf_to_dict(v) if isinstance(v, DictConfig) else v return d + def _print_cfg(d, indent=0) -> None: """Print the environment configuration @@ -89,21 +96,25 @@ def load_isaacgym_env_preview2(task_name: str = "", isaacgymenvs_path: str = "", if defined: arg_index = sys.argv.index("--task") + 1 if arg_index >= len(sys.argv): - raise ValueError("No task name defined. Set the task_name parameter or use --task as command line argument") + raise ValueError( + "No task name defined. Set the task_name parameter or use --task as command line argument") if task_name and task_name != sys.argv[arg_index]: - print("[WARNING] Overriding task ({}) with command line argument ({})".format(task_name, sys.argv[arg_index])) + print( + "[WARNING] Overriding task ({}) with command line argument ({})".format(task_name, sys.argv[arg_index])) # get task name from function arguments else: if task_name: sys.argv.append("--task") sys.argv.append(task_name) else: - raise ValueError("No task name defined. Set the task_name parameter or use --task as command line argument") + raise ValueError( + "No task name defined. Set the task_name parameter or use --task as command line argument") # get isaacgym envs path from isaacgym package metadata if not isaacgymenvs_path: if not hasattr(isaacgym, "__path__"): - raise RuntimeError("isaacgym package is not installed or could not be accessed by the current Python environment") + raise RuntimeError( + "isaacgym package is not installed or could not be accessed by the current Python environment") path = isaacgym.__path__ path = os.path.join(path[0], "..", "rlgpu") else: @@ -120,8 +131,9 @@ def load_isaacgym_env_preview2(task_name: str = "", isaacgymenvs_path: str = "", status = False print("[ERROR] Failed to import required packages: {}".format(e)) if not status: - raise RuntimeError("The path ({}) is not valid or the isaacgym package is not installed in editable mode (pip install -e .)" \ - .format(path)) + raise RuntimeError( + "The path ({}) is not valid or the isaacgym package is not installed in editable mode (pip install -e .)" \ + .format(path)) args = get_args() @@ -142,6 +154,7 @@ def load_isaacgym_env_preview2(task_name: str = "", isaacgymenvs_path: str = "", return env + def load_isaacgym_env_preview3(task_name: str = "", isaacgymenvs_path: str = "", show_cfg: bool = True): """Load an Isaac Gym environment (preview 3) @@ -169,7 +182,6 @@ def load_isaacgym_env_preview3(task_name: str = "", isaacgymenvs_path: str = "", from omegaconf import OmegaConf - import isaacgym import isaacgymenvs # check task from command line arguments @@ -182,13 +194,14 @@ def load_isaacgym_env_preview3(task_name: str = "", isaacgymenvs_path: str = "", if defined: if task_name and task_name != arg.split("task=")[1].split(" ")[0]: print("[WARNING] Overriding task name ({}) with command line argument ({})" \ - .format(task_name, arg.split("task=")[1].split(" ")[0])) + .format(task_name, arg.split("task=")[1].split(" ")[0])) # get task name from function arguments else: if task_name: sys.argv.append("task={}".format(task_name)) else: - raise ValueError("No task name defined. Set task_name parameter or use task= as command line argument") + raise ValueError( + "No task name defined. Set task_name parameter or use task= as command line argument") # get isaacgymenvs path from isaacgymenvs package metadata if isaacgymenvs_path == "": @@ -248,6 +261,7 @@ def load_isaacgym_env_preview3(task_name: str = "", isaacgymenvs_path: str = "", return env + def load_isaacgym_env_preview4(task_name: str = "", isaacgymenvs_path: str = "", show_cfg: bool = True): """Load an Isaac Gym environment (preview 4) @@ -271,6 +285,7 @@ def load_isaacgym_env_preview4(task_name: str = "", isaacgymenvs_path: str = "", """ return load_isaacgym_env_preview3(task_name, isaacgymenvs_path, show_cfg) + def load_omniverse_isaacgym_env(task_name: str = "", omniisaacgymenvs_path: str = "", show_cfg: bool = True, @@ -322,13 +337,14 @@ def load_omniverse_isaacgym_env(task_name: str = "", if defined: if task_name and task_name != arg.split("task=")[1].split(" ")[0]: print("[WARNING] Overriding task name ({}) with command line argument ({})" \ - .format(task_name, arg.split("task=")[1].split(" ")[0])) + .format(task_name, arg.split("task=")[1].split(" ")[0])) # get task name from function arguments else: if task_name: sys.argv.append("task={}".format(task_name)) else: - raise ValueError("No task name defined. Set task_name parameter or use task= as command line argument") + raise ValueError( + "No task name defined. Set task_name parameter or use task= as command line argument") # get rofunc.learning.RofuncRL.tasks.omniisaacgym path from rofunc.learning.RofuncRL.tasks.omniisaacgym package metadata if omniisaacgymenvs_path == "": @@ -362,7 +378,8 @@ def load_omniverse_isaacgym_env(task_name: str = "", # internal classes class _OmniIsaacGymVecEnv(VecEnvBase): def step(self, actions): - actions = torch.clamp(actions, -self._task.clip_actions, self._task.clip_actions).to(self._task.device).clone() + actions = torch.clamp(actions, -self._task.clip_actions, self._task.clip_actions).to( + self._task.device).clone() self._task.pre_physics_step(actions) for _ in range(self._task.control_frequency_inv): @@ -371,7 +388,8 @@ def step(self, actions): observations, rewards, dones, info = self._task.post_physics_step() - return {"obs": torch.clamp(observations, -self._task.clip_obs, self._task.clip_obs).to(self._task.rl_device).clone()}, \ + return {"obs": torch.clamp(observations, -self._task.clip_obs, self._task.clip_obs).to( + self._task.rl_device).clone()}, \ rewards.to(self._task.rl_device).clone(), dones.to(self._task.rl_device).clone(), info.copy() def reset(self): @@ -397,7 +415,8 @@ def run(self, trainer=None): super().run(_OmniIsaacGymTrainerMT() if trainer is None else trainer) def _parse_data(self, data): - self._observations = torch.clamp(data["obs"], -self._task.clip_obs, self._task.clip_obs).to(self._task.rl_device).clone() + self._observations = torch.clamp(data["obs"], -self._task.clip_obs, self._task.clip_obs).to( + self._task.rl_device).clone() self._rewards = data["rew"].to(self._task.rl_device).clone() self._dones = data["reset"].to(self._task.rl_device).clone() self._info = data["extras"].copy() @@ -449,6 +468,7 @@ def close(self): return env + def load_isaac_orbit_env(task_name: str = "", show_cfg: bool = True): """Load an Isaac Orbit environment @@ -488,16 +508,19 @@ def load_isaac_orbit_env(task_name: str = "", show_cfg: bool = True): if defined: arg_index = sys.argv.index("--task") + 1 if arg_index >= len(sys.argv): - raise ValueError("No task name defined. Set the task_name parameter or use --task as command line argument") + raise ValueError( + "No task name defined. Set the task_name parameter or use --task as command line argument") if task_name and task_name != sys.argv[arg_index]: - print("[WARNING] Overriding task ({}) with command line argument ({})".format(task_name, sys.argv[arg_index])) + print( + "[WARNING] Overriding task ({}) with command line argument ({})".format(task_name, sys.argv[arg_index])) # get task name from function arguments else: if task_name: sys.argv.append("--task") sys.argv.append(task_name) else: - raise ValueError("No task name defined. Set the task_name parameter or use --task as command line argument") + raise ValueError( + "No task name defined. Set the task_name parameter or use --task as command line argument") # parse arguments parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") @@ -543,3 +566,146 @@ def close_the_simulator(): env = gym.make(args.task, cfg=cfg, headless=args.headless) return env + + +def load_isaaclab_env(task_name: str = "", + num_envs: Optional[int] = None, + headless: Optional[bool] = None, + cli_args: Sequence[str] = [], + show_cfg: bool = True): + """Load an Isaac Lab environment + + Isaac Lab: https://isaac-sim.github.io/IsaacLab + + This function includes the definition and parsing of command line arguments used by Isaac Lab: + + - ``--headless``: Force display off at all times + - ``--cpu``: Use CPU pipeline + - ``--num_envs``: Number of environments to simulate + - ``--task``: Name of the task + - ``--num_envs``: Seed used for the environment + + :param task_name: The name of the task (default: ``""``). + If not specified, the task name is taken from the command line argument (``--task TASK_NAME``). + Command line argument has priority over function parameter if both are specified + :type task_name: str, optional + :param num_envs: Number of parallel environments to create (default: ``None``). + If not specified, the default number of environments defined in the task configuration is used. + Command line argument has priority over function parameter if both are specified + :type num_envs: int, optional + :param headless: Whether to use headless mode (no rendering) (default: ``None``). + If not specified, the default task configuration is used. + Command line argument has priority over function parameter if both are specified + :type headless: bool, optional + :param cli_args: Isaac Lab configuration and command line arguments (default: ``[]``) + :type cli_args: list of str, optional + :param show_cfg: Whether to print the configuration (default: ``True``) + :type show_cfg: bool, optional + + :raises ValueError: The task name has not been defined, neither by the function parameter nor by the command line arguments + + :return: Isaac Lab environment + :rtype: gym.Env + """ + import argparse + import atexit + import gymnasium as gym + + # check task from command line arguments + defined = False + for arg in sys.argv: + if arg.startswith("--task"): + defined = True + break + # get task name from command line arguments + if defined: + arg_index = sys.argv.index("--task") + 1 + if arg_index >= len(sys.argv): + raise ValueError( + "No task name defined. Set the task_name parameter or use --task as command line argument") + if task_name and task_name != sys.argv[arg_index]: + beauty_print(f"Overriding task ({task_name}) with command line argument ({sys.argv[arg_index]})", "warning") + # get task name from function arguments + else: + if task_name: + sys.argv.append("--task") + sys.argv.append(task_name) + else: + raise ValueError( + "No task name defined. Set the task_name parameter or use --task as command line argument") + + # check num_envs from command line arguments + defined = False + for arg in sys.argv: + if arg.startswith("--num_envs"): + defined = True + break + # get num_envs from command line arguments + if defined: + if num_envs is not None: + beauty_print.warning("Overriding num_envs with command line argument (--num_envs)", "warning") + # get num_envs from function arguments + elif num_envs is not None and num_envs > 0: + sys.argv.append("--num_envs") + sys.argv.append(str(num_envs)) + + # check headless from command line arguments + defined = False + for arg in sys.argv: + if arg.startswith("--headless"): + defined = True + break + # get headless from command line arguments + if defined: + if headless is not None: + beauty_print("Overriding headless with command line argument (--headless)", "warning") + # get headless from function arguments + elif headless is not None: + sys.argv.append("--headless") + + # others command line arguments + sys.argv += cli_args + + # parse arguments + parser = argparse.ArgumentParser("Isaac Lab: Omniverse Robotics Environments!") + parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") + parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") + parser.add_argument("--task", type=str, default=None, help="Name of the task.") + parser.add_argument("--seed", type=int, default=None, help="Seed used for the environment") + parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.") + parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).") + parser.add_argument("--video_interval", type=int, default=2000, + help="Interval between video recordings (in steps).") + parser.add_argument("--disable_fabric", action="store_true", default=False, + help="Disable fabric and use USD I/O operations.") + parser.add_argument("--distributed", action="store_true", default=False, + help="Run training with multiple GPUs or nodes.") + + # launch the simulation app + from omni.isaac.lab.app import AppLauncher + + AppLauncher.add_app_launcher_args(parser) + args = parser.parse_args() + app_launcher = AppLauncher(args) + + @atexit.register + def close_the_simulator(): + app_launcher.app.close() + + import omni.isaac.lab_tasks # type: ignore + from omni.isaac.lab_tasks.utils import parse_env_cfg # type: ignore + + cfg = parse_env_cfg(args.task, use_gpu=not args.cpu, num_envs=args.num_envs, use_fabric=not args.disable_fabric) + + # print config + if show_cfg: + print(f"\nIsaac Lab environment ({args.task})") + try: + _print_cfg(cfg) + except AttributeError as e: + pass + + # load environment + env = gym.make(args.task, cfg=cfg, render_mode="rgb_array" if args.video else None) + + return env diff --git a/rofunc/learning/RofuncRL/trainers/__init__.py b/rofunc/learning/RofuncRL/trainers/__init__.py index e75417104..3ff5d7ca9 100644 --- a/rofunc/learning/RofuncRL/trainers/__init__.py +++ b/rofunc/learning/RofuncRL/trainers/__init__.py @@ -7,7 +7,7 @@ def __init__(self): from .amp_trainer import AMPTrainer from .ase_trainer import ASETrainer from .dtrans_trainer import DTransTrainer - from .hotu_trainer import HOTUTrainer + # from .hotu_trainer import HOTUTrainer from .physhoi_trainer import PhysHOITrainer self.trainer_map = { @@ -18,7 +18,7 @@ def __init__(self): "amp": AMPTrainer, "ase": ASETrainer, "dtrans": DTransTrainer, - "hotu": HOTUTrainer, + # "hotu": HOTUTrainer, "physhoi": PhysHOITrainer, } diff --git a/rofunc/learning/RofuncRL/trainers/ppo_trainer.py b/rofunc/learning/RofuncRL/trainers/ppo_trainer.py index 90e0a99fc..343687d83 100644 --- a/rofunc/learning/RofuncRL/trainers/ppo_trainer.py +++ b/rofunc/learning/RofuncRL/trainers/ppo_trainer.py @@ -26,7 +26,8 @@ def __init__(self, cfg, env, device, env_name, inference=False): device, self.exp_dir, self.rofunc_logger) def pre_interaction(self): - self.env.reset_done() + # self.env.reset_done() + pass def post_interaction(self): self._rollout += 1 diff --git a/rofunc/learning/__init__.py b/rofunc/learning/__init__.py index 05cf8e86b..43b82fa2f 100644 --- a/rofunc/learning/__init__.py +++ b/rofunc/learning/__init__.py @@ -3,6 +3,5 @@ shutup.please() -from .ml import * from .RofuncIL import * from .RofuncRL import * diff --git a/rofunc/learning/utils/env_wrappers.py b/rofunc/learning/utils/env_wrappers.py index 0d90bd677..f9a9aef65 100644 --- a/rofunc/learning/utils/env_wrappers.py +++ b/rofunc/learning/utils/env_wrappers.py @@ -12,15 +12,14 @@ # See the License for the specific language governing permissions and # limitations under the License. -from typing import Union, Tuple, Any, Optional +import collections +from typing import Tuple, Any, Optional import gym import gymnasium -import collections import numpy as np -from packaging import version - import torch +from packaging import version from rofunc.utils.logger.beauty_logger import beauty_print @@ -28,7 +27,7 @@ class Wrapper(object): - def __init__(self, env: Any, device=None) -> None: + def __init__(self, env: Any) -> None: """Base wrapper class for RL environments :param env: The environment to wrap @@ -41,8 +40,14 @@ def __init__(self, env: Any, device=None) -> None: self.device = torch.device(self._env.device) else: self.device = torch.device("cuda:0" if torch.cuda.is_available() else "cpu") - if device is not None: - self.device = torch.device(device) + # spaces + try: + self._action_space = self._env.single_action_space + self._observation_space = self._env.single_observation_space + except AttributeError: + self._action_space = self._env.action_space + self._observation_space = self._env.observation_space + self._state_space = self._env.state_space if hasattr(self._env, "state_space") else self._observation_space def __getattr__(self, key: str) -> Any: """Get an attribute from the wrapped environment @@ -57,8 +62,7 @@ def __getattr__(self, key: str) -> Any: """ if hasattr(self._env, key): return getattr(self._env, key) - raise AttributeError("Wrapped environment ({}) does not have attribute '{}'" \ - .format(self._env.__class__.__name__, key)) + raise AttributeError(f"Wrapped environment ({self._env.__class__.__name__}) does not have attribute '{key}'") def reset(self) -> Tuple[torch.Tensor, Any]: """Reset the environment @@ -85,17 +89,13 @@ def step(self, actions: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor, torch def render(self, *args, **kwargs) -> None: """Render the environment - - :raises NotImplementedError: Not implemented """ - raise NotImplementedError + pass def close(self) -> None: """Close the environment - - :raises NotImplementedError: Not implemented """ - raise NotImplementedError + pass @property def num_envs(self) -> int: @@ -105,6 +105,14 @@ def num_envs(self) -> int: """ return self._env.num_envs if hasattr(self._env, "num_envs") else 1 + @property + def num_agents(self) -> int: + """Number of agents + + If the wrapped environment does not have the ``num_agents`` property, it will be set to 1 + """ + return self._env.num_agents if hasattr(self._env, "num_agents") else 1 + @property def state_space(self) -> gym.Space: """State space @@ -112,19 +120,19 @@ def state_space(self) -> gym.Space: If the wrapped environment does not have the ``state_space`` property, the value of the ``observation_space`` property will be used """ - return self._env.state_space if hasattr(self._env, "state_space") else self._env.observation_space + return self._state_space @property def observation_space(self) -> gym.Space: """Observation space """ - return self._env.observation_space + return self._observation_space @property def action_space(self) -> gym.Space: """Action space """ - return self._env.action_space + return self._action_space class IsaacGymPreview2Wrapper(Wrapper): @@ -250,7 +258,8 @@ def run(self, trainer: Optional["omni.isaac.gym.vec_env.vec_env_mt.TrainerMT"] = self._env.run(trainer) def _process_data(self): - self._obs = torch.clamp(self._obs, -self._env._task.clip_obs, self._env._task.clip_obs).to(self._env._task.rl_device).clone() + self._obs = torch.clamp(self._obs, -self._env._task.clip_obs, self._env._task.clip_obs).to( + self._env._task.rl_device).clone() self._rew = self._rew.to(self._env._task.rl_device).clone() self._states = torch.clamp(self._states, -self._env._task.clip_obs, self._env._task.clip_obs).to( self._env._task.rl_device).clone() @@ -292,7 +301,8 @@ def step(self, actions: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor, torch # self._obs_dict, reward, terminated, info = self._env.step(actions) # truncated = torch.zeros_like(terminated) - return self._obs_dict["obs"], self._rew.view(-1, 1), self._resets.view(-1, 1), self._resets.view(-1, 1), self._extras + return self._obs_dict["obs"], self._rew.view(-1, 1), self._resets.view(-1, 1), self._resets.view(-1, + 1), self._extras def reset(self) -> Tuple[torch.Tensor, Any]: """Reset the environment @@ -995,6 +1005,54 @@ def close(self) -> None: self._env.close() +class IsaacLabWrapper(Wrapper): + def __init__(self, env: Any) -> None: + """Isaac Lab environment wrapper + + :param env: The environment to wrap + :type env: Any supported Isaac Lab environment + """ + super().__init__(env) + + self._reset_once = True + self._obs_dict = None + + self._observation_space = self._observation_space["policy"] + + def step(self, actions: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor, torch.Tensor, torch.Tensor, Any]: + """Perform a step in the environment + + :param actions: The actions to perform + :type actions: torch.Tensor + + :return: Observation, reward, terminated, truncated, info + :rtype: tuple of torch.Tensor and any other info + """ + self._obs_dict, reward, terminated, truncated, info = self._env.step(actions) + return self._obs_dict["policy"], reward.view(-1, 1), terminated.view(-1, 1), truncated.view(-1, 1), info + + def reset(self) -> Tuple[torch.Tensor, Any]: + """Reset the environment + + :return: Observation, info + :rtype: torch.Tensor and any other info + """ + if self._reset_once: + self._obs_dict, info = self._env.reset() + self._reset_once = False + return self._obs_dict["policy"], {} + + def render(self, *args, **kwargs) -> None: + """Render the environment + """ + pass + + def close(self) -> None: + """Close the environment + """ + self._env.close() + + def wrap_env(env: Any, wrapper: str = "auto", verbose: bool = True, logger=None, seed=None) -> Wrapper: """ Wrap an environment to use a common interface @@ -1028,6 +1086,8 @@ def wrap_env(env: Any, wrapper: str = "auto", verbose: bool = True, logger=None, +--------------------+-------------------------+ |Isaac Sim (orbit) |``"isaac-orbit"`` | +--------------------+-------------------------+ + |Isaac Lab |``"isaaclab"`` | + +--------------------+-------------------------+ :param verbose: Whether to print the wrapper type (default: True) :param logger: rofunc logger (default: None) :param seed: random seed for env (default: None) @@ -1109,5 +1169,9 @@ def wrap_env(env: Any, wrapper: str = "auto", verbose: bool = True, logger=None, if verbose: logger.info("Environment wrapper: Isaac Orbit") return IsaacOrbitWrapper(env) + elif wrapper == "isaaclab": + if verbose: + logger.info("Environment wrapper: Isaac Lab") + return IsaacLabWrapper(env) else: raise ValueError("Unknown {} wrapper type".format(wrapper)) diff --git a/rofunc/simulator/assets/mjcf/bruce/bruce.xml b/rofunc/simulator/assets/mjcf/bruce/bruce.xml index 51db09eeb..ca9212294 100644 --- a/rofunc/simulator/assets/mjcf/bruce/bruce.xml +++ b/rofunc/simulator/assets/mjcf/bruce/bruce.xml @@ -36,7 +36,7 @@ - + diff --git a/rofunc/simulator/assets/mjcf/hotu/hotu_humanoid.xml b/rofunc/simulator/assets/mjcf/hotu/hotu_humanoid.xml index c034dd772..7c68eb0a0 100644 --- a/rofunc/simulator/assets/mjcf/hotu/hotu_humanoid.xml +++ b/rofunc/simulator/assets/mjcf/hotu/hotu_humanoid.xml @@ -20,9 +20,9 @@ - + - + diff --git a/rofunc/simulator/utils/dae2stl.py b/rofunc/simulator/utils/dae2stl.py index 82a4f8ef7..479688ea5 100644 --- a/rofunc/simulator/utils/dae2stl.py +++ b/rofunc/simulator/utils/dae2stl.py @@ -12,8 +12,8 @@ def dae2stl(dae_files, stl_save_path): if __name__ == '__main__': - dae_folder = '/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/rofunc/simulator/assets/urdf/curi/meshes' + dae_folder = './simulator/assets/urdf/curi/meshes' dae_files = rf.oslab.list_absl_path(dae_folder, recursive=True, suffix='.dae') - stl_save_path = '/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/rofunc/simulator/assets/urdf/curi/all_visual' + stl_save_path = './simulator/assets/urdf/curi/all_visual' dae2stl(dae_files[6:12], stl_save_path) diff --git a/rofunc/simulator/utils/get_inertia.py b/rofunc/simulator/utils/get_inertia.py index c27f8fb0a..98a23f3c9 100644 --- a/rofunc/simulator/utils/get_inertia.py +++ b/rofunc/simulator/utils/get_inertia.py @@ -34,7 +34,7 @@ def calculate_inertial_tag(file_name=None, mass=-1, pr=8, scale_factor=100): if __name__ == '__main__': - path = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/rofunc/simulator/assets/urdf/zju_humanoid/low_meshes" + path = "./simulator/assets/urdf/zju_humanoid/low_meshes" name = "WRIST_UPDOWN_R.STL" path = os.path.join(path, name) calculate_inertial_tag(path, 1) diff --git a/rofunc/utils/oslab/path.py b/rofunc/utils/oslab/path.py index 84db7cd9a..cb4ef94e0 100644 --- a/rofunc/utils/oslab/path.py +++ b/rofunc/utils/oslab/path.py @@ -20,7 +20,7 @@ import rofunc as rf -def get_rofunc_path(): +def get_rofunc_path(extra_path=None): """ Get the path of the rofunc package. @@ -29,9 +29,13 @@ def get_rofunc_path(): if not hasattr(rf, "__path__"): raise RuntimeError("rofunc package is not installed") rofunc_path = list(rf.__path__)[0] + + if extra_path is not None: + rofunc_path = os.path.join(rofunc_path, extra_path) return rofunc_path + def get_elegantrl_path(): """ Get the path of the elegantrl package. diff --git a/rofunc/utils/robolab/formatter/mjcf.py b/rofunc/utils/robolab/formatter/mjcf.py new file mode 100644 index 000000000..d64cb0547 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf.py @@ -0,0 +1,174 @@ +from typing import Union, Optional + +import mujoco +import pytorch_kinematics.transforms as tf +from mujoco._structs import _MjModelBodyViews as MjModelBodyViews +from pytorch_kinematics import chain, frame + +# Converts from MuJoCo joint types to pytorch_kinematics joint types +JOINT_TYPE_MAP = { + mujoco.mjtJoint.mjJNT_HINGE: 'revolute', + mujoco.mjtJoint.mjJNT_SLIDE: "prismatic" +} + + +def get_body_geoms(m: mujoco.MjModel, body: MjModelBodyViews, base: Optional[tf.Transform3d] = None): + # Find all geoms which have body as parent + base = base or tf.Transform3d() + visuals = [] + for geom_id in range(m.ngeom): + geom = m.geom(geom_id) + if geom.bodyid == body.id: + if geom.type == "capsule": + param = (geom.size[0], geom.fromto) + elif geom.type == "sphere": + param = geom.size[0] + else: + param = geom.size + visuals.append(frame.Visual(offset=tf.Transform3d(rot=geom.quat, pos=geom.pos), geom_type=geom.type, + geom_param=param)) + return visuals + + +def body_to_link(body, base: Optional[tf.Transform3d] = None): + base = base or tf.Transform3d() + return frame.Link(body.name, offset=tf.Transform3d(rot=body.quat, pos=body.pos)) + + +def joint_to_joint(joint, base: Optional[tf.Transform3d] = None): + base = base or tf.Transform3d() + return frame.Joint( + joint.name, + offset=tf.Transform3d(pos=joint.pos), + joint_type=JOINT_TYPE_MAP[joint.type], + axis=joint.axis, + ) + + +def add_composite_joint(root_frame, joints, base: Optional[tf.Transform3d] = None): + base = base or tf.Transform3d() + if len(joints) > 0: + root_frame.children = root_frame.children + [ + frame.Frame(link=frame.Link(name=root_frame.link.name + "_child"), joint=joint_to_joint(joints[0], base)) + ] + ret, offset = add_composite_joint(root_frame.children[-1], joints[1:]) + return ret, root_frame.joint.offset * offset + else: + return root_frame, root_frame.joint.offset + + +def _build_chain_recurse(m, parent_frame, parent_body): + parent_frame.link.visuals = get_body_geoms(m, parent_body) + # iterate through all bodies that are children of parent_body + for body_id in range(m.nbody): + body = m.body(body_id) + if body.parentid == parent_body.id and body_id != parent_body.id: + n_joints = body.jntnum + if n_joints > 1: + # Support for composite joints + old_parent_frame = parent_frame + for i in range(int(n_joints)): + joint = m.joint(body.jntadr[0] + i) + if i == 0: + joint_offset = tf.Transform3d(pos=joint.pos) + child_joint = frame.Joint(joint.name, offset=joint_offset, axis=joint.axis, + joint_type=JOINT_TYPE_MAP[joint.type[0]], + limits=(joint.range[0], joint.range[1])) + else: + child_joint = frame.Joint(joint.name, axis=joint.axis, + joint_type=JOINT_TYPE_MAP[joint.type[0]], + limits=(joint.range[0], joint.range[1])) + if i == 0: + child_link = frame.Link(body.name + "_" + str(i), + offset=tf.Transform3d(rot=body.quat, pos=body.pos)) + else: + child_link = frame.Link(body.name + "_" + str(i)) + child_frame = frame.Frame(name=body.name + "_" + str(i), link=child_link, joint=child_joint) + parent_frame.children = parent_frame.children + [child_frame, ] + parent_frame = child_frame + parent_frame = old_parent_frame + elif n_joints == 1: + # Find the joint for this body, again assuming there's only one joint per body. + joint = m.joint(body.jntadr[0]) + joint_offset = tf.Transform3d(pos=joint.pos) + child_joint = frame.Joint(joint.name, offset=joint_offset, axis=joint.axis, + joint_type=JOINT_TYPE_MAP[joint.type[0]], + limits=(joint.range[0], joint.range[1])) + child_link = frame.Link(body.name, offset=tf.Transform3d(rot=body.quat, pos=body.pos)) + child_frame = frame.Frame(name=body.name, link=child_link, joint=child_joint) + parent_frame.children = parent_frame.children + [child_frame, ] + else: + child_joint = frame.Joint(body.name + "_fixed_joint") + child_link = frame.Link(body.name, offset=tf.Transform3d(rot=body.quat, pos=body.pos)) + child_frame = frame.Frame(name=body.name, link=child_link, joint=child_joint) + parent_frame.children = parent_frame.children + [child_frame, ] + _build_chain_recurse(m, child_frame, body) + + # # iterate through all sites that are children of parent_body + # for site_id in range(m.nsite): + # site = m.site(site_id) + # if site.bodyid == parent_body.id: + # site_link = frame.Link(site.name, offset=tf.Transform3d(rot=site.quat, pos=site.pos)) + # site_frame = frame.Frame(name=site.name, link=site_link) + # parent_frame.children = parent_frame.children + [site_frame, ] + + +# def _build_chain_recurse(m, root_frame, root_body): +# base = root_frame.link.offset +# cur_frame, cur_base = add_composite_joint(root_frame, root_body.joint, base) +# jbase = cur_base.inverse() * base +# if len(root_body.joint) > 0: +# cur_frame.link.visuals = get_body_geoms(m, root_body.geom, jbase) +# else: +# cur_frame.link.visuals = get_body_geoms(m, root_body.geom) +# for b in root_body.body: +# cur_frame.children = cur_frame.children + [frame.Frame()] +# next_frame = cur_frame.children[-1] +# next_frame.name = b.name + "_frame" +# next_frame.link = body_to_link(b, jbase) +# _build_chain_recurse(m, next_frame, b) + + +def build_chain_from_mjcf(data, body: Union[None, str, int] = None): + """ + Build a Chain object from MJCF data. + + :param data: MJCF string data + :param body: the name or index of the body to use as the root of the chain. If None, body idx=0 is used. + :return: Chain object created from MJCF + """ + # import xml.etree.ElementTree as ET + # root = ET.parse(path).getroot() + # + # ASSETS = dict() + # mesh_dir = root.find("compiler").attrib["meshdir"] + # for asset in root.findall("asset"): + # for mesh in asset.findall("mesh"): + # filename = mesh.attrib["file"] + # with open(os.path.join(os.path.dirname(path), mesh_dir, filename), 'rb') as f: + # ASSETS[filename] = f.read() + + m = mujoco.MjModel.from_xml_path(data) + if body is None: + root_body = m.body(0) + else: + root_body = m.body(body) + root_frame = frame.Frame(root_body.name, + link=body_to_link(root_body), + joint=frame.Joint()) + _build_chain_recurse(m, root_frame, root_body) + return chain.Chain(root_frame) + + +def build_serial_chain_from_mjcf(data, end_link_name, root_link_name=""): + """ + Build a SerialChain object from MJCF data. + + :param data: MJCF string data + :param end_link_name: the name of the link that is the end effector + :param root_link_name: the name of the root link + :return: SerialChain object created from MJCF + """ + mjcf_chain = build_chain_from_mjcf(data) + serial_chain = chain.SerialChain(mjcf_chain, end_link_name, "" if root_link_name == "" else root_link_name) + return serial_chain diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/__init__.py b/rofunc/utils/robolab/formatter/mjcf_parser/__init__.py new file mode 100644 index 000000000..31b05c4ad --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/__init__.py @@ -0,0 +1,18 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""PyMJCF: an MJCF object-model library.""" + +from rofunc.utils.robolab.formatter.mjcf_parser.parser import * diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/attribute.py b/rofunc/utils/robolab/formatter/mjcf_parser/attribute.py new file mode 100644 index 000000000..26f8cfc30 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/attribute.py @@ -0,0 +1,572 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Classes representing various MJCF attribute data types.""" + +import abc +import collections +import hashlib +import io +import os + +import numpy as np +from rofunc.utils.robolab.formatter.mjcf_parser import util +from rofunc.utils.robolab.formatter.mjcf_parser import io as resources + +from rofunc.utils.robolab.formatter.mjcf_parser import base +from rofunc.utils.robolab.formatter.mjcf_parser import constants +from rofunc.utils.robolab.formatter.mjcf_parser import debugging +from rofunc.utils.robolab.formatter.mjcf_parser import skin + +# Copybara placeholder for internal file handling dependency. + +_INVALID_REFERENCE_TYPE = ( + 'Reference should be an MJCF Element whose type is {valid_type!r}: ' + 'got {actual_type!r}.') + +_MESH_EXTENSIONS = ('.stl', '.msh', '.obj') + +# MuJoCo's compiler enforces this. +_INVALID_MESH_EXTENSION = ( + 'Mesh files must have one of the following extensions: {}, got {{}}.' + .format(_MESH_EXTENSIONS)) + + +class _Attribute(metaclass=abc.ABCMeta): + """Abstract base class for MJCF attribute data types.""" + + def __init__(self, name, required, parent, value, + conflict_allowed, conflict_behavior): + self._name = name + self._required = required + self._parent = parent + self._value = None + self._conflict_allowed = conflict_allowed + self._conflict_behavior = conflict_behavior + self._check_and_assign(value) + + def _check_and_assign(self, new_value): + if new_value is None: + self.clear() + elif isinstance(new_value, str): + self._assign_from_string(new_value) + else: + self._assign(new_value) + if debugging.debug_mode(): + self._last_modified_stack = debugging.get_current_stack_trace() + + @property + def last_modified_stack(self): + if debugging.debug_mode(): + return self._last_modified_stack + + @property + def value(self): + return self._value + + @value.setter + def value(self, new_value): + self._check_and_assign(new_value) + + @abc.abstractmethod + def _assign(self, value): + raise NotImplementedError # pragma: no cover + + def clear(self): + if self._required: + raise AttributeError( + 'Attribute {!r} of element <{}> is required' + .format(self._name, self._parent.tag)) + else: + self._force_clear() + + def _force_clear(self): + self._before_clear() + self._value = None + if debugging.debug_mode(): + self._last_modified_stack = debugging.get_current_stack_trace() + + def _before_clear(self): + pass + + def _assign_from_string(self, string): + self._assign(string) + + def to_xml_string(self, prefix_root, **kwargs): # pylint: disable=unused-argument + if self._value is None: + return None + else: + return str(self._value) + + @property + def conflict_allowed(self): + return self._conflict_allowed + + @property + def conflict_behavior(self): + return self._conflict_behavior + + +class String(_Attribute): + """A string MJCF attribute.""" + + def _assign(self, value): + if not isinstance(value, str): + raise ValueError('Expect a string value: got {}'.format(value)) + elif not value: + self.clear() + else: + self._value = value + + +class Integer(_Attribute): + """An integer MJCF attribute.""" + + def _assign(self, value): + try: + float_value = float(value) + int_value = int(float(value)) + if float_value != int_value: + raise ValueError + except ValueError: + raise ValueError( + 'Expect an integer value: got {}'.format(value)) from None + self._value = int_value + + +class Float(_Attribute): + """An float MJCF attribute.""" + + def _assign(self, value): + try: + float_value = float(value) + except ValueError: + raise ValueError('Expect a float value: got {}'.format(value)) from None + self._value = float_value + + def to_xml_string(self, prefix_root=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0, + **kwargs): + if self._value is None: + return None + else: + out = io.BytesIO() + value = self._value + if abs(value) < zero_threshold: + value = 0.0 + np.savetxt(out, [value], fmt=f'%.{precision:d}g', newline=' ') + return util.to_native_string(out.getvalue())[:-1] # Strip trailing space. + + +class Keyword(_Attribute): + """A keyword MJCF attribute.""" + + def __init__(self, name, required, parent, value, + conflict_allowed, conflict_behavior, valid_values): + self._valid_values = collections.OrderedDict( + (value.lower(), value) for value in valid_values) + super().__init__(name, required, parent, value, conflict_allowed, + conflict_behavior) + + def _assign(self, value): + if value is None or value == '': # pylint: disable=g-explicit-bool-comparison + self.clear() + else: + try: + self._value = self._valid_values[str(value).lower()] + except KeyError: + raise ValueError('Expect keyword to be one of {} but got: {}'.format( + list(self._valid_values.values()), value)) from None + + @property + def valid_values(self): + return list(self._valid_values.keys()) + + +class Array(_Attribute): + """An array MJCF attribute.""" + + def __init__(self, name, required, parent, value, + conflict_allowed, conflict_behavior, length, dtype): + self._length = length + self._dtype = dtype + super().__init__(name, required, parent, value, conflict_allowed, + conflict_behavior) + + def _assign(self, value): + self._value = self._check_shape(np.array(value, dtype=self._dtype)) + + def _assign_from_string(self, string): + self._assign(np.fromstring(string, dtype=self._dtype, sep=' ')) + + def to_xml_string(self, prefix_root=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0, + **kwargs): + if self._value is None: + return None + else: + out = io.BytesIO() + value = self._value + if zero_threshold: + value = np.copy(value) + value[np.abs(value) < zero_threshold] = 0 + np.savetxt(out, value, fmt=f'%.{precision:d}g', newline=' ') + return util.to_native_string(out.getvalue())[:-1] # Strip trailing space. + + def _check_shape(self, array): + actual_length = array.shape[0] + if len(array.shape) > 1: + raise ValueError('Expect one-dimensional array: got {}'.format(array)) + if self._length and actual_length > self._length: + raise ValueError('Expect array with no more than {} entries: got {}' + .format(self._length, array)) + return array + + +class Identifier(_Attribute): + """A string attribute that represents a unique identifier of an element.""" + + def _assign(self, value): + if not isinstance(value, str): + raise ValueError('Expect a string value: got {}'.format(value)) + elif not value: + self.clear() + elif self._parent.spec.namespace == 'body' and value == 'world': + raise ValueError('A body cannot be named \'world\'. ' + 'The name \'world\' is used by MuJoCo to refer to the ' + '.') + elif constants.PREFIX_SEPARATOR in value: + raise ValueError( + 'An identifier cannot contain a {!r}, ' + 'as this is reserved for scoping purposes: got {!r}' + .format(constants.PREFIX_SEPARATOR, value)) + else: + old_value = self._value + if value != old_value: + self._parent.namescope.add( + self._parent.spec.namespace, value, self._parent) + if old_value: + self._parent.namescope.remove(self._parent.spec.namespace, old_value) + self._value = value + + def _before_clear(self): + if self._value: + self._parent.namescope.remove(self._parent.spec.namespace, self._value) + + def _defaults_string(self, prefix_root): + prefix = self._parent.namescope.full_prefix(prefix_root, as_list=True) + prefix.append(self._value or '') + return constants.PREFIX_SEPARATOR.join(prefix) or constants.PREFIX_SEPARATOR + + def to_xml_string(self, prefix_root=None, **kwargs): + if self._parent.tag == constants.DEFAULT: + return self._defaults_string(prefix_root) + elif self._value: + prefix = self._parent.namescope.full_prefix(prefix_root, as_list=True) + prefix.append(self._value) + return constants.PREFIX_SEPARATOR.join(prefix) + else: + return self._value + + +class Reference(_Attribute): + """A string attribute that represents a reference to an identifier.""" + + def __init__(self, name, required, parent, value, + conflict_allowed, conflict_behavior, reference_namespace): + self._reference_namespace = reference_namespace + super().__init__(name, required, parent, value, conflict_allowed, + conflict_behavior) + + def _check_dead_reference(self): + if isinstance(self._value, base.Element) and self._value.is_removed: + self.clear() + + @property + def value(self): + self._check_dead_reference() + return super().value + + @value.setter + def value(self, new_value): + super(Reference, self.__class__).value.fset(self, new_value) + + @property + def reference_namespace(self): + if isinstance(self._reference_namespace, _Attribute): + return constants.INDIRECT_REFERENCE_ATTRIB.get( + self._reference_namespace.value, self._reference_namespace.value) + else: + return self._reference_namespace + + def _assign(self, value): + if not isinstance(value, (base.Element, str)): + raise ValueError( + 'Expect a string or `mjcf.Element` value: got {}'.format(value)) + elif not value: + self.clear() + else: + if isinstance(value, base.Element): + value_namespace = ( + value.spec.namespace.split(constants.NAMESPACE_SEPARATOR)[0]) + if value_namespace != self.reference_namespace: + raise ValueError(_INVALID_REFERENCE_TYPE.format( + valid_type=self.reference_namespace, + actual_type=value_namespace)) + self._value = value + + def _before_clear(self): + if isinstance(self._value, base.Element): + if isinstance(self._reference_namespace, _Attribute): + self._reference_namespace._force_clear() # pylint: disable=protected-access + + def _defaults_string(self, prefix_root): + """Generates the XML string if this is a reference to a defaults class. + + To prevent global defaults from clashing, we turn all global defaults + into a properly named defaults class. Therefore, care must be taken when + this attribute is not explicitly defined. If the parent element can be + traced up to a body with a nontrivial 'childclass' then must continue to + leave this attribute undefined. + + Args: + prefix_root: A `NameScope` object to be treated as root + for the purpose of calculating the prefix. + + Returns: + A string to be used in the generated XML. + """ + self._check_dead_reference() + prefix = self._parent.namescope.full_prefix(prefix_root) + if not self._value: + defaults_root = self._parent.parent + while defaults_root is not None: + if (hasattr(defaults_root, constants.CHILDCLASS) + and defaults_root.childclass): + break + defaults_root = defaults_root.parent + if defaults_root is None: + # This element doesn't belong to a childclass'd body. + global_class = self._parent.root.default.dclass or '' + out_string = (prefix + global_class) or constants.PREFIX_SEPARATOR + else: + out_string = None + else: + out_string = prefix + self._value + return out_string + + def to_xml_string(self, prefix_root, **kwargs): + self._check_dead_reference() + if isinstance(self._value, base.Element): + return self._value.prefixed_identifier(prefix_root) + elif (self.reference_namespace == constants.DEFAULT + and self._name != constants.CHILDCLASS): + return self._defaults_string(prefix_root) + elif self._value: + return self._parent.namescope.full_prefix(prefix_root) + self._value + else: + return None + + +class BasePath(_Attribute): + """A string attribute that represents a base path for an asset type.""" + + def __init__(self, name, required, parent, value, + conflict_allowed, conflict_behavior, path_namespace): + self._path_namespace = path_namespace + super().__init__(name, required, parent, value, conflict_allowed, + conflict_behavior) + + def _assign(self, value): + if not isinstance(value, str): + raise ValueError('Expect a string value: got {}'.format(value)) + elif not value: + self.clear() + else: + self._parent.namescope.replace( + constants.BASEPATH, self._path_namespace, value) + self._value = value + + def _before_clear(self): + if self._value: + self._parent.namescope.remove(constants.BASEPATH, self._path_namespace) + + def to_xml_string(self, prefix_root=None, **kwargs): + return None + + +class BaseAsset: + """Base class for binary assets.""" + + __slots__ = ('extension', 'prefix') + + def __init__(self, extension, prefix=''): + self.extension = extension + self.prefix = prefix + + def __eq__(self, other): + return self.get_vfs_filename() == other.get_vfs_filename() + + def get_vfs_filename(self): + """Returns the name of the asset file as registered in MuJoCo's VFS.""" + # Hash the contents of the asset to get a unique identifier. + hash_string = hashlib.sha1(util.to_binary_string(self.contents)).hexdigest() + # Prepend the prefix, if one exists. + if self.prefix: + prefix = self.prefix + raw_length = len(prefix) + len(hash_string) + len(self.extension) + 1 + if raw_length > constants.MAX_VFS_FILENAME_LENGTH: + trim_amount = raw_length - constants.MAX_VFS_FILENAME_LENGTH + prefix = prefix[:-trim_amount] + filename = '-'.join([prefix, hash_string]) + else: + filename = hash_string + + # An extension is needed because MuJoCo's compiler looks at this when + # deciding how to load meshes and heightfields. + return filename + self.extension + + +class Asset(BaseAsset): + """Class representing a binary asset.""" + + __slots__ = ('contents',) + + def __init__(self, contents, extension, prefix=''): + """Initializes a new `Asset`. + + Args: + contents: The contents of the file as a bytestring. + extension: A string specifying the file extension (e.g. '.png', '.stl'). + prefix: (optional) A prefix applied to the filename given in MuJoCo's VFS. + """ + self.contents = contents + super().__init__(extension, prefix) + + +class SkinAsset(BaseAsset): + """Class representing a binary asset corresponding to a skin.""" + + __slots__ = ('skin', 'parent', '_cached_revision', '_cached_contents') + + def __init__(self, contents, parent, extension, prefix=''): + self.skin = skin.parse( + contents, lambda body_name: parent.root.find('body', body_name)) + self.parent = parent + self._cached_revision = -1 + self._cached_contents = None + super().__init__(extension, prefix) + + @property + def contents(self): + if self._cached_revision < self.parent.namescope.revision: + self._cached_contents = skin.serialize(self.skin) + self._cached_revision = self.parent.namescope.revision + return self._cached_contents + + +class File(_Attribute): + """Attribute representing an asset file.""" + + def __init__(self, name, required, parent, value, + conflict_allowed, conflict_behavior, path_namespace): + self._path_namespace = path_namespace + super().__init__(name, required, parent, value, conflict_allowed, + conflict_behavior) + parent.namescope.files.add(self) + + def _assign(self, value): + if not value: + self.clear() + else: + if isinstance(value, str): + asset = self._get_asset_from_path(value) + elif isinstance(value, Asset): + asset = value + else: + raise ValueError('Expect either a string or `Asset` value: got {}' + .format(value)) + self._validate_extension(asset.extension) + self._value = asset + + def _get_asset_from_path(self, path): + """Constructs a `Asset` given a file path.""" + _, basename = os.path.split(path) + filename, extension = os.path.splitext(basename) + + assetdir = None + if self._parent.namescope.has_identifier( + constants.BASEPATH, constants.ASSETDIR_NAMESPACE + ): + assetdir = self._parent.namescope.get( + constants.BASEPATH, constants.ASSETDIR_NAMESPACE + ) + + if path in self._parent.namescope.assets: + # Look in the dict of pre-loaded assets before checking the filesystem. + contents = self._parent.namescope.assets[path] + else: + # Construct the full path to the asset file, prefixed by the path to the + # model directory, and by `meshdir` or `texturedir` if appropriate. + path_parts = [] + if self._parent.namescope.model_dir: + path_parts.append(self._parent.namescope.model_dir) + + if self._parent.namescope.has_identifier( + constants.BASEPATH, self._path_namespace + ): + base_path = self._parent.namescope.get( + constants.BASEPATH, self._path_namespace + ) + path_parts.append(base_path) + elif ( + self._path_namespace + in (constants.TEXTUREDIR_NAMESPACE, constants.MESHDIR_NAMESPACE) + and assetdir is not None + ): + path_parts.append(assetdir) + path_parts.append(path) + full_path = os.path.join(*path_parts) # pylint: disable=no-value-for-parameter + contents = resources.GetResource(full_path) + + if self._parent.tag == constants.SKIN: + return SkinAsset(contents=contents, parent=self._parent, + extension=extension, prefix=filename) + else: + return Asset(contents=contents, extension=extension, prefix=filename) + + def _validate_extension(self, extension): + if self._parent.tag == constants.MESH: + if extension.lower() not in _MESH_EXTENSIONS: + raise ValueError(_INVALID_MESH_EXTENSION.format(extension)) + + def get_contents(self): + """Returns a bytestring representing the contents of the asset.""" + if self._value is None: + raise RuntimeError('You must assign a value to this attribute before ' + 'querying the contents.') + return self._value.contents + + def to_xml_string(self, prefix_root=None, **kwargs): + """Returns the asset filename as it will appear in the generated XML.""" + del prefix_root # Unused + if self._value is not None: + return self._value.get_vfs_filename() + else: + return None diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/attribute_test.py b/rofunc/utils/robolab/formatter/mjcf_parser/attribute_test.py new file mode 100644 index 000000000..66e5bf7fb --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/attribute_test.py @@ -0,0 +1,497 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Tests for `dm_control.mjcf.attribute`.""" + +import contextlib +import hashlib +import os + +import numpy as np +from absl.testing import absltest +from absl.testing import parameterized + +from rofunc.utils.robolab.formatter.mjcf_parser import attribute +from rofunc.utils.robolab.formatter.mjcf_parser import element +from rofunc.utils.robolab.formatter.mjcf_parser import namescope +from rofunc.utils.robolab.formatter.mjcf_parser import schema + +ASSETS_DIR = os.path.join(os.path.dirname(__file__), 'test_assets') +FAKE_SCHEMA_FILENAME = 'attribute_test_schema.xml' + +ORIGINAL_SCHEMA_PATH = os.path.join(os.path.dirname(__file__), 'schema.xml') + + +class AttributeTest(parameterized.TestCase): + """Test for Attribute classes. + + Our tests here reflect actual usages of the Attribute classes, namely that we + never directly create attributes but instead access them through Elements. + """ + + def setUp(self): + super().setUp() + schema.override_schema(os.path.join(ASSETS_DIR, FAKE_SCHEMA_FILENAME)) + self._alpha = namescope.NameScope('alpha', None) + self._beta = namescope.NameScope('beta', None) + self._beta.parent = self._alpha + self._mujoco = element.RootElement() + self._mujoco.namescope.parent = self._beta + + def tearDown(self): + super().tearDown() + schema.override_schema(ORIGINAL_SCHEMA_PATH) + + def assertXMLStringIsNone(self, mjcf_element, attribute_name): + for prefix_root in (self._alpha, self._beta, self._mujoco.namescope, None): + self.assertIsNone( + mjcf_element.get_attribute_xml_string(attribute_name, prefix_root)) + + def assertXMLStringEqual(self, mjcf_element, attribute_name, expected): + for prefix_root in (self._alpha, self._beta, self._mujoco.namescope, None): + self.assertEqual( + mjcf_element.get_attribute_xml_string(attribute_name, prefix_root), + expected) + + def assertXMLStringIsCorrectlyScoped( + self, mjcf_element, attribute_name, expected): + for prefix_root in (self._alpha, self._beta, self._mujoco.namescope, None): + self.assertEqual( + mjcf_element.get_attribute_xml_string(attribute_name, prefix_root), + self._mujoco.namescope.full_prefix(prefix_root) + expected) + + def assertCorrectXMLStringForDefaultsClass( + self, mjcf_element, attribute_name, expected): + for prefix_root in (self._alpha, self._beta, self._mujoco.namescope, None): + self.assertEqual( + mjcf_element.get_attribute_xml_string(attribute_name, prefix_root), + (self._mujoco.namescope.full_prefix(prefix_root) + expected) or '/') + + def assertElementIsIdentifiedByName(self, mjcf_element, expected): + self.assertEqual(mjcf_element.name, expected) + self.assertEqual(self._mujoco.find(mjcf_element.spec.namespace, expected), + mjcf_element) + + @contextlib.contextmanager + def assertAttributeIsNoneWhenDone(self, mjcf_element, attribute_name): + yield + self.assertIsNone(getattr(mjcf_element, attribute_name)) + self.assertXMLStringIsNone(mjcf_element, attribute_name) + + def assertCorrectClearBehavior(self, mjcf_element, attribute_name, required): + if required: + return self.assertRaisesRegex(AttributeError, 'is required') + else: + return self.assertAttributeIsNoneWhenDone(mjcf_element, attribute_name) + + def assertCorrectClearBehaviorByAllMethods( + self, mjcf_element, attribute_name, required): + original_value = getattr(mjcf_element, attribute_name) + + def reset_value(): + setattr(mjcf_element, attribute_name, original_value) + if original_value is not None: + self.assertIsNotNone(getattr(mjcf_element, attribute_name)) + + # clear by using del + with self.assertCorrectClearBehavior( + mjcf_element, attribute_name, required): + delattr(mjcf_element, attribute_name) + + # clear by assigning None + reset_value() + with self.assertCorrectClearBehavior( + mjcf_element, attribute_name, required): + setattr(mjcf_element, attribute_name, None) + + if isinstance(original_value, str): + # clear by assigning empty string + reset_value() + with self.assertCorrectClearBehavior( + mjcf_element, attribute_name, required): + setattr(mjcf_element, attribute_name, '') + + def assertCanBeCleared(self, mjcf_element, attribute_name): + self.assertCorrectClearBehaviorByAllMethods( + mjcf_element, attribute_name, required=False) + + def assertCanNotBeCleared(self, mjcf_element, attribute_name): + self.assertCorrectClearBehaviorByAllMethods( + mjcf_element, attribute_name, required=True) + + def testFloatScalar(self): + mujoco = self._mujoco + mujoco.optional.float = 0.357357 + self.assertEqual(mujoco.optional.float, 0.357357) + self.assertEqual(type(mujoco.optional.float), float) + with self.assertRaisesRegex(ValueError, 'Expect a float value'): + mujoco.optional.float = 'five' + # failed assignment should not change the value + self.assertEqual(mujoco.optional.float, 0.357357) + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=1), + '0.4') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=2), + '0.36') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=3), + '0.357') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=4), + '0.3574') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=5), + '0.35736') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=6), + '0.357357') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=7), + '0.357357') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float', precision=8), + '0.357357') + + def testIntScalar(self): + mujoco = self._mujoco + mujoco.optional.int = 12345 + self.assertEqual(mujoco.optional.int, 12345) + self.assertEqual(type(mujoco.optional.int), int) + with self.assertRaisesRegex(ValueError, 'Expect an integer value'): + mujoco.optional.int = 10.5 + # failed assignment should not change the value + self.assertEqual(mujoco.optional.int, 12345) + self.assertXMLStringEqual(mujoco.optional, 'int', '12345') + self.assertCanBeCleared(mujoco.optional, 'int') + + def testStringScalar(self): + mujoco = self._mujoco + mujoco.optional.string = 'foobar' + self.assertEqual(mujoco.optional.string, 'foobar') + self.assertXMLStringEqual(mujoco.optional, 'string', 'foobar') + with self.assertRaisesRegex(ValueError, 'Expect a string value'): + mujoco.optional.string = mujoco.optional + self.assertCanBeCleared(mujoco.optional, 'string') + + def testFloatArray(self): + mujoco = self._mujoco + mujoco.optional.float_array = [3, 2, 1] + np.testing.assert_array_equal(mujoco.optional.float_array, [3, 2, 1]) + self.assertEqual(mujoco.optional.float_array.dtype, float) + with self.assertRaisesRegex(ValueError, 'no more than 3 entries'): + mujoco.optional.float_array = [0, 0, 0, -10] + with self.assertRaisesRegex(ValueError, 'one-dimensional array'): + mujoco.optional.float_array = np.array([[1, 2], [3, 4]]) + # failed assignments should not change the value + np.testing.assert_array_equal(mujoco.optional.float_array, [3, 2, 1]) + # XML string should not be affected by global print options + np.set_printoptions(precision=3, suppress=True) + mujoco.optional.float_array = [np.pi, 2, 1e-16] + self.assertXMLStringEqual(mujoco.optional, 'float_array', + '3.1415926535897931 2 9.9999999999999998e-17') + self.assertEqual( + mujoco.optional.get_attribute_xml_string('float_array', precision=5), + '3.1416 2 1e-16') + self.assertEqual( + mujoco.optional.get_attribute_xml_string( + 'float_array', precision=5, zero_threshold=1e-10), + '3.1416 2 0') + self.assertCanBeCleared(mujoco.optional, 'float_array') + + def testFormatVeryLargeArray(self): + mujoco = self._mujoco + array = np.arange(2000, dtype=np.double) + mujoco.optional.huge_float_array = array + xml_string = mujoco.optional.get_attribute_xml_string('huge_float_array') + self.assertNotIn('...', xml_string) + # Check that array <--> string conversion is a round trip. + mujoco.optional.huge_float_array = None + self.assertIsNone(mujoco.optional.huge_float_array) + mujoco.optional.huge_float_array = xml_string + np.testing.assert_array_equal(mujoco.optional.huge_float_array, array) + + def testIntArray(self): + mujoco = self._mujoco + mujoco.optional.int_array = [2, 2] + np.testing.assert_array_equal(mujoco.optional.int_array, [2, 2]) + self.assertEqual(mujoco.optional.int_array.dtype, int) + with self.assertRaisesRegex(ValueError, 'no more than 2 entries'): + mujoco.optional.int_array = [0, 0, 10] + # failed assignment should not change the value + np.testing.assert_array_equal(mujoco.optional.int_array, [2, 2]) + self.assertXMLStringEqual(mujoco.optional, 'int_array', '2 2') + self.assertCanBeCleared(mujoco.optional, 'int_array') + + def testKeyword(self): + mujoco = self._mujoco + + valid_values = ['Alpha', 'Beta', 'Gamma'] + for value in valid_values: + mujoco.optional.keyword = value.lower() + self.assertEqual(mujoco.optional.keyword, value) + self.assertXMLStringEqual(mujoco.optional, 'keyword', value) + + mujoco.optional.keyword = value.upper() + self.assertEqual(mujoco.optional.keyword, value) + self.assertXMLStringEqual(mujoco.optional, 'keyword', value) + + with self.assertRaisesRegex(ValueError, str(valid_values)): + mujoco.optional.keyword = 'delta' + # failed assignment should not change the value + self.assertXMLStringEqual(mujoco.optional, 'keyword', valid_values[-1]) + self.assertCanBeCleared(mujoco.optional, 'keyword') + + def testKeywordFalseTrueAuto(self): + mujoco = self._mujoco + for value in ('false', 'False', False): + mujoco.optional.fta = value + self.assertEqual(mujoco.optional.fta, 'false') + self.assertXMLStringEqual(mujoco.optional, 'fta', 'false') + for value in ('true', 'True', True): + mujoco.optional.fta = value + self.assertEqual(mujoco.optional.fta, 'true') + self.assertXMLStringEqual(mujoco.optional, 'fta', 'true') + for value in ('auto', 'AUTO'): + mujoco.optional.fta = value + self.assertEqual(mujoco.optional.fta, 'auto') + self.assertXMLStringEqual(mujoco.optional, 'fta', 'auto') + for value in (None, ''): + mujoco.optional.fta = value + self.assertIsNone(mujoco.optional.fta) + self.assertXMLStringEqual(mujoco.optional, 'fta', None) + + def testIdentifier(self): + mujoco = self._mujoco + + entity = mujoco.worldentity.add('entity') + subentity_1 = entity.add('subentity', name='foo') + subentity_2 = entity.add('subentity_alias', name='bar') + + self.assertIsNone(entity.name) + self.assertElementIsIdentifiedByName(subentity_1, 'foo') + self.assertElementIsIdentifiedByName(subentity_2, 'bar') + self.assertXMLStringIsCorrectlyScoped(subentity_1, 'name', 'foo') + self.assertXMLStringIsCorrectlyScoped(subentity_2, 'name', 'bar') + + with self.assertRaisesRegex(ValueError, 'Expect a string value'): + subentity_2.name = subentity_1 + with self.assertRaisesRegex(ValueError, 'reserved for scoping'): + subentity_2.name = 'foo/bar' + with self.assertRaisesRegex(ValueError, 'Duplicated identifier'): + subentity_2.name = 'foo' + # failed assignment should not change the value + self.assertElementIsIdentifiedByName(subentity_2, 'bar') + + with self.assertRaisesRegex(ValueError, 'cannot be named \'world\''): + mujoco.worldentity.add('body', name='world') + + subentity_1.name = 'baz' + self.assertElementIsIdentifiedByName(subentity_1, 'baz') + self.assertIsNone(mujoco.find('subentity', 'foo')) + + # 'foo' is now unused, so we should be allowed to use it + subentity_2.name = 'foo' + self.assertElementIsIdentifiedByName(subentity_2, 'foo') + + # duplicate name should be allowed when in different namespaces + entity.name = 'foo' + self.assertElementIsIdentifiedByName(entity, 'foo') + self.assertCanBeCleared(entity, 'name') + + def testStringReference(self): + mujoco = self._mujoco + mujoco.optional.reference = 'foo' + self.assertEqual(mujoco.optional.reference, 'foo') + self.assertXMLStringIsCorrectlyScoped(mujoco.optional, 'reference', 'foo') + self.assertCanBeCleared(mujoco.optional, 'reference') + + def testElementReferenceWithFixedNamespace(self): + mujoco = self._mujoco + # `mujoco.optional.fixed_type_ref` must be an element in the 'optional' + # namespace. 'identified' elements are part of the 'optional' namespace. + bar = mujoco.add('identified', identifier='bar') + mujoco.optional.fixed_type_ref = bar + self.assertXMLStringIsCorrectlyScoped( + mujoco.optional, 'fixed_type_ref', 'bar') + # Removing the referenced entity should cause the `fixed_type_ref` to be set + # to None. + bar.remove() + self.assertIsNone(mujoco.optional.fixed_type_ref) + + def testElementReferenceWithVariableNamespace(self): + mujoco = self._mujoco + + # `mujoco.optional.reference` can be an element in either the 'entity' or + # or 'optional' namespaces. First we assign an 'identified' element to the + # reference attribute. These are part of the 'optional' namespace. + bar = mujoco.add('identified', identifier='bar') + mujoco.optional.reftype = 'optional' + mujoco.optional.reference = bar + self.assertXMLStringIsCorrectlyScoped(mujoco.optional, 'reference', 'bar') + + # Assigning to `mujoco.optional.reference` should also change the value of + # `mujoco.optional.reftype` to match the namespace of the element that was + # assigned to `mujoco.optional.reference` + self.assertXMLStringEqual(mujoco.optional, 'reftype', 'optional') + + # Now assign an 'entity' element to the reference attribute. These are part + # of the 'entity' namespace. + baz = mujoco.worldentity.add('entity', name='baz') + mujoco.optional.reftype = 'entity' + mujoco.optional.reference = baz + self.assertXMLStringIsCorrectlyScoped(mujoco.optional, 'reference', 'baz') + # The `reftype` should change to 'entity' accordingly. + self.assertXMLStringEqual(mujoco.optional, 'reftype', 'entity') + + # Removing the referenced entity should cause the `reference` and `reftype` + # to be set to None. + baz.remove() + self.assertIsNone(mujoco.optional.reference) + self.assertIsNone(mujoco.optional.reftype) + + def testInvalidReference(self): + mujoco = self._mujoco + bar = mujoco.worldentity.add('entity', name='bar') + baz = bar.add('subentity', name='baz') + mujoco.optional.reftype = 'entity' + with self.assertRaisesWithLiteralMatch( + ValueError, attribute._INVALID_REFERENCE_TYPE.format( + valid_type='entity', actual_type='subentity')): + mujoco.optional.reference = baz + with self.assertRaisesWithLiteralMatch( + ValueError, attribute._INVALID_REFERENCE_TYPE.format( + valid_type='optional', actual_type='subentity')): + mujoco.optional.fixed_type_ref = baz + + def testDefaults(self): + mujoco = self._mujoco + + # Unnamed global defaults class should become a properly named and scoped + # class with a trailing slash + self.assertIsNone(mujoco.default.dclass) + self.assertCorrectXMLStringForDefaultsClass(mujoco.default, 'class', '') + + # An element without an explicit dclass should be assigned to the properly + # scoped global defaults class + entity = mujoco.worldentity.add('entity') + subentity = entity.add('subentity') + self.assertIsNone(subentity.dclass) + self.assertCorrectXMLStringForDefaultsClass(subentity, 'class', '') + + # Named global defaults class should gain scoping prefix + mujoco.default.dclass = 'main' + self.assertEqual(mujoco.default.dclass, 'main') + self.assertCorrectXMLStringForDefaultsClass(mujoco.default, 'class', 'main') + self.assertCorrectXMLStringForDefaultsClass(subentity, 'class', 'main') + + # Named subordinate defaults class should gain scoping prefix + sub_default = mujoco.default.add('default', dclass='sub') + self.assertEqual(sub_default.dclass, 'sub') + self.assertCorrectXMLStringForDefaultsClass(sub_default, 'class', 'sub') + + # An element without an explicit dclass but belongs to a childclassed + # parent should be left alone + entity.childclass = 'sub' + self.assertEqual(entity.childclass, 'sub') + self.assertCorrectXMLStringForDefaultsClass(entity, 'childclass', 'sub') + self.assertXMLStringIsNone(subentity, 'class') + + # An element WITH an explicit dclass should be left alone have it properly + # scoped regardless of whether it belongs to a childclassed parent or not. + subentity.dclass = 'main' + self.assertCorrectXMLStringForDefaultsClass(subentity, 'class', 'main') + + @parameterized.named_parameters( + ('NoBasepath', '', os.path.join(ASSETS_DIR, FAKE_SCHEMA_FILENAME)), + ('WithBasepath', ASSETS_DIR, FAKE_SCHEMA_FILENAME)) + def testFileFromPath(self, basepath, value): + mujoco = self._mujoco + full_path = os.path.join(basepath, value) + with open(full_path, 'rb') as f: + contents = f.read() + _, basename = os.path.split(value) + prefix, extension = os.path.splitext(basename) + expected_xml = prefix + '-' + hashlib.sha1(contents).hexdigest() + extension + mujoco.files.text_path = basepath + text_file = mujoco.files.add('text', file=value) + expected_value = attribute.Asset( + contents=contents, extension=extension, prefix=prefix) + self.assertEqual(text_file.file, expected_value) + self.assertXMLStringEqual(text_file, 'file', expected_xml) + self.assertCanBeCleared(text_file, 'file') + self.assertCanBeCleared(mujoco.files, 'text_path') + + def testFileFromPlaceholder(self): + mujoco = self._mujoco + contents = b'Fake contents' + extension = '.whatever' + expected_xml = hashlib.sha1(contents).hexdigest() + extension + placeholder = attribute.Asset(contents=contents, extension=extension) + text_file = mujoco.files.add('text', file=placeholder) + self.assertEqual(text_file.file, placeholder) + self.assertXMLStringEqual(text_file, 'file', expected_xml) + self.assertCanBeCleared(text_file, 'file') + + def testFileFromAssetsDict(self): + prefix = 'fake_filename' + extension = '.whatever' + path = 'invalid/path/' + prefix + extension + contents = 'Fake contents' + assets = {path: contents} + mujoco = element.RootElement(assets=assets) + text_file = mujoco.files.add('text', file=path) + expected_value = attribute.Asset( + contents=contents, extension=extension, prefix=prefix) + self.assertEqual(text_file.file, expected_value) + + def testFileExceptions(self): + mujoco = self._mujoco + text_file = mujoco.files.add('text') + with self.assertRaisesRegex(ValueError, + 'Expect either a string or `Asset` value'): + text_file.file = mujoco.optional + + def testBasePathExceptions(self): + mujoco = self._mujoco + with self.assertRaisesRegex(ValueError, 'Expect a string value'): + mujoco.files.text_path = mujoco.optional + + def testRequiredAttributes(self): + mujoco = self._mujoco + attributes = ( + ('float', 1.0), ('int', 2), ('string', 'foobar'), + ('float_array', [1.5, 2.5, 3.5]), ('int_array', [4, 5]), + ('keyword', 'alpha'), ('identifier', 'thing'), + ('reference', 'other_thing'), ('basepath', ASSETS_DIR), + ('file', FAKE_SCHEMA_FILENAME) + ) + + # Removing any one of the required attributes should cause initialization + # of a new element to fail + for name, _ in attributes: + attributes_dict = {key: value for key, value in attributes if key != name} + with self.assertRaisesRegex(AttributeError, name + '.+ is required'): + mujoco.add('required', **attributes_dict) + + attributes_dict = {key: value for key, value in attributes} + mujoco.add('required', **attributes_dict) + # Should not be allowed to clear each required attribute after the fact + for name, _ in attributes: + self.assertCanNotBeCleared(mujoco.required, name) + + +if __name__ == '__main__': + absltest.main() diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/base.py b/rofunc/utils/robolab/formatter/mjcf_parser/base.py new file mode 100644 index 000000000..37f90adef --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/base.py @@ -0,0 +1,279 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Base class for all MJCF elements in the object model.""" + +import abc + +from rofunc.utils.robolab.formatter.mjcf_parser import constants + + +class Element(metaclass=abc.ABCMeta): + """Abstract base class for an MJCF element. + + This class is provided so that `isinstance(foo, Element)` is `True` for all + Element-like objects. We do not implement the actual element here because + the actual object returned from traversing the object hierarchy is a + weakproxy-like proxy to an actual element. This is because we do not allow + orphaned non-root elements, so when a particular element is removed from the + tree, all references held automatically become invalid. + """ + __slots__ = [] + + @abc.abstractmethod + def get_init_stack(self): + """Gets the stack trace where this element was first initialized.""" + + @abc.abstractmethod + def get_last_modified_stacks_for_all_attributes(self): + """Gets a dict of stack traces where each attribute was last modified.""" + + @abc.abstractmethod + def is_same_as(self, other): + """Checks whether another element is semantically equivalent to this one. + + Two elements are considered equivalent if they have the same + specification (i.e. same tag appearing in the same context), the same + attribute values, and all of their children are equivalent. The ordering + of non-repeated children is not important for this comparison, while + the ordering of repeated children are important only amongst the same + type* of children. In other words, for two bodies to be considered + equivalent, their child sites must appear in the same order, and their + child geoms must appear in the same order, but permutations between sites + and geoms are disregarded. (The only exception is in tendon definition, + where strict ordering of all children is necessary for equivalence.) + + *Note that the notion of "same type" in this function is very loose: + for example different actuator element subtypes are treated as separate + types when children ordering is considered. Therefore, two + elements might be considered equivalent even though they result in different + orderings of `mjData.ctrl` when compiled. As it stands, this function + is designed primarily as a testing aid and should not be used to guarantee + that models are actually identical. + + Args: + other: An `mjcf.Element` + + Returns: + `True` if `other` element is semantically equivalent to this one. + """ + + @property + @abc.abstractmethod + def tag(self): + pass + + @property + @abc.abstractmethod + def spec(self): + pass + + @property + @abc.abstractmethod + def parent(self): + pass + + @property + @abc.abstractmethod + def namescope(self): + pass + + @property + @abc.abstractmethod + def root(self): + pass + + @abc.abstractmethod + def prefixed_identifier(self, prefix_root): + pass + + @property + @abc.abstractmethod + def full_identifier(self): + """Fully-qualified identifier used for this element in the generated XML.""" + + @abc.abstractmethod + def find(self, namespace, identifier): + """Finds an element with a particular identifier. + + This function allows the direct access to an arbitrarily deeply nested + child element by name, without the need to manually traverse through the + object tree. The `namespace` argument specifies the kind of element to + find. In most cases, this corresponds to the element's XML tag name. + However, if an element has multiple specialized tags, then the namespace + corresponds to the tag name of the most general element of that kind. + For example, `namespace='joint'` would search for `` and + ``, while `namespace='actuator'` would search for ``, + ``, ``, ``, and ``. + + Args: + namespace: A string specifying the namespace being searched. See the + docstring above for explanation. + identifier: The identifier string of the desired element. + + Returns: + An `mjcf.Element` object, or `None` if an element with the specified + identifier is not found. + + Raises: + ValueError: if either `namespace` or `identifier` is not a string, or if + `namespace` is not a valid namespace. + """ + + @abc.abstractmethod + def find_all(self, namespace, + immediate_children_only=False, exclude_attachments=False): + """Finds all elements of a particular kind. + + The `namespace` argument specifies the kind of element to + find. In most cases, this corresponds to the element's XML tag name. + However, if an element has multiple specialized tags, then the namespace + corresponds to the tag name of the most general element of that kind. + For example, `namespace='joint'` would search for `` and + ``, while `namespace='actuator'` would search for ``, + ``, ``, ``, and ``. + + Args: + namespace: A string specifying the namespace being searched. See the + docstring above for explanation. + immediate_children_only: (optional) A boolean, if `True` then only + the immediate children of this element are returned. + exclude_attachments: (optional) A boolean, if `True` then elements + belonging to attached models are excluded. + + Returns: + A list of `mjcf.Element`. + + Raises: + ValueError: if `namespace` is not a valid namespace. + """ + + @abc.abstractmethod + def enter_scope(self, scope_identifier): + """Finds the root element of the given scope and returns it. + + This function allows the access to a nested scope that is a child of this + element. The `scope_identifier` argument specifies the path to the child + scope element. + + Args: + scope_identifier: The path of the desired scope element. + + Returns: + An `mjcf.Element` object, or `None` if a scope element with the + specified path is not found. + """ + + @abc.abstractmethod + def get_attribute_xml_string(self, attribute_name, prefix_root=None): + pass + + @abc.abstractmethod + def get_attributes(self): + pass + + @abc.abstractmethod + def set_attributes(self, **kwargs): + pass + + @abc.abstractmethod + def get_children(self, element_name): + pass + + @abc.abstractmethod + def add(self, element_name, **kwargs): + """Add a new child element to this element. + + Args: + element_name: The tag of the element to add. + **kwargs: Attributes of the new element being created. + + Raises: + ValueError: If the 'element_name' is not a valid child, or if an invalid + attribute is specified in `kwargs`. + + Returns: + An `mjcf.Element` corresponding to the newly created child element. + """ + + @abc.abstractmethod + def remove(self, affect_attachments=False): + """Removes this element from the model.""" + + @property + @abc.abstractmethod + def is_removed(self): + pass + + @abc.abstractmethod + def all_children(self): + pass + + @abc.abstractmethod + def to_xml(self, prefix_root=None, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + """Generates an etree._Element corresponding to this MJCF element. + + Args: + prefix_root: (optional) A `NameScope` object to be treated as root + for the purpose of calculating the prefix. + If `None` then no prefix is included. + debug_context: (optional) A `debugging.DebugContext` object to which + the debugging information associated with the generated XML is written. + This is intended for internal use within PyMJCF; users should never need + manually pass this argument. + precision: (optional) Number of digits to output for floating point + quantities. + zero_threshold: (optional) When outputting XML, floating point quantities + whose absolute value falls below this threshold will be treated as zero. + + Returns: + An etree._Element object. + """ + + @abc.abstractmethod + def to_xml_string(self, prefix_root=None, + self_only=False, pretty_print=True, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + """Generates an XML string corresponding to this MJCF element. + + Args: + prefix_root: (optional) A `NameScope` object to be treated as root + for the purpose of calculating the prefix. + If `None` then no prefix is included. + self_only: (optional) A boolean, whether to generate an XML corresponding + only to this element without any children. + pretty_print: (optional) A boolean, whether to the XML string should be + properly indented. + debug_context: (optional) A `debugging.DebugContext` object to which + the debugging information associated with the generated XML is written. + This is intended for internal use within PyMJCF; users should never need + manually pass this argument. + precision: (optional) Number of digits to output for floating point + quantities. + zero_threshold: (optional) When outputting XML, floating point quantities + whose absolute value falls below this threshold will be treated as zero. + + Returns: + A string. + """ + + @abc.abstractmethod + def resolve_references(self): + pass diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/code_for_debugging_test.py b/rofunc/utils/robolab/formatter/mjcf_parser/code_for_debugging_test.py new file mode 100644 index 000000000..22f54cdc8 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/code_for_debugging_test.py @@ -0,0 +1,82 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Constructs models for debugging_test.py. + +The purpose of this file is to provide "golden" source line numbers for test +cases in debugging_test.py. When this module is loaded, it inspects its own +source code to look for lines that begin with `# !!LINE_REF`, and stores the +following line number in a dict. This allows test cases to look up the line +number by name, rather than brittly hard-coding in the line number. +""" + +import collections +import os +import re + +from rofunc.utils.robolab.formatter import mjcf_parser as mjcf + +SourceLine = collections.namedtuple( + 'SourceLine', ('line_number', 'text')) + +LINE_REF = {} + + +def make_valid_model(): + # !!LINE_REF make_valid_model.mjcf_model + mjcf_model = mjcf.RootElement() + # !!LINE_REF make_valid_model.my_body + my_body = mjcf_model.worldbody.add('body', name='my_body') + my_body.add('inertial', mass=1, pos=[0, 0, 0], diaginertia=[1, 1, 1]) + # !!LINE_REF make_valid_model.my_joint + my_joint = my_body.add('joint', name='my_joint', type='hinge') + # !!LINE_REF make_valid_model.my_actuator + mjcf_model.actuator.add('velocity', name='my_actuator', joint=my_joint) + return mjcf_model + + +def make_broken_model(): + # !!LINE_REF make_broken_model.mjcf_model + mjcf_model = mjcf.RootElement() + # !!LINE_REF make_broken_model.my_body + my_body = mjcf_model.worldbody.add('body', name='my_body') + my_body.add('inertial', mass=1, pos=[0, 0, 0], diaginertia=[1, 1, 1]) + # !!LINE_REF make_broken_model.my_joint + my_body.add('joint', name='my_joint', type='hinge') + # !!LINE_REF make_broken_model.my_actuator + mjcf_model.actuator.add('velocity', name='my_actuator', joint='invalid_joint') + return mjcf_model + + +def break_valid_model(mjcf_model): + # !!LINE_REF break_valid_model.my_actuator.joint + mjcf_model.find('actuator', 'my_actuator').joint = 'invalid_joint' + return mjcf_model + + +def _parse_line_refs(): + line_ref_pattern = re.compile(r'\s*# !!LINE_REF\s*([^\s]+)') + filename, _ = os.path.splitext(__file__) # __file__ can be `.pyc`. + with open(filename + '.py') as f: + src = f.read() + src_lines = src.split('\n') + for line_number, line in enumerate(src_lines): + match = line_ref_pattern.match(line) + if match: + LINE_REF[match.group(1)] = SourceLine( + line_number + 2, src_lines[line_number + 1].strip()) + + +_parse_line_refs() diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/constants.py b/rofunc/utils/robolab/formatter/mjcf_parser/constants.py new file mode 100644 index 000000000..ed24b0da5 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/constants.py @@ -0,0 +1,83 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Magic constants used within `dm_control.mjcf`.""" + +PREFIX_SEPARATOR = '/' +PREFIX_SEPARATOR_ESCAPE = '\\' + +# Used to disambiguate namespaces between attachment frames. +NAMESPACE_SEPARATOR = '@' + +# Magic attribute names +BASEPATH = 'basepath' +CHILDCLASS = 'childclass' +CLASS = 'class' +DEFAULT = 'default' +DCLASS = 'dclass' + +# Magic tags +ACTUATOR = 'actuator' +BODY = 'body' +DEFAULT = 'default' +MESH = 'mesh' +SITE = 'site' +SKIN = 'skin' +TENDON = 'tendon' +WORLDBODY = 'worldbody' + +# Path namespaces. +MESHDIR_NAMESPACE = 'mesh' +TEXTUREDIR_NAMESPACE = 'texture' +ASSETDIR_NAMESPACE = 'asset' + +MJDATA_TRIGGERS_DIRTY = [ + 'qpos', 'qvel', 'act', 'ctrl', 'qfrc_applied', 'xfrc_applied'] +MJMODEL_DOESNT_TRIGGER_DIRTY = [ + 'rgba', 'matid', 'emission', 'specular', 'shininess', 'reflectance', + 'needstage', +] + +# When writing into `model.{body,geom,site}_{pos,quat}` we must ensure that the +# corresponding rows in `model.{body,geom,site}_sameframe` are set to zero, +# otherwise MuJoCo will use the body or inertial frame instead of our modified +# pos/quat values. We must do the same for `body_{ipos,iquat}` and +# `body_simple`. +MJMODEL_DISABLE_ON_WRITE = { + # Field name in MjModel: (attribute names of Binding instance to be zeroed) + 'body_pos': ('sameframe',), + 'body_quat': ('sameframe',), + 'geom_pos': ('sameframe',), + 'geom_quat': ('sameframe',), + 'site_pos': ('sameframe',), + 'site_quat': ('sameframe',), + 'body_ipos': ('simple', 'sameframe'), + 'body_iquat': ('simple', 'sameframe'), +} + +MAX_VFS_FILENAME_LENGTH = 998 + +# The prefix used in the schema to denote reference_namespace that are defined +# via another attribute. +INDIRECT_REFERENCE_NAMESPACE_PREFIX = 'attrib:' + +INDIRECT_REFERENCE_ATTRIB = { + 'xbody': 'body', +} + +# 17 decimal digits is sufficient to represent a double float without loss +# of precision. +# https://en.wikipedia.org/wiki/IEEE_754#Character_representation +XML_DEFAULT_PRECISION = 17 diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/copier.py b/rofunc/utils/robolab/formatter/mjcf_parser/copier.py new file mode 100644 index 000000000..b8ca2501a --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/copier.py @@ -0,0 +1,71 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Helper object for keeping track of new elements created when copying MJCF.""" + +from rofunc.utils.robolab.formatter.mjcf_parser import constants + + +class Copier: + """Helper for keeping track of new elements created when copying MJCF.""" + + def __init__(self, source): + if source._attachments: # pylint: disable=protected-access + raise NotImplementedError('Cannot copy from elements with attachments') + self._source = source + + def copy_into(self, destination, override_attributes=False): + """Copies this copier's element into a destination MJCF element.""" + newly_created_elements = {} + destination._check_valid_attachment(self._source) # pylint: disable=protected-access + if override_attributes: + destination.set_attributes(**self._source.get_attributes()) + else: + destination._sync_attributes(self._source, copying=True) # pylint: disable=protected-access + for source_child in self._source.all_children(): + dest_child = None + # First, if source_child has an identifier, we look for an existing child + # element of self with the same identifier to override. + if source_child.spec.identifier and override_attributes: + identifier_attr = source_child.spec.identifier + if identifier_attr == constants.CLASS: + identifier_attr = constants.DCLASS + identifier = getattr(source_child, identifier_attr) + if identifier: + dest_child = destination.find(source_child.spec.namespace, identifier) + if dest_child is not None and dest_child.parent is not destination: + raise ValueError( + '<{}> with identifier {!r} is already a child of another element' + .format(source_child.spec.namespace, identifier)) + # Next, we cover the case where either the child is not a repeated element + # or if source_child has an identifier attribute but it isn't set. + if not source_child.spec.repeated and dest_child is None: + dest_child = destination.get_children(source_child.tag) + + # Add a new element if dest_child doesn't exist, either because it is + # supposed to be a repeated child, or because it's an uncreated on-demand. + if dest_child is None: + dest_child = destination.add( + source_child.tag, **source_child.get_attributes()) + newly_created_elements[source_child] = dest_child + override_child_attributes = True + else: + override_child_attributes = override_attributes + + # Finally, copy attributes into dest_child. + child_copier = Copier(source_child) + newly_created_elements.update( + child_copier.copy_into(dest_child, override_child_attributes)) + return newly_created_elements diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/copier_test.py b/rofunc/utils/robolab/formatter/mjcf_parser/copier_test.py new file mode 100644 index 000000000..15c03fc4f --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/copier_test.py @@ -0,0 +1,85 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Tests for `dm_control.mjcf.copier`.""" + +import os + +import numpy as np +from absl.testing import absltest +from rofunc.utils.robolab.formatter import mjcf_parser as mjcf + +from rofunc.utils.robolab.formatter.mjcf_parser import parser + +_ASSETS_DIR = os.path.join(os.path.dirname(__file__), 'test_assets') +_TEST_MODEL_XML = os.path.join(_ASSETS_DIR, 'test_model.xml') +_MODEL_WITH_ASSETS_XML = os.path.join(_ASSETS_DIR, 'model_with_assets.xml') + + +class CopierTest(absltest.TestCase): + + def testSimpleCopy(self): + mjcf_model = parser.from_path(_TEST_MODEL_XML) + mixin = mjcf.RootElement(model='test_mixin') + mixin.compiler.boundmass = 1 + mjcf_model.include_copy(mixin) + self.assertEqual(mjcf_model.model, 'test') # Model name should not change + self.assertEqual(mjcf_model.compiler.boundmass, mixin.compiler.boundmass) + mixin.compiler.boundinertia = 2 + mjcf_model.include_copy(mixin) + self.assertEqual(mjcf_model.compiler.boundinertia, + mixin.compiler.boundinertia) + mixin.compiler.boundinertia = 1 + with self.assertRaisesRegex(ValueError, 'Conflicting values'): + mjcf_model.include_copy(mixin) + mixin.worldbody.add('body', name='b_0', pos=[0, 1, 2]) + mjcf_model.include_copy(mixin, override_attributes=True) + self.assertEqual(mjcf_model.compiler.boundmass, mixin.compiler.boundmass) + self.assertEqual(mjcf_model.compiler.boundinertia, + mixin.compiler.boundinertia) + np.testing.assert_array_equal(mjcf_model.worldbody.body['b_0'].pos, + [0, 1, 2]) + + def testCopyingWithReference(self): + sensor_mixin = mjcf.RootElement('sensor_mixin') + touch_site = sensor_mixin.worldbody.add('site', name='touch_site') + sensor_mixin.sensor.add('touch', name='touch_sensor', site=touch_site) + + mjcf_model = mjcf.RootElement('model') + mjcf_model.include_copy(sensor_mixin) + + # Copied reference should be updated to the copied site. + self.assertIs(mjcf_model.find('sensor', 'touch_sensor').site, + mjcf_model.find('site', 'touch_site')) + + def testCopyingWithAssets(self): + mjcf_model = parser.from_path(_MODEL_WITH_ASSETS_XML) + copied = mjcf.RootElement() + copied.include_copy(mjcf_model) + + original_assets = (mjcf_model.find_all('mesh') + + mjcf_model.find_all('texture') + + mjcf_model.find_all('hfield')) + copied_assets = (copied.find_all('mesh') + + copied.find_all('texture') + + copied.find_all('hfield')) + + self.assertLen(copied_assets, len(original_assets)) + for original_asset, copied_asset in zip(original_assets, copied_assets): + self.assertIs(copied_asset.file, original_asset.file) + + +if __name__ == '__main__': + absltest.main() diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/debugging.py b/rofunc/utils/robolab/formatter/mjcf_parser/debugging.py new file mode 100644 index 000000000..a63f42a70 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/debugging.py @@ -0,0 +1,368 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Implements PyMJCF debug mode. + +PyMJCF debug mode stores a stack trace each time the MJCF object is modified. +If Mujoco raises a compile error on the generated XML model, we would then be +able to find the original source line that created the offending element. +""" + +import collections +import contextlib +import copy +import os +import re +import sys +import traceback + +from absl import flags +from lxml import etree + +FLAGS = flags.FLAGS +flags.DEFINE_boolean( + 'mjcf_parser_debug', False, + 'Enables PyMJCF debug mode (SLOW!). In this mode, a stack trace is logged ' + 'each the MJCF object is modified. This may be helpful in locating the ' + 'Python source line corresponding to a problematic element in the ' + 'generated XML.') +flags.DEFINE_string( + 'mjcf_parser_debug_full_dump_dir', '', + 'Path to dump full debug info when Mujoco error is encountered.') + +StackTraceEntry = collections.namedtuple( + 'StackTraceEntry', ('filename', 'line_number', 'function_name', 'text')) + +ElementDebugInfo = collections.namedtuple( + 'ElementDebugInfo', ('element', 'init_stack', 'attribute_stacks')) + +MODULE_PATH = os.path.dirname(sys.modules[__name__].__file__) +DEBUG_METADATA_PREFIX = 'pymjcfdebug' + +_DEBUG_METADATA_TAG_PREFIX = ''.format(DEBUG_METADATA_PREFIX)) + +# Modified by `freeze_current_stack_trace`. +_CURRENT_FROZEN_STACK = None + +# These globals will take their default values from the `--mjcf_parser_debug` and +# `--pymjcf_debug_full_dump_dir` flags respectively. We cannot use `FLAGS` as +# global variables because flag parsing might not have taken place (e.g. when +# running `nosetests`). +_DEBUG_MODE_ENABLED = None +_DEBUG_FULL_DUMP_DIR = None + + +def debug_mode(): + """Returns a boolean that indicates whether PyMJCF debug mode is enabled.""" + global _DEBUG_MODE_ENABLED + if _DEBUG_MODE_ENABLED is None: + if FLAGS.is_parsed(): + _DEBUG_MODE_ENABLED = FLAGS.mjcf_parser_debug + else: + _DEBUG_MODE_ENABLED = FLAGS['mjcf_parser_debug'].default + return _DEBUG_MODE_ENABLED + + +def enable_debug_mode(): + """Enables PyMJCF debug mode.""" + global _DEBUG_MODE_ENABLED + _DEBUG_MODE_ENABLED = True + + +def disable_debug_mode(): + """Disables PyMJCF debug mode.""" + global _DEBUG_MODE_ENABLED + _DEBUG_MODE_ENABLED = False + + +def get_full_dump_dir(): + """Gets the directory to dump full debug info files.""" + global _DEBUG_FULL_DUMP_DIR + if _DEBUG_FULL_DUMP_DIR is None: + if FLAGS.is_parsed(): + _DEBUG_FULL_DUMP_DIR = FLAGS.pymjcf_debug_full_dump_dir + else: + _DEBUG_FULL_DUMP_DIR = FLAGS['pymjcf_debug_full_dump_dir'].default + return _DEBUG_FULL_DUMP_DIR + + +def set_full_dump_dir(dump_path): + """Sets the directory to dump full debug info files.""" + global _DEBUG_FULL_DUMP_DIR + _DEBUG_FULL_DUMP_DIR = dump_path + + +def get_current_stack_trace(): + """Returns the stack trace of the current execution frame. + + Returns: + A list of `StackTraceEntry` named tuples corresponding to the current stack + trace of the process, truncated to immediately before entry into + PyMJCF internal code. + """ + if _CURRENT_FROZEN_STACK: + return copy.deepcopy(_CURRENT_FROZEN_STACK) + else: + return _get_actual_current_stack_trace() + + +def _get_actual_current_stack_trace(): + """Returns the stack trace of the current execution frame. + + Returns: + A list of `StackTraceEntry` named tuples corresponding to the current stack + trace of the process, truncated to immediately before entry into + PyMJCF internal code. + """ + raw_stack = traceback.extract_stack() + processed_stack = [] + for raw_stack_item in raw_stack: + stack_item = StackTraceEntry(*raw_stack_item) + if (stack_item.filename.startswith(MODULE_PATH) + and not stack_item.filename.endswith('_test.py')): + break + else: + processed_stack.append(stack_item) + return processed_stack + + +@contextlib.contextmanager +def freeze_current_stack_trace(): + """A context manager that freezes the stack trace. + + AVOID USING THIS CONTEXT MANAGER OUTSIDE OF INTERNAL PYMJCF IMPLEMENTATION, + AS IT REDUCES THE USEFULNESS OF DEBUG MODE. + + If PyMJCF debug mode is enabled, calls to `debugging.get_current_stack_trace` + within this context will always return the stack trace from when this context + was entered. + + The frozen stack is global to this debugging module. That is, if the context + is entered while another one is still active, then the stack trace of the + outermost one is returned. + + This context significantly speeds up bulk operations in debug mode, e.g. + parsing an existing XML string or creating a deeply-nested element, as it + prevents the same stack trace from being repeatedly constructed. + + Yields: + `None` + """ + global _CURRENT_FROZEN_STACK + if debug_mode() and _CURRENT_FROZEN_STACK is None: + _CURRENT_FROZEN_STACK = _get_actual_current_stack_trace() + yield + _CURRENT_FROZEN_STACK = None + else: + yield + + +class DebugContext: + """A helper object to store debug information for a generated XML string. + + This class is intended for internal use within the PyMJCF implementation. + """ + + def __init__(self): + self._xml_string = None + self._debug_info_for_element_ids = {} + + def register_element_for_debugging(self, elem): + """Registers an `Element` and returns debugging metadata for the XML. + + Args: + elem: An `mjcf.Element`. + + Returns: + An `lxml.etree.Comment` that represents debugging metadata in the + generated XML. + """ + if not debug_mode(): + return None + else: + self._debug_info_for_element_ids[id(elem)] = ElementDebugInfo( + elem, + copy.deepcopy(elem.get_init_stack()), + copy.deepcopy(elem.get_last_modified_stacks_for_all_attributes())) + return etree.Comment('{}:{}'.format(DEBUG_METADATA_PREFIX, id(elem))) + + def commit_xml_string(self, xml_string): + """Commits the XML string associated with this debug context. + + This function also formats the XML string to make sure that the debugging + metadata appears on the same line as the corresponding XML element. + + Args: + xml_string: A pretty-printed XML string. + + Returns: + A reformatted XML string where all debugging metadata appears on the same + line as the corresponding XML element. + """ + formatted = re.sub(r'\n\s*' + _DEBUG_METADATA_TAG_PREFIX, + _DEBUG_METADATA_TAG_PREFIX, xml_string) + self._xml_string = formatted + return formatted + + def process_and_raise_last_exception(self): + """Processes and re-raises the last ValueError caught. + + This function will insert the relevant line from the source XML to the error + message. If debug mode is enabled, additional debugging information is + appended to the error message. If debug mode is not enabled, the error + message instructs the user to enable it by rerunning the executable with an + appropriate flag. + """ + err_type, err, tb = sys.exc_info() + line_number_match = re.search(r'[Ll][Ii][Nn][Ee]\s*[:=]?\s*(\d+)', str(err)) + if line_number_match: + xml_line_number = int(line_number_match.group(1)) + xml_line = self._xml_string.split('\n')[xml_line_number - 1] + stripped_xml_line = xml_line.strip() + comment_match = re.search(_DEBUG_METADATA_TAG_PREFIX, stripped_xml_line) + if comment_match: + stripped_xml_line = stripped_xml_line[:comment_match.start()] + else: + xml_line = '' + stripped_xml_line = '' + + message_lines = [] + if debug_mode(): + if get_full_dump_dir(): + self.dump_full_debug_info_to_disk() + message_lines.extend([ + 'Compile error raised by Mujoco.', + str(err)]) + if xml_line: + message_lines.extend([ + stripped_xml_line, + self._generate_debug_message_from_xml_line(xml_line)]) + else: + message_lines.extend([ + 'Compile error raised by Mujoco; ' + + 'run again with --mjcf_parser_debug for additional debug information.', + str(err) + ]) + if xml_line: + message_lines.append(stripped_xml_line) + + raise err_type('\n'.join(message_lines)).with_traceback(tb) + + @property + def default_dump_dir(self): + return get_full_dump_dir() + + @property + def debug_mode(self): + return debug_mode() + + def dump_full_debug_info_to_disk(self, dump_dir=None): + """Dumps full debug information to disk. + + Full debug information consists of an XML file whose elements are tagged + with a unique ID, and a stack trace file for each element ID. Each stack + trace file consists of a stack trace for when the element was created, and + when each attribute was last modified. + + Args: + dump_dir: Full path to the directory in which dump files are created. + + Raises: + ValueError: If neither `dump_dir` nor the global dump path is given. The + global dump path can be specified either via the + --pymjcf_debug_full_dump_dir flag or via `debugging.set_full_dump_dir`. + """ + dump_dir = dump_dir or self.default_dump_dir + if not dump_dir: + raise ValueError('`dump_dir` is not specified') + section_separator = '\n' + ('=' * 80) + '\n' + + def dump_stack(header, stack, f): + indent = ' ' + f.write(header + '\n') + for stack_entry in stack: + f.write(indent + '`{}` at {}:{}\n' + .format(stack_entry.function_name, + stack_entry.filename, stack_entry.line_number)) + f.write((indent * 2) + str(stack_entry.text) + '\n') + f.write(section_separator) + + with open(os.path.join(dump_dir, 'model.xml'), 'w') as f: + f.write(self._xml_string) + for elem_id, debug_info in self._debug_info_for_element_ids.items(): + with open(os.path.join(dump_dir, str(elem_id) + '.dump'), 'w') as f: + f.write('{}:{}\n'.format(DEBUG_METADATA_PREFIX, elem_id)) + f.write(str(debug_info.element) + '\n') + dump_stack('Element creation', debug_info.init_stack, f) + for attrib_name, stack in debug_info.attribute_stacks.items(): + attrib_value = ( + debug_info.element.get_attribute_xml_string(attrib_name)) + if stack[-1] == debug_info.init_stack[-1]: + if attrib_value is not None: + f.write('Attribute {}="{}"\n'.format(attrib_name, attrib_value)) + f.write(' was set when the element was created\n') + f.write(section_separator) + else: + if attrib_value is not None: + dump_stack('Attribute {}="{}"'.format(attrib_name, attrib_value), + stack, f) + else: + dump_stack( + 'Attribute {} was CLEARED'.format(attrib_name), stack, f) + + def _generate_debug_message_from_xml_line(self, xml_line): + """Generates a debug message by parsing the metadata on an XML line.""" + metadata_match = _DEBUG_METADATA_SEARCH_PATTERN.search(xml_line) + if metadata_match: + elem_id = int(metadata_match.group(1)) + return self._generate_debug_message_from_element_id(elem_id) + else: + return '' + + def _generate_debug_message_from_element_id(self, elem_id): + """Generates a debug message for the specified Element.""" + out = [] + debug_info = self._debug_info_for_element_ids[elem_id] + + out.append('Debug summary for element:') + if not get_full_dump_dir(): + out.append( + ' * Full debug info can be dumped to disk by setting the ' + 'flag --pymjcf_debug_full_dump_dir=path/to/dump>') + out.append(' * Element object was created by `{}` at {}:{}' + .format(debug_info.init_stack[-1].function_name, + debug_info.init_stack[-1].filename, + debug_info.init_stack[-1].line_number)) + + for attrib_name, stack in debug_info.attribute_stacks.items(): + attrib_value = debug_info.element.get_attribute_xml_string(attrib_name) + if stack[-1] == debug_info.init_stack[-1]: + if attrib_value is not None: + out.append(' * {}="{}" was set when the element was created' + .format(attrib_name, attrib_value)) + else: + if attrib_value is not None: + out.append(' * {}="{}" was set by `{}` at `{}:{}`' + .format(attrib_name, attrib_value, + stack[-1].function_name, stack[-1].filename, + stack[-1].line_number)) + else: + out.append(' * {} was CLEARED by `{}` at {}:{}' + .format(attrib_name, stack[-1].function_name, + stack[-1].filename, stack[-1].line_number)) + + return '\n'.join(out) diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/debugging_test.py b/rofunc/utils/robolab/formatter/mjcf_parser/debugging_test.py new file mode 100644 index 000000000..4f3f9731b --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/debugging_test.py @@ -0,0 +1,177 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Tests for `mjcf.debugging`.""" + +import contextlib +import os +import re +import shutil +import sys + +from absl.testing import absltest +from rofunc.utils.robolab.formatter import mjcf_parser as mjcf + +from rofunc.utils.robolab.formatter.mjcf_parser import code_for_debugging_test as test_code +from rofunc.utils.robolab.formatter.mjcf_parser import debugging + +ORIGINAL_DEBUG_MODE = debugging.debug_mode() + + +class DebuggingTest(absltest.TestCase): + + def tearDown(self): + super().tearDown() + if ORIGINAL_DEBUG_MODE: + debugging.enable_debug_mode() + else: + debugging.disable_debug_mode() + + def setup_debug_mode(self, debug_mode_enabled, full_dump_enabled=False): + if debug_mode_enabled: + debugging.enable_debug_mode() + else: + debugging.disable_debug_mode() + if full_dump_enabled: + base_dir = absltest.get_default_test_tmpdir() + self.dump_dir = os.path.join(base_dir, 'mjcf_debugging_test') + shutil.rmtree(self.dump_dir, ignore_errors=True) + os.mkdir(self.dump_dir) + else: + self.dump_dir = '' + debugging.set_full_dump_dir(self.dump_dir) + + def assertStackFromTestCode(self, stack, function_name, line_ref): + self.assertEqual(stack[-1].function_name, function_name) + self.assertStartsWith(test_code.__file__, stack[-1].filename) + line_info = test_code.LINE_REF['.'.join([function_name, line_ref])] + self.assertEqual(stack[-1].line_number, line_info.line_number) + self.assertEqual(stack[-1].text, line_info.text) + + @contextlib.contextmanager + def assertRaisesTestCodeRef(self, line_ref): + filename, _ = os.path.splitext(test_code.__file__) + expected_message = ( + filename + '.py:' + str(test_code.LINE_REF[line_ref].line_number)) + print(expected_message) + with self.assertRaisesRegex(ValueError, expected_message): + yield + + def test_get_current_stack_trace(self): + self.setup_debug_mode(debug_mode_enabled=True) + stack_trace = debugging.get_current_stack_trace() + self.assertStartsWith( + sys.modules[__name__].__file__, stack_trace[-1].filename) + self.assertEqual(stack_trace[-1].function_name, + 'test_get_current_stack_trace') + self.assertEqual(stack_trace[-1].text, + 'stack_trace = debugging.get_current_stack_trace()') + + def test_disable_debug_mode(self): + self.setup_debug_mode(debug_mode_enabled=False) + mjcf_model = test_code.make_valid_model() + test_code.break_valid_model(mjcf_model) + self.assertFalse(mjcf_model.get_init_stack()) + + my_actuator = mjcf_model.find('actuator', 'my_actuator') + my_actuator_attrib_stacks = ( + my_actuator.get_last_modified_stacks_for_all_attributes()) + for stack in my_actuator_attrib_stacks.values(): + self.assertFalse(stack) + + def test_element_and_attribute_stacks(self): + self.setup_debug_mode(debug_mode_enabled=True) + mjcf_model = test_code.make_valid_model() + test_code.break_valid_model(mjcf_model) + + self.assertStackFromTestCode(mjcf_model.get_init_stack(), + 'make_valid_model', 'mjcf_model') + + my_actuator = mjcf_model.find('actuator', 'my_actuator') + self.assertStackFromTestCode(my_actuator.get_init_stack(), + 'make_valid_model', 'my_actuator') + + my_actuator_attrib_stacks = ( + my_actuator.get_last_modified_stacks_for_all_attributes()) + # `name` attribute was assigned at the same time as the element was created. + self.assertEqual(my_actuator_attrib_stacks['name'], + my_actuator.get_init_stack()) + # `joint` attribute was modified later on. + self.assertStackFromTestCode(my_actuator_attrib_stacks['joint'], + 'break_valid_model', 'my_actuator.joint') + + def test_valid_physics(self): + self.setup_debug_mode(debug_mode_enabled=True) + mjcf_model = test_code.make_valid_model() + mjcf.Physics.from_mjcf_model(mjcf_model) # Should not raise + + def test_physics_error_message_outside_of_debug_mode(self): + self.setup_debug_mode(debug_mode_enabled=False) + mjcf_model = test_code.make_broken_model() + # Make sure that we advertise debug mode if it's currently disabled. + with self.assertRaisesRegex(ValueError, '--mjcf_parser_debug'): + mjcf.Physics.from_mjcf_model(mjcf_model) + + def test_physics_error_message_in_debug_mode(self): + self.setup_debug_mode(debug_mode_enabled=True) + mjcf_model_1 = test_code.make_broken_model() + with self.assertRaisesTestCodeRef('make_broken_model.my_actuator'): + mjcf.Physics.from_mjcf_model(mjcf_model_1) + mjcf_model_2 = test_code.make_valid_model() + physics = mjcf.Physics.from_mjcf_model(mjcf_model_2) # Should not raise. + test_code.break_valid_model(mjcf_model_2) + with self.assertRaisesTestCodeRef('break_valid_model.my_actuator.joint'): + physics.reload_from_mjcf_model(mjcf_model_2) + + def test_full_debug_dump(self): + self.setup_debug_mode(debug_mode_enabled=True, full_dump_enabled=False) + mjcf_model = test_code.make_valid_model() + test_code.break_valid_model(mjcf_model) + # Make sure that we advertise full dump mode if it's currently disabled. + with self.assertRaisesRegex(ValueError, '--pymjcf_debug_full_dump_dir'): + mjcf.Physics.from_mjcf_model(mjcf_model) + self.setup_debug_mode(debug_mode_enabled=True, full_dump_enabled=True) + with self.assertRaises(ValueError): + mjcf.Physics.from_mjcf_model(mjcf_model) + + with open(os.path.join(self.dump_dir, 'model.xml')) as f: + dumped_xml = f.read() + dumped_xml = [line.strip() for line in dumped_xml.strip().split('\n')] + + xml_line_pattern = re.compile(r'^(.*)$') + uninstrumented_pattern = re.compile(r'({})'.format( + '|'.join([ + r'', + r'', + r'', + r'' + ]))) + + for xml_line in dumped_xml: + print(xml_line) + xml_line_match = xml_line_pattern.match(xml_line) + if not xml_line_match: + # Only uninstrumented lines are allowed to have no metadata. + self.assertIsNotNone(uninstrumented_pattern.match(xml_line)) + else: + xml_element = xml_line_match.group(1) + debug_id = int(xml_line_match.group(2)) + with open(os.path.join(self.dump_dir, str(debug_id) + '.dump')) as f: + element_dump = f.read() + self.assertIn(xml_element, element_dump) + + +if __name__ == '__main__': + absltest.main() diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/element.py b/rofunc/utils/robolab/formatter/mjcf_parser/element.py new file mode 100644 index 000000000..477d914b9 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/element.py @@ -0,0 +1,1414 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Classes to represent MJCF elements in the object model.""" + +import collections +import copy +import os +import sys + +import numpy as np +from lxml import etree + +from rofunc.utils.robolab.formatter.mjcf_parser import attribute as attribute_types +from rofunc.utils.robolab.formatter.mjcf_parser import base +from rofunc.utils.robolab.formatter.mjcf_parser import constants +from rofunc.utils.robolab.formatter.mjcf_parser import copier +from rofunc.utils.robolab.formatter.mjcf_parser import debugging +from rofunc.utils.robolab.formatter.mjcf_parser import namescope +from rofunc.utils.robolab.formatter.mjcf_parser import schema +from rofunc.utils.robolab.formatter.mjcf_parser import util + +_raw_property = property # pylint: disable=invalid-name + +_UNITS = ('K', 'M', 'G', 'T', 'P', 'E') + + +def _to_bytes(value_str): + """Converts a `str` value representing a size in bytes to `int`. + + Args: + value_str: `str` value to be converted. + + Returns: + `int` corresponding size in bytes. + + Raises: + ValueError: if the `str` value passed has an unsupported unit. + """ + if value_str.isdigit(): + value_int = int(value_str) + else: + value_int = int(value_str[:-1]) + unit = value_str[-1].upper() + if unit not in _UNITS: + raise ValueError( + f'unit of `size.memory` should be one of [{", ".join(_UNITS)}], got' + f' {unit}') + power = 10 * (_UNITS.index(unit) + 1) + value_int *= 2 ** power + return value_int + + +def _max_bytes(first, second): + return str(max(_to_bytes(first), _to_bytes(second))) + + +_CONFLICT_BEHAVIOR_FUNC = {'min': min, 'max': max, 'max_bytes': _max_bytes} + + +def property(method): # pylint: disable=redefined-builtin + """Modifies `@property` to keep track of any `AttributeError` raised. + + Our `Element` implementations overrides the `__getattr__` method. This does + not interact well with `@property`: if a `property`'s code is buggy so as to + raise an `AttributeError`, then Python would silently discard it and redirect + to our `__getattr__` instead, leading to an uninformative stack trace. This + makes it very difficult to debug issues that involve properties. + + To remedy this, we modify `@property` within this module to store any + `AttributeError` raised within the respective `Element` object. Then, in our + `__getattr__` logic, we could re-raise it to preserve the original stack + trace. + + The reason that this is not implemented as a different decorator is that we + could accidentally use @property on a new method. This would work fine until + someone triggers a subtle bug. This is when a proper trace would be most + useful, but we would still end up with a strange undebuggable stack trace + anyway. + + Note that at the end of this module, we have a `del property` to prevent this + override from being broadcasted externally. + + Args: + method: The method that is being decorated. + + Returns: + A `property` corresponding to the decorated method. + """ + + def _mjcf_property(self): + try: + return method(self) + except: + _, err, tb = sys.exc_info() + err_with_next_tb = err.with_traceback(tb.tb_next) + if isinstance(err, AttributeError): + self._last_attribute_error = err_with_next_tb # pylint: disable=protected-access + raise err_with_next_tb # pylint: disable=raise-missing-from + + return _raw_property(_mjcf_property) + + +def _make_element(spec, parent, attributes=None): + """Helper function to generate the right kind of Element given a spec.""" + if (spec.name == constants.WORLDBODY + or (spec.name == constants.SITE + and (parent.tag == constants.BODY + or parent.tag == constants.WORLDBODY))): + return _AttachableElement(spec, parent, attributes) + elif isinstance(parent, _AttachmentFrame): + return _AttachmentFrameChild(spec, parent, attributes) + elif spec.name == constants.DEFAULT: + return _DefaultElement(spec, parent, attributes) + elif spec.name == constants.ACTUATOR: + return _ActuatorElement(spec, parent, attributes) + else: + return _ElementImpl(spec, parent, attributes) + + +_DEFAULT_NAME_FROM_FILENAME = frozenset(['mesh', 'hfield', 'texture']) + + +class _ElementImpl(base.Element): + """Actual implementation of a generic MJCF element object.""" + __slots__ = ['__weakref__', '_spec', '_parent', '_attributes', '_children', + '_own_attributes', '_attachments', '_is_removed', '_init_stack', + '_is_worldbody', '_cached_namescope', '_cached_root', + '_cached_full_identifier', '_cached_revision', + '_last_attribute_error'] + + def __init__(self, spec, parent, attributes=None): + attributes = attributes or {} + + # For certain `asset` elements the `name` attribute can be omitted, in which + # case the name will be the filename without the leading path and extension. + # See http://www.mujoco.org/book/XMLreference.html#asset. + if ('name' not in attributes + and 'file' in attributes + and spec.name in _DEFAULT_NAME_FROM_FILENAME): + _, filename = os.path.split(attributes['file']) + basename, _ = os.path.splitext(filename) + attributes['name'] = basename + + self._spec = spec + self._parent = parent + self._attributes = collections.OrderedDict() + self._own_attributes = None + self._children = [] + self._attachments = collections.OrderedDict() + self._is_removed = False + self._is_worldbody = (self.tag == 'worldbody') + + if self._parent: + self._cached_namescope = self._parent.namescope + self._cached_root = self._parent.root + self._cached_full_identifier = '' + self._cached_revision = -1 + + self._last_attribute_error = None + + if debugging.debug_mode(): + self._init_stack = debugging.get_current_stack_trace() + + with debugging.freeze_current_stack_trace(): + for child_spec in self._spec.children.values(): + if not (child_spec.repeated or child_spec.on_demand): + self._children.append(_make_element(spec=child_spec, parent=self)) + + if constants.DCLASS in attributes: + attributes[constants.CLASS] = attributes[constants.DCLASS] + del attributes[constants.DCLASS] + + for attribute_name in attributes.keys(): + self._check_valid_attribute(attribute_name) + + for attribute_spec in self._spec.attributes.values(): + value = None + # Some Reference attributes refer to a namespace that is specified + # via another attribute. We therefore have to set things up for + # the additional indirection. + if attribute_spec.type is attribute_types.Reference: + reference_namespace = ( + attribute_spec.other_kwargs['reference_namespace']) + if reference_namespace.startswith( + constants.INDIRECT_REFERENCE_NAMESPACE_PREFIX): + attribute_spec = copy.deepcopy(attribute_spec) + namespace_attrib_name = reference_namespace[ + len(constants.INDIRECT_REFERENCE_NAMESPACE_PREFIX):] + attribute_spec.other_kwargs['reference_namespace'] = ( + self._attributes[namespace_attrib_name]) + if attribute_spec.name in attributes: + value = attributes[attribute_spec.name] + try: + self._attributes[attribute_spec.name] = attribute_spec.type( + name=attribute_spec.name, + required=attribute_spec.required, + conflict_allowed=attribute_spec.conflict_allowed, + conflict_behavior=attribute_spec.conflict_behavior, + parent=self, value=value, **attribute_spec.other_kwargs) + except: + # On failure, clear attributes already created + for attribute_obj in self._attributes.values(): + attribute_obj._force_clear() # pylint: disable=protected-access + # Then raise a meaningful error + err_type, err, tb = sys.exc_info() + raise err_type( # pylint: disable=raise-missing-from + f'during initialization of attribute {attribute_spec.name!r} of ' + f'element <{self._spec.name}>: {err}').with_traceback(tb) + + def get_init_stack(self): + """Gets the stack trace where this element was first initialized.""" + if debugging.debug_mode(): + return self._init_stack + + def get_last_modified_stacks_for_all_attributes(self): + """Gets a dict of stack traces where each attribute was last modified.""" + return collections.OrderedDict( + [(name, self._attributes[name].last_modified_stack) + for name in self._spec.attributes]) + + def is_same_as(self, other): + """Checks whether another element is semantically equivalent to this one. + + Two elements are considered equivalent if they have the same + specification (i.e. same tag appearing in the same context), the same + attribute values, and all of their children are equivalent. The ordering + of non-repeated children is not important for this comparison, while + the ordering of repeated children are important only amongst the same + type* of children. In other words, for two bodies to be considered + equivalent, their child sites must appear in the same order, and their + child geoms must appear in the same order, but permutations between sites + and geoms are disregarded. (The only exception is in tendon definition, + where strict ordering of all children is necessary for equivalence.) + + *Note that the notion of "same type" in this function is very loose: + for example different actuator element subtypes are treated as separate + types when children ordering is considered. Therefore, two + elements might be considered equivalent even though they result in different + orderings of `mjData.ctrl` when compiled. As it stands, this function + is designed primarily as a testing aid and should not be used to guarantee + that models are actually identical. + + Args: + other: An `mjcf.Element` + + Returns: + `True` if `other` element is semantically equivalent to this one. + """ + if other is None or other.spec != self._spec: + return False + + for attribute_name in self._spec.attributes.keys(): + attribute = self._attributes[attribute_name] + other_attribute = getattr(other, attribute_name) + if isinstance(attribute.value, base.Element): + if attribute.value.full_identifier != other_attribute.full_identifier: + return False + elif not np.all(attribute.value == other_attribute): + return False + + if (self._parent and + self._parent.tag == constants.TENDON and + self._parent.parent == self.root): + return self._tendon_has_same_children_as(other) + else: + return self._has_same_children_as(other) + + def _has_same_children_as(self, other): + """Helper function to check whether another element has the same children. + + See docstring for `is_same_as` for explanation about the treatment of + children ordering. + + Args: + other: An `mjcf.Element` + + Returns: + A boolean + """ + for child_name, child_spec in self._spec.children.items(): + child = self.get_children(child_name) + other_child = getattr(other, child_name) + if not child_spec.repeated: + if ((child is None and other_child is not None) or + (child is not None and not child.is_same_as(other_child))): + return False + else: + if len(child) != len(other_child): + return False + else: + for grandchild, other_grandchild in zip(child, other_child): + if not grandchild.is_same_as(other_grandchild): + return False + return True + + def _tendon_has_same_children_as(self, other): + return all(child.is_same_as(other_child) + for child, other_child + in zip(self.all_children(), other.all_children())) + + def _alias_attributes_dict(self, other): + if self._own_attributes is None: + self._own_attributes = self._attributes + self._attributes = other + + def _restore_attributes_dict(self): + if self._own_attributes is not None: + for attribute_name, attribute in self._attributes.items(): + self._own_attributes[attribute_name].value = attribute.value + self._attributes = self._own_attributes + self._own_attributes = None + + @property + def tag(self): + return self._spec.name + + @property + def spec(self): + return self._spec + + @property + def parent(self): + return self._parent + + @property + def namescope(self): + return self._cached_namescope + + @property + def root(self): + return self._cached_root + + def prefixed_identifier(self, prefix_root): + if not self._spec.identifier and not self._is_worldbody: + return None + elif self._is_worldbody: + prefix = self.namescope.full_prefix(prefix_root=prefix_root) + return prefix or 'world' + else: + full_identifier = ( + self._attributes[self._spec.identifier].to_xml_string( + prefix_root=prefix_root)) + if full_identifier: + return full_identifier + else: + prefix = self.namescope.full_prefix(prefix_root=prefix_root) + prefix = prefix or constants.PREFIX_SEPARATOR + return prefix + self._default_identifier + + @property + def full_identifier(self): + """Fully-qualified identifier used for this element in the generated XML.""" + if self.namescope.revision > self._cached_revision: + self._cached_full_identifier = self.prefixed_identifier( + prefix_root=self.namescope.root) + self._cached_revision = self.namescope.revision + return self._cached_full_identifier + + @property + def _default_identifier(self): + """The default identifier used if this element is not named by the user.""" + if not self._spec.identifier: + return None + else: + siblings = self.root.find_all(self._spec.namespace, + exclude_attachments=True) + return '{separator}unnamed_{namespace}_{index}'.format( + separator=constants.PREFIX_SEPARATOR, + namespace=self._spec.namespace, + index=siblings.index(self)) + + def __dir__(self): + out_dir = set() + classes = (type(self),) + while classes: + super_classes = set() + for klass in classes: + out_dir.update(klass.__dict__) + super_classes.update(klass.__bases__) + classes = super_classes + out_dir.update(self._spec.children) + out_dir.update(self._spec.attributes) + if constants.CLASS in out_dir: + out_dir.remove(constants.CLASS) + out_dir.add(constants.DCLASS) + return sorted(out_dir) + + def find(self, namespace, identifier): + """Finds an element with a particular identifier. + + This function allows the direct access to an arbitrarily deeply nested + child element by name, without the need to manually traverse through the + object tree. The `namespace` argument specifies the kind of element to + find. In most cases, this corresponds to the element's XML tag name. + However, if an element has multiple specialized tags, then the namespace + corresponds to the tag name of the most general element of that kind. + For example, `namespace='joint'` would search for `` and + ``, while `namespace='actuator'` would search for ``, + ``, ``, ``, and ``. + + Args: + namespace: A string specifying the namespace being searched. See the + docstring above for explanation. + identifier: The identifier string of the desired element. + + Returns: + An `mjcf.Element` object, or `None` if an element with the specified + identifier is not found. + + Raises: + ValueError: if either `namespace` or `identifier` is not a string, or if + `namespace` is not a valid namespace. + """ + if not isinstance(namespace, str): + raise ValueError( + '`namespace` should be a string: got {!r}'.format(namespace)) + if not isinstance(identifier, str): + raise ValueError( + '`identifier` should be a string: got {!r}'.format(identifier)) + if namespace not in schema.FINDABLE_NAMESPACES: + raise ValueError('{!r} is not a valid namespace. Available: {}.'.format( + namespace, schema.FINDABLE_NAMESPACES)) + if constants.PREFIX_SEPARATOR in identifier: + scope_name = identifier.split(constants.PREFIX_SEPARATOR)[0] + try: + attachment = self.namescope.get('attached_model', scope_name) + found_element = attachment.find( + namespace, identifier[(len(scope_name) + 1):]) + except (KeyError, ValueError): + found_element = None + else: + try: + found_element = self.namescope.get(namespace, identifier) + except KeyError: + found_element = None + if found_element and self._parent: + next_parent = found_element.parent + while next_parent and next_parent != self: + next_parent = next_parent.parent + if not next_parent: + found_element = None + return found_element + + def find_all(self, namespace, + immediate_children_only=False, exclude_attachments=False): + """Finds all elements of a particular kind. + + The `namespace` argument specifies the kind of element to + find. In most cases, this corresponds to the element's XML tag name. + However, if an element has multiple specialized tags, then the namespace + corresponds to the tag name of the most general element of that kind. + For example, `namespace='joint'` would search for `` and + ``, while `namespace='actuator'` would search for ``, + ``, ``, ``, and ``. + + Args: + namespace: A string specifying the namespace being searched. See the + docstring above for explanation. + immediate_children_only: (optional) A boolean, if `True` then only + the immediate children of this element are returned. + exclude_attachments: (optional) A boolean, if `True` then elements + belonging to attached models are excluded. + + Returns: + A list of `mjcf.Element`. + + Raises: + ValueError: if `namespace` is not a valid namespace. + """ + if namespace not in schema.FINDABLE_NAMESPACES: + raise ValueError('{!r} is not a valid namespace. Available: {}'.format( + namespace, schema.FINDABLE_NAMESPACES)) + out = [] + children = self._children if exclude_attachments else self.all_children() + for child in children: + if (namespace == child.spec.namespace or + # Direct children of attachment frames have custom namespaces of the + # form "joint@attachment_frame_". + child.spec.namespace and child.spec.namespace.startswith( + namespace + constants.NAMESPACE_SEPARATOR) or + # Attachment frames are considered part of the "body" namespace. + namespace == constants.BODY and isinstance(child, _AttachmentFrame)): + out.append(child) + if not immediate_children_only: + out.extend(child.find_all(namespace, + exclude_attachments=exclude_attachments)) + return out + + def enter_scope(self, scope_identifier): + """Finds the root element of the given scope and returns it. + + This function allows the access to a nested scope that is a child of this + element. The `scope_identifier` argument specifies the path to the child + scope element. + + Args: + scope_identifier: The path of the desired scope element. + + Returns: + An `mjcf.Element` object, or `None` if a scope element with the + specified path is not found. + """ + if constants.PREFIX_SEPARATOR in scope_identifier: + scope_name = scope_identifier.split(constants.PREFIX_SEPARATOR)[0] + try: + attachment = self.namescope.get('attached_model', scope_name) + except KeyError: + return None + + scope_suffix = scope_identifier[(len(scope_name) + 1):] + if scope_suffix: + return attachment.enter_scope(scope_suffix) + else: + return attachment + else: + try: + return self.namescope.get('attached_model', scope_identifier) + except KeyError: + return None + + def _check_valid_attribute(self, attribute_name): + if attribute_name not in self._spec.attributes: + raise AttributeError( + '{!r} is not a valid attribute for <{}>'.format( + attribute_name, self._spec.name)) + + def _get_attribute(self, attribute_name): + self._check_valid_attribute(attribute_name) + return self._attributes[attribute_name].value + + def get_attribute_xml_string(self, + attribute_name, + prefix_root=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + self._check_valid_attribute(attribute_name) + return self._attributes[attribute_name].to_xml_string( + prefix_root, precision=precision, zero_threshold=zero_threshold) + + def get_attributes(self): + fix_attribute_name = ( + lambda name: constants.DCLASS if name == constants.CLASS else name) + return collections.OrderedDict( + [(fix_attribute_name(name), self._get_attribute(name)) + for name in self._spec.attributes.keys() + if self._get_attribute(name) is not None]) + + def _set_attribute(self, attribute_name, value): + self._check_valid_attribute(attribute_name) + self._attributes[attribute_name].value = value + self.namescope.increment_revision() + + def set_attributes(self, **kwargs): + if constants.DCLASS in kwargs: + kwargs[constants.CLASS] = kwargs[constants.DCLASS] + del kwargs[constants.DCLASS] + old_values = [] + with debugging.freeze_current_stack_trace(): + for attribute_name, new_value in kwargs.items(): + old_value = self._get_attribute(attribute_name) + try: + self._set_attribute(attribute_name, new_value) + old_values.append((attribute_name, old_value)) + except: + # On failure, restore old attribute values for those already set. + for name, old_value in old_values: + self._set_attribute(name, old_value) + # Then raise a meaningful error. + err_type, err, tb = sys.exc_info() + raise err_type( # pylint: disable=raise-missing-from + f'during assignment to attribute {attribute_name!r} of ' + f'element <{self._spec.name}>: {err}').with_traceback(tb) + + def _remove_attribute(self, attribute_name): + self._check_valid_attribute(attribute_name) + self._attributes[attribute_name].clear() + self.namescope.increment_revision() + + def _check_valid_child(self, element_name): + try: + return self._spec.children[element_name] + except KeyError: + raise AttributeError( # pylint: disable=raise-missing-from + '<{}> is not a valid child of <{}>' + .format(element_name, self._spec.name)) + + def get_children(self, element_name): + child_spec = self._check_valid_child(element_name) + if child_spec.repeated: + return _ElementListView(spec=child_spec, parent=self) + else: + for child in self._children: + if child.tag == element_name: + return child + if child_spec.on_demand: + return None + else: + raise RuntimeError( + 'Cannot find the non-repeated child <{}> of <{}>. ' + 'This should never happen, as we pre-create these in __init__. ' + 'Please file an bug report. Thank you.' + .format(element_name, self._spec.name)) + + def add(self, element_name, **kwargs): + """Add a new child element to this element. + + Args: + element_name: The tag of the element to add. + **kwargs: Attributes of the new element being created. + + Raises: + ValueError: If the 'element_name' is not a valid child, or if an invalid + attribute is specified in `kwargs`. + + Returns: + An `mjcf.Element` corresponding to the newly created child element. + """ + return self.insert(element_name, position=None, **kwargs) + + def insert(self, element_name, position, **kwargs): + """Add a new child element to this element. + + Args: + element_name: The tag of the element to add. + position: Where to insert the new element. + **kwargs: Attributes of the new element being created. + + Raises: + ValueError: If the 'element_name' is not a valid child, or if an invalid + attribute is specified in `kwargs`. + + Returns: + An `mjcf.Element` corresponding to the newly created child element. + """ + child_spec = self._check_valid_child(element_name) + if child_spec.on_demand: + need_new_on_demand = self.get_children(element_name) is None + else: + need_new_on_demand = False + if not (child_spec.repeated or need_new_on_demand): + raise ValueError('A <{}> child already exists, please access it directly.' + .format(element_name)) + new_element = _make_element(child_spec, self, attributes=kwargs) + if position is not None: + self._children.insert(position, new_element) + else: + self._children.append(new_element) + self.namescope.increment_revision() + return new_element + + def __getattr__(self, name): + if self._last_attribute_error: + # This means that we got here through a @property raising AttributeError. + # We therefore just re-raise the last AttributeError back to the user. + # Note that self._last_attribute_error was set by our specially + # instrumented @property decorator. + exc = self._last_attribute_error + self._last_attribute_error = None + raise exc # pylint: disable=raising-bad-type + elif name in self._spec.children: + return self.get_children(name) + elif name in self._spec.attributes: + return self._get_attribute(name) + elif name == constants.DCLASS and constants.CLASS in self._spec.attributes: + return self._get_attribute(constants.CLASS) + else: + raise AttributeError('object has no attribute: {}'.format(name)) + + def __setattr__(self, name, value): + # If this name corresponds to a descriptor for a slotted attribute or + # settable property then try to invoke the descriptor to set the attribute + # and return if successful. + klass_attr = getattr(type(self), name, None) + if klass_attr is not None: + try: + return klass_attr.__set__(self, value) + except AttributeError: + pass + # If we did not find a settable descriptor then we look in the attribute + # spec to see if there is a MuJoCo attribute matching this name. + attribute_name = name if name != constants.DCLASS else constants.CLASS + if attribute_name in self._spec.attributes: + self._set_attribute(attribute_name, value) + else: + raise AttributeError('can\'t set attribute: {}'.format(name)) + + def __delattr__(self, name): + if name in self._spec.children: + if self._spec.children[name].repeated: + raise AttributeError( + '`{0}` is a collection of child elements, ' + 'which cannot be deleted. Did you mean to call `{0}.clear()`?' + .format(name)) + else: + return self.get_children(name).remove() + elif name in self._spec.attributes: + return self._remove_attribute(name) + else: + raise AttributeError('object has no attribute: {}'.format(name)) + + def _check_attachments_on_remove(self, affect_attachments): + if not affect_attachments and self._attachments: + raise ValueError( + 'please use remove(affect_attachments=True) as this will affect some ' + 'attributes and/or children belonging to an attached model') + for child in self._children: + child._check_attachments_on_remove(affect_attachments) # pylint: disable=protected-access + + def remove(self, affect_attachments=False): + """Removes this element from the model.""" + self._check_attachments_on_remove(affect_attachments) + if affect_attachments: + for attachment in self._attachments.values(): + attachment.remove(affect_attachments=True) + for child in list(self._children): + child.remove(affect_attachments) + if self._spec.repeated or self._spec.on_demand: + self._parent._children.remove(self) # pylint: disable=protected-access + for attribute in self._attributes.values(): + attribute._force_clear() # pylint: disable=protected-access + self._parent = None + self._is_removed = True + else: + for attribute in self._attributes.values(): + attribute._force_clear() # pylint: disable=protected-access + self.namescope.increment_revision() + + @property + def is_removed(self): + return self._is_removed + + def all_children(self): + all_children = [child for child in self._children] + for attachment in self._attachments.values(): + all_children += [child for child in attachment.all_children() + if child.spec.repeated] + return all_children + + def to_xml(self, prefix_root=None, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + """Generates an etree._Element corresponding to this MJCF element. + + Args: + prefix_root: (optional) A `NameScope` object to be treated as root + for the purpose of calculating the prefix. + If `None` then no prefix is included. + debug_context: (optional) A `debugging.DebugContext` object to which + the debugging information associated with the generated XML is written. + This is intended for internal use within PyMJCF; users should never need + manually pass this argument. + precision: (optional) Number of digits to output for floating point + quantities. + zero_threshold: (optional) When outputting XML, floating point quantities + whose absolute value falls below this threshold will be treated as zero. + + Returns: + An etree._Element object. + """ + prefix_root = prefix_root or self.namescope + xml_element = etree.Element(self._spec.name) + self._attributes_to_xml(xml_element, prefix_root, debug_context, + precision=precision, zero_threshold=zero_threshold) + self._children_to_xml(xml_element, prefix_root, debug_context, + precision=precision, zero_threshold=zero_threshold) + return xml_element + + def _attributes_to_xml(self, xml_element, prefix_root, debug_context=None, + *, precision, zero_threshold): + del debug_context # Unused. + for attribute_name, attribute in self._attributes.items(): + attribute_value = attribute.to_xml_string(prefix_root, + precision=precision, + zero_threshold=zero_threshold) + if attribute_name == self._spec.identifier and attribute_value is None: + xml_element.set(attribute_name, self.full_identifier) + elif attribute_value is None: + continue + else: + xml_element.set(attribute_name, attribute_value) + + def _children_to_xml(self, xml_element, prefix_root, debug_context=None, + *, precision, zero_threshold): + for child in self.all_children(): + child_xml = child.to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold) + if (child_xml.attrib or len(child_xml) # pylint: disable=g-explicit-length-test + or child.spec.repeated or child.spec.on_demand): + xml_element.append(child_xml) + if debugging.debug_mode() and debug_context: + debug_comment = debug_context.register_element_for_debugging(child) + xml_element.append(debug_comment) + if len(child_xml) > 0: # pylint: disable=g-explicit-length-test + child_xml.insert(0, copy.deepcopy(debug_comment)) + + def to_xml_string(self, prefix_root=None, + self_only=False, pretty_print=True, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + """Generates an XML string corresponding to this MJCF element. + + Args: + prefix_root: (optional) A `NameScope` object to be treated as root + for the purpose of calculating the prefix. + If `None` then no prefix is included. + self_only: (optional) A boolean, whether to generate an XML corresponding + only to this element without any children. + pretty_print: (optional) A boolean, whether to the XML string should be + properly indented. + debug_context: (optional) A `debugging.DebugContext` object to which + the debugging information associated with the generated XML is written. + This is intended for internal use within PyMJCF; users should never need + manually pass this argument. + precision: (optional) Number of digits to output for floating point + quantities. + zero_threshold: (optional) When outputting XML, floating point quantities + whose absolute value falls below this threshold will be treated as zero. + + Returns: + A string. + """ + xml_element = self.to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold) + if self_only and len(xml_element) > 0: # pylint: disable=g-explicit-length-test + etree.strip_elements(xml_element, '*') + xml_element.text = '...' + if (self_only and self._spec.identifier and + not self._attributes[self._spec.identifier].to_xml_string( + prefix_root, precision=precision, zero_threshold=zero_threshold)): + del xml_element.attrib[self._spec.identifier] + xml_string = util.to_native_string( + etree.tostring(xml_element, pretty_print=pretty_print)) + if pretty_print and debug_context: + return debug_context.commit_xml_string(xml_string) + else: + return xml_string + + def __str__(self): + return self.to_xml_string(self_only=True, pretty_print=False) + + def __repr__(self): + return 'MJCF Element: ' + str(self) + + def _check_valid_attachment(self, other): + self_spec = self._spec + if self_spec.name == constants.WORLDBODY: + self_spec = self._spec.children[constants.BODY] + + other_spec = other.spec + if other_spec.name == constants.WORLDBODY: + other_spec = other_spec.children[constants.BODY] + + if other_spec != self_spec: + raise ValueError( + 'The attachment must have the same spec as this element.') + + def _attach(self, other, exclude_worldbody=False, dry_run=False): + """Attaches another element of the same spec to this element. + + All children of `other` will be treated as children of this element. + All XML attributes which are defined in `other` but not defined in this + element will be copied over, and any conflicting XML attribute value causes + an error. After the attachment, any XML attribute modified in this element + will also affect `other` and vice versa. + + Children of this element which are not a repeated elements will also be + attached by the corresponding children of `other`. + + Args: + other: Another Element with the same spec. + exclude_worldbody: (optional) A boolean. If `True`, then don't do anything + if `other` is a worldbody. + dry_run: (optional) A boolean, if `True` only verify that the operation + is valid without actually committing any change. + + Raises: + ValueError: If `other` has a different spec, or if there are conflicting + XML attribute values. + """ + self._check_valid_attachment(other) + if exclude_worldbody and other.tag == constants.WORLDBODY: + return + if dry_run: + self._check_conflicting_attributes(other, copying=False) + else: + self._attachments[other.namescope] = other + self._sync_attributes(other, copying=False) + self._attach_children(other, exclude_worldbody, dry_run) + if other.tag != constants.WORLDBODY and not dry_run: + other._alias_attributes_dict(self._attributes) # pylint: disable=protected-access + + def _detach(self, other_namescope): + """Detaches a model with the specified namescope.""" + attached_element = self._attachments.get(other_namescope) + if attached_element: + attached_element._restore_attributes_dict() # pylint: disable=protected-access + del self._attachments[other_namescope] + for child in self._children: + child._detach(other_namescope) # pylint: disable=protected-access + + def _check_conflicting_attributes(self, other, copying): + for attribute_name, other_attribute in other.get_attributes().items(): + if attribute_name == constants.DCLASS: + attribute_name = constants.CLASS + if ((not self._attributes[attribute_name].conflict_allowed) + and self._attributes[attribute_name].value is not None + and other_attribute is not None + and np.asarray( + self._attributes[attribute_name].value != other_attribute).any()): + raise ValueError( + 'Conflicting values for attribute `{}`: {} vs {}' + .format(attribute_name, + self._attributes[attribute_name].value, + other_attribute)) + + def _sync_attributes(self, other, copying): + self._check_conflicting_attributes(other, copying) + for attribute_name, other_attribute in other.get_attributes().items(): + if attribute_name == constants.DCLASS: + attribute_name = constants.CLASS + + self_attribute = self._attributes[attribute_name] + if other_attribute is not None: + if self_attribute.conflict_behavior in _CONFLICT_BEHAVIOR_FUNC: + if self_attribute.value is not None: + self_attribute.value = ( + _CONFLICT_BEHAVIOR_FUNC[self_attribute.conflict_behavior]( + self_attribute.value, other_attribute)) + else: + self_attribute.value = other_attribute + elif copying or not self_attribute.conflict_allowed: + self_attribute.value = other_attribute + + def _attach_children(self, other, exclude_worldbody, dry_run=False): + for other_child in other.all_children(): + if not other_child.spec.repeated: + self_child = self.get_children(other_child.spec.name) + self_child._attach(other_child, exclude_worldbody, dry_run) # pylint: disable=protected-access + + def resolve_references(self): + for attribute in self._attributes.values(): + if isinstance(attribute, attribute_types.Reference): + if attribute.value and isinstance(attribute.value, str): + referred = self.root.find( + attribute.reference_namespace, attribute.value) + if referred: + attribute.value = referred + for child in self.all_children(): + child.resolve_references() + + def _update_references(self, reference_dict): + for attribute in self._attributes.values(): + if isinstance(attribute, attribute_types.Reference): + if attribute.value in reference_dict: + attribute.value = reference_dict[attribute.value] + for child in self.all_children(): + child._update_references(reference_dict) # pylint: disable=protected-access + + +class _AttachableElement(_ElementImpl): + """Specialized object representing a or element. + + This element defines a frame to which another MJCF model can be attached. + """ + __slots__ = [] + + def attach(self, attachment): + """Attaches another MJCF model at this site. + + An empty will be created as an attachment frame. All children of + `attachment`'s will be treated as children of this frame. + Furthermore, all other elements in `attachment` are merged into the root + of the MJCF model to which this element belongs. + + Args: + attachment: An MJCF `RootElement` + + Returns: + An `mjcf.Element` corresponding to the attachment frame. A joint can be + added directly to this frame to give degrees of freedom to the attachment. + + Raises: + ValueError: If `other` is not a valid attachment to this element. + """ + if not isinstance(attachment, RootElement): + raise ValueError('Expected a mjcf.RootElement: got {}' + .format(attachment)) + if attachment.namescope.parent is not None: + raise ValueError('The model specified is already attached elsewhere') + if attachment.namescope == self.namescope: + raise ValueError('Cannot merge a model to itself') + self.root._attach(attachment, exclude_worldbody=True, dry_run=True) # pylint: disable=protected-access + + if self.namescope.has_identifier('namescope', attachment.model): + id_number = 1 + while self.namescope.has_identifier( + 'namescope', '{}_{}'.format(attachment.model, id_number)): + id_number += 1 + attachment.model = '{}_{}'.format(attachment.model, id_number) + attachment.namescope.parent = self.namescope + + if self.tag == constants.WORLDBODY: + frame_parent = self + frame_siblings = self._children + index = len(frame_siblings) + else: + frame_parent = self._parent + frame_siblings = self._parent._children # pylint: disable=protected-access + index = frame_siblings.index(self) + 1 + while (index < len(frame_siblings) + and isinstance(frame_siblings[index], _AttachmentFrame)): + index += 1 + frame = _AttachmentFrame(frame_parent, self, attachment) + frame_siblings.insert(index, frame) + self.root._attach(attachment, exclude_worldbody=True) # pylint: disable=protected-access + return frame + + +class _AttachmentFrame(_ElementImpl): + """An specialized representing a frame holding an external attachment. + """ + __slots__ = ['_site', '_attachment'] + + def __init__(self, parent, site, attachment): + if parent.tag == constants.WORLDBODY: + spec = schema.WORLD_ATTACHMENT_FRAME + else: + spec = schema.ATTACHMENT_FRAME + + spec_is_copied = False + for child_name, child_spec in spec.children.items(): + if child_spec.namespace: + if not spec_is_copied: + spec = copy.deepcopy(spec) + spec_is_copied = True + spec_as_dict = child_spec._asdict() + spec_as_dict['namespace'] = '{}{}attachment_frame_{}'.format( + child_spec.namespace, constants.NAMESPACE_SEPARATOR, id(self)) + spec.children[child_name] = type(child_spec)(**spec_as_dict) + + attributes = {} + with debugging.freeze_current_stack_trace(): + for attribute_name in spec.attributes.keys(): + if hasattr(site, attribute_name): + attributes[attribute_name] = getattr(site, attribute_name) + super().__init__(spec, parent, attributes) + self._site = site + self._attachment = attachment + self._attachments[attachment.namescope] = attachment.worldbody + self.namescope.add('attachment_frame', attachment.namescope.name, self) + self.namescope.add('attached_model', attachment.namescope.name, attachment) + + def prefixed_identifier(self, prefix_root=None): + prefix = self.namescope.full_prefix(prefix_root) + return prefix + self._attachment.namescope.name + constants.PREFIX_SEPARATOR + + def to_xml(self, prefix_root=None, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + xml_element = (super().to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold)) + xml_element.set('name', self.prefixed_identifier(prefix_root)) + return xml_element + + @property + def full_identifier(self): + return self.prefixed_identifier(self.namescope.root) + + def _detach(self, other_namescope): + super()._detach(other_namescope) + if other_namescope is self._attachment.namescope: + self.namescope.remove('attachment_frame', self._attachment.namescope.name) + self.namescope.remove('attached_model', self._attachment.namescope.name) + self.remove() + + +class _AttachmentFrameChild(_ElementImpl): + """A child element of an attachment frame. + + Right now, this is always a or a . The name of the joint + is not freely specifiable, but instead just inherits from the parent frame. + This ensures uniqueness, as attachment frame identifiers always end in '/'. + """ + __slots__ = [] + + def to_xml(self, prefix_root=None, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + xml_element = (super().to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold)) + if self.spec.namespace is not None: + if self.name: + name = (self._parent.prefixed_identifier(prefix_root) + + self.name + constants.PREFIX_SEPARATOR) + else: + name = self._parent.prefixed_identifier(prefix_root) + xml_element.set('name', name) + return xml_element + + def prefixed_identifier(self, prefix_root=None): + if self.name: + return (self._parent.prefixed_identifier(prefix_root) + + self.name + constants.PREFIX_SEPARATOR) + else: + return self._parent.prefixed_identifier(prefix_root) + + +class _DefaultElement(_ElementImpl): + """Specialized object representing a element. + + This is necessary for the proper handling of global defaults. + """ + __slots__ = [] + + def _attach(self, other, exclude_worldbody=False, dry_run=False): + self._check_valid_attachment(other) + if ((not isinstance(self._parent, RootElement)) + or (not isinstance(other.parent, RootElement))): + raise ValueError('Only global <{}> can be attached' + .format(constants.DEFAULT)) + if not dry_run: + self._attachments[other.namescope] = other + + def all_children(self): + return [child for child in self._children] + + def to_xml(self, prefix_root=None, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + prefix_root = prefix_root or self.namescope + xml_element = (super().to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold)) + if isinstance(self._parent, RootElement): + root_default = etree.Element(self._spec.name) + root_default.append(xml_element) + for attachment in self._attachments.values(): + attachment_xml = attachment.to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold) + for attachment_child_xml in attachment_xml: + root_default.append(attachment_child_xml) + xml_element = root_default + return xml_element + + +class _ActuatorElement(_ElementImpl): + """Specialized object representing an element.""" + + __slots__ = () + + def _children_to_xml(self, xml_element, prefix_root, debug_context=None, + *, + precision=constants.XML_DEFAULT_PRECISION, + zero_threshold=0): + debug_comments = {} + for child in self.all_children(): + child_xml = child.to_xml(prefix_root, debug_context, + precision=precision, + zero_threshold=zero_threshold) + if debugging.debug_mode() and debug_context: + debug_comment = debug_context.register_element_for_debugging(child) + debug_comments[child_xml] = debug_comment + if len(child_xml) > 0: # pylint: disable=g-explicit-length-test + child_xml.insert(0, copy.deepcopy(debug_comment)) + xml_element.append(child_xml) + if debugging.debug_mode() and debug_context: + xml_element.append(debug_comments[child_xml]) + + +class RootElement(_ElementImpl): + """The root `` element of an MJCF model.""" + __slots__ = ['_namescope'] + + def __init__(self, model=None, model_dir='', assets=None): + model = model or 'unnamed_model' + self._namescope = namescope.NameScope( + model, self, model_dir=model_dir, assets=assets) + super().__init__( + spec=schema.MUJOCO, parent=None, attributes={'model': model}) + + def _attach(self, other, exclude_worldbody=False, dry_run=False): + self._check_valid_attachment(other) + if not dry_run: + self._attachments[other.namescope] = other + self._attach_children(other, exclude_worldbody, dry_run) + self.namescope.increment_revision() + + @property + def namescope(self): + return self._namescope + + @property + def root(self): + return self + + @property + def model(self): + return self._namescope.name + + @model.setter + def model(self, new_name): + old_name = self._namescope.name + self._namescope.name = new_name + self._attributes['model'].value = new_name + if self.parent_model: + self.parent_model.namescope.rename('attachment_frame', old_name, new_name) + self.parent_model.namescope.rename('attached_model', old_name, new_name) + + def attach(self, other): + return self.worldbody.attach(other) + + def detach(self): + parent_model = self.parent_model + if not parent_model: + raise RuntimeError( + 'Cannot `detach` a model that is not attached to some other model.') + else: + parent_model._detach(self.namescope) # pylint: disable=protected-access + self.namescope.parent = None + + def include_copy(self, other, override_attributes=False): + other_copier = copier.Copier(other) + new_elements = other_copier.copy_into(self, override_attributes) + self._update_references(new_elements) + self.namescope.increment_revision() + + @property + def parent_model(self): + """The RootElement of the MJCF model to which this one is attached.""" + namescope_parent = self._namescope.parent + return namescope_parent.mjcf_model if namescope_parent else None + + @property + def root_model(self): + return self.parent_model.root_model if self.parent_model else self + + def get_assets(self): + """Returns a dict containing the binary assets referenced in this model. + + This will contain `{vfs_filename: contents}` pairs. `vfs_filename` will be + the name of the asset in MuJoCo's Virtual File System, which corresponds to + the filename given in the XML returned by `to_xml_string()`. `contents` is a + bytestring. + + This dict can be used together with the result of `to_xml_string()` to + construct a `mujoco.Physics` instance: + + ```python + physics = mujoco.Physics.from_xml_string( + xml_string=mjcf_model.to_xml_string(), + assets=mjcf_model.get_assets()) + ``` + """ + # Get the assets referenced within this `RootElement`'s namescope. + assets = {file_obj.to_xml_string(): file_obj.get_contents() + for file_obj in self.namescope.files + if file_obj.value} + + # Recursively add assets belonging to attachments. + for attached_model in self._attachments.values(): + assets.update(attached_model.get_assets()) + + return assets + + def get_assets_map(self): + + # Get the assets referenced within this `RootElement`'s namescope. + assets = {file_obj._parent.name: file_obj.value.prefix + file_obj.value.extension + for file_obj in self.namescope.files + if file_obj.value} + return assets + + @property + def full_identifier(self): + return self._namescope.full_prefix(self._namescope.root) + + def __copy__(self): + new_model = RootElement(model=self._namescope.name, + model_dir=self.namescope.model_dir) + new_model.include_copy(self) + return new_model + + def __deepcopy__(self, _): + return self.__copy__() + + def is_same_as(self, other): + if other is None or other.spec != self._spec: + return False + return self._has_same_children_as(other) + + +class _ElementListView: + """A hybrid list/dict-like view to a group of repeated MJCF elements.""" + + def __init__(self, spec, parent): + self._spec = spec + self._parent = parent + self._elements = self._parent._children # pylint: disable=protected-access + self._scoped_elements = collections.OrderedDict( + [(scope_namescope.name, getattr(scoped_parent, self._spec.name)) + for scope_namescope, scoped_parent + in self._parent._attachments.items()]) + + @property + def spec(self): + return self._spec + + @property + def tag(self): + return self._spec.name + + @property + def namescope(self): + return self._parent.namescope + + @property + def parent(self): + return self._parent + + def __len__(self): + return len(self._full_list()) + + def __iter__(self): + return iter(self._full_list()) + + def _identifier_not_found_error(self, index): + return KeyError('An element <{}> with {}={!r} does not exist' + .format(self._spec.name, self._spec.identifier, index)) + + def _find_index(self, index): + """Locates an element given the index among siblings with the same tag.""" + if isinstance(index, str) and self._spec.identifier: + for i, element in enumerate(self._elements): + if (element.tag == self._spec.name + and getattr(element, self._spec.identifier) == index): + return i + raise self._identifier_not_found_error(index) + else: + count = 0 + for i, element in enumerate(self._elements): + if element.tag == self._spec.name: + if index == count: + return i + else: + count += 1 + raise IndexError('list index out of range') + + def _full_list(self): + out_list = [element for element in self._elements + if element.tag == self._spec.name] + for scoped_elements in self._scoped_elements.values(): + out_list += scoped_elements[:] + return out_list + + def clear(self): + for child in self._full_list(): + child.remove() + + def __getitem__(self, index): + if (isinstance(index, str) and self._spec.identifier + and constants.PREFIX_SEPARATOR in index): + scope_name = index.split(constants.PREFIX_SEPARATOR)[0] + scoped_elements = self._scoped_elements[scope_name] + try: + return scoped_elements[index[(len(scope_name) + 1):]] + except KeyError: + # Re-raise so that the error shows the full, un-stripped index string + raise self._identifier_not_found_error(index) # pylint: disable=raise-missing-from + elif isinstance(index, slice) or (isinstance(index, int) and index < 0): + return self._full_list()[index] + else: + return self._elements[self._find_index(index)] + + def __delitem__(self, index): + found_index = self._find_index(index) + self._elements[found_index].remove() + + def __str__(self): + return str( + [element.to_xml_string( + prefix_root=self.namescope, self_only=True, pretty_print=False) + for element in self._full_list()]) + + def __repr__(self): + return 'MJCF Elements List: ' + str(self) + + +# This restores @property back to Python's built-in one. +del property +del _raw_property diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/element_test.py b/rofunc/utils/robolab/formatter/mjcf_parser/element_test.py new file mode 100644 index 000000000..bad50c719 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/element_test.py @@ -0,0 +1,1073 @@ +# Copyright 2018 The dm_control Authors. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# ============================================================================ + +"""Tests for `dm_control.mjcf.element`.""" + +import copy +import hashlib +import itertools +import os +import sys +import traceback + +import lxml +import numpy as np +from absl.testing import absltest +from absl.testing import parameterized +from rofunc.utils.robolab.formatter import mjcf_parser as mjcf +from rofunc.utils.robolab.formatter.mjcf_parser import util + +from rofunc.utils.robolab.formatter.mjcf_parser import element +from rofunc.utils.robolab.formatter.mjcf_parser import namescope +from rofunc.utils.robolab.formatter.mjcf_parser import parser + +etree = lxml.etree + +_ASSETS_DIR = os.path.join(os.path.dirname(__file__), 'test_assets') +_TEST_MODEL_XML = os.path.join(_ASSETS_DIR, 'test_model.xml') +_TEXTURE_PATH = os.path.join(_ASSETS_DIR, 'textures/deepmind.png') +_MESH_PATH = os.path.join(_ASSETS_DIR, 'meshes/cube.stl') +_MODEL_WITH_INCLUDE_PATH = os.path.join(_ASSETS_DIR, 'model_with_include.xml') + +_MODEL_WITH_INVALID_FILENAMES = os.path.join( + _ASSETS_DIR, 'model_with_invalid_filenames.xml') +_INCLUDED_WITH_INVALID_FILENAMES = os.path.join( + _ASSETS_DIR, 'included_with_invalid_filenames.xml') +_MODEL_WITH_NAMELESS_ASSETS = os.path.join( + _ASSETS_DIR, 'model_with_nameless_assets.xml') + + +class ElementTest(parameterized.TestCase): + + def assertIsSame(self, mjcf_model, other): + self.assertTrue(mjcf_model.is_same_as(other)) + self.assertTrue(other.is_same_as(mjcf_model)) + + def assertIsNotSame(self, mjcf_model, other): + self.assertFalse(mjcf_model.is_same_as(other)) + self.assertFalse(other.is_same_as(mjcf_model)) + + def assertHasAttr(self, obj, attrib): + self.assertTrue(hasattr(obj, attrib)) + + def assertNotHasAttr(self, obj, attrib): + self.assertFalse(hasattr(obj, attrib)) + + def _test_properties(self, mjcf_element, parent, root, recursive=False): + self.assertEqual(mjcf_element.tag, mjcf_element.spec.name) + self.assertEqual(mjcf_element.parent, parent) + self.assertEqual(mjcf_element.root, root) + self.assertEqual(mjcf_element.namescope, root.namescope) + for child_name, child_spec in mjcf_element.spec.children.items(): + if not (child_spec.repeated or child_spec.on_demand): + child = getattr(mjcf_element, child_name) + self.assertEqual(child.tag, child_name) + self.assertEqual(child.spec, child_spec) + if recursive: + self._test_properties(child, parent=mjcf_element, + root=root, recursive=True) + + def testAttributeError(self): + mjcf_model = element.RootElement(model='test') + mjcf_model.worldbody._spec = None + try: + _ = mjcf_model.worldbody.tag + except AttributeError: + _, err, tb = sys.exc_info() + else: + self.fail('AttributeError was not raised.') + # Test that the error comes from the fact that we've set `_spec = None`. + self.assertEqual(str(err), + '\'NoneType\' object has no attribute \'name\'') + _, _, func_name, _ = traceback.extract_tb(tb)[-1] + # Test that the error comes from the `root` property, not `__getattr__`. + self.assertEqual(func_name, 'tag') + + def testProperties(self): + mujoco = element.RootElement(model='test') + self.assertIsInstance(mujoco.namescope, namescope.NameScope) + self._test_properties(mujoco, parent=None, root=mujoco, recursive=True) + + def _test_attributes(self, mjcf_element, + expected_values=None, recursive=False): + attributes = mjcf_element.get_attributes() + self.assertNotIn('class', attributes) + for attribute_name in mjcf_element.spec.attributes.keys(): + if attribute_name == 'class': + attribute_name = 'dclass' + self.assertHasAttr(mjcf_element, attribute_name) + self.assertIn(attribute_name, dir(mjcf_element)) + attribute_value = getattr(mjcf_element, attribute_name) + if attribute_value is not None: + self.assertIn(attribute_name, attributes) + else: + self.assertNotIn(attribute_name, attributes) + if expected_values: + if attribute_name in expected_values: + expected_value = expected_values[attribute_name] + np.testing.assert_array_equal(attribute_value, expected_value) + else: + self.assertIsNone(attribute_value) + if recursive: + for child in mjcf_element.all_children(): + self._test_attributes(child, recursive=True) + + def testAttributes(self): + mujoco = element.RootElement(model='test') + mujoco.default.dclass = 'main' + self._test_attributes(mujoco, recursive=True) + + def _test_children(self, mjcf_element, recursive=False): + children = mjcf_element.all_children() + for child_name, child_spec in mjcf_element.spec.children.items(): + if not (child_spec.repeated or child_spec.on_demand): + self.assertHasAttr(mjcf_element, child_name) + self.assertIn(child_name, dir(mjcf_element)) + child = getattr(mjcf_element, child_name) + self.assertIn(child, children) + with self.assertRaisesRegex(AttributeError, 'can\'t set attribute'): + setattr(mjcf_element, child_name, 'value') + if recursive: + self._test_children(child, recursive=True) + + def testChildren(self): + mujoco = element.RootElement(model='test') + self._test_children(mujoco, recursive=True) + + def testInvalidAttr(self): + mujoco = element.RootElement(model='test') + invalid_attrib_name = 'foobar' + + def test_invalid_attr_recursively(mjcf_element): + self.assertNotHasAttr(mjcf_element, invalid_attrib_name) + self.assertNotIn(invalid_attrib_name, dir(mjcf_element)) + with self.assertRaisesRegex(AttributeError, 'object has no attribute'): + getattr(mjcf_element, invalid_attrib_name) + with self.assertRaisesRegex(AttributeError, 'can\'t set attribute'): + setattr(mjcf_element, invalid_attrib_name, 'value') + with self.assertRaisesRegex(AttributeError, 'object has no attribute'): + delattr(mjcf_element, invalid_attrib_name) + for child in mjcf_element.all_children(): + test_invalid_attr_recursively(child) + + test_invalid_attr_recursively(mujoco) + + def testAdd(self): + mujoco = element.RootElement(model='test') + + # repeated elements + body_foo_attributes = dict(name='foo', pos=[0, 1, 0], quat=[0, 1, 0, 0]) + body_foo = mujoco.worldbody.add('body', **body_foo_attributes) + self.assertEqual(body_foo.tag, 'body') + joint_foo_attributes = dict(name='foo', type='free') + joint_foo = body_foo.add('joint', **joint_foo_attributes) + self.assertEqual(joint_foo.tag, 'joint') + self._test_properties(body_foo, parent=mujoco.worldbody, root=mujoco) + self._test_attributes(body_foo, expected_values=body_foo_attributes) + self._test_children(body_foo) + self._test_properties(joint_foo, parent=body_foo, root=mujoco) + self._test_attributes(joint_foo, expected_values=joint_foo_attributes) + self._test_children(joint_foo) + + # non-repeated, on-demand elements + self.assertIsNone(body_foo.inertial) + body_foo_inertial_attributes = dict(mass=1.0, pos=[0, 0, 0]) + body_foo_inertial = body_foo.add('inertial', **body_foo_inertial_attributes) + self._test_properties(body_foo_inertial, parent=body_foo, root=mujoco) + self._test_attributes(body_foo_inertial, + expected_values=body_foo_inertial_attributes) + self._test_children(body_foo_inertial) + + with self.assertRaisesRegex(ValueError, ' child already exists'): + body_foo.add('inertial', **body_foo_inertial_attributes) + + # non-repeated, non-on-demand elements + with self.assertRaisesRegex(ValueError, ' child already exists'): + mujoco.add('compiler') + self.assertIsNotNone(mujoco.compiler) + with self.assertRaisesRegex(ValueError, ' child already exists'): + mujoco.add('default') + self.assertIsNotNone(mujoco.default) + + def testInsert(self): + mujoco = element.RootElement(model='test') + + # add in order + mujoco.worldbody.add('body', name='0') + mujoco.worldbody.add('body', name='1') + mujoco.worldbody.add('body', name='2') + + # insert into position 0, check order + mujoco.worldbody.insert('body', name='foo', position=0) + expected_order = ['foo', '0', '1', '2'] + for i, child in enumerate(mujoco.worldbody._children): + self.assertEqual(child.name, expected_order[i]) + + # insert into position -1, check order + mujoco.worldbody.insert('body', name='bar', position=-1) + expected_order = ['foo', '0', '1', 'bar', '2'] + for i, child in enumerate(mujoco.worldbody._children): + self.assertEqual(child.name, expected_order[i]) + + def testAddWithInvalidAttribute(self): + mujoco = element.RootElement(model='test') + with self.assertRaisesRegex(AttributeError, 'not a valid attribute'): + mujoco.worldbody.add('body', name='foo', invalid_attribute='some_value') + self.assertFalse(mujoco.worldbody.body) + self.assertIsNone(mujoco.worldbody.find('body', 'foo')) + + def testSameness(self): + mujoco = element.RootElement(model='test') + + body_1 = mujoco.worldbody.add('body', pos=[0, 1, 2], quat=[0, 1, 0, 1]) + site_1 = body_1.add('site', pos=[0, 1, 2], quat=[0, 1, 0, 1]) + geom_1 = body_1.add('geom', pos=[0, 1, 2], quat=[0, 1, 0, 1]) + + for elem in (body_1, site_1, geom_1): + self.assertIsSame(elem, elem) + + # strict ordering NOT required: adding geom and site is different order + body_2 = mujoco.worldbody.add('body', pos=[0, 1, 2], quat=[0, 1, 0, 1]) + geom_2 = body_2.add('geom', pos=[0, 1, 2], quat=[0, 1, 0, 1]) + site_2 = body_2.add('site', pos=[0, 1, 2], quat=[0, 1, 0, 1]) + + elems_1 = (body_1, site_1, geom_1) + elems_2 = (body_2, site_2, geom_2) + for i, j in itertools.product(range(len(elems_1)), range(len(elems_2))): + if i == j: + self.assertIsSame(elems_1[i], elems_2[j]) + else: + self.assertIsNotSame(elems_1[i], elems_2[j]) + + # on-demand child + body_1.add('inertial', pos=[0, 0, 0], mass=1) + self.assertIsNotSame(body_1, body_2) + + body_2.add('inertial', pos=[0, 0, 0], mass=1) + self.assertIsSame(body_1, body_2) + + # different number of children + subbody_1 = body_1.add('body', pos=[0, 0, 1]) + self.assertIsNotSame(body_1, body_2) + + # attribute mismatch + subbody_2 = body_2.add('body') + self.assertIsNotSame(subbody_1, subbody_2) + self.assertIsNotSame(body_1, body_2) + + subbody_2.pos = [0, 0, 1] + self.assertIsSame(subbody_1, subbody_2) + self.assertIsSame(body_1, body_2) + + # grandchild attribute mismatch + subbody_1.add('joint', type='hinge') + subbody_2.add('joint', type='ball') + self.assertIsNotSame(body_1, body_2) + + def testTendonSameness(self): + mujoco = element.RootElement(model='test') + + spatial_1 = mujoco.tendon.add('spatial') + spatial_1.add('site', site='foo') + spatial_1.add('geom', geom='bar') + + spatial_2 = mujoco.tendon.add('spatial') + spatial_2.add('site', site='foo') + spatial_2.add('geom', geom='bar') + + self.assertIsSame(spatial_1, spatial_2) + + # strict ordering is required + spatial_3 = mujoco.tendon.add('spatial') + spatial_3.add('site', site='foo') + spatial_3.add('geom', geom='bar') + + spatial_4 = mujoco.tendon.add('spatial') + spatial_4.add('geom', geom='bar') + spatial_4.add('site', site='foo') + + self.assertIsNotSame(spatial_3, spatial_4) + + def testCopy(self): + mujoco = parser.from_path(_TEST_MODEL_XML) + self.assertIsSame(mujoco, mujoco) + + copy_mujoco = copy.copy(mujoco) + copy_mujoco.model = 'copied_model' + self.assertIsSame(copy_mujoco, mujoco) + self.assertNotEqual(copy_mujoco, mujoco) + + deepcopy_mujoco = copy.deepcopy(mujoco) + deepcopy_mujoco.model = 'deepcopied_model' + self.assertIsSame(deepcopy_mujoco, mujoco) + self.assertNotEqual(deepcopy_mujoco, mujoco) + + self.assertIsSame(deepcopy_mujoco, copy_mujoco) + self.assertNotEqual(deepcopy_mujoco, copy_mujoco) + + def testWorldBodyFullIdentifier(self): + mujoco = parser.from_path(_TEST_MODEL_XML) + mujoco.model = 'model' + self.assertEqual(mujoco.worldbody.full_identifier, 'world') + + submujoco = copy.copy(mujoco) + submujoco.model = 'submodel' + self.assertEqual(submujoco.worldbody.full_identifier, 'world') + + mujoco.attach(submujoco) + self.assertEqual(mujoco.worldbody.full_identifier, 'world') + self.assertEqual(submujoco.worldbody.full_identifier, 'submodel/') + + self.assertNotIn('name', mujoco.worldbody.to_xml_string(self_only=True)) + self.assertNotIn('name', submujoco.worldbody.to_xml_string(self_only=True)) + + def testAttach(self): + mujoco = parser.from_path(_TEST_MODEL_XML) + mujoco.model = 'model' + + submujoco = copy.copy(mujoco) + submujoco.model = 'submodel' + + subsubmujoco = copy.copy(mujoco) + subsubmujoco.model = 'subsubmodel' + + with self.assertRaisesRegex(ValueError, 'Cannot merge a model to itself'): + mujoco.attach(mujoco) + + attachment_site = submujoco.find('site', 'attachment') + attachment_site.attach(subsubmujoco) + subsubmodel_frame = submujoco.find('attachment_frame', 'subsubmodel') + for attribute_name in ('pos', 'axisangle', 'xyaxes', 'zaxis', 'euler'): + np.testing.assert_array_equal( + getattr(subsubmodel_frame, attribute_name), + getattr(attachment_site, attribute_name)) + self._test_properties(subsubmodel_frame, + parent=attachment_site.parent, root=submujoco) + self.assertEqual( + subsubmodel_frame.to_xml_string().split('\n')[0], + '') + self.assertEqual( + subsubmodel_frame.to_xml_string(precision=5).split('\n')[0], + '') + self.assertEqual(subsubmodel_frame.all_children(), + subsubmujoco.worldbody.all_children()) + + with self.assertRaisesRegex(ValueError, 'already attached elsewhere'): + mujoco.attach(subsubmujoco) + + with self.assertRaisesRegex(ValueError, 'Expected a mjcf.RootElement'): + mujoco.attach(submujoco.contact) + + submujoco.option.flag.gravity = 'enable' + with self.assertRaisesRegex( + ValueError, 'Conflicting values for attribute `gravity`'): + mujoco.attach(submujoco) + submujoco.option.flag.gravity = 'disable' + + mujoco.attach(submujoco) + self.assertEqual(subsubmujoco.parent_model, submujoco) + self.assertEqual(submujoco.parent_model, mujoco) + self.assertEqual(subsubmujoco.root_model, mujoco) + self.assertEqual(submujoco.root_model, mujoco) + + self.assertEqual(submujoco.full_identifier, 'submodel/') + self.assertEqual(subsubmujoco.full_identifier, 'submodel/subsubmodel/') + + merged_children = ('contact', 'actuator') + for child_name in merged_children: + for grandchild in getattr(submujoco, child_name).all_children(): + self.assertIn(grandchild, getattr(mujoco, child_name).all_children()) + for grandchild in getattr(subsubmujoco, child_name).all_children(): + self.assertIn(grandchild, getattr(mujoco, child_name).all_children()) + self.assertIn(grandchild, getattr(submujoco, child_name).all_children()) + + base_contact_content = ( + '') + self.assertEqual( + mujoco.contact.to_xml_string(pretty_print=False), + '' + + base_contact_content.format('') + + base_contact_content.format('submodel/') + + base_contact_content.format('submodel/subsubmodel/') + + '') + + actuators_template = ( + '' + '') + self.assertEqual( + mujoco.actuator.to_xml_string(pretty_print=False), + '' + + actuators_template.format('/', '') + + actuators_template.format('submodel/', 'submodel/') + + actuators_template.format('submodel/subsubmodel/', + 'submodel/subsubmodel/') + + '') + + self.assertEqual(mujoco.default.full_identifier, '/') + self.assertEqual(mujoco.default.default[0].full_identifier, 'big_and_green') + self.assertEqual(submujoco.default.full_identifier, 'submodel/') + self.assertEqual(submujoco.default.default[0].full_identifier, + 'submodel/big_and_green') + self.assertEqual(subsubmujoco.default.full_identifier, + 'submodel/subsubmodel/') + self.assertEqual(subsubmujoco.default.default[0].full_identifier, + 'submodel/subsubmodel/big_and_green') + default_xml_lines = (mujoco.default.to_xml_string(pretty_print=False) + .replace('><', '>><<').split('><')) + self.assertEqual(default_xml_lines[0], '') + self.assertEqual(default_xml_lines[1], '') + self.assertEqual(default_xml_lines[4], '') + self.assertEqual(default_xml_lines[6], '') + self.assertEqual(default_xml_lines[7], '') + self.assertEqual(default_xml_lines[8], '') + self.assertEqual(default_xml_lines[11], + '') + self.assertEqual(default_xml_lines[13], '') + self.assertEqual(default_xml_lines[14], '') + self.assertEqual(default_xml_lines[15], + '') + self.assertEqual(default_xml_lines[18], + '') + self.assertEqual(default_xml_lines[-3], '') + self.assertEqual(default_xml_lines[-2], '') + self.assertEqual(default_xml_lines[-1], '') + + def testDetach(self): + root = parser.from_path(_TEST_MODEL_XML) + root.model = 'model' + + submodel = copy.copy(root) + submodel.model = 'submodel' + + unattached_xml_1 = root.to_xml_string() + root.attach(submodel) + attached_xml_1 = root.to_xml_string() + + submodel.detach() + unattached_xml_2 = root.to_xml_string() + root.attach(submodel) + attached_xml_2 = root.to_xml_string() + + self.assertEqual(unattached_xml_1, unattached_xml_2) + self.assertEqual(attached_xml_1, attached_xml_2) + + def testRenameAttachedModel(self): + root = parser.from_path(_TEST_MODEL_XML) + root.model = 'model' + + submodel = copy.copy(root) + submodel.model = 'submodel' + geom = submodel.worldbody.add( + 'geom', name='geom', type='sphere', size=[0.1]) + + frame = root.attach(submodel) + submodel.model = 'renamed' + self.assertEqual(frame.full_identifier, 'renamed/') + self.assertIsSame(root.find('geom', 'renamed/geom'), geom) + + def testAttachmentFrames(self): + mujoco = parser.from_path(_TEST_MODEL_XML) + mujoco.model = 'model' + + submujoco = copy.copy(mujoco) + submujoco.model = 'submodel' + + subsubmujoco = copy.copy(mujoco) + subsubmujoco.model = 'subsubmodel' + + attachment_site = submujoco.find('site', 'attachment') + attachment_site.attach(subsubmujoco) + mujoco.attach(submujoco) + + # attachments directly on worldbody can have a + submujoco_frame = mujoco.find('attachment_frame', 'submodel') + self.assertStartsWith(submujoco_frame.to_xml_string(pretty_print=False), + '') + self.assertEqual(submujoco_frame.full_identifier, 'submodel/') + free_joint = submujoco_frame.add('freejoint') + self.assertEqual(free_joint.to_xml_string(pretty_print=False), + '') + self.assertEqual(free_joint.full_identifier, 'submodel/') + + # attachments elsewhere cannot have a + subsubmujoco_frame = submujoco.find('attachment_frame', 'subsubmodel') + subsubmujoco_frame_xml = subsubmujoco_frame.to_xml_string( + pretty_print=False, prefix_root=mujoco.namescope) + self.assertStartsWith( + subsubmujoco_frame_xml, + '') + self.assertEqual(subsubmujoco_frame.full_identifier, + 'submodel/subsubmodel/') + with self.assertRaisesRegex(AttributeError, 'not a valid child'): + subsubmujoco_frame.add('freejoint') + hinge_joint = subsubmujoco_frame.add('joint', type='hinge', axis=[1, 2, 3]) + hinge_joint_xml = hinge_joint.to_xml_string( + pretty_print=False, prefix_root=mujoco.namescope) + self.assertEqual( + hinge_joint_xml, + '') + self.assertEqual(hinge_joint.full_identifier, 'submodel/subsubmodel/') + + def testDuplicateAttachmentFrameJointIdentifiers(self): + mujoco = parser.from_path(_TEST_MODEL_XML) + mujoco.model = 'model' + + submujoco_1 = copy.copy(mujoco) + submujoco_1.model = 'submodel_1' + + submujoco_2 = copy.copy(mujoco) + submujoco_2.model = 'submodel_2' + + frame_1 = mujoco.attach(submujoco_1) + frame_2 = mujoco.attach(submujoco_2) + + joint_1 = frame_1.add('joint', type='slide', name='root_x', axis=[1, 0, 0]) + joint_2 = frame_2.add('joint', type='slide', name='root_x', axis=[1, 0, 0]) + + self.assertEqual(joint_1.full_identifier, 'submodel_1/root_x/') + self.assertEqual(joint_2.full_identifier, 'submodel_2/root_x/') + + def testAttachmentFrameReference(self): + root_1 = mjcf.RootElement('model_1') + root_2 = mjcf.RootElement('model_2') + root_2_frame = root_1.attach(root_2) + sensor = root_1.sensor.add( + 'framelinacc', name='root_2', objtype='body', objname=root_2_frame) + self.assertEqual( + sensor.to_xml_string(pretty_print=False), + '') + + def testAttachmentFrameChildReference(self): + root_1 = mjcf.RootElement('model_1') + root_2 = mjcf.RootElement('model_2') + root_2_frame = root_1.attach(root_2) + root_2_joint = root_2_frame.add( + 'joint', name='root_x', type='slide', axis=[1, 0, 0]) + actuator = root_1.actuator.add( + 'position', name='root_x', joint=root_2_joint) + self.assertEqual( + actuator.to_xml_string(pretty_print=False), + '') + + def testDeletion(self): + mujoco = parser.from_path(_TEST_MODEL_XML) + mujoco.model = 'model' + + submujoco = copy.copy(mujoco) + submujoco.model = 'submodel' + + subsubmujoco = copy.copy(mujoco) + subsubmujoco.model = 'subsubmodel' + + submujoco.find('site', 'attachment').attach(subsubmujoco) + mujoco.attach(submujoco) + + with self.assertRaisesRegex( + ValueError, r'use remove\(affect_attachments=True\)'): + del mujoco.option + + mujoco.option.remove(affect_attachments=True) + for root in (mujoco, submujoco, subsubmujoco): + self.assertIsNotNone(root.option.flag) + self.assertEqual( + root.option.to_xml_string(pretty_print=False), ' diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/attribute_test_schema.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/attribute_test_schema.xml new file mode 100644 index 000000000..aa62f3bab --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/attribute_test_schema.xml @@ -0,0 +1,100 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included.xml new file mode 100644 index 000000000..40f88427a --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included_with_invalid_filenames.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included_with_invalid_filenames.xml new file mode 100644 index 000000000..a58f6e25d --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/included_with_invalid_filenames.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/lego_brick.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/lego_brick.xml new file mode 100644 index 000000000..ba8561e3d --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/lego_brick.xml @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/cube.msh b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/cube.msh new file mode 100644 index 0000000000000000000000000000000000000000..0a2f278f0ddfd555d8f4437efdd32fc61441a596 GIT binary patch literal 880 zcmdthSqj2H5Jk~A&l=}>idl!*nk#EpB!VD{AI4iWfv4yOY&fKNsY<$o#(`fkmnQCM zy1#+)Xf>SG53biQ^@Z#y{n;!t$=T-#nX_kEMz6D(&-%pu9PhDQXLUcCYrodIXPwnt z`+x06&#SYV>#UwpYyCbtt7p-DYQNU{Or51>9r$L-r|+5F&zAQ7f6nhJ$fJNFN+_d( oDr%^s0s9ZM&_)L#y6B;g0frc1j0vWgVU7isSYeF~wurF93&?dACIA2c literal 0 HcmV?d00001 diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/cube.stl b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/cube.stl new file mode 100644 index 0000000000000000000000000000000000000000..a5bc8256d455db5520cffbbf6f47b935db378487 GIT binary patch literal 684 zcmb7>K?=e!5JltOLu9E7MO+AOEC^mi8dqv1DtNl~L?Q^HxUkM(Ti#@6A#{@Y?@wm3 zx*Upl3c26JV&|9Ju+KvrO~+h7 kmyj9GjZT)JiZthD31;{nbh3o(y7{nM(w1O`_2}f>7h`SuivR!s literal 0 HcmV?d00001 diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/more_meshes/cube.stl b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/meshes/more_meshes/cube.stl new file mode 100644 index 0000000000000000000000000000000000000000..a5bc8256d455db5520cffbbf6f47b935db378487 GIT binary patch literal 684 zcmb7>K?=e!5JltOLu9E7MO+AOEC^mi8dqv1DtNl~L?Q^HxUkM(Ti#@6A#{@Y?@wm3 zx*Upl3c26JV&|9Ju+KvrO~+h7 kmyj9GjZT)JiZthD31;{nbh3o(y7{nM(w1O`_2}f>7h`SuivR!s literal 0 HcmV?d00001 diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assetdir.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assetdir.xml new file mode 100644 index 000000000..68bc57346 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assetdir.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assets.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assets.xml new file mode 100644 index 000000000..2521511fc --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_assets.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_include.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_include.xml new file mode 100644 index 000000000..fbe2d4190 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_include.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_invalid_filenames.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_invalid_filenames.xml new file mode 100644 index 000000000..ff972e1b0 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_invalid_filenames.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_nameless_assets.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_nameless_assets.xml new file mode 100644 index 000000000..ad615c6c1 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_nameless_assets.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_separators.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_separators.xml new file mode 100644 index 000000000..27cd4aa4b --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/model_with_separators.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/robot_arm.xml b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/robot_arm.xml new file mode 100644 index 000000000..5b6d6a076 --- /dev/null +++ b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/robot_arm.xml @@ -0,0 +1,200 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/skins/test_skin.skn b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/skins/test_skin.skn new file mode 100644 index 0000000000000000000000000000000000000000..651fdc18def13ac765eea7f6fcb39416db814bcb GIT binary patch literal 472672 zcmb4qd00+g)OPb+nlvd58fYFgJm;MCG?PN5Oqq!cAwwclLZ#9?XhNg84AF4*q9_?6 znF*mtBB3IwzN6pwUDx~m`SsU*o%Y#hKYQ=B*S+qw_FD~s|Ne{x1e`hawPhNb$4^GL z<&pH^(plJa)fz=6t)&;&c;WNMJY2tICOxfZ3SM2s!@xNk=}q}7R9osvr|0ppW``AqKHWv1Q*g$kizngu^bp#gcEwY#EpT(o zLHc;UBW~@s!@oB3=tTt-K5Vnc>7L%S<0(7TuQ0^1r^4txj|ddxK7>>)#fG8VPkyo+h09Q{*g+PO|#Hd(**h9vGldO(^3182G*!0(=*Md;L4)$ zSRj)?Pgk3PrA8E<$Sk35H%-AM3mj3rG>__=G!@rIJL2kP60}?047Apw@a+Nx+AV4} zj**y*uivWEgP;8I*;pIAIVFW!;O>a^_R8on^9Z$JwI}um$m2lGR4U$P3cgg8=jKs> zZu4=(*LM`rI9`ZeYGjLdtCVq)iWqH?Xp7CKRj_q!9;FuUhV6UAaYm5~Et2exAss^4 zFxG$$)bYk$I|Om8rVV}fyC=%lh~dgoKU&s&5iVBvOA0nEqo0b;!m@i}D4MvNzB*w=!HvRFSU#1Fy80z+x3glYqJ18t1+d7Y?k2kxIg5_ZxQ<1Ss$F?DTqhw z?odjP+|jvG2<@UyQ$bnon6Xe41Dk}XJhADx@1qUI_liJ3IrM|%lkEqz9^gTrit^&I7C*r;GWt7fOXIwa651*`-;_0L~GH}0HE)!wv4?H8K(<8K%>D8XRP z+i`elyA_q;})h-sjjV5YrmsvEw2CV@i}&-4E0x-a6+F*yqfT;$u!GZ^v1 zZ8IdWVaXkyd*D12oUV@L*I9az&k~GR(ngD$HFW>^xoA_OgA&gQX`yC6bo5onT7@Fo za-ttP$SR=Or3~6dXD&v~RYd)nmucJj6&SQsAHUh>(;?pi&^pNo31^S0S5{%uPa`Zd z-$jeNF2W;diu=X{(=$y&a8N)WedA*2frabQe}f)6F1bX%Ojv{R9l98|?G?Qsd@GjU z*2OBxU-Tx;?Rep!4vv`Jq8rk~aiO0MUVofH?^K+JJ&_Wq{vw?Y->?iXR*nz>xqMpx z(K3|t5W+oP4fL890r>Tj6w(JO>3Jj3c`a4O(9k)lwosUy!!RRFHKO%umoQse=nS@lL6t3fC(vG}Xl)o*H{5S)8 z^PX57_ecqcYNP2@Er(F%Y#XuMHb|dOOhCn|x8%-=2D(r<1%)cQ$=ZvL>8qxP@pR>P zqG2S;sO*nM+2Ve3!$^xcyy5^hNOzLiR%4mqp)~aJ|3)&7JJQGQrr`^*ZgMj(i|%HU zNBis+PNF>yCZo#pHZnKJmi}>JC${&!B~2>N=vS*FaPsjtTKVL%Y zh8)0-+Sg=fK^J`@elMB{wUGr~(#*MaTk*6^8@c5xz{G^_!=}8qq|hOPHklEN#v5Ld z^HFhhWc@yLO!!D5WK8Iq#8^xSct=9T9Ox%^H=@~sE<)!d(AAOaQ6c&Z(aEc(y-U~N zNc%T3Z_itL#t?%IkF`+u`ZY>DmPW-EEeyGJkNVJSiw>USF)zD=+TQDkKa7m=N!ejRI*i#sQ4Y#G~MfG}k?C?T-%Ka|X(ZdNp7U9;@ zw$v3{Jv_8@A>P?Oz3ODuE7JRG7Vh1Bwo2#4E7IBHgDXc=syep5AgUfdSY=quOA>rR z?t1#+UN(q#tLHhXaq__x-bvI{<^@@!>WAT~S=5>2*W~^me|%dQPf7Q@CL3&K<1OKH zynFSn(z7wT_q;kVTo-TqXQ) zSKMxwKzV1@lgUr{IP_75ZmYjeLX%z4|E(6?RC9|YZgR&1+g0dLv74mRU<$5Uf09Za zxlM$s+)xtixii0p%rrE|IhHw9p~=_D<2@$$G2nKE*(W6X`;GC`bwTPHznb_Ao8#DL zS9#j|t`W&vV{BeiL+uhovbn|_m)X3cZr`|0cIa5+qGJt|Y)CB$*0x6B_CDSg^Lp}) zXNh~#3M<)iT`Y5y#Qc5nl@h6XxG+QvTaW4UUQ6jB&ruX5xB61qyT{|AnUXksfu;-@ zU3^v`iYu4BrplbP@kf9p_C`w3+iG<%s#O-txqT&ZSO@26%Hh>|7ivki9**#2aCX!^ z2kl@hRD0ls-gZ`1o4U*~SbrKy@0iZpz10|HPfW+C;S7hB?WVZg%NvKRORC288sKq1 zAGCb?xk8?rh)un-@O0XXs>eHxF|A-WrtE%Salq9A%S2|Or`7=npZ7NSYWGb1c6}Dl zy3GvF4Nk>npN>&w^UZPcQ4ieEFpi#JYK#IU9N#jQrLV_N!jE^oP@+7Eda%y`*U9idCQ@At#`#nqKwUEhetZ(mGKILuprvy)VA^1{8GPxrstK|Gs1@qO_)I=SK% z*>!0KhMT{m-nq9DSB^W5OPfI1t9>RbD!g&(7+=~n=o=~A?1viCYV^C5HWIveHWpjF zpzhCkL-h4$VUoTI9d)sXz$8E1;h9cFG=CtgJZ7V7xe3)NCWXrScKGA-X{t?468+;j zPL13of&O63v>>@&8;R~Fi|^mhsTu-6*T$p_Lm zA_vLgueNx#d>QSreUP{lTlD>^LEqTjPF_+D7=TOYKiMD1hBpovH&%)s)RMx@Dt0)2 z=K=c1QfXAEXg<+ z_TD%QiO-|#Pb=ZqDcZO%x`5J&P{zP>x+pY1oPsZ+=u@YMpE>UBcU}xzR19#x?^epe zT^!f#HNuZfE@k#r8O6->G30U~RWMBt>m+osb|8ncDb&V@Om*x#FG2uH0clMwtg2m1-^x?O&ly_SH&u!@84^L&Rk|3)_oSD)h@t^!=N7&qw1$HY-ci%W zj|Vd8RgtVfu2L*eLJ)&^L?rKPQSI z6AW-xMQ+(;9_w!pFIh4s>JC^2V>kaMiLFo$5rO& z7-Mz6C`t*<<4NQi;H^ecTw)Yd>Q=gf7{`>oiXlmlfjoS z_VV!kB=kQmg7nM1lz#dotcn#y(Jj5y{C<5L2;};?_??ROF~GxFBA9w`HFYX>5}uwU ziAkmEbY|-$JSZ-U3se76*Od*>Q9}-YB#P3RiTZfbUlQFP>CiqJ+*$iU7902OquSOR zV7mSo3=mmC1!k_siH{~?zOorD^>Z<1&NavKZF=v z3m@#nZL_p-y5>xJ`pr#7!OL;e9Ze*ug;lEs1JK}}Hm3hbukx9vhnr&@P$f*5UM8%EF;nbOvUf2Z zsmaBHd_Fdvn@gLHRmRv&d|dQfg5GQ;hJ7Bc*yrF!=Pwn*y7R7>mLy0o_7KM%=iM>4 z_aNn3s*LF}PN-#&Le<>U!vk^@E^6OL6%9yAA^jt5EH1g{jLV86>HH^>I5yD>U#(wE&$}&-|6<^m;ZgLQ=>~X}IAMpsI30LJ zA0P4@F-tF+5-C$br>kyw=rI@b@>J1PXbQHimZP`sltdpNPh6s#NX08lq3<;>3|k{b zhm=piz*Gjy0wz;mPL0KND_xN1JD+;ERs!!Td0=dg8)Y(Rj^Y<=u#w}pc+(uyR@vZT z_)7J2{7B&TWE?2)q#mubLJX#{Cw~?fBUobV40}9xC4{EctZ-gDg=?{gAUni4=QuoAi+&Zyt?`p)xOFBt+%$Hz8yI`u#GqC;}ds4wG+p6Pb?%r_RSG;N-b z+v;Xj-Faz1!LNfIUW)EN0` z6Op%aCzUv4iXj}A`lzswzBgimL)VNkM&ls;p-%^w=ubwy8=L4&C$%x&+ycuz@@Zo& zQ~Z!)h6_~ksenpTj8?P2O_gKl9V6Np`PK@Tmz}31IsVojX@hICH0YK!CKw}Qf~sUX zRp`WVd=Cp0@~Yg!wW`?7&m9#oQeu zlsl+{OP`Q!!ESiLgr+yIdq{NWJ7LDQh4dG(W^(-?gZykOdR}rfi7{qyv-T6}vX&AG zdYPl@@J2e_QVIP}nq!K)27M?;2|vxW#H7cUsBtgGB0XYLipIn>lfQw-i^pRXNubQ_%&^o= z2VENk=zrS4qLy*kw|hA?)bo>+r5WJudwZy>2m8qB9wT(qx22qATgjF0M)=^!cuI+j zaknq#*3zbgr!?_BVY^JRV~i42*V<2-R&u`Z+%{_F++U=UZ;HDvby5wL@5%L7=6HYj z0_EKGj+Fki!1D*q=|6}2iN+gKZ1bK%Pu2cOZ2lVIqOg5*T+wUt?{{YX-cA?vw~&AS zPqW*KHY@#3w%JU;=)cbNw=+M;?AH@eV@C(IEbcXtd~JZf+^%h%-bjw!nS^(#1_z>l zpD0F~;z^--RXeMih}upIOjHYSQ1f^|WNWR^dgW58XU%=`qtgndZ%WW{XYP}Od zRkOlZp?snU2Jd7k^SFSjL-P)xuDvim|Das8c6tnk5B?;RvcB=Yx*fvB z5kq8Ac~YfabQ}hL6haNt?+$VC37jt;Cbz#yQ65EyQE#Z9n3tXBX)lULamVju5_fKg zj3i@8`7k*lbeU>bO2Ng`evsv2mDC5RM4agInP7ee_09Vb4t8{spsHF*X?X%hX^COw zh2zxM92zUigfWcc=hq`?d>AE+p^G(XQD1xfASr^Nqe`2vwa4z;!dPj<>BBwNn7Ba% z#dj#ux|%k)r$!jB=Veh96S+7bR}`NGl=FsH+T)@ZqUb94oOdXd#;!l2cw}BH@6LJ} z@9verSV>3PY#WV}_sXDrxjbF7)E+(7$>3nD6#aO*Jw7=jfmIb-7ERn`boW9C>+GAp!G?qSKe5^&jA@ETDbdr8xUokRdo@4s1lKrX`*Iny{;WiIu5v_?jS^Tj z)s0@i&=KEVmPV~Kehu@a5jEl6uufCfRZc9xKuB;h{&b?7#){HjXy>(@GA=jmWd#zv%tRaRCw4bjU$~?AV@L=jO*pF z`h*GCiKf8)UrIRpx)O|2%!HDMV{qb1MQ9uE1@Q`!_%|^gHjntizAa+7=2R|}Z?^)M zR1v)X=NM@BnnF;xB*%vn;o%K=2rw1JB5G6jWiHToLuu3R}pMmr_S6|RKfIp zh2X03(*Bvsc)a-iIE1ZD0N;XQ5ThnKA{i0;=BCaE|P&bBrZ{_1{4$>R_lkEthGdfm+C$Q^CA$Etss! zVNK0v!i+Usn>8`)72|23-MtnH-hHloFX{_rn|6=lA4|R9bWijs=5j>PIuZ>64%=Aw z)ovgz7X#4)KiG9Y9YIH0VYJPpMjDi|^+&P5J6Fh4FaYCmPuUHMuJG`t0=%2l&Jtk; zmiZZh{~SN!o$Ly(s>-n9;S$2s@}XhJ2xGl9n7lQi;8esQlj-n-{k_!|F8m!}{*BFT z#$=FO5X}72IY647OyS#2A;xV(6!+VW;8Ly#laeY)INcTo?`~j%FN+h=+6i#VLv-}r zPt!GEuVu(6jyww%kM1VT<|ecvEnlu zvtI-*eaa)5TFc38O=-xGdrI2Yd6RLu5@0jqIawj~l-)rK!FirI-n+mM#rINh-(Ldf zx7M&C2_m3;K?47c|HlzQ_#yd%{KIWChMDk@W1~3ETM&kFh1gmRBMcwj3R1%r?1IZC z*qIj#_A|6eY_b7Xo9DvVmLgJ;Yk^mlQX$FAi`0kMayhn0*qJlTrfOQEV##WFx}=P1 z!f5iYTn9v7Tx73%9we7T)M54HD)vT|7-78RVa~i$)T}B=GQma_3O%l}|HiXQRR*F= zj#K~eToWaz7?TA88~3pmMXn&ZJ_{Z^5+HSaXW)NLf|*i3*(qQ7pno|Dgr!1Roh2?{ zdOT@#-SZ<|A?w$XQT#E~4P-u+jpEN2=Yi3tE2DT~#B%7hy8^|*$?Ve2E8zayGT;)x z?4mXELH)>OI3O=izSOOR2basBxlxH2bOykDhf}cHMTtCr;RBmRPJxv{3j1om4{U2c zIojtMo)5%6I0-F(I!V;L-SDZk6n-CkMmAqR05jcBL$huV5z9`5qVWYVEFp|1V-LZ^ ziNz4HyO+$`n+KtE4%n|1MO(ciu<1iQbS_jtTm1wuJ(>-_UrA!$@d&VdRsaL+FVc2% zJxqK0j@~@EfxLa(0Oj9eS!I3;Q5dd=iUMWU*IX92PAP}|YlWGNIl}m9-4&3&lFZE9 z(MyizT!CxN2~5o6axyum0c1DMAv0Z-QENdNNCfO7HUl3?m{~0pA8#Q)%03Wsry5?n zUMIy>V{z@lQ}FhfBGg>yAO(`;5VUhLkZqmhyXQrCvTHW1UDHjxy2_y6Z7$^AxJ+Dh zufxN)b|6@Dfjo-30V65O@F=>Jm_DonxfjQw%Bw~z$V*PzEI4N}gP z67}0xq5EqFl<0Sn*wQl)G35}bK?ND}=qeZ$#)6Y#KZ%}v8tN`)LCZS}k}lr}2d1Y$ z)+&k|SlI}xYO+Sxg^M#_<*npVyyY5XLpi~l}!*~o;_-_cAZZ_jp`r8J31b~u8vGH zJL)^ZHf4y#Omfm!0^RClK|H6LY<@FB*0GZCmCIk~4!3Xrxq8SUAr0<-m4~;vRrYk)pi*9(m*8N_~4;*U*I3jAgxztVx7TMD0E#)crH^A zTpd91k2)G1wZW>P&G6#34(>?RMl0#Voc%hCa<-7q`@uNg3}c?_;FGjKsG0AHw;Q_2 zP~k>cy~h?$G|FOCoiB(hOu~-0>gW+{50+E(aaXu0{*ZEmE>7F|mzQBHXTZc4#`q#b z5Jff}g@NC0cx=-?iwRq!Czg%+XZ~;_&3dH6M`^l4lBfvJy z$LE)klyt{}H1ctp37_QNyaHZrbCEmC$?276;Pg`${I{m7MOfHmxnLAu%PEC8lMSP| zbzC9%-C2ic6U9m2+T-vxKL%%)s1bfxBs4CMM5QbqVWkd1i^@UlvA)4R^i6=RpJOqi zC!dWt8U;?j4vzLSJSGW#osApC#qu#=Jv(U>OIhrL_2&|?$0Cw-@7W749vsHbBR|=t zTX%qA+)m_6>?4*I5x{$N09OV1lBb8m;M|K?=n)HC zRVj$mhZuOf#|fj_+sTI4GoZ-M3d;qb6WL-rc#xF_7mCGE#W$6yuTc&R-RYgJ2_FWi}PQRX|z*j~f<1ssDdRf5RAKgGoS%7rn@{*tff zZZTS)^1&if4F5d7z}z`;0&EV-q2iw`X6=SzSdt=zl?zgsRg(52K$*MyBYk`sE+Sb+L+aH z(~!EYf(4%Un7XPd=vAtRTwKmX>NuhOVKZE&aD%b25XZ2Cd@O-tM)GPWNmX-0&*Qa> zNBsy{Qa%;Uw>L9vhCKeQb4Ib&a^_!rrapTLPAq6;S`)`{Jl6?dO4Kp!e}09~B+_|NW& zuc^YPUx50R$!z`sbx`V_jq1Yd*iTW0kQwTTjZ0;Su;_SLO3%a4dGFX+-zLE|kqtP* z>nv;WdotKZufr|7CbQ!=TEngIwWEDT$6CR{JvHE^D^JdAHG-h>4fyx1lm(Aq_x$Qn zJh1K|bRDjSXM?h2fo>zr2`nFdzKQcMH|@(gUZF&4hws9s^A&JtcO=PFt%3RWSK;}~ zon&}v4Lml#2@>0Okzvl~>ZUeA^V}rz>)aJcJ$nP*NvD!q?w8?`D*@5yOhTN?AzGjY z9!$+5TKrS6Zu%`So1acXb_cKe1$9M?vf1#rXiEj(C}MjRVXK$**DnEfV!Xm%F@9{vjHl?i0=%u{gGtsS_vBahV1fp5uo znEmGvxp}Az3{pOUs82j8Sat!T8s0!pOf1P*kPRiS9i#KPb8HsubNvJforj2A(9zL0 z7BiBGkwX6eYX9%u|M$GYts7n@uO-1^M<8b9Psm;}gB;tE33J8zpv`7JDYnXnFW0|8 z@5$}tbx#iLD)|Mjw*yJf*gVKL{{ggJBpFaX&T)(Z_}CFe*0i03O9%Sk=ZAx2&fX&M znl}h@7jGt4eU8JE^COUt;pF@3LYQz|h@Zc9D=GL<21&ldkh@_%IX_Yjd$0Y5o%s>O z{_Q2GFdc!Z)PC~j+*#n62=V*F!^q3FVlcQM!dFmRM-DAJ0ZqZ;eAoE7K$*@(S&VDFn=nCqlV8q99Oz}4Rne94OBPrDAGqJz+V=??ok zwE=wP|Bl*-fyiAb+tojc@BC^6%O_u8W@bGbUfc+e)V{*Vb_>!Kd<#Cve}^eY^vEmY zTQEJ~J1k#!h21)#5f+MmAAMKa`99q4>>9;!zwZNF`viCVoyiXE2GF8EL51OK_Wj{T z=$zOw+Geli1K9WV?I>X;dM8yOE>XSzT$eH^*?|Wp_CRInZdJZ zteJjzIlq?`*c=HH{D#5g%`H|YWe=1c8~{#pXLouZgvj+GeD|Cc?B9(mft@PG4?i`J zWvtdg(03vJU}h1!?fqtmT_VW0n_tL^Y6Qcgs1f+&6UB;42Z8cpA-?*}MQrMp<MrxR{T;cB%#U+-{g*K82*a*Fw?IH<;<>NG|5q0mR1HzG4m3 z{rmw}TNtA8_BzBXe})~YOUPj7H4vNH3ESEhk%Nvm;O>Txux#8WGTXWay2Cz!^Tdrr z{U*X0!%v_Q9Zm#iv9MtI2M~H5K@8(q@H_tzPPQH-?j{vb=GY0VrbQ4XvnmiB`p;&! zMl6M~rQ)M&*DbmVz8(}7@Q-snisy3+&Iiu>4Ko!jAZZRe=X3cKxt45OY=>@+qEUO)Zs3~_q1 z4$_!k;77Z%K~=%9ZssuPK2T>HSFQki<>Arxyv*egEA<3|dcsKEvfJ>_Hyh2|K-7nB zLF=YFu&#SG5gDq7X3-~bRCWis?pY6eU%i2caRFqj%Pmko{~B7Xmy%AGMi4po7W~gx zkj}47(Dm^>JW^62OGEBKW%?Va3om57sb=^k{03f#3X_bihp@rs3HQA&cIWkn;3D%F zT*NlB(~KWM_Kt_6W3yLz41dPlhA+xz*uLIosJ(R;-k+5qUG)#Ra)MiM*8|AJJ&mwh z^d|J$>k_SxcR^s}F}#|xpX6n|1+LBwG<*Zdo5U8_U(^IE_Rc3AC!T{}+FkgN9Z8<= zeGT#p>%p>e6&X-^0*|lMf{s%Z`Tgq!@Mc^CAGI_xbwVqgu5JK3ekyS=c@L9&n_%XY zbaL@wJ3M~=24bFtlBcI0LTkz^ko7%C#(aAL>ZSLgJ1v0(?Rf$da~^`Z!+x?sr3nHh zYGB5*R3baO86-E=!;*>^0*~&(qoQ(9$)86~|6C0#yvm^3YdNV;S_m)aTml2#WD?S~ z0rt!;g$WATgsYPU5C4;}EI6N>`Q#1evroabz!jwStPeO1MT6A?TXNu-17tfTgYYhU za?6kh@&?%uw#JpLp9AoGdS}xjD>uvK#!4 zgb~{eOE}}Y0W5oC$gK;u&>9&GB1r*6RK*Fr(sl!vA17}1G@J!fFnO6v7JGTX8x1v3 zbt@u_>J%9HY7GM(cgQ0Iu|*{CRtF?dPD#`r&L*R`Jylbh3!U5M%&1T+W{U7#ob@k$+atdNc7x<=Qi}Qe@7f(w&fi# zilIoEODrfGHbV7Eabh?a4eE&xA>Bid+{liF+|~#1roopSe-jT4_yV3LIgmB8EcTdkK$T+-74p z9|HZ}N3ikWc{cTL416lN2kyrb*__ZQ(09E*YHR*&2O%Zx@hFxFh=HUnEu;9t$rv!2 z{+zR`G&1ICD}-IU1MK2#lED4nq~sy!94X{O)TUb=g!tSzsBKGVR z@LCAuzRe*Oj?XyW{tE7GwICWHPa&0y84moML{>CEhQ`XI%ssghieus-rg{wK zqy$5cRw(TLAc%{<`-9zt{g6>6jcfA*!Q#eVU@uDJA?FAfXRr}m#|hxk2i$pnRUS)r zNnrJ?F(7S;?Ch5|%@#7B8jt1JvlCD`O?>rX77hNZPEBtV$ zryLxVEF?2~X5h&!qG02bMS|xkp_GLnY}P3vcFF2^MZTR0)x1U&Y!$G-=L54Xpn|x3 zl)~4`hnash$>&~4<9N+4jQy`?L^DGS>uCY_b|(S8L_a4MRn5#-xkC_mvxOW{yv_L2 z`=KD?BcT=Qn92K(z?O{ zW+d$r;NSg@quYKnftM!WKhD46krY_IoPgcCPqS9evhcZc0xC-yl8EPu@L=ZzY);xl zWZTuDBESg$e9t7cya~{F)D7M9st9B01mfFg;VVurE~%OgJ>$6iz6T+6$p$#&x(zuV zMV6^0fmy>kJiH^1_@6!i4;SphXuprF{=HMzjd3%e>*eJ-wmZD z%y84wrOcCDu0CJE1YJIQGD<&9(ZW+6o8Eq7E)FC#rU}Gy;zjY?sN&IA{C;uf@ z&NDE6x&XAi*TAVO-FK93xa3J~X$n}+7lf>xYW!b`qU=V`EQqRC8|8t-fXlr!{}(Ux&d7#y>oxdB8v1OSPc{_B ztMUJy%VRySWJ8FYD&Kw2ZZ`aV76|Jp^CwuJW$Wj1x|-Ek{??0+*=H|vAk$WXKW^m^ zduH)b*u71jZ@Z$IP56)p=UQd>(uTvV%f;g`CtQ}VdQ_Ek*yV$UofJR(j5#^`j??)r zN%D`~QX-pu3IHi_{`zhDWPlVv$a!&o%S#u+@kLl1Bg*GAX|md=5WXsk@=2p5apSby zmrX+aI9_u8E6-9Q}S6ydzA!(-YxB zbU#erT*E%Q76I9oo@g>Mq0&HeAB?f7t;`b%ptl zY7*J?!eQX!FUB9!N3%w_5!Ou<<#U=9YjkuA*v}H<_y0+)mQ>yZg7M;fxjwdi=Sjz0=phv;$(J`(*055LmXL6~?!Rl9lyI@F4FkM6X#w5*y;7s`VXw4YDGWLJz@` z2k%GytiO5`gj{$JO8aZrxkl0Onip z4;idzTp={gkmhr_0QTXTe2}jY=9fN|B&KGCu$mU*fA<<z6(O*Hnn$cBOrML+8 z4v6rxyiT)+R}_K8I|06xfg-6=D}bJpU{6oYhOW>q_`9WHXfH)lwQ}H;?N{)%*v<~UN&??Q zUC`~6$J(o>!-L2k80+wY-5Hby!+XB}2;^yCT*xtHmyW zh51;#_I?tx!TL04E|$mo)J4qj(^7cgtcsJ$%Sfp6SPi9X08+!!WmsFT=PDVk#^69M^;Ao(>j)sQ!Id=o6PX_ zg?UVuz)1*_vBC6KJ!b39Q_x#%kDV_}nJHO^VIgk@8>CcQ)a-$+R|NQ69XA`8x(jkNhe26TygGi` zUO2_+JpZ_grRiSatr{4`p~;aj-){i^MlP!UaxfD1d;c7LzU^exzx?JX_Wm3PjjOsL ze9^V)&Zlu)ebG;Nvmm+Jttbk9&iw@It&Q3A=jm`X^D`9Q6k+`}l3`i>f0~1oXEGE! z{HGsIoRR^99AB3ao6Bn5&4JZTA4dBxF3g29pZ~+}c5->A6&)e_J#6&{^`?|a3tZS#L; zwNX?NOzRQjcTQ7hgN%#7q)wQB?2H*(>e@suD{o-8!=4a$b+t@LAp!7|i|HrPbx@#mC%J!UvdVdN}TFWp`J5Gb- zZ(Hn56lG?aoCS-u+lnmp z$>MVP=gi%GM`6LGu_$-_6_b3l0Os_JL+VZ~vx3VN(yzF>wbVi8+qOJ#tQEx|#Xcr) zdM>>F`iEed6c}`7gTi`obhjA;r)K2BfqfmsEkqNF6_0{($wML_rfArd-4JdFTX;R zvvxpM^jXl$NTg@P#Jw=f+HzJ3Jx zuuww6(qMe+8}Qt@pX^mm|6jS1zh{3y^>IGYI+F&07rw&$>j6a4FAaK!dO`Q2B5Cl* zfVn|^u<-0e@+v4DQiZzU`0ypxT=2-KpE3ye!LC%xgpXrBj_$+krYtB8?117NH+GA0 z7Ayrd$g2u2Z>?v*YM*+jw#cKLuM2zY?+Bl_2k@2RDxNlK(^3T}M^9ec>LbLqe2L z8bm}X5vBH8Qv?J7Q53{3?ABvixSH^|^UQ+4GM-b)DXuK90Vj^mcV5vw(r} zJ>sJxcY`Tgdmt^zk+VAKEy*J;k<$7-R(|<)p}d=&Y3nGV4F4NVjwS=?Oal#Z!q|d} z!h6%;%%@6FQ4QJ?-=E|Fg0g#&rwg)wN!`gdjd~zf4Y1&`rld+fb`nrpXWA_<8dvxm7 zL}Xoj%&xcFMHdX6g*+qX7s9tv|1`eo-8^|uN>_wi@8aXe zESL94OvT3^EBUn%Q>ZxSi!x>YasGVBP&#z7Qi)mdjJNsRkIp)kC=aUYQt9sgbZh51 zC8kW5b{qB~|8bj?V<(9=nf4=h%>#?-G5J-bk2|GmYF{(lm138uc4TQ2seZ2IRmD+E z+`ltRn!n;{@6L1@>TaZHmbIdasC4>qXkqcR^O5A`mahK((^gUREGUDHEK5*c6oymg zigbFaTB6v6wV=^Q*HQM^5~a&`S2Az4iQYZPRMx+0M$0Fr$@$(Z%Gg{>dZe+A{93$F zw)W5^v*67X;;t)9KV9IXf3K&ieLs{917GuXYqwI%BgW#=(*j;;l0~C*ErhA@7JhYV zF8%H5AZ(tt<~uX9N&lR+c-J_IKigGEI!~QNj}$|`W@Z63x#%R6U{@}$!$jg?H!-T$ zJboY}LSWao#9|XSOz{_KNq%B}Q~}3%Kw{Gt;%CQK{M}eL;r2=Hoc_AN{Z{CR4}D`q zrnWVuE|l}vxt{8CnjwHBQ<;;BodhWK!`t>~5OOW0l29O5qKzFJNPe|=YG z+-WY>ET2q+9~p?Ld8Xn+`Zl`u#6sLSbV)hT`Vf5|=^(D|@1+FTAEBVN^#nej>@caI zgxhUIXwMX-_5MIIyxU*o%^j!&*tAfebyUwnc-@~Y&c5(fZpTJYN_;cnFn^EIdrxDU z5MwVK9-LHKrn}M%p(Q?l{-sP`ZboO%7>ldgPnDz2wp5TMXPV@k`6iR^{JZHNC8LL~ zFzKL2gHz;=i)^sW_r1bncGM8v#v6z`bDwfe-%rZw2xD>Q=5=1a)=+3Pt07wcD(7yW zU4{7t9g!S#gs+e@8zBaAKL5miJ~q-_l#bIC8<%aAOIvYALYvTQM}8KcEWwvALYS3dB!p>S}EH$QHh^YiyjoW zQGUn%DGtdnq+^F;)iZ2mmAYi$8l!ya^-Qtxb0l^sQdtv{tK{h0P_Eq|Wym)xG4HrJ zEgRBV`F>4b^!a2*y3q@jpLz|%w(pPloBQLG-(Tf?Qez#uzx|5Re7}nrcxD^VT((@W3io46`GC3s^8BW@2=EEwM|Qgkv;9`0hJJ|=3YxhVc=}9CldGAl7E}krI zuSAol@K-;VBi6*w=6bD2Uc)L2Qsb!Yjpp)tbB$trCYovw>rPdxHAG?M1lp?6p4x4H zs!aZ;4}DG>LrEQKh+!Aj(uF>QseAhxVy$XEJxd=?L1_g_Mp!B3oET4Gk3T8rhwhPQ z8WYriR%u=fb^? zx9DN;U5;JuF^9KO<9YImzwD*5cUvxfZg__$`N`+h`XutszQfCAnTgFQE9laX+x$mQ zZPE4mAi804o8LVDP#HR{J@xUu%D3E~pgfxIM=v98aGg;(%Bx*1Xmj_=JTB=^@$#09 zX~dCB>Oc2d7cX+o$)Rh<>xy9w-!i|n19Bd~UYz}Phux{OpZ<2T7sK0V^5F>w$>L01 zaVuAc|47ZIS*KluZQ_0Q>(5>~t8x*Qt2FqPf_!p#5G4lRp1|%eD5T6MtwcAuV;;A@ zfMzrf7b^otGbJaFCbWtWqYUSl;U~)Z2nIhsm8yt8T1=twL!n zNp!nBj+Mz6){NFI#Dp2M*~P+QYWP9!vyWQA8ht3FpHG{MNjK8iV9g>byAdkB^c}?7 zrWKRX)NrAj9m`@y9wy6Q{=!0gC^PabrN#@Iiu?&3*w3dWbmBr2QQl`1`xaC}rWtvvRXSYP~l=%*eaSJ|^bTJGq;$$&Rs9e}#rb`-;tr3)rscVsbI}5u3Cwu{$^O z$#R*$=$`n4&3bW&E_UN0l_5S+vEoqS@aW3TeXxo&n6ai~L#lmyL*KL99um z5=uD|Eq-kdW1+8(klwmj5%#G*yJS;Nb%Waor}LcY>^e-1^dg1d*kNp-`%&uAUUr&# zHD*>nN-1z)OR;Emd$z#v6zyElTnv;wt}fq?(KHv8n0=YCu)jxX+b9xeEF#%>o0F6~ zG*qNs3uUoY<#Mi|g@`@UkWp0yWsV6Ko!UFHtna5t-X9cqpIETs+%q(9L4>$6%#)3N za)u0jLq*N*o^1QA3aYh4wm&+>uq&4<2)m`1zBOmFPnVO6XegenN?SoXm@O7yc5 z0kv42IZ-BkLrr6J%-sQ?&AY0L=XcM~|nop@2c7lhjXBKYxM7-D+NwTR_y$)}t{vUgW6gYBDJNU^q-V%*Lh>}$OuTBl_#sKzGNerOS8 zzp5j?q|9Z<@8{9vCi3@bJW>5`rL)IUXgvyJN2eCj8ABV<(YQYwaXX)$7ubk3EBZ6n zOL^+o&%V0dSaZswJJ;k+{*dwP$njj-vrC?{4PU~V@;o}#&QhGdv6j6%T}Yorgz)Q8 zpV_@Bkn?{nh50leHvVq`<=1Z|+FYwtt#vG*RdZU3x&il9c7f_#C zVdA`JQ+D)VA^ah3@$;szzsuX?Q#r z?PNb;c5(?}pL)>o<}BoT33X0rEFRAHW7l>Ga!>IVemfti24|O$*I6$yGvJ46N83_* z9_cNfJb$kmJ+73}s~U^dDfQX37Nw-+=_~3?ab`E)me8oKKH}>QUzTxQzMk7Q6;4-Q zsGO#k&}iQ#V$JnWD(qeKSkOW=R-UP5@2Q{-_rk@%XJx9cAIk~d#-VaIe67w2nmQv) zbdk@O$r`6AB0ECNm5saii%yg6<|xszaEB^s)G_LCB0&uLQHSZAI!>D3BG8C;+Cl`^YJ=G_x)7%!`g7!3GM-Eg_`exZBsauQX zG(00`_dSI1+P|vGujeUxl9!k(`#ck`oul$_Z=v0IzRL90Y4Z5&Dc;#dV(LW1S6CVS(YFSJLT^4OcRMQEnjf78xepTDeH>59}{jm86u@iv~@^ z&ee5T*~oJ0wx+T8y5_N}Y-|x#9*h<(=blv=P%%Z+j}{R}Em(e$LQUj7;G?zlS)q$U z4oBOH{!s<0RxbrhZLDf2<_>$R+7nbt9pc=?L-|^FJ+72iJa-iyD;l#$E6Qni7dO#;yCX~W zDIzq89DCejG^2>*d8AlyFN;+f%Jz=e44S*R-BKV!<@V2QS4u9Fqy zirLA>Sd*6f$j!H@(9X(WPcH7I#0NpbH+MVJs=b$L9SIaIV^6UW5BAZQL=r{Xr`Y54 zYzn#FTzDpAF!L+><*c5cIJnY)UH+0yo;8^GCi_d{dhMePnJSU4J&<*b&Zc9U%|y0+ zA{*{_kkG_fQP`a|ZJI*^4ttASuE|;j6;Rez7g657J1cLTOJ91qiOvH$vlH(ND4?0E zm@FTMSw4Am!l;p$nxM@VL=_O46)!g}SACt3N5z+X#TD6z&_8sDwr};;^)<<- ze&akuX1`r3s}Y5?)3%|Qms_H;Eh;3<;U1#r$z7^_{ST5>p4^#A@5tKUKS&d;?bI#tWSxe-j&K&H;_HA zyPwA91PeLi&dTZ@prhx5#fZ1HS=H-#CYB-ol9O$h4qEMjw#bBE}}72^~8-?{aK@|coB2N zMkHSU!tBnr7pYMe;*`%@wn8^X7?xRzm@az!-qSYX;Z8ddKiG(etqB)>C)E)#5te-L z*jA$P7YFhEybW)e5F?Jo)fYdopBv$#IjQJA*Zou_}|}y z#iHM?VnfqJ8qq~8S)~VF5<{N9g&f$&2y9E#QZ8>d9kg;C##y`R}E`EV|p)f@X8P6uTyP4<8WuO*9qXq=5!XhJH9JU&e2@HsR+F!4RNZcKi_tAgjjR(y>j%A zFMqRPfO!Ayi<0#)f=^sMPK-PLRjIk1cxc`*5wP>OVmC0JTi)&`Dqm`dM{Ni5Yu3F) z_R1g1)-B!m)4h|$o$H#Sd}#zXPWVSW-l8Mo-*@ASMobfd`Eu9(Vl;n!bBs7xWh7dq z^x|)44i$-aOoT(;Sl-8buz0TM39Z%t@V!3M#D+PwMeMjpzIEpq(dCA@Xc^gq58g6K z^cZF%dNpmq8?7ECBJ0?Sp*<7$=;4FJx50K|!Nj55uH{g1d!VK0_Fy#EOdTz(W$(;6 zrzzLoJw&kIPNK)dNWS<}9})V>S(x7L!FSY%5aDLBrF$^W@{90b1*?T zY;zN_k9u;=Bi+?M>-t?s^A-Ai#QHb~(Q4yN-uP}mQD{*|__m+J^?dq^5ivDIqu+CQ z>dv0xm9>`mRWOZrecwkk(lZd9+t22PZQ|th#81WScURu;d1p~0|CiD^ZUlcZuC;ib zq$wV%B6voRa52}#KrGqOl&3}qiy0o)LQ_84K5B-j`zoo|8t`%TLd4WCXJN-0@_|kr zMZGw4;aFc@=icco>R&Vx!Hci6&+B@MlgG8i)^5+)#^B-N!KP=*xt!X(%a?v)@AXg0 z=0FX;`2BdHH|>S;yr~m!dTqLB(BZw3dZ-b<5Sk<$YyMUSM*H%Ng4yC+dwsF9!k-WB zG)q)Xv=NKry|~uQ*}{5pEiuB}kAEo`DbQ1Mxn;_?{+uMLx;qMsJV!pKO%HX~w9}gB z%(h2=v42rLG0yuBGriYIuuN+qM%-X>CQPI^F)vYj-piqR*Lkm5yio(ab)s)rTW~pr`H6!+G(x&*BR4>(es*1gxrZ%mV8L0@mo_w zQo`rr*V_lvwTCMO_Fu*~?Ms`#Ef-qeCyK9I^`vcWXNq$_XB5wwO|-Fao_OLNTI~2S zgfu=Uivf486kVy+g3d0UE@o^qC>}F_k!oME`p;@GESTym)6~B{yIVz;6|;oF?gPa^ zRV}Dw-E7hS`0e81+2K?$Lbh-{Hx$n_iz3y_`JymuR`D#IaO$qLOt_yoU!1(FGcBIE zPy}SwRu(tzO1Y*>MZ(t;#Z$cFshR$KadN4NlC(FDZg?yf$M578Z?0@Z`MGn&@;(~M zkNnoub>JNeSTbDUNw>+a#(lb-5u>z?ko(B#mnbf5y>ij%39WU!Am@%XQg(Ei`aVU$vq=>Hsg$Pm&{LM~nJV|HifLw& zkz&!}AG-LWket@EQKANnqd#tk$u2ik*}Huvx%mirPhzrSSAP!8YhFNmza=ZnET_^) zpFOVe@w*4$r$|KUKed`>W87h>VOWSDm-90pG)eU9Jwsd)4U?)usIjVdv-cNmJ zWs~lZ1B#aCK{}GMi{?I;yLHnJQ}ENRr12 zlfF?VeKB-W@OgP&S*H5ms^jS*&-3qB$ z|4bz)Jd=9XQs`COR%Pz%4RQwm08RceU#VAim`dffl~bb(#WOO85_jyS=2NYeUuCE1 zp!YuY|IhV17wM_>dV!zmKf%3e=)QHrdu3(Ok0YBu^+TS{D{a zeukUGk)Q6x$~C0nX=e*s9kEypX;xU|VHHd{q05Cw ziF2{sFD2^*%YMELQ(nM;0|Fvt=nlvus{*!rTaIZM#&= z>fWc=%0G;ryj>}tOrKXgN-vnE4_hHhJNGKy+=xmJXvZz}eg5l+hf)uPU(wZ&syL#bfr8u5CB{QAa@F5TfmH1{$XQi_;{fYH`&A&pdVm4(_Hq+C5j2FshLCM} z+A$=F;oR4}z>nHV#{vGrW*vWmzW|rv%13X4%YZY0`%8TYc0-0)h&Va6A=yg1K^aZr zS4R(m?*RAV+&|s~_W>S+-v(cT2LZ?7_jiAS7Mi#;4)|gITKt4*bSo> zxX`x$*$r<7*%9o9nbLPyec6Hj-U?xGA5xAx)0UIrY7ZjztSiBTfa72n;!bcJ;4hqO zXGicC;4(bFRfpg*z;4)*RfnqWh7qx51iJygL&e701m6MfLu|GM!F_-Sv9OahHJ2X5 zqPqT~?pr&$EIXXpqvAxLChpWi8V#@;Ol#L8*bQN0BgL8qu4E%k2Uri?3Ootc1MG%5 zh4uuy0j5Li7uE#R0WJe`Xi9Jy;5D>t5=8JC(6C&vp*d}9XTab)Odr*p^ri0r_u&W& zBDfE59KN{w5*!D(4EN5O)0+l*>~Xtb@%w%)G+G!Ohaa9b362AN2g^}43BCi|hxcvF z3GM?Nhu@`^bYHe);V+!+VMOp3;4++hs7r7eU^fI^)1_*=VFUZY&-G4J`wlx(Gzh)} z+=rB3nxw7k%HTohtkNTR5O5r#FV-M94(RsZ*=$7c8sIprx@$~u9N;?)?rconjzwz6 zp_!Qx!Eu1g(EF?=!DWEgFtN7=!E1oyurT)<_m*cn@Exw0{^jr;;68Yt(IU7Ha2#^~ z(V=m*wbd5Gp3ajK(sY3Jka4*w!Ft%F7bCX( z^rejfdTMha-=i79To_rXLerQI$ZK{O4Y&^sqXCXXLLDE1r^@OO+y{6KSzj6vyarRV7}2YbCk05y0lveRH}wg= z1007Fxy}T~0d~W2TWcE9ZF2xjhtdA_1k=IhPrO)=s85S;o(w``H7H!4TFM^ge;*sL z9{#@8r#l(hL2w!RxtI}L26zoa2i7Hc4KK1giMV1%8g_rH+IQIG=0NZr;66Ad)+M+P za2yT{uSIYi^uv0HqnAAhMgts&_S+j!wd3$m-;LlnzFg|HWFdASt zsCsG=>;{+)?;rl=FdgQbcNTVO`jmTNwc2HPU)O=)GQev%T+5!|HNbH=JJFWlIKX!Z zmi;aG4xRtb6D3FL5Zni&h`GWo)|z}K)>XRZis?TY90xuBXB>_LyoSKadmLT^9EU&Nuer~TGzQ;c)YLZ|z5^TwuJMq= zae&J(%(IfiWq{XE|MhJSuK|w3wH`M)90&Lgqfg!8@ExA+pCSw#?(?(KeSqVj5md?H zIKXH)Gv_{s(E!I`Q0grX$HCzEEHSm1c{-|8QB`)LZfXJ@ha>fnYtvMag^V zrxFMT1Z;>WMqLRu1RRIVaotESxlJMVo0dd&AealgrN!{3W(R`B0Ha~5M;yUufaCD8 zR~%J44)+sc368_x@i&#wp0N}ttp^wo272uX1_W#fCsXR$D!A2xpVo|n7x**B&X@kDQs$* z3I@aplVE}Y0UILsZwSGLfaBnNPWH(tKy5B8YSx5cF2G`ty&LKwEe0438?SlM&02TV zj>AZEZ>n}2nq6;1a2#MgWE;EF^%D3~wp8snlnja`I1UTPxr;#2ntuOY69@xhttygWK){9wdm2r!A>cUt zT+xQ$IKX1C8s3&*F~Dokt&FB>uVJA}EWvAl>EKx0nqWF${wqGG6~TId0dd-_6~Taj z#h@DyN3a;+HFTNZmg4RI^%@@3N+5U*Fdf_j+7nC%SP%2=w;@;$Fd$yvi>B4`H3wcp zx10om*8s<1L)|!n;{e}b(zv$t?D%FCT!uHsa&}C*46gegDRa!*(^Kg+EL&fx@H=hk zjC35}JET;^5PS!?59iHe3GM?Nhj7#O1jhkJ!^m4P1fv0V!}=331iJyI!{Db;w>X$~hC4VZ;H@I8>K9f#XlK?KJE)`Og_ zC0GwIAZBFv5)25~5KV*p2sQ*9hn8gl1jnKF#wW^>j{&q$x&ZJRMqO$~OYZ#ZHGGc^ zAn$X%SeY~(_GtOhtF4J@>p^>U6MFHtFT>oBb4U|{0Rf9ac8&-ZLw~J5iqFkJy76c( z+gJ0IGN)e%ZIO-xOo#8AIh}XytF|8SJ+K~NK+JLXqobqesJ(`LwL%D90~`mN@0|1< z9oh8-Mj|C3h~`M&0p@~hs0+bdfW@$IRRek|Ery6}*>LixPyVK3)s90-xf4}84pVM9 z(@Xi;+at?d$oWP}lGXzZh-Z&%Xp}S{U_*?XU{A0i;5a<8cOp0ruozmlcOqB}@EQ#E z*b%%2hhI8Ewzp`C^cu!W)1gZfIs0~?r`mcLcA*ZzdVm2Tttf&40gE9ipgzH3fY^#nenZj>GDdqEcBnsx&+d6uZQ9s<2x2-bsffRp&_?Lg0^0RgX}&5(w) zUV05TiY&zVAXh3_YNGZXv})C(lR7mRT!y!KMg*4uUc=R31A^B8$KlgM9fIQk-{Gc_ zF2Q$z`>@H?fZ#sBaaiBQh}NE+9t5MIAX}SYG@xDWIz@+`UH+gp9d2yaA(#%Z9%htk z6RZcEDPA68Krk9$H}q_5La-aQJ!phpF2zgJ0oDWle_%blAK@yFs7xtJ-s6Vp@cXAR zwd^@dM-+?3Xa1a zGZ(7m^RMGz>uE=D9AG`nAK*Z+9$+_27-~(h8(=yNUTj4$9bh-?ih9psH^6k*_UI*t z=>Vf4pwfY0G{Dqb+Pnc3{LgVnxo<1)oo_8PHyj}9UUH^;(t3coP+BjTU@i=a(ii(H zTGGc$b5$@J9vurM7!7b7^5zjOc=oU3V9_&_;5fi~h>RzK^#B7RvztG`fPf7l_a!NA zfHs5UkX=8Bu9VGE!D6rojv!bJ@ER69YC(TCB(YUj3`L9W(Il_i)TYDHoR$RB0oKE0 zzZL}R0rx{nLm0t;fW>xjfU;dEVk4e0Vt9S}t~{w`IU4!tgiQPt;E z6|9HfvCRqA0}O~4mx2if1iXe94OR9CD`kl8)UQweQfh!k6GXz-}<==TER3uzz-EmWp6Hz;0Mdj9@pwbeNDHL@*uT zIG`s1#{pi0rDj`#*8s->?@e$V;5)3PD7tFmqDqr?!+{~~XpvD{R$-9Drq|W zi20&)OAV(c^5+iILD;q?m=6EgeN*(WMo?GjI27xVm|RW-ivdPMyG0?y&Ae3|Gy}xC zykI&e?FRS`omX(G_8sK)D#3Sv0kQoiClT(ab{S+7gTi$Bs_lllYl5lTZqPg|+ZEDo zfbS6I97^yV{(A-mqoJ%_E1ECw7*(i*v9S4tL5d_C!+|m%yFfWw2v>rO;t6)8l zgR~o9I<)HEf?zt#o#HAwKkH26F2omlY01ZfTSp3%j>E<@Cy`WT-;&wE_Zh+}2$LGrJYRae&1zc$XW&Vt~=`_O%DWXn@_IXW=gIVb@gq4qiqLsM>eXpWKk(JHUXb zo8w9_AYe4)xAZ0$4P}2kgx%Ffl>9%(VR}$gg5v<|VZEj|jcnSTSuJ%E+Nr)YKpG8j z9CmnlQ?=u;?~4z?ae(!peZZ3*2c)a*hKD`833dZaheP$;38n+QhG7>&WkWPk?KmuY z5G>~`b=1DY*sGl2JHT#0Ll<@fOotU=EeWOrc8@C8G5Wi!iQ06C85vA49pE@*1~Y== z0I$Kke`A8zuu3`(V}uu#G_zsw9h`c5(JRwYYP;dqvnDjyVg-Zg(AC19U^>8V*sbeN zup3}Hpos$00gl6lhfN5M!`devf=uLlT>JGZI1X=SS<&oEhRmhhUHFcxL+SE;4R*t; zWwr#nft~ggsTPj(N}3LhrQL9=t0N7{(@>iZ%Zuy@rUM*@1s`k(jsq-)A5$6;ECvf{ zG~CkgBujZN^ds+qvUW@(I_|q82)@HrJvV~y(9r0<`q!7G?*Ieh)~@;l0|G`v_$Lp7 z(a`WkrE=4-vFsOmGnfvQAG`>r1FVN@@g4;00Y*c5l-%uk6~fY`-7wLpKCL{{gpJ9# ztAyNWMC+vK0P7*HmK(u(NR)O%vyb%&b^}a@u~qd5rUSeN|7G5^A*yHK)_QV)c%uis zFzHgbFY=61a=#({39JY-9Cl7|&}c$6q}>41!Sk9A!F0$fJ*i}`bCX?d9kuC@;O|K= z9pE?|?dC>s9N;x*x3DDVO6wvx4ss@+;5fi{$e&h|20eUPFlk8-(R7g+!Eu1m;IdVl zU^KvScs0_H+@#}h!(*7Za?OD1dM{I34?}!R2-X9<2Dg~H1g`;(L(gb?g5v<+LC2vk z!FMPeHdeG5YEDcUFsijM)(s6*rV5Vb0uo&PqXqM?ywbu~8%81%{=(0o7 zUl=&kh`veFq24$qdapJj6KOrbfcUyvpI|`1V(?mJOpbTgs9->J3NfZHxBvATW>^^! zyat#K`)<}Cm=3TW;*=T$>j4JDLuX@x0RgW;M_c|Zq}PDI%QsB}y7zrp5PS!DpPk@4 zU^a89t}fNFe-Z@8p?iuJ!Ex9>Ay}*+EqZ*;S#3AenXOOLJGW#o9keGJ5ln}peS<|8 zD`U#_&r-p3Fg{a*?4{}8G)tbnTNzMyd1ec*;dWCas`eUom>Ccphl>Zjg*c%@tN!OZ z{J*{jM#HhuMzlQfn+kS=o?=X}8~*!y!fO~ZREOX-z;PIBY(UT7SgGxX{4i~T-2i7{ zUfY@kX94~~qZSqfe*rE-!6|cs%V3wAM9Je#<^9Hg?S}4WY7*=Q_zp8N4GF%(pl4&z zwWlG?f(RZ&QYRyV2LZd`Mn4mR-2jW>jj=gJ9WhrM4N$a2D{HAI<{&h43f?g1-QlA?IBUg3AEAAvwiBeg^*6 zZkQCJL$Dj*J0xUk6MP4_4_oHz65I!P5W5=~5IhLj4X^fU66^*z3pX2B5}XD23%+|z z2>t?GhLM{s2`&Tdh5{EmsMoDVlVcxE~1m6Mf!_Bu21or_R1g@drLBMW! z;cic`8{jN_sC9t%?WRX*kqhY9{&Eg~0WQNO{nH#S!}HopY43x4?)^WzLBrq%hur|* zA@5c>hwlLQA-Tmq4)*~b#L_cc`9M)uZ8v1aZ{j#RhQ(kLcZ|bgfYC5z!2u4V0d_;? z%S{}1155|cT01#Rhs(eIq0>W(c;HWMg599fKhI$|z*%^)U?79D&_)^!9c#>DFdASt zI9RM=up3}HjPx?+#TQ!xTn4LkuNYhg7z)yuWiS+AE9^coh{INZxv;xl zcMfv_F2j{ecUZN{uzp7@hs&_c%vH{6o@1~Z;3Fh0*5L3FU@PS4>TuW!Fc*xU>vEV2 zPN%i_pfz*k-`!1ZG&F0S#9=hRQ&_)$8ZUe3qc#y@<`*)U2yhcR=A2`b*uQRq>{@WR z39uEUKh0q)z+AXLyeEgb0E;0)=MjU&0Q=y^oMr_304BoG1KtD^0an6>?Xs69tppef zID>_u@JreXSG*h0h~Hz?R)RcxB3KD<5Y`#$aX1L@5sYeRbNC24(oJ|adN$uV(wg8Y z$gV7hrvUH3weGP<|x6@!BSAHgT`2ZN6QH^JF)EQ6Z>r=axMLI$S*enIw% znjC%sTm#uO=5P&QAH-NLX4UqA^q@KH1NaEdOcpZu2rvkwk3%pBU=#crWk#?GU=~DA z*CCh%?v5E$%U+ABU4w1gt9aaujcWVgOVnEq`v4|_!@jE=CIYO4x~|W8a_4Dk*TCWN zXAai@PQl`>RUA%1`vKZKZ>Sc*FMw+>D$JPBWrcSTIN&CScK`<=yXP?u2LZ0Z@jnMS zTmzT|N6*Q}``j$rAuR)+TaS3?=_0jp(AoJ3hj9S=K<=E&25Pq2DQNyOn`2&HJE9Za ze3Qe&oXga%!P4cgIa~vH2Xa=5!#jY3@aMMNZ8MZ}n#(Q7?BE{mC0zs91k?E^4x0de z!Q-|sc(q?Z{c}0|0vHDuuJ7S64hp4xF#c#dhkXDOp}xU&4if=3LH@a54x0e3L1msl zhid@uKz=sk@DAV(l&1%9xC1Z?)?0B7v*3n)7Ydu#f={k=>KoiR5<$o#!qxamz}wMUs7GQ7ckc7E{7KY zQ=oUl2mJ24e@%g-Cf_(r0k{ME4gPSr1Mmnc2FQDY(j$OVAm~HEc>C@(hbaJe0G~bJ4xBsT zBvN-e$VTK6wNs!v=u2=4U<$;)B7!LZ7r^R4G5316Q0)bn-kHVW1;7!gJ9Qn0BLHjQ zXxe=aYoLFYpV-+sm%|!>NAPNw22CHeN$mo-KGx=N0siX+w0PJ_XlvQ?Ea?lt9aug^ z#Vw^ffX=^W`Z$KpKa7B}Y3rEY=465$F!ORTgB=jwCrNaB;m1Rb7O1U(jbAJ{tO2+H zcS2sX4r3;%JO8cbkLKw7qyN9M3vu-S;R5t1bLMaX;00vox8d*t;0S!_H=V-~fD53Z zyOzTRK<8iD=p3DY^#7C3Y7qMWZ~>m4HX^tHU8NUrR!5uW=GYP(fybF2I2-}E0978> zI9vcU{PWXl5E}ky`wxjRAhi9_{O@}0H%IdyE&%SgR=WUKYQE%f0bmDo*!fo8BHX7o z1(wzP!C?x(8j$V`!5V-IVBf7K!399WzwDBRNo9;}o17Hg14z;71HSejd0j5!pU=6?p_}0vgc3SRGxBc;%3T=Nh z|Krw~$j4Ng+5(7Ot4p=7%lB#N1*|xyLDwGt>jlIt`oZA^z!Z4z|Bk~HK*L}DTnG*S zfwJx2<(?%K#+>EyEL@mW)+IFm;R3`@aHa7+54rnlAF*nIEx`qV9gupbA;AuSDKKxS zAHfuWHIVGkgkTM%IJXc{>7H`8O74SO)Dt~3R8)WFdUf01zgrNY?T_Yv_?%!u^Z(>p zGhutH1y#EM9)rUPE&%L+e@;YD_~eUfQ(%W@81>0GqP7NBuOosr02g54!2p5_fX;u# z*Km%`Kl=Z8jG_Mz7a;iLMh+JMUcmBesT^Jao+B$qPvCF_-~zO{9n9eZpy9t-xH6AX zzUsDri%;7a|K3d9{2!!wi=p`s7eF(iJF9j9q>aSk0>BQiN?gcb2fXql^(+}o0kryM zFN>qqkB0y8%$Xbwf3*DrPS)h;2c!Sru3Zg|{y)5cmH!xXcmZhp#~zpet$eRRt3Phm zN{&`P8vZ7u*K#!c(e`)GUd_?=NAusoe>q3<9~Quu8A~}V0JQz}YOms|)qB*f{sy)w z9Ibvd{D;+Fz|ru3XD{3PXJ_(8lS|dj|Gi2-j^;lsfDOZDb65bXvkz(hzy%y_fAsk$ z$1msT^P}N^O>-HqZurZFH%G&N;<_{RvFiek&OiG9rEeB+^#9=kmVF-PYg{r?pPOZb{MTZ#KTAd{slI9veq`G-$P z;pq0G=l|GpK1a_Vo&Wn;GdVi{_#UsE`5gWK|9=1f@9SvwFYhyxqt%a|zwA!)>Yo21 z>qL&8Kbrp@a}qe3|60-lFh3NXvb!a|^Uzom) z-jsf)-l22(J30H=?Z96$cbmY``A4_kq+$$De7v2?z5bGjpT%G8+e3P#-)Q98X&jw@ z^#A1!5f9LiyU5Z7h~Fn|u&Qi&xL>FFqG1Dh%|4mxR)1p)A1-98A3gtf0bO}@&;J!! za`gPs{EuA}!qNPP1yCo7@$M?wT9ZbAco5HF1fbRbblDY#RzEub2HTD@bpFx*mkt?2 z{~vw+=^e@$`uynjKhgK*==P)Me{q#PN6#Of|EK!<7&`y|ZSSMWUuBfd(Bwy}|L|)E zj#fV!{<7uH(eOvxe@A2qL)#y{eedx<8G8HZ^PAqd%FyRWw?8b4_$0>)ij-ab*k?63 zy87ttZ`P>6(c4FdKP}OPt2_L%&o6hwIr{wQ_8<1p;`n^%COiC9&u%kx_|et37`>fc zmR)`H_HPZ_!)}*uBrnQ2amldlp`@IT# z@|v=}k0yV9SeSHLmZ|&s^8PnRKYyQW;Oq6d$u!%|Rd@2wXuV<8o&2PfBMhBVH0ln=fpL)E=~uQweSdi&_-Yu1fr=;xDc;G=9G(2b z>)%pEQYc4DAC3J-OJX=0`)Kd~42|Sy@1v7{d*pDAPJUYC3pv}>mH%yCuI}o8eAbPl ztB-zu@zkMw!_mpFl>PkH8q+!Y`RMAeygi^kGssM;jl_d^D@j%+Io}qWf`e zIokN>-nZ`h4@dVNJ^ZYnGdX(r=;V(aFqY4~l&^kHHMQ)+Tj>?5d-(Rt=5X}z(aG<- zawP7-D0dn5>KjI_X+d5bF}W!v@dYkz|ge+=h;JQ zGpII4>mCjKzuKN04ScljL-+h)Xx*b@|3J##=-8um->7q6hSohA_=hqdGc@qgx9_g0 z%h9(-(_S_|Ihyup-G^@s;%MDtkFx84B z8UOa}vyA)l85UR74gB5b6F3_9XyYfQcjRc}qnWQcau!E3AAS2pqgHbC?Ptp!=h^p@ zdH$u-)M))B8rEkPe`a}}?&_DybEV~SZ|S1Cb#E>fbF}XJt-M3NlV)=?@X^NC^c>CG zWy$`%Y}D)L_Tp&Nqg}sw&1Q~vJ(~8BL8%-~dvxzLH}vF%DgSow`?OBs{a%hxxA9Xx zci@|<2B~}Xi93dK^y<;EKX!5&$9+fi?GG0Q^Whz3HonDjYJH|Dzv338?&0sQ@5`5M z2~_v(Cv_Xl(YNosdK&FM)tsYUkEZ>!#~nGE_GsM?cbLb~x^HuJ8m)gmhNFRxMt!F9 zE{;Y$+V#!a+~8=}qiH{}<^_(XJ-YXNSO%}|-usU^!O^`(8-K9QdX6?edi7iE-*cn$ zt<@d-`AuGMbnMZ$5BDzMQ$0!Dy`L2-IJ)=f;Ts-5!g23szU!$)9$osPo0~bh^yt;+`ektR>d~}+ketd5{@1kcQI;;x2_MtG zm>WcmR&vv8_tlMhlOTVNMm^f~zgsonXxASKyF;x`dhnGauc=$~4<}{u>$RQ{8ue3- zWO6j>(XMYcZyQIu{+Ddp4+`1I>)m;*ZryK>-Oa}Z|J$w~5x9ro^+qXxDF9wvnSPG##bEbqweJ9zjKf104 zpdzgoL1@&YU7vfj2BBS#ru~K=8ib}j+Vw|!|KVuYqd#Bu#-7lh zKP?;e(xjv6Mt$N^2STHMMT))X^23bKvHyCewpg^?K<@F#`vfIsqF|Xmp?i-;efuGe z35|NR>pwkeOla4mX&*c`gwV7{yWW4F+?82xt!~jFYTf^=Q{8T6N`U*Z=o?2JQOEzwTjAk(!6Mm3=jNRvi)lW{pe=;gmyjp_HBFBB=qgkpFeFb&tYVLK23J%FI>~4 z8)p~u+eR_sVHYhjkiB|z?58t%&L=zeeOCTb!V+Q#EqXNS7cFQ*Xw=h-qe^916ro*@ z7X6pC_JkHa8ufgOC!tY~cKv|wD*0NjPw3Kb$TA~z>2X$oxmNV*(VTzVaScOr9xZy4 zVU`RndbI1KpS)3_U5^&M*M$)bEqXNPO-;WrH0RNxAJpwELyI1bdaK*p7#j6x(Kj?c z#n7ThbKX_QgQGc*7X9)nbB-208ufkT9yuEIXwh5Sn{l-0(VVYn7|YR|M~i-5(_oGk zy-?{le|E}=qfw6*y|%p9f09b9Cv^tCu}?j$S=_@`mvi96fn-=7*iu;ONYwKffX74nuz)jrwtp8oatupW#x- z(5Oep-YWeDL&qMSc|J9bp)-#b{U@7ZR^6hvJ2;D>MUP&+qLazct4DMGbA%T|a~>`F zK8f=gTJ&htCroU|(5Od?{%)=gLyKN4(r+Fo+XLv&qf0-RhO5w}M_YbvsTW6E9?kit zW!<`$Zv11@^$gv3^yIh55(IkkU1ew9daXM{XC6Iy>-_c%J$ba^=jTpjXvL!^ zf4s56s(bR&m!>fEY;l{RIgeKS;!hb&PqyOGlYji_Gt+VWwQ#*4RJ4BdG2dyR=GEEkIG+Et~kGoW^LQft|_%-qaB%1K(#^XH= z-S}BX2kH7&ADSb(@o3A-=MkYTkM3)qTLJVsRmIVw$G)U?_!xB)o{gzV$7B=!N$MU- z8)QaKbN}teOBb8ajYnJlQJmb(k!^W2=L`1LB{b*1$rioeRdYg%9#pU{LyD?ZuTm(YqwLtZc0lhBYyXa1DG4^?;O zu}6l^JX-W;>$?+L^k~KZD3tTYvK5b>ysvWus_w}Tcd{q+^v z1CsktvPF-E{DjcwL1@UMEnnMgr3!6%G~w&XeiEASvS~q{pleVd$}=+5W_75JR&aJ@$XTv}NeAqtk9*)1RT! zj=uWb-wq6Yb#&Ja7u8^ujkeKm*-@|Y;=KwTb@bH_I-OOauii;^)KA^op+ZN!{&m^F zsZh}y*+@q_z3WVWLOUHzbw5*iUwx4-M{E84kRY1kZLIF1{~GB^=%S;SUhLU`&`U>0 zodtNwYh81B|0174qCKg-?5m@@UKl7JOR~HEt3xiuc5|U~dGYE-`k+@%ghsk&be6pD zXiaFRqp3d8&5_VlM{C`|uK}U8jz;=8U0XsU9qshVCoBlFB6`sVe5^sHat>)2PI|9DQ}P(?ep) zINIrGszkT)M z^Z#)4)zMDZwe7^wPDfL{>1P#3QyuN}s~WBx?Q}HN*Q;uBG}ZC?Jk{tGLpvQ!b)U_9 z7@F#6ryslH$Iwnk3q9<(3;ob#>PGt3v5nN{P5-^0BJXJnugi@I9d-28k0rPg`s(Pe zpF8GA=&qxq{@|Mp^{U@Y-AErC??-5)qn+NUhe}?v?pHU}XB_b+G}X~sZ`IYE&{{_$ z{e5`|p^=Vuy4Adgy)?5}N9U{`-`A9fJw2b@bAwzH3bArK6+n;~7losH3m$ zb1i@{bBT_6!+vgrj=E}>4V)}OFMZ9LTFNLBPn!FhtNZFjHysIm^&4Fe6W%{an={tjea`e(2I@BYL@+yvwy5?LJ9c=fC zqpyxGddcF499{JN+5_p--DmvqmX_*{dWl&TM@Jofb)SvbIQr`7u5Zyk&Cy*)NBu-< zF-J#z_L8BL(OZwuNJl$;>X6SI?Q}HNcU*kT(Nsrk{n~^-9IbUU(&a2Hp^=Vudf#vp zLOUHzb@@6-XsV;Np5Dfk&{{_${Yj!TrO8G*+UabsEybtL;;nY2(9kLidVXuIy0vb8 z)t1m&Mt#wOPV?t{kz4TVyEa|)KrK6+%_qi>hqmI5hc3aR_M>`#} zl*YeTs+;P=_vjFs>S(7|eZ0@nPDfMy+uctbO?9->>s~&?TO84)u3!2|6IbDtRdvS(P?=aHkej&}O4 zv|NUEI-2VB?r&#ks-uyUOMKp&`U=beYUkZH8kC# z?xlCUDtBt07pS}FHV^Ak4c{bnFWq63J)xKWf9N{%u$-RvkBf*DDY8VA5{VSib7n?V zmdKWU->v9sJK6W0h%6B`r#VQrr0kMC`@V!M;dkH1_guf}bLqdi?(2Qdb5A_a zd7pb`Ubn+^V0%8T$UX$P(qVh!ne&fItOxMYk%fM2HPp|7;;6R0u}B>Td$56#j_mZ& zSF12&r{|1u6OD@~Z2qrHG(5Vj7~RB=*>!$Jk&7OZ-Uxb!7i7pww;2zAOW>s=7rnsC z77WkBBQO0(r)CU!>BvRj^no$tqT?AcyD8Ne^3szZmlVJ5T%yQDM_&5+3)T#I>BvZL zRj?aHMmjRj;r|bP-a7YsE;7fA*X+3Cna_b+^oA`2ZE>D^+YC^FKK zh5o(zV~Q+vWTbmn`azMA{?O`I!pV{53|Z*NNUuE0g3T`aP3NCSb}7n`e~w)A2@Bv% zI&jhDcT8lbBPRjb>Bva07*vEIBOUqYQCH2_Nwa93i++E;Ig4AiQRk(%D-XXpz)MGt zy7!X;3_0q^KOb~0ha&$Rx#;|K4n;0H^3v-xHDkz2M~?b}2frzD)RBw6@ckE3XKN9L zymazyG(}!Ive2&%K1`8?j*Rp=^Pf;;q$3Nx%<=^tA(BnZZTxnO2%17aiH@-A_9+WT*c)b2A|&umr0$ zV#q~LSWU!u*COmEaM6*S&UguZ-3VFe zJKE)E$U;X(dawNj88Xt5h2CdEB0&~9GSW9645Y|NZ*a3dn=*0*MgBQ*(QOW$q{u}_ z{`umx#}xVJ$VGSR@S7qRJ*`hD8{WSNtVzz*x#%kf6=BFlNB;RBt1OEAbL67;IC+#J z7rp(BvCM0%KSlmIGS9c~_o2uta(GQ&&GS87o?)bYALnb-0%4=pW9C7r8l&#%aE6job&g;d>L}ikxyR9vI;{!IdaRDf2%O$mLtzRqL({Eo;fnl z{R+4YQ`y`S2bGoO5KD7yC*XGR%>4 zo;a5=gL591SeGH^99igN&(ve(uN~9b=KfVZ8M4ihc|NbF7enSb^32cp)Mv;uN6z{C ze+YZ}@u|)~Z?MaUbp!r6vd#TnYcgb;zXj&`k?1PyGBD4PNnW5&2ty`0vdXvr+nyn- z92w?oYjkE-3#raI_cLz~JjZ6_7jVvxHSNNjcev>+^a>R^GGw8521fe&10f6<>Bvr> zD_S#Tr$={!f71yqai6))D(^cvfFY}V%AVt_UHK-gf8Rem^SJ|q81l@Kd0wwwFhk}! zvd~=*v}DLaM@G7OGl(H09hu}Yn;S7?l1F_@W*=WQVavXhBuO97vNLl7S*<=5b1uyntSNn zaoIgHh(y|6hpQ-^3O*;vS$YWd|$T=@krwl{RIdaRpji~@{kX!CEC!S68D#^wH&m1}DSIz_X2{`9dD#Wqj?zX`8 zT|mMg#j~yr?N|VC(UEhWVFr8^;GA!|d{qCbZEVL%HTahx=lt!@KIWo^R&7NiSTSSmm zzR1m=ZD+Oh-@vCU8Zcy-BisD&+5mQ<(|u*t>o|74O8~R|AOHM@sWJPU{ZK(hI`EPh zGSZP@ZoW8>A;TPhSCbn0GlO$prf2{|&N;HsVQrF?J(;Pq%FnbhF=Uk^&pb22ml-_s za(n7AdOea7+u z|NPFT6Uf(P?=~J$ka_<2Hetv-M{aqST3!sf<;XL)3#!8gmZ+k0&RsruGvu5j|9tcs zPlo(+`f&6p( zM0bY#bL66*I8v1%7ack0$Ui~OIr7W{?>1q`Ge^$(1rL9QoO9%#yI2LV3wtj(9kvvIp@ei56)@BVw)Y*S>?#pc@7L@WSGBO=F5;_ z{-y*xBaTq$%eYbTTAR#@eJ1R}|M=%YUJV%X&(kt4vYT21b_e)8r^h8S;DE4)UvDYM zJomd$n<4WYx#d{PMQ%Cr%zcCFFyxsd=e%fdAGQ^~r^r9wqt%8zB9nA3`k`Ik47upY zIoGz>2=6PXSiy`wIdFI`^z&?54nIq@CzbS|z=N$RxR_B8l^3T01 zC$ON57OWd^&XH$+g|uhLGe^$(KW=Rpa?YCo|GeV1HVpaa$T|PLtQ|wnIkL)&T6Jc3 zzAx7q=7T@CXUH%|wz+mUgdy7;`RDlm{M-Nd=hrK@V8}m5MtZmNEg3S>k!>Enun9x9 zIWo@!#sx8Co+HovpaOp%;F%-m{Qi*I3_0h>KQDWs4nzJqGR!aTC#)j;yCCQM<^#qI z&bjgXi7fOOwE;sGdbee#Sn{wctP?QIk!>!1xiDm#BlCRJz$y%x=g2}&u&ByvEPkpW z+dL!1i6Pq@ndivsK;}8J%{RrAW5_liQUreg7nNfZdM(yD=fg^tWym>4hWX0ol^HV3 zk!`;Gd^I+4YrM`pZ!p}QA@dwr=s$E97h>4&yibh6XU^{1A^#k?=#R?QVaP>C&UwW38Y~t#=g2UBTB#~ShB@_wea2&}u-3pi_Xo~-haeX? z(^Euepa*p8{~skzu~AS7Y|$J|*Sq9AOm)H)c`r+m6ihRWJS7&$yxlS?D!W;H(F* z(2-|8w}d}Ko_X`aM;S2n*m&TaBmeyKi6#vB=g2Vc+O0A}hB>m$H%)M1$TmmjIq*ba zuTx=yEcERzF5ugm>umFPPwF#dnPA?F&;`Ke-+8S>AOi;id8k&ABiJ5)s3y0QVD&N{2S zQ1xQWt9V(RVLsHM5JQGJvdtqc3NmDyBmex&Ln~(R&mUwJU^h1u&>87HP5^Tf80p9= z_w@KpkyVZi^N*LZDKgBFZNBUECyH!yAg zYfTmh)|6n#NJpM|yWf@A{TtnN&UqKxN(?#YHfu);-xd{_Bk<3=9d0kY;;OKgu+OZ) z%obuw{;Dh(IOoVe@8|*y9N?cL+nf)qz>sZTEU}w7W?h+82Ie`k&8PP&#*l4}%=470 z_6(Wl$Tn~4V8M`Wj?8o12b6qdvd%Vd`tUnNwmCA-7pH!s$UH~3`3_$ThHP_Wo)=w{ zk0JB?6R^#ZEpRcTiq1S==2wP!H*nTD=j%IFV#qm1p850J`5E%ek#ipK)RH0R9Qo%B z2ih{^pCjAc+&qgS+Z>taj_03HWS%#;IYsoF@|La!wmCA-yX|>Kk$H}6^9TJ4F=U$~ z^Sqns2Sw&Nvdw+B+AzQ3KJ+ax&kHUBwoj`XI@`R&NJoZjb7Y<$-2s0eV4fq}{LWS< zhHUd$ExLAB812Z|3v&N(v7Px|^2WSAq{+!A_2A=@08=hrq*CdfQT7W%xI z<^);j$Srr@y_?Le(^u!2kNx$AAkQ2*=WC}Fp~yK$p82O6CkXP)6BkSo$*;2%WR)Ys z+!wirQ{&SDIi#XtCm;bd8H>ht9-_}ZS=PGOlOz}FWE)!Z+)(_%I8(xMUhpG4D*}cw^3x6BddJfT8RkppPo>B(m-hoB!+cz9H;N2%mzr^oD}$SN;)Zy(#0 zaDyU;9Qous!&HiVa^#k0y2erDmOCaNWQ!YJrN}c!4mq=4Ly<$?bZHbjWxIrqo_w6W zoPK}>tT;fCTaG;QjiHGYdFIF@AKs%pMJBo52-yF0s50FEta4AmxjvVr1mr7COkhj~jR$PRha+j)h*SX?* zT9hZq6-VB9h{Fa2dE>|=A6Y6%x!AcUTQPU3u+5B6kROhWaV34df{bww{|HgS#*Vl& zQFIP@^oO#*glnL4!XK_}O^_3Qy4+&1bz@snsxGjE-YyrTD^4RL3i;{0@uhvH5#)^{ zC)~2hQi7atWQp5EE+-jX|FFdCG+RxOC62uD`e~a9^2U)9jvC~IBTM|8<5pt3;}1*x zVDfB&EOF$G-zyE*ZtS4*!_W8cMvxzlTyftX(+Tznko#WAJz{)Z<5}G3V37)3Ai1}i z+%IYEPtK}uX)Wlz#kqRwVLi&|owvEW1}wTx;@Z(RO6J7luwSC97<}qVt{zEp?apqjAv4FkE zx%x55{gvc?aQNlzTGDy&C0SZ*mW~#RX3@@`#9*Z`LWZtDI-^#x)Sf-n7ou=j$%i5RCq4 za$h{Tca_t!lfW$Z6=z59SLB{_axW^mui3hP&$2sBYKjKgdzCRgPBGEWL%_L1{ax7T z`6c)HlKbMx{ea~DR&ozDxwqP~32Cg#DKF8`A6VsZ#>1(8E$Ev$BUe8%xlftgqfPGV zCii+fG5#{MpXDvGM_pFresFSMGr69FJu8ixZ3+0^bv)XNxxn`hzo(DpH)r@gmEYy@ zJ8RSf<#!*sChXb+)*yOxWKZC`*&n_~O;5IEkKlVGzt_v}`*NLGuGP!+{6UkBvuW$P zFo!2s6uIUv*AwKr3VvUVdJBGEeu{Pszc2XzJmP9chX2p;ERRu7kn0R`ZB4GZ$+aE1 z=7Zn;1$&z@{O;rTvAb_;hTli*#b(qZ)F?+)%;ZU^5T{Qqx7>oNTQFV~mkx}{v}!0(Y!kCkhcat#x|`}_6-a}U1z z_}$#S(2wDF6TkaLZAz|x%Ih8SItc!5v|QJi;qQjLej(TB@cUxa?(q9!x><|i_XYo- z`>ge1`2Sq4U&(bXxqc|u74xbS%5^{d9r)3$2D^EEum0WiYwHQ?J2P_C#PGXm)XL;~ zj$G%F->LEU1f!C*T>wg(Y9I@ymNA;Q7J$M{ij5T_Fhv zVeJmj5;m+lJfZ9v!5Y25?NpX$g1+5YG&LF7aB=!HRXpM z0kTGp%lDDv_*t_Q55;|zoq}VR-@(d&EjvuI{>98O+V!^mlmkn?`O3M;dO0rlXOa81 z)VZ};TxvQ?-IrXStuC=i*x4*sXO*Pr!J)s>Gh|&Zn0dVz z0q5)0s(o{)TU?yDymW->?evu1u{tJ1y*cWZ5f5qAfLL)DSUF!q@6c7<4+`^V3ssxR z*>p)uA-0qrrrLB&rAv>fqIR2E>aMBhDV(Vkbq|E8PwU51PtOwq7$WKja)govnt(n^ z>e1W#X}zEE;@7*mYO$6{bkc{@qF~*D>X1phfE$t|)QQtn$2ME(KNiVi-NnADP*>8a zJI;v>Whbl2LzdD$RnLk@vzclmbv~{3I#GQ4I!pcM?0TB>>!Jv4*Gv7edk%fMKSj(9 z9ZWFCBk0G2m&B;4W7I*B1E^2;G!a;8irOKu3vJlsg2*zPuBIf9 zrRSer7b|9VRv#DaL}zN(#G0)m)cgs-bXtK7(buwrYMSXs9p0piS=WZD1B%z7fr&ST z$!)B<@3b2=O}#2^mztms-qL_3w!bI7Z4FW9tahWGZSF#kj8L^}q4KoZ<4kd`YAf~i zIvZ;H@u65*ZGbx9wK-k%_JOEr8m2x>drySvj#%wGQVrZ(oMs$;CV(ZSo<8)MtiAD6 z??cqj`5q~J_O+U3^bvah1*$o1qsWpmAH=dlUDUSqmyuCww&*yvq1s^g0&<~xwwUs`gWCV{0OB0+ zMU?5@L#5}uNiprc{<(hX|B#hSehRmrOnnYKZRc`7#r8sN)doFlliEpUnz}+!?SNxE zf2EnW#MDZC1srL$ubBpnBz0A*y-JG>Ib!UvE^3v~UrN1m=Gp>>dg`5^vcz(Sxdwag z)Qlcil>W&U8uZgshXG@A_W=uS^WrAzgZ|r;Qp+v0^ARmoznBlE>66X1!P7!i+udqYrmzo;ADUrI~ADB(bn4R%O2`5oAb(mt=8J1M}F!s=$W#3g|#NO zH&z|@?({9R-cswiteF~cevm1CfsN)6T1}0D=bFcC8*QUKRb8(HC|*76v={GO)s6#W z6|1gxT6mDJS{wQoJnLwu9geN94z1kf*!9UaTKgUT>Qc`__13xAYg5CW)k&3Nl#(!x z9$ZJY2DX3P<1$*QiWSutmkug3o|MtnZmOk51oz|s)piTxeE$h_(?(@kt8akE zZffMFMNX`s#y|2?62`l04JTNtyG}gw>#T?Wb?gdS(C@y!bgsdMjDQ)JEUat*a%DX;j9WlNO|7%$NBs~P)Tb&a7%O^rYcH5Kx~ zYty`os+lm(OD}8WdC7B;^O18%tJO$b_2V%gJY!+5d@$bUfW8D7JJzf)X#%pnotKr`wFTJdh=Pu7z&PUE+drWU_##NQu zEDOz*55_w@OykkOYn3&Dkps1;{IPuAh~5g0-J6`_pLUq*8bcod@%&}dcqhmouf1Y_ zlW&3i^U}*2dG7Lj<$UBE*r%b|4X^#Y(u&Tx^1*oi=o38RXg)>OZ22)#YwWol%E!UV zHW)wca)eg|PPnY!3h^&9IWGqJf6p4KY06pt9rBm;@*L%PO_urt%6$@VEZ!ze=?=V_emsCsTtIWCt z?G;b1wNy`!c4F1H9}>WyQQIH4Ww-u4C>oRuRu}t~V1<_)6{n`#s0ZG`-sQou;<|s3 znl=O4V@xt$XqW)xQYwuN&IUT1Y5^8IBLy7X^EUP5kAvg-Sl`dZSI&RT6OVN-CHl9cQ0NQ^%mw=t2UWV_vTy?d)NA? zyZt6oue~?LlNI^Y4=$l}<A}wyZK*;DjpyB z!#FGIIO4g8nBk_L{bWwxeS9N;9mHGQ`9OOA^G3KHa#7DaWs=!0SMNIuCd>8D0+gZ~w_lx3EMJ>xY*JaZ+`hhK!Y^~Jew$nTozjOqdTOp+jULQ_)vp@mlCrJdTkQ#Dfgo~1S{GNs7RFh@llHXxXTE0QN2OS87j4ttXkItlhTMd4G4&nq)Zv}dFThRvm9U4mX;O?t z!nkgkmwX-Ujm-MjT}$1!lP?P>O6r2=dAsT{Up?fhQV4vAyS9~2u`W!4V2r^S?CSyGb4Bf=ru3j2jh+B zpX1G8UzV)FXY|OdMZ6xIx7Wwd;CU2qTGtqQ*<;|fhDXXvFKgsE=9Q0}Ln?TTE9Ue0 ztB+4}<%6D~$^gNqZaJ>V8hkF-w4cMXoE|7WVH|Sm7{3U8A7s7kF)(g;q`dU9MxMJo z-~Zm<$N{~@n~@hDXXvFKgtv%k!1&6E|PT5 zFr)KUejWA^$$HsiVBGLX82_7I*2r_0=PTb|&S4vPjMuCB@e9c!S3c+&V11Bp0zSN~ z!RPh9_-;Hu>}|twAD>nHIJ|4fdf8)O-0(1B;PcX_`5y}ywIdXIj0+VMRW2Xp09 zAL8?uE#(hWmgyeG(4Y_TXwsC=ud-A3FgJFG^Qw>LDY9PnIkNx3YyYN~HS*l$`O5c~ z`#~RGyItpPo@x@vUWRNJnay|e1MdP@+xENlc*je1m}a|Myj{MX*Bw`fjUO2;ww-$( z7v92!jfJ`yKeUA}%&yGNZj906&GVOJ&AP{kduulFF$e6}{h7z~cuehrY5AZrf+n+oqiq&7i7mqwhp~kMq9r+fzGA2cMyDsDQ z*_)~7(Muw8)#JEc&m-uk*_T9!)ly#BDS}R&d`*w9?mUY=YIRNEZ)~;2GwJ14>3aNI zpW(EtYr0sKv4DR#JCvFN@96QKz8&ea@^{41lk@ny742#L5fAkErUia@4d?eGy1x*+*39JnmzAL3d%o4< za|-_^djj5yGgGJYX}f=r(3x3!e2?=Tayl$aT)Q}hKRA?5{GNQ(<7;jUl5***@VGyL zpAO?BWX3N&J|TDqu^stKjE)}5_uSq>2D#+dFrT%`5|U9NzjkEeNS=It0U2mpP;>78 zAa3{RNo0t1LG4q}FrN8o42d->tj8y1^&zK!T4?RMhVgOGAE(=MOFf>@p*2Z(VyUgD zHh>4k1(9-Rto3-lEdkJr*;>1n-J3I8MmDXr(c`oQA=lQ}XmyJ8;F%xl5K})pJ??<# z_WRmtqi=TR(~~?&BzPOlr}t=YeVnkfJ#Pi)KIC{6@Hwbyc-@nP!Z>GC8=iQvS}uLe zRtH^EaDEN)8OGgax8Rva+{oiWj(R+_S9RhB{%1qmAfCFTUe?H;D}NSxA^hB}=j?KQF2)m1c<{TwixF9aJ_Pk{=Zg~@=Pa(u zp)R9q3_ZpT|AyDfzV2^&StHL;o|l}DoCEqL%x7gr(OmgpJg~b9kLqthWDWWd)YrIe zL2$fbSS9{2ynwDT^txC1pRdDf4NsVtUe?HSm;XL;K5`D|g)pC)uM6bL2YuROTAoLb z`K|jgLxVm9$LD|i*6Td9Wf|V?cDC;84882@{_FStrk6GH+~xVo`N%n-7s7l#KaU3VTEY7FTey(c_z3i#*TG{XYO)qQYx#QTFubhvZ19~CM z=X#~*x$?odOHNUqe*S^(#|#bnB^>V$c%XZve#sVmDfAna^|GhJxZw%W!~9JzYvj4h zf1m%}-^c;I5RMNArsv8B<4Ly*@M$YA>we78pbx?EaCo1>+DnmkzvEMGo!2#n9yNxi zlKoy@dRZgSU7oL;kDLSgCCrCI|33Nt=#kEk&5obvm#BL-LxX+{pOs6mstVSZI(K~; zZ(aPT?%52z?CbFUhTqFeFKgtv=arAVrw(gV#$G$DO*uh7UaU=_fAcS~KtcbO)h<#% zeSlzX$`|}wGw2P7{;fXLrfxkdNU%2bzE-p-H*Tgf^-E>8bK4;?4}K4@HkH&ZMkK>p z(4hTx3^+o<^x2GTds~3L2skFLLyxsI@Nbo%HgyGl589dD&{JwUNp{&k|`=m2={y=O@Lx)qdLK z#5v(}X_$ik?R>=)(X8Qn#p?7%Y6Jdl4D)_u~VEttA@j7~KDiPi_t-4gu z{hNp8qH$9I{g3cWrfFx39UiV)Cp^u=W);IYMc+-G+pN_j_Hoh~mAplJ4v9{^$v1 z4=HOfZrn%K$ni>0H%nf;ND0ldCU?LS)_HEO?3h@AU=7WE%RFWOJ4@Z;E&K*Ga=UW+ z7(W-i;(tA)p^@(+Yh;fq=PB#a%Y9!mTe-a3f)s>t_rd(p$L6J%HS*l$`O5joIiP=g z5;a&!fb#?L{W0!V?3Sr_?LR)#(4cpkJ-@H=+2K!ZFf!_rX#$)zll8I>#5m@UJ{IGD z)5{up?s?@S=YT%5PIOnrx%r>kpmBeUyEQpyx@YspXBryxPM^}+Dh(#w*L~fy&=aP_ zvDvy8HT1F%lzl8-`!~I;k>@VYSI$Sy0sY&G1I?93;pw^ZafbN7LUE?T>O0*-8XELY z?O^Xi)nk`+Uzfe@fax-LJXtUMK)gTx{n5u_{BL?$BhOu)?|<)ay*`^wzmn5+jiHylDEdRpAAKxdYv|=U%AYIW zAHCU-?CQ!d=Rb8n<64X#gI-9lh?DP+@oX{2RO0qYMb@A{T-dL;vSrE+-9s++ z9ck(r6{~9uz3ek(kBT1B(93g_KNr_7jk5{3r_MOP5S_kR%z8AQ;GQ~MyX?KJ8Ns#7 z_gi;}BBe(X+*3EnZI}32H;|mW2{Q73Hh&l+JVE z;_l;mWL>3~6ppxwQVV*Ldm*Xx{60;Lu=636CS0KnV^4}F;72z2#?y=Dr^Lk&Z?a*w zpfBE?7UTDHA{EE(qTKVW=sn$&9DE!_?-ooJB^tITqheRmAwCzx=K~((-+*;A^yfvf zGrbL2vt0{5Z4ztk*oeev}U_|!UuYWFP-5==hVJ0 zye>GBHvf20@61ebUNj&{({1RbLyyGiZw_Sgta9|^p=V-kAR|}9Ka+*SpNq~_%aWA) z=5*}o*TUVoHhO^P6LmGm5m~%n2#c8l^rRkX{0~T7AwDd zllj2O+2He4?7VJ68qqCe&f=e<8l1PDIKMCP%=#%za8@;W#~c!U%1k?1&4XOqV&<7i5Kh>YcbA|%*;Hi;M!$$v3w+BOi_aS!7BVJ zN4CIOU0l1IG2y$i!_%C+?QW;V!WsJh&^LJ@tX<;yDaKF|B@83#(u}66c9&F^fiwZ0AQs1u?1-)T6uHL2K+T}Laa|-MAMBiKG5BIZs zy-mTj%j6k}%5PZPBCyYDW5b{P*E<;+^aJZIK2kc=f^+>a zj_Pqtx&8B+J~ra`ELLvcQ9LWH*4GWMsE3qglhShOWiNsEk$ukJ^s+|wayXWAGxCvh zK%dYD)>PMdEzgw?#=n=@ryPd&eOZIgU)X1&SOhH5*9~Lf@A{=~lCClIvX{VXWuNmm zy{wVvj$>oKaz1hn=mB6qjMAswf?WAvJmb?A#bt%2`w&Be&)+U%Pbx?IhwI)Tf5>{} z4!mE$+Rx0D5Bdk_ai;tlepvS*hDLuz zA3m&{fcJSEXVzG%6u%g)`x!%zal=csJo;BaC*Sic2KBHg0+o{yI8?Ji~@8`3WLVLF98bdGpjsN-_Lod%!{#^O~=mBiu zd;H61V6M-?ci5+w0gK^|De|Z?8*Sic2`VFiXRe0J=_bQ*NcTl>1ovUjM zz3gXXpM%#LdU=lWyySD2C6})j#@S5V!(aH`Qu5v1#B5>z|F(k*$T&O7w2xcFpiT=( zquIc8%h)D5bPp%*Yt>-(C3lIOIrB)@)#X@i*xMhoVHWJIuD}Ym*ejZbhm%dKE%h2# z)uS`W_(IS#yW2s5+^Kv2X49`eF=A8NG?LvThnDw`75+FaIhM9`#RWZHnGv}&UZ;$r(zqyQgF zJ4L4mp95jUzSeZ=&^1le7&x5tjP62j?Y|_PG6#_1%LdR&ldp=C0|yiAFB_V0O<0%e zOROS;>CWRfh12+fWZFJATHsZ>@T%97&@Z*=_Ih_j{P@1)#q{FTzSUh(A*?I$eB(ez zzkZ;5uz4HblW*@HiXt0365p%lG~cr)B6>krvSWP`nR@N1@H*a>L_NDpKDfWqHEkU> zkfy(1i3%TEk>OFXWOBlL5xT!EF%S8N=ji$WO(->`zg4LLm7DTqz&e>keEIve79@DFA!m3r05}U&_AUa)wXh4$i#9}%NooBF|CcjzBYIsi-R)H+Ko=rJKvf_s>7 zPdo7E$-Xwzl;*H^9sTE`n5DjzVNbhjM=#P1z6-ejoPDWHhBhg56!)%|fSOSK+70zR z>T7|qou6edb<;J;*=Fk;ib4I_z&Jyh|N@FM34Ts-*kuPoB6( z-5P3R3!;1!+)wUW&V>{&l~E7&q-);-9m$3uUwzN{?CO=snTdUTaWDFlapg$DFrwhT z@d_U02_L`J7x$bOf%UqGaHjad-g4NxP9l}FzPRW7Gpx~NK^+kHhnJ{dlAP%Cz!&$H zS9n*93@~HLY}i9Sw3Q8M{r$Bs?k&fDWTST~z)-58UF>B=&R757i{sDjEXXrjFIOD* zTKDf=m|P0T^2Kr4ao~|!*48zKUiLP!M!pvJbpr#IO!&`zFmBoIx3a0cry^^LTA8%Y zqwqd!^2M?HuXjqFoGQBCFyi=} zU1#}0`2;!W-T>;!;mOXr#?b5W|M?cYkKuXp(#sk-e>rD4A2|nn)`!%1p)BtHIafZq z2Y@vqvpbHu-!L@zoSgyt=5~V~$IiuWDNa%4{&hr+;=|=WWcR@< zG;`cx(d*=7qV&2+PwzP@=7shoC+c&0Dj-hJ&BOjU1um9o|Gq16{$~fR`6NM%updhf zjM+og$H&E+@J^(pWdtqU<)l~(Ea9F$t7u}ABoSY%JuwTNN{>XH7PAKrBcltXuon6suME8f+p#!E|7eU>ckk4<6)07oA#LiMZN%jB-TE-zmlzkLHn%cc1-j!~P zh^AdhYPkaR=$Cuq(1ZqLalI4d?eqI$^2ClLa>Y$@ru<_u*^CkI6U&MD_s2Rj#H!O? zG9luHD7Dr^I*n>ioIAc0i!QYy^%l+`=AGY(hZXCRmNTr#So8N{e1TxHKAMuG{-4G8 zW8NeL-oe8@e-;~En*xY4M;R0OLs+-+Bw9qO>3R7aF|Sh~x&LH^BJ!JQ*mKrn+_?Aw zUS=BRcEizJx!`TCjTl;$BtKVpYzK2~E!?|#)r0lwceT(O0yo$1(LDZRjDKz|CSv&@Ftcg z!5DjXn{L+U_nwu}e0tdszxoGwCm3VRXX-#7-Z{!aJD+Vu0-r_lB6}RPowknTc0YHX zG15^3-Vs?nYzuEX!coJ0NwyU$@`z?mnwNbclGT?<*0tvtLjms`R35Uh87 zz4$A>!|fW{gtPCJ@iS*}TNrP2wjh@2pW>&1S1EV>g))59G>+qWuexaW8CmCc&+Sh{-&2T@*L&A!+-B@q6zE!guX=Y#Q(;+K`7=VIbz4L*On z6g{kjz&<}5<8!}A|0rE!=w<(a*UH}JZ+clH&poevVd*J{Obq7%n4oMBR4cAKYb3_ZpT52Jez$=m!*FKgtv%k!1< zk#j(AQ0~Z5C2?cfT>0QWB7e{AO7CgY<7Ewc4BM--mENbVIF4g}ty0FT1LI}A>|tbY zlb2rB$a9zfKJxvKoL;H#7n(WDlkNPtN?#8;Z}NgZBJ0HD9fe8bl}^k|Td%KiVDHY+ zhc}BBi3Q1iPg~ac{uXhuN(1tX+pz)JJH*fA0_557{4CCCm+0M|5j?-Pv3iu)bJdLO zF7u2!w%RK`&s0dOaxdw|Mh67;4r{mK0(I+oP|S;|N35b#>129D%z!gD8=l0_Ld|0Z z^yej0N*|@OipC54{kKiuKz~_tF}@Pi5?r^?!Uu$i*^{M|t38j7*s1By;td-Y(jGMv z#f-J@l;16e)7oWDiLJm+b_3R1r=@2^X4EUC-?3J7%}}Vr055qG^k9Db0uCGib2{{) zH?62%5a%m!=B^&Lr9WxIh}yTLRZaszHCj*zmhzopw`scy$BW~ANb`9 zikVrsqMdmww!#^#FU!s-kqbVF8L;+ZW--He@ykyFpWOmDApG-pfqnYsZ}H=80)B{y z&DP}JkxB8s3Hh{`N5_@0yNCGWjC`7FswFvpu`dtIDWKVYR+T$--tjwj=30D?1sRoe zfIslI&@vw%Q!Zp%slx*;v=-G1lJ!k*^W7a`ztES%%JBT<)bD*QwTGSalOADTc#BYL zZ5^C}7&*0)>OR6+Uqk8On_oTF-$n}qzEp^rv+5pZgJ;8)p$*K{uoiY&GVodVm#d`C zXa!?ftBEu#ppJ2}*WAnPP-+h^ug1anBdp0}{P@jlzJUEg)wd{~$4aY_&&z00=bkH9 z;hCF|yIHI5qaC&HGwv!`)1UA+!A_cO z{T0f9-i6f%&7Cy&2RD`A+jsZ~;-ZZN26Lec1=L8zMMI`S$enBaNmDn?-*2HZ)B88? z31i&5HRIexUS^WJwyyPD<=EJ4ejWUYH}H~Mbvw(~f+zXjdzRwY@V!39ckO;~HcyVD z_vkWengV-DbiaXr|F4JCTzc7`;MmZ}*P^dzf97AM)|AX#_rbUV>*UpoALX(Jy-KMU z|0pR7ZtK3H&w+!A|B!>a#?Z??1g|xG5nlT@y{ySAXE`4^2lN%Ei-syU`L$g6U>x5) z3%-itvId{&vugHMe!aNJ@qD^JFn~)p-KlE~z3fkP-|{~nm6u-D$a9zHE9WEUfZijp zO=o3G_L*Gypx+34zFBFzb2FDU_)Nc33mAS?PUwEadEh!_YW{Ux)}zMoCwQ&luQ2{M zy{wVvF36w40rx$?nyv!oSD!|5xytihT?yRi+Gb$w%WzcJEji4t~i zv92-nvOmFV4S$94zv*R-Ja>7%az1hn=qpODH7VDY?ah^s?nz*e+)^@+%Nl&9r>I`a zkS#lOzY+3trh?~fWWDT9FmCuOjQ>q9Yvj4h^ZoDrjU3Qd;J(U9aK=@>KgK^FnWWr+ zbB3}8pXs=-GV#|c-EZ`d8KD$-@sF-C^s+y}YYl&e@xSS1jXd|f@{w~uU-9@sS><0i zLnYrIJxT140ZPB^{kg0`4}<$2V~Wh?SceH-+fMnO)|Sh9*(1r`DKEXOk>{RQKKahC z(9g9UcvFMTvs@`+-pyBn+d$uom1{+x@2}&4KgU2O?sSW+OQ^H zHwoxZrv#cxu=6?F_4uzEW-Nv65K(lxa&4L!J6(5==wtUTZpYHc^x&91Vr7#lN|^5x zTCMYbJwErxIr@F&esR6j1Z8sMd79PfupUqFIY{>|KP+4yk5TeHKS;-V$LVp);_K+r zusDJLcB{^=qhlW=2xpHEao!#0(D$W;*g0*e^3E=tHVr$e#~Tg_r5iWEUYeGnN~@1y z)c3||J#Kp>h>j|BMl|ZxUzz9MoL*9r_4vXB5BhvyvcTWfer;>gIr~!e__3rCH0MUD zNXqG^eClgQ_p__QxlvYJzDe)N-2PXE`Gro(^~5aVlrLS6J61nVaDO%aoA!WyVCMPn z>hXk^OUNddyJF$M*2+Nt<)lR0Og--Lsu7tpGE=<%H&{{j29p9`pXu>b=BHv>rdhcFm-w)PL7W| z@?DQdE?UW_oc=Cw|Jx%tV>x$QJ`MFw`m^ zJ^uN%Ne$^|t&R3`Q+#^XR*Uwr(c?>>E9x~EW1rlSlj^AH&F%E~#fiRZk6=43=eDC# z+}~S$SIJ(>9Ge~I(5wzH#q70qZ^|jRylSc=!2e+UO;Jzv9~f_d+Ig6HwOsKj(Xba9 zG;KRo%cX%HmD(Msqx;URtOksQGyb57-BDT12V)8~?3NEIs7G5k>GAQE9o11Vo&36@KF)sg%2f72etm3ss{eW| zLnGfu*2r=B{^(oqvwkHP$n{xIAUI84H(nrrvepb&a7%jp2XrK8An8_}}!hMxMJoUpXH+ z2lO_W&y1kBT=`%;{6vJQ4KPh)4SELDw}N*f95;D1&$Rd69$jPTF>ZJ;yw>n7%az1hn=xs2c`9pW-$_L|Tr%pF@3EakI4SFZkR|9SW`lbEn2AMMLR_Pi;FMBZA zo8_gKHS*l$`O5i_Gb;u3AXc%yg#KzIMnZk5?$|wI*W(R5 z6#P}?#s|djy}(LZb%9P_wO=G(SjVS;zbe3vhyzEg)FaPgsMm_aV(hgwyv)mkbg5Om z=nl^xkBkkp)ZjQ#BjS;WW%MQK+ef)V>{t z)5;r9iZ3b4_{=Y1v|q#-G5DsrnsmGs{Q>^U{>W0UHf~OTyi6AOT)ObWn+_Y4EY2h> z=Bqo_q_soR#QEp>)ON+o&{;QA#n{sed6hwS^kMo{@iy}(uR?wj>j78As(tf$g9}-t zTSU5O`RN;PP%?!)0RBMZ*txvgfL) z!9Q=e(*0HNu_3$#t)#w!`cl}mD|{935Yb=lJ2!|gEm=bihWb)+L@FOvy^^{T{1q}o zK6%vE>q}L(C-YX(PHLIHHkwEOUi?j$I(mI+&XF_x)|raBzgjr98;>dOt=E@2>`3J8 z9m?zeDkZQJAM?A0iuI+KSdA|Ro)>y8j}Gnlh0LnC{FNNXx|8i$&duuDs_3tVxU}Zi zT31#lK;3Cr`ca++bu;u=DL%n`zg8j7`(QmP^+gPyU|m@ET~_8zxn0jPzXE_{D@`D%PpG00+h@?F&Z__URDe zWq}d)Uq5EV|LgaR`=duXYQ3G0TMKnU7=wT2n}8jLKE%G_W?nJ!xn6?;|ICx3|M)R{ zuAxtpeI4ozjeH+jlUHuCUjAJ4KTnIT=ZB6w%#{OrC-Ck3#pa*72QxId*T}!pYJTrg z2FEclmU$9ecz58l z2LJJ9h6eq{FaISxq0&X&3&DE?zjffL?#&Fn?49sFm=AhCjQ>q9Yvj+BKMQL|soo2C zdaE)C>&g)4Lz%cwPzKU-;;WH+7Anmpu}CC(IK)US4`x zBhOKumz7M6PiY-U~BkN_4 zg!jk%(c@wKZ+clH&t0DHfA4SPfZhg~Ezs92*ZnaL?`}L|!5D5H_rYObwJ=h{feQBu{O|WB!c1DUiGyhdH9u;KFd6%$o4OZ3n1z3&b zeZXuSqh=I(OWj-V6@B{!sWTj3(yFP4bO!i|m@Aa`Iw-Q2HCC$}NTr?j9@Tl>AN@JC z4UQFUuLP(E9FEfRJynr(DNG$Qb_caA&c(BQ4b`w}Tj=$tz`7hXQ0-w8LCqsIG10TW zn!0r%y%Urq-u>>Yt{5|wo-TVz+#E*K1)ayzd`r#=ZB8$BOF%E`KK!g0ywO*Mz5ldv zN{VRb*j)wAHH}HQAkNa+XzIZOuO1Y}3 z1!|C0UEYbiPK{Indv4C3eJiT9cUCVbXO#{EKZ{ZE4b`V~gR=J3CvkjcMRo0o5=!Ac zKSYr>_0_JYu9$iU{t#_r%B#%=kBtu~V5Z%?si+CI!{ftl=hF^+D676v`f%&o=GxHV z_0+u!eR-df=2}3d((3wK`}qvmk5s^-jv5U9@^GMqwy|ePm4k01qb+sj_D}Pjob|KR zYA-IKJ^}t?Bh@#!zsp0#r;UIUs~;0k@M=X-d8!NsA>UgYPcV1 zdAllVD7+8Og!R5-?nTsL6Z5OMAF20kXZ82SBRmf3UClceQaio-rSC_|9$8VXYqOv4 zhV{P4H3ihEzyikoNQ*4XtCv^r;<(;N&gN5FYjX0?vEY=`KxdaA=hVN{06M8r33R< z)}Xif(&;;Y4QwwQFE*v|XFU(-8bdF871>|O_mtz9k1;QKF0x+!+*;sIRt?DFdxi|i zl>_<^n@-zE$cRnOLup7cQbT%Hwc1+lz_B!qqIthf^-W8 zB5{TxBorhh1Tg?xQ4s?aMg8vI@!o4~Ss$!*uj_uUdCvcN_j~q<8P3eUYoq_U9^aF^ zvE(;KzJ1iiqu<*M_V}8fpJf_ZJ3kYsPk-(mBX2!-!RYr$gZ=#A`;+1CuRdu1@Sfqv zKKyuxuV?rgd|z?$T2GG5^N*GP=X&_n@-vAyZ}aKV?`;Nqd`-XYkVi&-Fy}I(-_QJc zzw1Uu?l^sP&tU)X_b28IfA94F?H}GV{Md&d@9^~uUxV)}Hag+{k!$ijJwKSw&;H1j zBlFFC{OI>TgFU{cACaH&+;;DIMtmRQ_bH3baM)DpXuDOk1jgtnv0zI zmC@IHnf42RUgN0azAi)H9k4nGvikK z%+X^v`N>vmyt(%C;}(A8@UbtSx#Aih|NKkirhn&ajx{!&|3~9inf0Kt|6XB& zH75DpYoo7G^3LNguRhOvzZf^o$$O98;oL8;K4#Z9#;thGN5*dV?CGmtIPqKK=6zwe zv3ZHu)&KR*+vBF3c;~T??*6a*-RbwnEw||QV;`L1vekaS+;|Vn`Qfd{KAxZd|9gHW zdD06vAG^~8S_Wcq)H?>YsPaHFl@`9%J}*H>Swf`d`03 z+t_Ut*=)+l60$dE}*EUNX98u-~4+*K~6RU+X_;|L~sS$NoXrGkgucRt{eCVt79P?+w2< zGWPWIM}OXUu*cV+!RuxCy6N9wU;V~2NB0c&4}U#1XZUOV|F?g5&+udapz9gFhT+$| z7``4~ALoASp^+KR_~d=Q&JJE9!`I>qAG~Yi@?G}4Z}@BX`@g0S_6*M%-ZT6dKj>UP z+dO#94rdKs%VV>7kAA?v!~FXrSN@;Z_2B)U;?DbiJZ5;0*OK$^3_tSA8CUZfc`J{c zG4jG=H;?Wa?0+M#NjLl17mchp_k^Q?{h;gdcnANErTv3{-_mvJkKBIaYQuZ@cb|RXzWjUNqmN~< z$MyL4v|pL~%+(%G-}F~c-Z#Ofr;qL#-aoiM@1Ha9!}s%p&gBRH4wC(Ye^1HG&#(ID zG0)}SI2hjJo*X*U24kk!^1s(S*z=p*fB&ACf6LPKU%1k8W5%EO^wIl2*gyQZhVRJ- z?H}GVd_OWx27CDT-d%aMtMl(>4)1Y2!>`XcqQP;Q*wC!@Z);_1KpUd->shWB{e9rD_|FYdPD$nYM||Ci@`Y|M7~I|4pt&);!^)$V#|x{=}i z!;gy}+>;O5KfGu7etyvP@PnUEuz&D#3*JY5&hYB|`}o6qT>qP2UwuqoJ8WclkL&UC zkjLdU72N+f-&lOi(^qUT`gjNXhada!oMAtFKR@VPe(>k{_7DD?-<ge?h_IUpLe__k#&sf~&FXVgb9cS8L^!^X_4?nKq$NNG1hxZKM z&*5txz8-$?du{s%zi0PYyl%y!TmN?S`-H(Be)l^MAKCdk%a1;m!5;VApFiAq-%aiIV&wU z`Y}7$GyJ`QYyQ@c&KUXbv!AnO@8onnVw10Td@csOt>+w3ge_eE@{Q2j1$2e>7 z{mkgO{eHmf@J_b!ukSnO?v+;?{+_`#48G0|?|;7^d|fujYigW!^Wy*WHF|jd@Sfq< z4j#VF_wN~8{|C)+ZG&sj2VZBscJR{o??2|i{M*Fu|5`lw`Zc^?ANGTL2bK{v7Mt2A`LP_rKo{ zK98B>XUOwfVxzD1Jb2sT`NMmLAJ_18zJJf)`afunYa3j{@aGx#_P#^k{M~)S zpS$cIe7q0uANC&O;PZoXm;CBXBTM~ohX46oF+6{G&+y|Kek{X#hW!W48NLSBHu!k= zwj2Cvvyl%^H2#?3&j}vO;P({6`-i=mgO6F)Irvx@-ZMOZc+dME*WjKE?|J`Y99-vz z^51yL_)7l63Can>iQ19JiIYj%k;h3B|LOkYCrc(zrfA10yPhhXx*d5mXPS28aoWT@ z9r@{!>601SamKD^3TJLd9-TW&JMuVdVxErtY{~4&9PKz~*K>t)w@uH5x1;i~P(qjSf!Baf>k=IO|aWjk)w_157w?a1S{$#(6?qw6$JM}GUn{2khH$F6q@cWy@>cS&|_M;>=e%+rzo zaI$pb`K06S-Ttc{AlU%x{n<4=sxe=jy&#@?A4CE zbDZnG=(um`+`Zb7M|1XTM;_e=Gj!xXmU!Oo-;M`#ZU2Go$m2T6+U>~W28nq(@&_dc zCm(OeL%LodT&Nv+oGUrB9eF$~F;BYsn2m>*M}$YVBah=H3$`PVuEz`=`J)nZ z%+>Me(z(a9Bag=>pKM1Sk4wzZk@r|U-c{T2_^ww8PiRLTPfSi~M;_fD^K|4-PEJWq zZO79RbUm&`M;=}O>Fvnl8Hss1@@FPzC1z`?nx`ZGndGy{=i2e&uI+an9P;QoFKI^}FHOwTk-sc){m#?z z^QHM_bI7CXxx5{D{6b=ej{FysE0QbQ@k?Es<2pFx(RE(cjyztSn5W}lj``Ol=HRvE zb>a2x$fN6YjXLt^dd$#~zacT-c{<)$x}KZbk;fAg9|t<}xJqJ%j{H2yOv%mdcuUti zg?qLmj~_{HZATvGP0Z7gpCy?pxvd?)-1QdW_U*{yZprQK$m6Vuc{=jbB$Fn0wBuL0 z-YDFz9eLa~`D#1zIBjB{j{GFa#L3s%@#|f08gATxE;UM^&{bZ(F>dddx?2E^3NsDCoi<)i(P*|e5oCId^!0+JM#ESVxErt50f7y zKW@jLbp2}hT08Ridh*kDTc{=hxPkxd7vK@cb^{>OoiYC{?Ex@lE1d&+g-mC{;eH(bgt{rkw@2Qo{s$A z6OYSd((&EWefUQ^^5|UGp(Bs3(+nN?e2_SE>t(~`+L1@+x(*$Abe-nu$S#KBag1rJRSK} z6OYSd(s4}bKCIS`JUZ8P=*Xk%G($&z^<<4?&30U?YhQPMm~hCWuOn->BaiDO=IO|< zo2-|t-;Nt}{c7g;dd4A-&UL1aJi1QvbmTWoHcB>b$4$C^J#YV7!Xb~&b*7Fyx=!wFz~be-nu$ZwyRW1fyXl+Hah;gH8ul8X`@dAu+& zLr4CG^i`5|6CHPq$90mO+L6cW;;-qiA&*xiX6VSfhaT_F?YK+VyN0{9Bai#!ZTC)e znx`XwP;zkc@pe3<>qEoC+L1@+x(*$Abe-nu$bTa7xI88u4=>$^BifNi=eiCZ zd32p-=*Zuh_r>JNk?nX?f*!B?s3VWA=je9iaqG-6Pe*>TaN6XUc04vgkJo+Fkw@n` zQ%4?Mr+GT^Uk$fSKG}}PCFt?Gk2><`TxaUYqw6$JM}C{owFz~be-nu$Zr;UTpp8-pG(kvxVRm8bguJtG*{N%^6#VJdPw^Y)2m7iZ???-tX~wPRA<}H0RzrB!$6?v{L|9lx63*OITdBahB?zK%S)PV+{uE#!9%JuZ()$2${rAHLC!JUZ9; zI`Zf`&CrpbHkl^5s~x}D^%L3iorFUkzn9$Ijyz76n5QE@f5LM*-cy?MY-b^l&m{M@ zBad?@X6VSzlkl95_m$>6-C4-vQ^`m>@;GZ^hK~Gf3D4;`wlwF-&O#pDH}_0O9^Gd% zbmTpsJ>Twc$8lZH6wcU=JWiQB(2hKMKA5K??>X%G_Fy|c)b$+U?Cr>-b6tmyJi1Qv zbmTpUJ>MQ~$8U8#LpX0c^5|UGp(Bs3(>xt{&tZ?tW76@F(tVhs9eH%F>(G%$*J*~1 z{Bn68&7M5kj*lg{RI+3{^0;8~csugAeCC*^BR^X>Z}RPS{7!-^B+IuWkIr?zjy$?f z^K|5I4L_1R(T-0hxJ0sQJM!pU=j+JhyqRO3j{F{>$K^5U_}v5-OcrQI9-Zra9eH$} zX6VQ-nk)qZe_opNLT4e5?wfn2BaiO089MU6NS4mN{SqC2 zS?-g*TRZZ&Yx1jh*WV&SfcATN> z8N->{kw@pc4jp-Po#yGt&z#JX%-W8#bv=7HM?3Q9T-Tu^kFL`^9r-yEkIQ4yajw#R zn7bW$bgt{rkw@2QhK~IDd0(uU%+rqZCg}0Hk2><`dgg0K9yiDw^K|4_2vBw)MY>{l)j$3uT zb+}DC^0;lXT|4r)ePW)D{0_;E$xiLKbJx3syS5{byColPM;>=i%+rzIBl$?OXFKlI zwf**T$fNlmZATvWPR!Gh-zV8O*{>Zx*7g430qw}+fyqJb$m79@c{=hRPYy{AZO6m9 z{zQ0qJMwr$a%4O5cvNDZj{MQdG0Cy*_{px13y*I{9#2S4Y)2kXO3c%dKRG!iIkg>6 z>-zNYjCSPl%;co0{@wIh#LC)czikJl#V>BwJ~T%X*~jyHCFQ+RVb@_0*fYdi9ITVkG${Fjs4 zlRMh+D_wj4Zr6@HZkv3y9eMm(VxErtIf*&u>iG52xp%fBkKah{YDXT=P0Y}d|7NmL zvOzoE-Szt6J?+Tjy~%y;$m2+2o{s$3$4kafbmVb@ z#5^7O3DeED)^VcJ{)yX>$4Qb&+mXk~5;JtQRW@$$rXHCr0k)JJ@J(;5&=j?i}aPD^Gah_z}cI0us z#5^5&*W)_pZ^s3?UNBs!9eG?hS)?6#^tjB^kzX`fELprAm*{%QaH)3Wap`24cI0u{ z#5^7O<&x!-720vdu2%|IZbu$hNmgw~9>*l+>Bz5^te&jVj%#-9`R2LCA&-+JYqcYf zYbWOE$gh*Eo2=K4>vz3DxM4f;xKXlkJMy?mVxErtrpac>=Iyve*IR~LwIh#PC)>0m zkJ~2Z>Bw)F@SKj@m*(uyjy&#|?9`4t?wpvRBfm?sYqDEAezvWAe^5|Ui zbmR|84o*Jaj)!#ZT>CiW(Hz&VBaa^Mq3w8B@`>c|kI9$lw- zI`YRP?t}ZHRem}=ryY4bH#x5zd33HBI`Zcy z7bF+9<3(NDZ!d>Dn*W)0X~#>ucCLLK@@URw?a1Tj6Z3TBFHg+3 z*6|Ca{a%8J@_1chhK~I83D4&BtLA&A9d~h;y!Z7 zqx<~hcI5FViFrEmuO=rX7q;VTUAxcjF^4>Qzr5a#JpME>Pe=Y|$(YHbupN1HuItc|N7reFj{F0OkBi^5<8QluBm7-E z^7#AY5ADd~gNb=M^502#PRBP(bN<+lJbFL=xE*vm70KV*k;iuvGj!ztk?@?3|18aUuN`^ZEcsVE z^7!w>3?2FZBs{0%hbH_l&DpdLd34|0M;&=|pUu#bA1@g{nV=mf?0TYb;&$Y5l4R0$ z!7c}e=L?a1S7$?WaO;~a?@I`VTSb0u@P<2+sOoB8`B z9P;RTyuFS*ns1(t{NdU2iDce(oG-!olLgw5#|4vx+L6a2GRHg}`Gu2X(vMDbT%0d zN&52b$m8kpr}o#7$5RqBbmTY8b9IAcg?3yq!IhGg+mXjrl2zN0$Bi<_JRSKl$!f{! z?YKtQYldsJBadq*>$D?}>n7&u$gh`}W3GkItRF9eJEBF+)dw zt;}09*}EP0N$|G#Tl;Is<1NX)?a1Tm@#g8s@0YBYzCxno$4dL{<&a17_islY4@k_= zkv}jwC^@(tKi>5r;i2uwqd&KwGS5*Rd7L6KPe=Z+#Q&G^|73LhL}`v09P;Sg!`qR^ zBN8)o!5i$@+;JHI-XmatPUOV!*QeuXV{2DoD_2m3^ zydc48;-~JfA&>t5*M;rK<7D|Y^K|4dO8o!33A5JmGo}6Za>%3kf9)B_qyPVChK~Hd z(#^Nl@v{lq@BdZm$m8e2i`$XM|K!)q(2>6+xiq<~9Y5do<>43Fk;i58c$P_YB#>uF~>X|e^fg6@q|MjA4`7Rjy(P(F+)fG)r9AC ze62L+hnm?f} zzih`}b^S*6{3hX$M{~^3kw@p6rz8LC6k54D&>Bvu% zOq@*8j+1u%V)prb#vzZ-CzG`!kCP|n>Bvu!@SKiQmgcP|9%s$l&ywiKqjSyBk@q+}u6YJMoR>@HOXhD!9v4U!Y)2m5 zXY=&Y`xMTd*?wQSP&+Q1;3CPQ?Z~5Zov$O0uG2gn`Lpv}@cY?S6CD?e$5oQW+mT1- zI$uW~U8fm3@=GM1C!RMtE?IiKOSL19ODD^;Bah1_X6VQ-mn@&G(2gs1y;8VxJM!rH z;CZGak25Fc>Bz5={3MU%)kMctOJ7gNv?GtJC9Ah1k831m=*X{`__*^ir{h|skJBF} z9P;RTyuFS*ns0`VJo3)eaqZG|uG5Y@uA8jajy$?fGj!zFPc}$4Y{!kdo;;kQ9eFgz z3>|rNu6a808z&Pd6Sd_M5Y9;%#xea{F+HcI465HDA+o z9eLa(F+)dw*JQWk!|k|x*S=5iJpzY3x*l(@Bah~rrz5{d@{wfEcHFCL-{<%qheIBn z>r5Sabe-nu$bU5PeW33Pb=t(|O+mXkEl7rik$B!rG>B!HRm~XA)A*KC?wj+;+ zC7);3O%rQg9qZ4%QG406X zvB@Xfkw<^tYle>eamn$?3GH}d*K20~8VQFynq!8JJUZ7r9r?X;jyY!Ncv6DSJ-Hou zoH6@OX-6LY{~9xN{pnflcy@vZ$A79Fc{Ili9eH%Fc{=jn%wB(P@ac9u zCqaK+@rnK#^5|UW>&T<)G*3tV+~nz;^;Dwcd8PTz;gCny^Zh#H@x{ap9r;O;iIel& z@q(_$565dq9$k;O*O5o_&C`+JIN2<@upKYzdW&%LcI45yu0uy2U8i|E@}EgQn|!Vv zFYbCw?!y;zO&s!gb#h5N@_1=to{s!w$>)>H+wlusFQ56#B^>hTTxaUYqw6$JNB*{4 zi#cZK_{9XBdqq3)cxCdXcI5Gsd3!T-y*ApGDFP&>2hdi2dLp$=gOs>NW9r>l>mPl@F$D0z|B6B~L=*Xk%@%B3MXuf$m z@>^z)IcDg1bArxYJkgQI#gbdvk;kp`_GakF-M* zKQTi`{`TaKZ*pHd^0-K1hK~HA3D4;`QkpZi9eKPz8P|?H&X<^> zBR_w_b2>gyn)6^g^7v5la69t2Kw^fD{Jsg#>G-YEoJZP`$48UL+L6co5;Jt<=T7EI z9&g8QcWu7w<&Z~@>pShpqd)gBPe=ZVWV-li6CIx{?YEah9?kcD(2+;)FEe!HPs?-J zd}|%Qo1p!kFFNw*dG%B~^0;@NlV<41Kb?&JTupvW-y?jcwBKG1c{Jb0fsQ=-crimq z{@G-%oV7=yJq-i|!__%%aEe(t=j`PMo_GakFzmi;%esQAX56jEbf7FgVUK@W+e+_xO zIx#~>e%3q=^R0FKaf0^GREIqJ{`M#B$m4ABX6VSDoE)FL+K#Vvy<_I@m3|1cI0uFyuBGZ@;^%!%*WU1Ia|k{m-gGsA&=%C z(~dkIk(i+)zffkIZ>{4m614yDcI5G}9P;RT4sJ&t4@%6_k^e&O?d8cE?fAO{zZ8FEe+_wD zCD;G^cI0u{c=L4R|B(2(f<+S@-z@F7mqQ-SU%3u>^z#p9=*a&uIU;A>k?8nV>0J9b zyXD|5;Jt<|CIRoy2Ijh{B!AC`#9v$oTKZI$De1889MTRNq!yg-&4@>ucdSC zq zzxF{v_A-?{?&In#?gnNB%#FpWB=~(eXnQ|CjdL%OQ{E|F~x$kACja3?2FLl7n*A zfr*aem(I11LmtgJxej?eDKSGweuCt>tiP7%IAQ5r`#9v$oQc|z$B7d&bmXtkUh}PW zoFqZ}Cv8U_Crc)8M;>p;+nb>ye{;xlI!=+GIa9VHk5eU6w0J9bySskKQ%)~e#Ybn z+3(+@(Q&5Ix%P3$qd7O^d88wc*CuA@$j_V{pZ&)rI?hr$*FFw;H0PSmKpwA5%+Qg) zBK`BptnD~kg0m-cv?GtM$J^`3qxt6PIM{E_oQeH7SLylbxy&Jtp8qE#I`ZgTGj!zV zPUcDGZO8e#_WbmG=a5I|I#Wj;U8i|E@|Wdtd^VZC9T!N@x%TPEqdD%Mjy$^0=IO|P zCcHFRupJjlaN%T;cI45y&eV}d*J+-PypKos!9CD%(b60({b6-x%P3$qd8xzLmvIPjTt)f%O&e){(6ay%a_izk3$~K*}t=pM}Kd^ z3?2E0;vP&^XvY;3yf^-y{u=V=dc3`kJeqHwj{M`{W64VGxN?F|#DBZLhCDjg`8x9G zI?dCOUnLnye=5;&)$+UPW7?6&XXBsluOW|LOU%%bUoF`v>u)AHu3kFVJ`Q;_=c{$d zz4N0%OQ{EFItB@o|HLe=*S-#XTG(L>m_LaiFL^13Ca5H z$m3D*X6VRokZhQ2)Q%f>Jy#y%90`X!&X%m4=*Z(riFrEmn=e%+rzoaI$-{M>~F`>pjE0+L1@+ezYBV+&eK(M}D8goPFDIzpg(P?%$3) z9*`W^jyxWen5QG}@w%Ra+wtRF9}*tgjy$^m-VZwRxK(1Fj=aa~`kklaVWsQ&L_6~6 zT-Tu^kFL`U9eLMa|KaU;MAysa`L|5MA&*NZN46u6+a%`c$h!vDc~mNB)%L)a0~wJiY5P!ZX{E zM;|ZSw z&LNLJEk9lzGK``~_a z$fG%5Z$}>QOw7}f|3+fIwT^d{_J6Y-dAvKhryY5`H!(v;{=US0_CC>Zq;&nRokJd7 zkGI#6NAu0lk>4WOJQ>@L_jf%me4rh9d@y;a9eLa;F;B;VxBuaK{8rbGgpal(kGmzi zwj+<`o2?`NSn_!C?RNZ5*H45`wj+;wCm(G`9(PX6(~(Dh$9DW~*E@tywIh#DC(pDa zkFL`^9r=BeJ(FkK@q1lA7e3#PJid^;*p57YEHO_9eMmo@@hNscwSsM;_lv{??8>{yi~INB-T!d}|&5QQH5{cI5HB{FghVpIL`IdLE9~jy#T^n4u%@x$5~mK|4;E;6%y9?Z~4! zX6VSHbIsF{KP$W-nWP;jO>nYg@^<8Lie$=mPWi<24Jk;fSm^K|4tm%SfLUQBeHDIQ-)W^P9w z%`rnq9-V83j{Gdixb(4!j9#w}t9+a%mjy&EPZ-zcPH~ePScP3v?bX+kWuS{;QLmqEVR%%Bc?~XS^NB+L> z-sGM{$CcyJetUJ~(fph0kjLv2Gj!xvNmfn9wBu@B`*X8RvX4U^H%x9wbmY{Zb(79{0Badq)YqcYf`{nJ;(2@UG$a6ZbouE1Ev?Gt(m(6#xlmqQ*st_|Cf$Bh#6bmZM9_if{L+$6zGlg-+ZM{~^3kw@p6rz5|4 zvPH6GJ8sprIc9LkqjR@zM;^CH%+rzIHrX!Oz8!by`uBNUz8~a}$L*4B6CHW0z}x<6*<$a@}nKYAbP_>t24eb08}aj)c~?Z~6+ zF+)e*J#;;;MaR8M`|ahBNAve-M;^Uj%+QhdJo3ESw;lKE`nfz_U!yqW@$vYNwIh!n zuX#H19xu=7xPNKRQtim2>vWAe^5}7yp(Fo%X1LA++VQ{yJx@GebmYY#Sy@rBGW zPe3DFtY54JWUcJUd+mXjlC7*6b9-V83j)VQ? zoRfH4JhwbAJii@zydb%-9eH%F89EO3n{!d(ZSgbZXT#66Baas+m$V~~&NV~F!G3ct zO}s5$R(?Lbyd8P`Lh{9SQN> zu4>1tyY}~_t`h5T)Q5iV^qM;4(Yfa7$UBSYbi8)3&Ky6-${~+_-u1e6@_q+GGjyIL|+sh%3=HJ>gkjGmRGj!x{PCRct zXLY=#bgq3I@}tb#Po2+YI`TMGVup_VrxWw7b-cB-f3faG9v4n-YeybWOU%%b|8jCf za(X-7-nISqa>%3k3-%1;(a$NFrz3x4V!pMGca-*D(zih#N1wOtp1VAHo|~Z~e^TP} z=U3YCt6d+KKO#CQ8U3}8w>~lXT08Q13fGSO*ORl7GurXauI=}B9P()XO+5p7ygD&Y zNB*3|d}|%QQQCi1_acv%CU>nusJT@^yM}BN_ zOmb{H-ru!z?co@e>Yt954A+JM#EQVxErtqsb)MKXIbtW2O0KbI7CXdAuEY{B~l7 zj{J9$Cz2=I@w;6=6+YdLJZ_TnHcoWpaihdM9eLze&F5SlpDF#k`m^oG28kMAbt>Bx^4PL}+z9eBxULoFsX@9eB|mG&pC>qV{FePS z*~-@mC4{ zI{8gI^7z~2jdtYmOPOPyj{LMahv#(sU4rKPz8!h|L-J-j@;H6o-V7c2KPJ~_{;Bzx z)A6m+etS9O(fmKPBaeSh%+Qg)A+yc5*6}Y1+W*&f9eMQpF+)fGf$))J z%66P8!KssJ+L6a;lj+)##|JaVJRSKb!zYsI+i`{jXG~^lM;>QRW@$$rpUNEbbmX54 zzn9F~j&T<)G*3tVrSQdM&UTzD!MT%p+L1@+I$uW~U8i|E^3R99 zznZrl=Sy(@WPx_%(Yemokw@2Qo{s$Eq4$gTiH-{<=>51*JM!pU=j+I$>oh}0e&J-1 zWYKn9tn0kak;LS4_9bM9#>3OYDXSdPR!GhUnMbT z)pi`y^=jej?a1RA$(rrR<64P%I`V5L=B(3>>vp|fxPCkGxIwaEJMy?uVxErt#>pnh zrtP>{*B+Pq#UYRGr+cg;kKQll>BzfY*YCdQxOr*5*&OoddbVgs9z9+&bmX^8mQ0pt z$E~_vJlwh+dE6%1wjFugE-_C>e*47zbYFGcp>#bvwj+-_B|EnxkGmvh=*aJyn6q0u zez@!1!#&!O$B!g?wj+;wCFbeKe>8DDu1m+gOXu3hA&=(l(~dmuo0y>^zhB~dT$hd? zD_#Ho?a1Q+$${<2<3WiTI`ZBZ-d_i|Cxs`sBah~v(vCcynwX~}e_C>Saz;Cz z+4U}==NgARdOn=hjy$>^^K|6TPTV*5Ovg`^9C|eBY#8U`oGwYH+JoM zZfZv!Z%%G$M;>oY%+ry-E#WyGzg(Jgdpq)YNAi_+r5RVE}i?WcI5GqBxUCIW;+@9iQv^*zoyw z`FT6?_>06m9r<4-ze;}Hj=$;px8WP@$m8#l-?t-=e@M*Jk$*G!WAauz{;BIfhkt2D z9{-xW-HtrIlbEL?|F`7t$-C|NkFNh2zSoXC{ww)+JM#FS#5^7O4^5Uo3rogNbey1^ zFr26zd7L%2E&+`S^k;es-h1!wFg%dM$9PBs8$BnneMM@uE zi?$<=izSPb9~%-TU?^_alK?a^0-v8bUX6sTr+eW>^H~9v$w@%O83p< zm$S;>HpRCZ1D|Wq7xNM->=5cb! zqx-N)JM!pUGj!xPO*Tt5Z^tdV-ZI>(9eLb3*`^(N+%_>!$H9JcwoAM%ZvTHY-DS9~ zRo#Vgq`RfNySuv^q`SKt>F(~9?k-7b>5x!5r4$sUk$3!f$NDg?`<`RZ=RcnndvVz3 za46Rbe^*C6uAQt?M?E^%432~S=B%5z7S}7+4>zcz9yd%js-qsAYX--`eseZXT#K8O zo;QzEhkEopY+6S>I@b)2`puHzli}*PdDp{+ThvjHTP9o8QIA_E=5ZYCH)oi{wYW_= zbhvFD^|)QKeI51aTr)Th_M0^D)T49F;HY0YpIvJtyVY^`1ouextfL;!$^Nqvj(VIaF^}V5zd3s)_T%2= zKHW>PKO%AN%K?xq598yO;dOp2A9QEjRG>@bH(B!b> z@H!sR^^xIGb=2e0$uV`*)gco|K$iM?E^%432~S=A4qa z7Edit3s0}39?wY5tfL;CYX--`esj)BT#ILyo;QzEhkEopoKr_VI@b)2`g0TeJ!c%x zD?Q%x>!?Tn{^j4pIO=h)#0-vu{pNVi?8ggAkN3hl>T#Z2KX<}WkIprN<6yrzo-_OL zqSE8NxQ=?cevgEs9-V6jNByPAG|AL; z{6p7Mg_qS)k6w4LIY&KupP0u{e|a)@i zyraA`ysM6STrG1}O*rb&xn^)2>^JA`#D2V|^t^eTI@F`*VTXjH9-V6jNBtiYKlku6 z503Yieok^<9rZX$GEyD&IAUT3NB#YYpU=FRaD1S2u6;VxqdAk*QI8WOW^mL$nD{x* z+X=^qO6S_ALp_=^ULEx~c47ucy~pc$@N*-Me=418pAPkC&X{%7qvy>Gj{1j_(UNiN z_(<2|gpbxykKWJM)lrY$59V^EoP#I^WXIZ^m{9rft_?E8eH9-V6j$H9JcCQIzc zC(1FxC+nz3?`Pj99QEj2GdK?Rn=^W1KmNHKE%Z2bs7KGk-F4KXbIstWe=2!8d8Urf zcKuxVd>!?;P+sph5{`P@KQWKvV81ypB=+Nre0DoaMb@T`6lcC zCLG@={hag7I_h!mWX?M3agM|cj{3KfFEhu_Lpi=(I@dlO>d~BK>Zr#h5;HjJ-%0+R z>%U4kzFRuiJ{{`OoW<&>$AuCzIO;uK&%@UV$M;I-+NVQ3nzKM1_2_vsgQNcaWZq=a zI)2dgBH@R1)T8&a?-P!C^nNgp<6yrzODFc@N99uC$92@B_p|R4j(T*i85{@u%~>w7 zAOBv?AAV9tJ$gU;KH;cG=bFKBu-}~d68rJf((~qV>QIlK2j3GM_2^tPIO;!3R!!Ea zXeK@Sk4c*moofci!G3c# zP3*@n%hkiL>ZnJ*-}h|7QIF0wgX3VoIjbf1d~By>!`=|6Z1Ige@cE% z{#VCex^}L8I@F^%>()_^YbEA!)O)<1hapD%f5+b>=v@0a>d~Av5{`QGyqU*QKV;(f zmHwA-9IE^|K6D-R=zhFT9QEk=G=rmlnB=?6`8MG=Z0TJ4bf`yjye1s===n5*qkg#L z$6Wt?!g2W0x%TN$|LZ!}drdg%(er5rN4>}BdH5;eI6~=M`*f&BbG#-T_2_vsgQI@L z^kc4w}}}X2fh6sj~>S<-KTrhp&mW1aqFl@^UdI> z_dIxh4#*iC$1D9@ar`>!ae`#RI_lB6W^mL`l-!y*`)4l4iA&F$$Eia-y3a}KsK-eY zGdSueOY}O9lb7artUA=A`*e>S_2_Y#!BIa&GG#JV9jETvx%TN$kLFBMM?FrPn8#6% z`swO8eb*1>d3zwyp&oBfW~iec-KTjR^Ss=7NoK9%Y+cVD&QV7_&Y8?rM?KD+n8$Ij z-<)|8*W$e8eBu0c)Z+rlf_2oRbIss5*l*54iEDA;a*=S+I_hz;Wbr!c(Ya=D9PBq| ziNv+IWa)YHICZE;&%;u6)T49F;HY0ZvEOsXahcNNUAB&T+&Hh@RtZNvZl9RJaj@SU z&zb$WT{`5_o*2i z^&X?=Vf%#RI;C^%)1e;CnYE63^t_qDQNM1oUb222H|To9aHBfvapPo@I_h!L#5|7r z%@XsiIc{FszeOGOxMi|c9rd_%Vg^V3Hp#Zhc6Hpo>m9-!>!`<_lAY_Q$6XThIO=yz zc1w1z;~rh_8SYg_J?@?CQ%61So0!K@zhAO{azGt_-}QmvL3PyQ!O0hb8r437F^lI`-}mu{PIJht2>eq0^(czkj~9rbu(Vg^V3 zNy*8{DRn%x>(j#1>!`<_a_)`^M?L!go0!K@e@1dZ*83+M&n)+gpH)Xao}HXiM?IdK zn88thWM&+ZoL9&56TBd~u#S4XD7m^*o%GaJ;hg|B1V*j(WU0xu%YK^t_qDQGa%3c>j34IbNHf_rrB{)Z_KZ z4RzGxIl0~pj`|yuo06OBcuUu}hPTyGkN$i4a}$nw^#9d0kE8zfhDi>OLnc}16_N4AFQJuA4>jIM?F5An8#87Nb+d%SREhl+8pzA zs7L2|PjS@arHOeQ^-m;ECV#HuQ(f;A?pQ}X?vOlPM?F51n8#7?`S$!jTgT_Rem;Dm zj(U7Cd8v+i^m>`cQU7w{|IhVk!tpPq|L*>kI_lAU=Wx`c`!R!~{?)|)hwG_?<7=h= z|JUnv)T8Iq_hTMM{ZGly$#;1@IR3BvHvUT;_2^vp@$1*ZU-yUZ^Vb=r zeu$CsbISaE0z*g~e^dUF`9s!Gk3%Ix*HMqdBxdkm=Z3>3!zIJlafGhzw^xUHG=Ic8 z>T#sRJdXO26VIF1mE$O-*L~DF>T$GW^g8NsjKmC%`Z1HSlCkUf+pfn6$E~9t$4kbq zqaG(n%;Tt^FqtTsxQ>%_J!v>u9rZYQGDRKrIAvlUNBvaE)X6k;oVM%f!s+X%M~}MU%zqsK><j(YU>hMC7vzkISnvSJ-q>e}BEvZ7drzxLq@$;$0ekExN#lz zxJj~U9rfsWFps0&InLdzj+=MAMYv@h^|)2CbshESKF#B(cfWca$8Ab;wymQcw@bFK z;||G=iN|XO$DI=U&Dpt*yL7#4xLY0dxO=ik9rfs3^Em4FOw2Kt<6fn6Js&#Mqvvh! zI_hzs#0-x5eG|Qo<9?+%``1yA2PD6*qaF`T%-}fa?LVkJ9^CaI;h}ZZ<6+6+b=0Hz zW^>dZksO!r$72(YN0!ILkE){{o$Ee0>d}3g!BKxoW|(iy@#qBYKc%j{4)<`#Q%HN^?%EqaII6POhUK&(2IUIOe2m}!BKyEV!!J+-cg!=XC3u;S8{h9^>|NW21mW` zN8hJ^tmD01-xuCrM?F4}JXl9P`o1%dqyC{}-Ng4C$3KZr#9l4t9v$LA6=I1YOI_ivBScfCdULLK$^V)9ZQ^=Q7?90&W& z*(`A_zFe*!dLDJCN6+(L>ZnKOn!!>3O7caXug?>Xua=+1U#p`YuSssJqaJTf%;2c^ zI(S{aOgO$?I@dlO>d~Cr>!?TX6EisK|C+3utW(Fob-haXMjiF|X7W}Y_4syT9!LE< ziGMzxQpa}_bgq3I^=Qs}b=2egiFq9LA0+;L;irV-hoy7v)1e;C`KXS1{5Ua#qu%57 zJgi*Dzjy6i`*f&Bb3Un~9zAd7anygBe3pD($1l46NBGY=>ha6ut2*lOUx|4f^iA>VKZQTnQIEIg=N>mF9QAlpVjf5R z|B_#lAx8dx$KND)efC|KaMa_8$&hu_<4}ot90$GqC-fQ|I$y`*lVR$p$6=G<>ZnKa z&E}{dJ{chyv5q5kJ#sio9rbux&OIgJsK=8N^Em29O-4&buj3e9pPPN>Bs$dN*~yr7 z)Z=GdSum%-#!<@#;8!g72h%yI(^+`Z?_c zb=2cU>CNM)pD>vynYfOVbUkS}SsnGbOx_zyB^>p*WMUpi{p86M$&_`Rs_Uu4Y3iuQ zX_M*dsK@CO^Em34$=@~W@6ny1jx#1`j(HsQ=-ip=sK;e9$2^YunUh(PS?f4k*RzLn z)KQN2rAQI_lBqo6k9pdh~f{21oroiTiZl9Oo@P zuKDVy$N7^5>Zr#B6EisK7fO6S`#j~iaOv}Qkvi&e(PXhY>T&VJ437FE@;*H@S)z_h zCg}6TX9-6=4x21hM?D^yIp%TH`DN$?8z(E(QI9JpW^mMxn#bYi z@T=5u)dW{dRT#pQJdXMgve)mUZCuAq65KS|td4rzJlUd-di*eR z%;Ts(EIc~dvW{CNI9{H^aTAVu94Fbjj(XfbbIjwYKOofWIBt`mIn#F*>T$Yc+dAs; zz+7(zNBwrmdhyK?j@y@8$9Jfs9w*QI$r6rwoHQ|mqkhN4KOfIaIPO&Xb0bIRb6kgd zTrSryn{d>lf3BIqQNMHYPOcxXj=Lo2T>Cic(VWTZsK-eY^Em2vP5l1X$hn5&Zsi#9 z-Rr2wMbj_Ruc01CO3dJ>_xq6MTXWnaLHkGSUex1I$)0u8qu+ltgQNcRJcoOQKV{8v z@2>5)SBH8uf5@JJdi491W^mNc5T7I2r;ht3xL>k=9rbuX^7}gKamLIskE8y; zIv&#XT-h^cqC-6{m>gP1Jsy^r$5DTHazt`u9gphz=T#CLpDE#}NB3_YNByzM zamn#@JfUmn+NVQ3n&Ua(s7KG6c^vg8CO$vct>Z~u`#e0kj(VIw^XE%A>T%x0JdXNV z;~wuRbv!k})snU9s7Igkr`1u9vt^EX9QCUw=9tIv^wPPWV;$vBdN^|(f221osw z$$6P`S;FzG($6z*&-+-1db}+;yN-H1CozMg{@mn@Tz`JT@w@@!_UTZM=A2*0U-yR> zB)`rm^%o|Gxjx}|QR!U!b*M*kF0P{EsWM{_Q#qaH6$ z%;2cMBH1U`@0)PEvUIL}I@F^%SJhFES0`q0)L)bAn(OyWI9^*i*FGKU(VXk*sK@IQ zGdSvZ%eCfPbG#uz`){nH9&bu+uA?4z&-G?-)Zdcan%q{$+q=Fayt9sayfW8bk#N-G z4T*Ui2m8&rE3qH%F7FBdSVukHoa=8)IO@^4W^mNso7`ocaJ;WH#|$0n(Yg26QI8KK zW^mNMo9{(G?|mvWI6jyjoogRQJ(}}S9rgHLt~Z0D{!hu&$&__`xa%pxN9w4@>vG<; z2}eC%lbFX*kNVfz;iKu$&sRUneQ?y{vdK(!)T8?}kE7makVSsQ+_vL2`Z_pX%Cvdv&Ns^PjGx9-m3f*vE4>Zr#{l8fu8 zNB3zS$H9JcUQAqzFO@Hcf2pG$FHbJ3qaK}W21orX$*ak0b$q?+t3#hvI@F{2&f%y> z_hTMM{dI{sW^nv#>D<57QIBsVZ`M(d*C%Fh)ZdusbsXO+&3U_ydVD8&w~l)Bxn~AP z{d<$(T1P#8mYBy; zKViN%r%XPt;};43Bl%|?_4sA-RUP#>QRbM(Q9o5UR`Rbp{yV|1lmFCFkN-`+siPjJ z&K&bN>cCij{ocWmvD$t{{L&JN6&-j zfTJEgZ{~3v>^J8(*=s)zSq>ErT}M6o_t1$Gj(T*i85{@u%^4=KABQbB%)b|{pXgAJ z{(X77+!IGVI@b)2`r(q{lM(7TV%Hw8_lpko=zTR(9rZYJVjf4m_k-7Klsb-@;AqL{ zb=2b+$(VK2qxY409Q6z4{{^-{GJnExtn}!grw?TxM?F4}j9o`PE|h&{a2)jZ-`{KS zxA{8yzV>~{QIEb)$El+p%{QB)e%xg7^ou1N$16Q9_n|{Qnqvk>Jv!G6j(XI8+OOgG z>CorQ1a;KoQklDC!cmXz(>#v)<>U6-%W=X4&G%WzQI9@9C#s_!SIG5daMZt@y*}qB zuHz&Lu9`h7Cmi*-QZi{B_2{1q=5f^jEqpbZtd5f>xMt?8o^aHobDhaikM7evj{0@7 z#~d>_PLZHN@Ii{am|V!cmXro6T{s z-yFa0u^*=?pNUUfM?G$w>o-a`>e0Doa2)J6=jqPE>GCyvB6&RFs7JqU+$=LV>e0E* zT&qQJdXOAlUb5k>o{B2BZocpEan#S5%$3Yt$9cN8-(DT+(frSQ2I|qT6U^hNNBtE28qS*z{Ty|^I_h!$WPv*B z(S4f7QNLiaP_l3x7wOs@^K__3=kAbuEp(Yed#9y#jqzVzmC)cgH>^Q}29lc4?g_8QdVACqP4 zs7HSuzzmN1<&r6K-sB0#<;&^gE7Vbso8;P!6OMY^C^3Vh9`!5Mais*eOTTg*_2}PE zAIaGq_2@p$<2cxF&K{kGtK@6w=M}5gQICGkaDBgqdUUQcIqGl8S@ye*<7x?-e{(z3 z<4wuxb=2dn>CNCc=!?TneEgtaLp_>r2FJmEb0*E&wYXO4pMxhQ zI@F_o&iZF8M?E^%437HWC5NRyG~u{*xlXul9rd_gvVI-)xItnD$H9Jc7RYn$THLVo zbKs5YsK>kuW^f$z_Fvv>aEE*i z_fB@KqaMe~oUs#*dNki`j{2RF(Xt*j;ka{Yju|@CqjUG_*{H`o6EisKN6fV&B)imc z*95oCzHJhY`d`=a-Rh{vku%3Uj{4n`mE$WV9QP>wKKPz>)Z<>s-gVUDK8YC|_4_9K zCHvR$fUeCkPltMR?nXTu_2}OR&Eu&5eR5!OP#q8M+PU`WP><#eQ%5}xm6*p-e@Jp@ za#$S?@7lTc=}?d6{HBh2^zYH;anv7?9GM(d$D_MGG_+5LdNk+f&O$x<^`3bg^~WT~ zCdbwB_^zF6pAPkC&Wv@`;|z&;9Q7w8?$bSTJh3$Yq&n)+&prJ7gQFfN$mfz79QB@C z^Q}3aT-rZ=uR%SImz+{ZJ$k*&;HW<}@jme$;dokUzr8xtqxoCr9y#jKpF=Q%quzVl zd~1%Um-ZjkYfz6zCTG-9kG@~b;HdY#rq^*ivovR^+=~wNIBarO9rft@*9?yOvy*d@ zbL)6s*Y?}1Lp_>5OwT|)`ty+Han!$_e@4HSoL|Qa5_GP89QA0s-qtL`BF1D>Mu^d&->xKgySWp{r2imkLC}N=YXRg zf9VWvmLB!Xw8Kl&;lY{nhdSzU@noqw>d}3g$5DS-vQV-_9WU?N9P@OjN9P{Yvr&%+ zCgyR}FPxZf&GCxT{%!L(bf`yve&)(L>T&+W437G%lDU!v>Uee6_S>sNJ(@pF&pG$c^P>*wDju{;FbEh-kn&Zt0+CO_c)Z=W)Ep^o6 zyy?y0s6R1h>2(}$P0*av+MyoTNp7p79@k5621ot+pV#sDG@zj^pE{IZxD4 zk4L9}vW|NEb7BTZ{Zq-)$uo6)wrl(C)uA5EKeA__9*;=OEsW zM{|zv4AkRsiFq9LSLM0)_fU;7?EgEylpg(kSr_N)9QAln@^T&Zcy)U7IO@mAS$ZAE zza(hR1np3dAE$q%j(Qw7Uo(TFe%tmsj<1&HeAHQ}#}AX&>Zr$U5;HjJw@mapj<1*I zY?1rWp&mC+{#r*pZkCwAanRfUxAyo(f^Q~o)lrWdC!5z%kLH`rQNLMc`@Zmg<@k1j z-k9(@j&!BKyH;@>Z3%J(S8FG_!p-|2ae>QImV`>B7_QIF>&W^mM>o9J~M|5=(d zO5O)L)T5und|5|5?vt3oQNMel*Kz!+G-tOu>T#Ex`>#6capmkcgQI?hbb1}feEq+t_ z`_1OgYpX*&`uo;iZijkwt{EKlZ|Jjs{#?iL+w|z~ReQA^>hYQ6yE^Le;q+#3)ZZWK zbsWD>(442+p&oZgeyF1!cS~;uNB!=hUdQpr1kKs59qMu0iE9|?YEbs9?jpSj(YTSPV+eGM^9(IHOF5Pw14<^sK=8te~3~4-%*eLdqy)j>X*#x z=e1i-X$D9AC^_Tnob^M(ame)O=U_wCQIA6>!_-la zqvd)tI1cukb5ho>#bL`MxsgN>!`;`l1b~R z$H@}&IO-=)rbwo&<5XQw9Zpk6Jvw*VI_hz{#5|6A&$s7)`Z~_g^^D<6b=0HB>v`m; z$B`5BI1cukGjn1;&QiJ`_o72Rx_{3jM?E^%437F)li|JJ5{|Q#Bgbd2qaNLl$H`HT zBP3>U9PBq|*3QB?d_9~cnX`_1^te1Gj(T*iGdb$#O6E@HspGs|&lk>LM?Ef(ELcZ9 zE|i$ZQ9o|t{k(7;7wLM@aIre-aq(n{I_lB;-#m``C6lF+rR%s%*UN^>)lrYjCo9xZ zk1HnTan!Grc%OUUb6mNcB3z}8dR#SGt&VzJJu!o$evM?!WUV^>uIshKb?T@`&%f7! zqaM9p=5f@oo2-|tU&jr)-Z0##j(Qv;@2k-hj(YU@Y#vAb#)<$sT}M4`lbFX*zinc^HOK8r`?s&79z8#v8;*MP ze44>gzeA$;ymQ>K^t|m{3TP?wXjvQNLTVd$LCz_w3q!dv&Ns^Y^Nw9`{bn z<2dN;cVBwkr*!{bCmrh1>#}bh^=Q5s9QFGp`zHs~@%LRH7#>tdJ&u};Qb#?GoS4T^ zKSnZMa&R3F>H5&{usZ6|{kWc^9?dt8qkjBkvgGhO9?|uY;Zb$eT!}};yUWlxn^+GpPihOoLk59x;{U=ppJT6Hd(rkdR!_okE8y= z>V#pMu(!Pp+urm0d3sE?7rBE|6SRM?H?7n8#6n zb#hH|Z5^-c+J1X=s7LeHsiPj(PR!$|zdo5PnY4~KbnSJ#v5tCNK3T4gdR#U!kE8yk zHp^$5DS* za(8l19sk(1{r2imkLKT7M?Kz`n8#6nf8u?$a2+4$dYth1I_lBq$%A#&<3ovg9QCOG zQym}f`jPO_I_mMF3OsG}aeugv49KPx#i zdAg3zbnRUGbf`yjyiYmmagxM5j{0X4?-TDEj?b0eSI^f`k1r%I)=`fyC1!BcqyFVO z{-x`a!V~ML$ElN*>Zr%n6Z1IgUr829uBhXyUHe=*sE&F(FnO(xdVD=GkE8yt$=u0Y zb^Ke`&b3d6dNk*aI_mMw#5|7rx01J$ck1|V*YAbz*HMo?pZ`!tJzkoa$8oUVoDY)s z%MZ&#!-MOn$MKRS>ZnKOn!!!`=$67x9f?@fGOty0G?x}GBZM;-O}&*aNG>e1($c^vg$CDSEy z*709m`}g1L6CLW&ug|xyqaL?O%;Tv4cd|vYZ5_Yvdc$ysI_h!PWRE)PareYLj`}SV z^Q}4lr`$c-z=VzmFK`M;^79*0bZs-qr!r|+vN6)k8n4=!ur+FOpBP8aS z%W=fgxg*t4k0U3e)KQP4CT4Kd51(^JPp(Zkj+P#;Nk*@u9>++=tfL;ij%IMw9}s?) zj8(_66Ew#>j(T+NZ|kVX1Jj$wQ9n*HZZcjS$M4$bjL#b#>e1)Yp@WqE3Rsygb?`_OxkqaHn8GdSv< ztMfdS6XfM?HF6Cnp^Bcv4~p$H9Jc zrcdn08Oq^8--kNXqvywS!%>gUHG`wxKgWEY3}43?6Exp!j(T)I-rpSc=>2aVNBvC6 z%*iZuoVDxO!rAMn$2pQY>!`=M67x9f=T7EH=B?v=T|3u49qQ4X`Rl011rqZ(>K9BF zN*1o;B3&;UE>=f9x_^&@qaHn8^Em1kPnJlQtm9H$FC8vZM?E^%eQ?yH`!tWEe%WNX zWcfO-(DjPpN_EtubKM6=J-ScxIO69@Zx&19|Q zcXeF5>vh6)>!?TPx(|+ebf4yN)UTJ!lX$&3u3vgTY*0r%I@f)0)T8?}gQI@Kci zi&b3d6dNjxVanz&xH-n>o zv*dux*+1d9dFfpHbf`yjJii?E==nE;qyE@jYrZwdEfTcf`+%b!y-&8RqaKgT^=5F? zKbOa@*Kyn`L36y1IqGqVWa~QW@%dbD21ori$tUs85{}!J_S>sNJ(|CG9rd_SVg^V3 zr@7XAYmVC`X#awB)Z=W)_I1?b2D#o0j(YDg@5A3^&2fj)etUJONAqW?qaM9)&ETlt zF}XDVzu`*~jysiS#&@ox9_L6FtD_zlP0Zk^e=0M~x8}G@g7z;{M?Ef`>{>@XK9=jv z;Hcj%xi|h$!g2S~etUJONAp*zqaIgG%;2csBe^Np-C$9)ns$7du*J^EbTw~l%|Ki8YV zQGY?G*Kyo0L38G>qaNo<_OGKJPtWycaMYg>>UA6sNYI=)>!`;$67N%vdh~uagQNc8 z;qvSF{5@Jj_%qFM{C#>HCONQ!B-fk4QGZBczw0<2TADw6&pOpb&7=FHPscvilK3npjRQICtJU!-3{Jv!H!90&W&Ss-yO zo>R^rKevv0Ts-|^{Tk}gxn^)2>^En=#I<-{IZOQfI_mMW+~-358tT!xW^f$rH)rO= zwRl1KpUkw13{Op&p%U2FJmEb1ur-wRmy)X8KS1HPqwB$(*?lj(T*i865SO zB$p}%A0;}}qyNA2ZTT~R9QAl>Vjf5R<;fMvm36$TYvh#^Em2nPHstVt>bN7JJ&uP>d~B+Is^6iVqzXg{q2eQ)*SCB?SG|vQIGz=%s=L} z<*3L1C1!Bc-ps7LPyGdSw+PNvWG(!`+&M?D^!98*Ug%Yt{EKluO(mP&!WFx$G;}{x8#jF>T!a+j&Igck8dUBan!$^ zoRj(Q)bZT}-%H-FqaHsy?S)KQPlbv{Qux=%AW>OW0B zOFpmT7hV4&{AV5Y_+|1{9rgIH#5|7reJ~-;peVWHn|8w%c33)Q^^oo{Uk)F}ofs9J`Ks{B1H$9rZYFVjf5Rc**$51a+LS>xsgN>!?TP zx(|+ebf4yN)K8L3noL&5$-AB+oU)F3bguj0s7Lo{9!LFD$<)a-b)2^A*YkTQ)74Rr z(#v)8Iv{B&s4{m6PzWPwT^mpuKVDqNB3zSNBwNc?8zK;oU`k>!ny0H zN9Q`9qaNL-c^vigB=aWo)p7o=7YG-uqaH8KoQ3MB$AuH~IO-Qk7EKnb@ZxsbuM7nK~}p^>X3zb=0GC-3LcKx=-^s>Q_isOjfGn%3ZG#KAq=6 zhk9H!T&<3JTs<+5qkfHK&19`Q{;un_!zVINhkA6bGdb$feVWHnzfQ7lvR)n6?|Osq zsm#!!9-ZqtvfcZrk;C z;r4aZqjTK{M?Jbv^Em2vNOnwis^iXG?-K4>M?E^%eQ?yH`!tWE{+ax2Z?|ywI_}Z+ zp5b0~)Z=@(=G}y&9`_E-UFZ~+o@rmT|grgq!3(erD-#e1sekE8zSoaO!xtK;Db9+4bbM?D^u+@EVW>hb8%JdXNf zl4FzOlHv&Pu7l)VB zQID4g1X_>e0Doa2)J6=i0=zcwKpYctaia zcw=%?9rfs3GdK?Rn{#vGTD+yaHN35kdb~ZkqmFuXt{EH$`^~vCaV_3e-W}dkM?L;A zxwnpbbgmg32m8&rFL5p2Up^2%SVuiRl>DiVdUUQC90&W&c{p(`K2km!K2}FPKAt>L zM?E^%432~S<~*6W7XMs66+T@@JwB5>TSq-Q*9?w>{pLKExE7x;UkG2UqaI&MUaq4a zoofci!G3f8lDHOMDPIj=tD_!YPySj*Jv!G6j)VQ?{4H@UzEQpzzEwv(zMZ^NM?E^% z432~S=DeG@7T+u14?n1*9zRSzs-qsAYX--`esexfT#J7%KM6mrqaHs?KCh!5oofci z!G3eTNL-8mDE}FLSw}s7mHexYdUUQC90&W&`FG-4{JQ*4_}@C}@tfq^I_lB6W^f$r zH|M*=wfKGcL-=DI_4rfra~<{QTr)Th_M7v+#I^WKIm8(Gcf~}9dK@wtD&eR{=bFKB zu-}}a6Z>(Pa@cUVI_h!wWQ02E(Ya=D9PBq|#Kg5YQZjNfN-}C4N9%g@aExTkQg7{C zGdSw)87mn(`E5B)IBqgtGJYK==z79%qGaMyZ#_veX&v?UOqNWZOi@l5PL)iZOjE~c zyPhtbKAEAMF`OxxIhm!7vnKY;mdu{aQO+68mCT*YQ^$F`o-dp~S)g1nTqs#MS)`7O zCiX0rES@Y;E*UPBES)S<$7Q=-E?hoYp8LpN5E?K*d z>vX+txL&e;xk0#LvQe^e9XCnr*)-WK*}U8$+%nlJ*}9I~biHl3U9x?-L%3tIQ?hd% zcS-EoHQ6oMz1$<*GubQIyN>&Gy>GZ*vVWC-&np<+0&$b=2ea zx&GROqaK}W2FJmEbB<5!#}mpE!;|W$$6Is#%?U?6I@b)2gZ<{5oY;@2l&6NL)lrXk z=lVMnj(T*i85{@u%{e`>AI~Vy49}{g9v{f{_az+l=v*^64)&XKc49xCQ=S{1S4TZQ zn(O^KkE0%)YX--`esj)G?8ghr3&V@*sK=*rym zsK+;RypYHnbgmg32m8&rDX|}KE^i5M zt)m`4$@PAn$5D^YHG|_|zd5%h_T%m49pRmI)Z;&Myque?8eppJU{A=mqL9!EVo*9?w>{pLKF*pCmD ze+nP2qaKGy{F;uV9-V6j$H9Jc9!c!SN6W{;$LpxaVUwZjs7L3T!BKC&IZxE_$*%t# zK2=9OKAk*MM?E^%JdT6?&&Hoio-bbrUrb&~UasR`x_%{mHF>RkJ^X9pTr)WSEwSf~ z!`;=^LiYdaMa^LiFq6c`^{M_u^$&Nmk5`vqaKgU^@k@M z_2^tPI1cukvs7X~E?q7YE?Y-E9-HfrPB`k(xn^)2>^En*#C}}9Tp?Vsj(R*X*B_s7 z)T49F;5gWC&Ps{>xN^BlxN05scxtXcIpL^B=bFKBu-}~368mxWa*c4!I_mMvTz`7P zQIF0wgX3VoIcp{MhYFbe^bIykIprN<6yrzyC(MIZsqRb9(B~?9l8Ft zgrgpvYX--`eslIr?8m*5y_0>Cee1Yi*Z1W5yAmDh(Ya=D9PBq||HOVgp!|J!U>)^% zf3Ckb;iyOFn!$0f-<*RI`|;r9kmS(husR;z^`CP6gNY9H=v*^64)z}rKQcM0JUTok zIW{@2j>mWXSgwC0(V-rlYX--`{uAOSCMT6Aho>Z`Ca2Z$^sdhc&rHrL&koN?oNETh za}#^cOU_R&C@%~zN-j<=spF+x{~^3AxxBn0yfV2exw?+mB=%gJT$fy5-VolH+?3p0 z$6LC-HM}jky}Tp5Gr23dyN>rH_WUuqH@UC8KYSp0FnOqsf9m?-@R8)v^0Dyo@VVsqT!u&zgWUikIprN<6yrzV<-0G zZ_9DQaqFnZWpe#e2}eCT*9?w>{pO69*pK6v6ND4iQI9L+`sEUidUUQC90&W&nJBRz zCoU%mC#|C%SIPA&B^>qWTr)Th_M0sL!S>e0Doa2)J6XR5@0 zoVuJQoVJd7TszmVm2lLfbIss5*l*5siTyZzIYT&O9rd_=u3tCds7L3T!EvzPoS72) zaprQCaMn8NapPRSVZu?5&NYMMV81!DCHCX&e1 z9~Ukc2^X!S9(T_5J0=|U=v*^64)&X~SYkgeUM>+XSw}tYp6ho_IO@^4W^f$rH)pBD zeq6d-CS10TdfX@1FIUIqlNA!@n!$0!#C~&Ds^iLCuM)0WM?L;Nb5^V4>d6|3bIs$p zW@5iNYt`|0U9TOkQ%60no2-|tUv3a?m^jxwjvFQRn6q&mH|cuQaI-qxaTWB@dT+ z>qnAD>!`QqvE=dOiSo(t&&gBC({+5N>u1B~lIP18!WWa5l9%iFm&Be|l2?=0%Gblc zCVxxbsN!`<(67x6?_M7ub z;#&N){4D&uj(Qw38NH5rbgmg32m8(WB5^JLqx@(1WgYc6PBL~K_2^tPI1cuk^Ht(n z{8#z!@asD2ae`#LI_lB6W^f$rH|IZzYw^G3H{rK+)Z-+{M0M1obIss5*l*5viEHuu z@`v!pI_hzXWU@Ny(Ya=D9PBser^L1RbNRpUmpbZknq;av>e0Doa2)J6XNa-?|62S_ zfvXmR7X9|k?UtmIO@^4W^f$rH)rI;ejKG7H5{#udYmWM&y{f0qjSyRIM{E_=!yL} zMmc6URvq=YK(3!J;iyOFn!$0f-<+`%`|-EsIN`W;)Z-$#exZb;9-V6j$H9Jc#!KwS z@yiLq3G1lGC35{@2}eCT*9?w>{pL)R*pCyJlZ2DjQIE^y`lS+%dUUQC90&W&nJlp% zCoiW6r>vtMSIPA&B^>qWTr)Th_M0(@#+>e0Doa2)J6XS&3G zoW7hPoUx92+%(s3oN&~mbIss5*l*5EiTyZpIZHTe9rZX{GJ7&dske5n865TYm@{V` z=St>I=1JzQ<9uDuA1;tASS}PUoGg+oTF1o_dlpZYNR}*@3YSinNtUhSa$Wx)ad!cA z)s?Snp5X2d3GVK;=3KbDySux)LvVL@cXxMp2<}dBg7ov&ox4v)s&cB%?c3co#&10T zHJNL!3SS_5?=Mn}7Dox!lC%^`ql}x?ve2G#D31!R6=@|@Min=!Ro!(pS{*f9YtmY% zjXG{t>q2|#p*|Y8Hl&Tv7){))Hg(s{Xmhl1ZAn|9HQKmYZ42#bhxX{;+L3lbXLND1 z+SOfmqutTNRqML$iC%72wXQwA(Fc89`_cXwfPrpS2f6FPbO?sJ4x_{ID@M3k9SQ9j zh0z$}I+l*Zcua7!I?-KEqLVSjRqMK*ifL|EwLTp)Fw@QIEO$Md&T+Ge6wuIlyJYiL%ruIjluL$ey#uX9#H z`_)yhtLYjyt6En-aQ{1KR<*9`xjI9$8rZLM)KRjsSvx&JFPt6Ep}T%Dm=4eZxBTcQ2xHrMTRhnrQct3eUO z&8pT_Jy&OFRs;KW&Q9oFb(iaIy2s6`*42;*?q*f%s-CMeG^>IAI%h9*ue#55KRw`P zRqJY4gm$y4byd&R8Jg9=ew}j=x>r5qdYB$@v#ND9BEq{_)w-(Z>I}_lV86~e3f-$7 zb3IN^xLMV@8WoYbW{Yvl`g1 zbIwBds^?tK(+h4^wXViRY&WY~SM^+-p;-;=*EtuVd(}&>m+2KZt6EooL3}r>T37X4 zouOF`?AJM0p?lS9uGi@eH>+A#6CD zn^mo=dalmUtOoY$oIB9H>Rs1+^uC)_t*fb#(#@*YRXtZ{XjTLJb$y5Zv#NFNd4ZRB<@%bw!S8tMX7!!BeosH(qpQ|+{RyAltZH3* zbj}wytAF4tzTvx@)gSIUNDSV4BB*OH8XO@I(#>ipXisQ_L0H#tG&~|8qMOx7?m9A! zf~c<1XmrFtOgF2spgpk>2XS5F(fIfozqnaV;I0$WL`dwKgeFBYBzLo#0@{-jsgT+= z4NZ%5NbhDfgS*a1Ga<8U7Mc~=kloE{4rotK%24{^1BwG1yKlv z-K-XY_7p`i6n8B_OQIA?yIC#cuFKMLDDPTXY8TL{gn)>S=MXJ}Rf`*lu3XusOXwJ~ktW>xE|UXLw>W>xE|o~tu7 ztAYJGrzx~wZRXmXws5nmbycs&^g2(os&!S*)ft-Az zI#08zbyd&R8Jg9=ex1`6+OM{AZBIM6S=G9_nfvuRPqV6ZRnOHKn$^I5ozoH8uXb|n zOuM*Q)w-(JV_TtF)w-(Z>I}_lV871k3hh_Bxpt>L+^lL{-Oc?wp;^_ss^{tq&1zu3 z&glv5S9`hkrhVM3YF*vW{d=KV)w-(Z>I}_lV871k3+-3?x%Q_6+^lL{)$6f?(5z}* z)pK=*W;L*1=M04QtAktz(;;qFwXW***imR!wXW*9IzzJ>*spVjLi^QWuEXiCZdSFf z>h;)3XjZkZ>bW{Yvl`g1b4Eb>)se2F=x8^qT363=|5<2OwXW*9IzzJ>*spWOK>O9P zuH)!+A#FLVDzXjZkZ>bW{Yvl`g1b0$Fh)rqc?=wvsmT37XY>?$;?T37X4ouOF` z?AJL{p#ADp*J*URn^mo=x48c|XjZkZ>bW{Yvl`g1b7nyM)tRod=xjHuT37FJ{~c&n zwXW*9IzzJ>*spWuK>O9XuJh=8H>+A#7hs{ARjsRfuFlY`2KFyvUW_HKOX)H!#|k&A zE8VqTkF9dEx*BVs=jsg2>RRZ&by$xLt{dqlY{nKht6SamHo6@H>;Q3^%Z&* z*IcjD8~6=3-K^e%_T0uD+;zQ2@8ba;x>AUcm)pgloi@_HLVU4zl!2!W7pRztb#&@>Ffx`w0S z5djh1tVY67US}OfWH+l(phiVBH>+A#tMmVxEIZSJoL&8pT_Jy&OFRs;KWPHbqu8pky*jpt@n>uP=OuM5qp)>S=MXJ}Rf`*luy zXutZi>n}8cn^mo=jk&)eG^<)y^<15ySq<#hISHZtY9iOfG>My4t*gzszbQ1UT37X4 zouOF`?AJL-q5Wzy*W@&Xn^mo=t+~G?G^<)y^<15ySq<#hIVqw2YAV;%G>w~8t*h<1 zzb!PYT37X4ouOF`?AJMIq5Wz)*Yq@ln^mo=ow>gwG^<)y^<15ySq<#hIT@k-Y9`mr zG>e;6t*hO+zbiDWT37X4ouOF`?AJM2q5Wz$*X%Thn^mo=y}7?9G^<)y^<15ySq<#h zIXR*IYA)B@G>@BAt*iaHzb`baT37X4ouOF`?AJLSv|lx@milg1wXP24{(;b}YF*WH zb%tg&uwUooh4!oYT=UZcZdSFf4(I-%(5z}*)pK=*W;L*1=M;qYtA$(((;{wGwXTlh z{t?iuYF*WHb%tg&uwUmCh4!n(T#M5ZZdSFfj^q9@(5z}*)pK=*W;L*1=ahu@tEF5^ z(=u*WwXRO${t3{mYF*WHb%tg&uwUnth4!oET+7o6ZdSFfPUHS5(5z}*)pK=*W;L*1 z=TwCDtCd_U(<*LOwXV+M{u$7$YF*WHb%tg&uwUm?h4!n}P#rZ;)6HrvcU_y#;fy-2 zTGzFnt1~pKTGyVssE7Kl4QN9&LSr|pP26=;+6>KIThNwhh1PCX+dzBTq8-}1cAy>6 z37y@nc5&BTX*YCt?Lm8@7kax{?E~%Ui+cQMrNc1X^;bFqBQeU& z>S$=s7>va@*YR`$CSsDC)yeL93Z05+uG8rZ%)~4=tFxg!b1)b4T<6mTScpY#Ru{YL zC3Gp4xh|(GuoA1>tgeRktif8Wb6rn2U?VoUS>5cex6rNF=DMBkz)tLPv$`AFvj=;z z&vidNfP*;XX7#YUK0=S;nCo$R0w;0G&FX0!4(HvhYF&+r$Zl4( zuIhE5&eN<0_UoJr(7ozK*Gu%Wn^mo=F%jL(s@7FKS7&He1N(K(73f~|s_Qj+-OZ}j z)wqc5W>xE|o~tu7tAYJG=LU4I`kU)bddtnK*41AS-_5GlRXtZ{XjTLJb#ClsGc>D#{W|A9bg%lr^&x%aW>xEIawK)Ls&!S*)ft-Az-H8oPYS=G9#=jsg2YGA+4c@EvHzHog>U%6S;x|$wo-K=U|)pK=* zW;L*1=e&mQRo}S&PT#s&)w-G)8QrXEUDb1ShGsReU+27o?p5ErexM)StZH4&j;wB0 zwXW*9IzzJ>*spUwLHDYkUBA#j+^lL{&5fLHR<*9`xjI9$8rZLMzC!n^-(0`bA8uB) zu3C6*R<*9`xjI9$8rZLMg2eh?_o_cZ4T@lHR<*9?XMbL3R<*9`xq7~4HLzdj1c&yk zAzVY!P;OSWt`_Frg3zpLUDb1ShGsReU+08|_N!rB!_shWR<*7c=l-J5tZH4=b9IJh zHLyQCa|A?mjpQ1cMsc&Mb+t72mxN|j>#ClsGc>D#{W>Qqv|o+p8lA>)v#NEqJolG{ zW>xE|o~tu7tAYJ7nPVZgYaG|OG@hGPt*e!}zaliNT37X4ouOF`?2pg(Y9t@7jPiL?bkIv)TmO(-h6n+_eR5 ziB@RsX0?sGZcE#ty=w>B5uMQ4&1x5DPgit9ch?@YCwif`o7Fz*RSJwq`J!(D%+BQO%9+^mjv*JJ2djB_1NCtxBbxmlfz7`%3ijwx26lF zuAbx1^E1$_YF*XqK%J*q4eZxBGobzIOxIa-wwqP0tCzU{0yL{ySM^+-p;-;=*Ew^b z{pwuTd33&;RjsSnxc>??t6Ep}T%Dm=4eZxB3!we#Lf1ufv71$`t2ep-1~jW$SM^+- zp;-;=*Evg|{pwQJWpuflRjsRfJ$4(KRjsRfuFlY`2KMWm70`ZlrRyrX+RdugRlOd& z56!C9RXtZ{XjTLJbq+ zcC)H=RjAH*VcC)H=^#k|6gJxChs-CMeG^>IAI%f~GU)}4vkM4J~s&!Sb$38)`s&!S* z)ft-AzYF!PA zAZ}K*uIjluL$ey#uX9d7_o^pdPtntER<*8%L~u8&T37X4ouOF`?AJMGpnKJ`uIK1^ zH>+A#FCa87x@uk5dalmUtZH3*bj~F=tC!vN6?)aps@B!Wh~Q>b>*_UJce5JUuXAod z_o~0S-lVtOtZH4oji|Wes&!rKxjI9$s&(zrId|Qx-gDRY=>s>bT2~(;79P23UDuEC z#LcSKwMXYXb+h`+T|cKU+^lL{eTi3i?fQoPj<t1%KeHo7Hdb z`aAvMW;IA`-b)}Tg1K1@4&4`mhD0dW&@>FfBAlDm@a{SSjfhCDk!cj@xjI9$8Wq|T z4bc(9H71RP*ofn1HLkmkN8{sX*I#G?Bt#-NtBIjKNstuDT$9rjNQqQ#R#Us{G&C*J zxu&NXkP(^OtY(JxWI-`HHbxUSt6Ep5@#o1DXjZkZ>UE&b)2s&e>zt<0ezlovbK1hqs@Bz6 z+&=@FRjsRfuFlY`2KMWmme78+m1}F-#?7kM)p^`M2bxu_t9q`^(5wdb>zuaGezl!z zd)mRxs@By-+`j;tRjsRfuFlY`2KMWmj?jL!lWS+%#m%bL)n(kj1e#T?t9q`^(5wdb z>zuC8ezluxciO|vs@7G#9@FbQ&8pT_Jy&OFRs;KWPETmR+RL>!?c-)u>*_l0Ujxmm z)>S=MXJ}Rf`*luVXusOewLcx;W>xE|UXST@o@Q0+s-CMeG^>IAI%goXUmfH+m=1BX zs&#c6_iuq_RqLvrt1~pKf&DsXD70T4<~p4I>Sk5z>Mriz0nMt`RXtZ{XjTLJbLKnw0L`k_RXtZ{ zXjTLJbIAI%fv7U!CbXi_Uhls&(}o_n(1gRqLvrt1~pKf&DsX4zypL>pG9l zceAQ>^$Pdvb)IHb>#ClsGc>D#{W@m>v|nB5x`-}zv#NFVCimZfW>xE|o~tu7tAYJG zX9=`lUFy1wE_bu4b@e{?--TvX>#ClsGc>D#{W@m_v|nB6x{9uLv#ND<4c20v>w3BY zdalmUtZsz%Y{F)2aotL{VLNuXS>5TbchTK$R`*~p_F=!9)dSFd2XP38U60VCIELeH zR!_L=lk^l$yPlzEq37xh&FVR5&v{(HMb}I8GOpmNo7HRX`Z~RV-&}9fTeyuoZdUI? zd+y;r9=JZFkMI~z+^jxz*U#v4yl{O}K_gyZ(cI z#W&aQ^ap~(;dL}Lt3jbX!Dw)Va1BXAAvD6cSq-(}1WA$1&1!OYJ(quvb_zGET2~wM$J`K_ zRjsRf9jNm(tAYJGXQ?|&P05d`OOVRVs@B!!+}{+MRjsRfuAZq`4eZxBtKC^@YJN;z zg*0wfwXU}2{+7_JYF*WH^-RrbV871U=+08p@?+`-q;s>Xb+tYBw}oa^>#ClsXKGdh z`*qHCcb1x-A5*s>gPT>YtDU*OBQ&d8SM^*yQ?nY_uXFagv($|In7Rj<+^lL{?auvO zp;^_ss^{vNn$^I5opacorDo>G)I-SPW>xEIZ|?62&8pT_Jy*}vtOoY$oRjV>H7h@+ zo)w(*E`v*d^s&!S*)iX7# zf&Dt?syj=~$&aa5kju@g*45$MKNOl(t*d&jo~c<4?AJNB+*xXFeoVcIJZ@ICu8!jV z5zwq^UDb2-OwDRwzs}Kr^Gf?w&-FgDakHv*bsYDPfo4_fs-CMeG^>IAI!FJ_EA3aU z>r-am&8pVbN!&jHnpLfMZV`0nMt`RXtZ{XjTLJbxu)ezgo<-I4$93RqN_J?wLTu60L`k_RXtZ{XjTLJbxv7mzgo_QDGAUCUnp*=$|6vJGH(_b+H zBi*cya@V8j7>sotN5^9VCc0Uj1nrrODVXXyjZVi5%yhFl%U#c=b1>I+9-WT`Sm~`Hl_hKLRyIDPegE)l4IO2Mg9>Z~*aI<>SU7w<--K?I$S)9XpH>($L5tncoS6r{s zYq*XZZdQMD*Ei`c+;+V~@8TZryIFmJhj@g?c;fn$KErdoaI^Z-UF*58+^oLF8~l#9 zZdTvnJwD(gKDmCTU+@RMx>^0^uD{bC2om>y^(Pt>!4TZdY6yfxD1=5B*RV7k!Xtv4 z)rjs|&yD0}H8P?gDx$erjgA;AXWVDxor}psH&%S{*e| z)6HrvcU_y-L0#8+v_2Z3p_|o4XpAOkie|3OX$!POD>tjH-L;1MT;yY5Z*^?s z#u(SJbR5QG0w!V-CSwYwVw#)P>F#<4orzhP4XvwlFc~RdhAhU@f$+uETn4aNS5ZVKcU1E4E=fc3>xVxmn%quJ_Qr*oXblx_STyame*B zJ%Xb+hT}MalQ@ObIOAsZth+u(&*K6vLhI@!T*ejGtMnSK;|6}iP257qHtjpK;kUwn z_rKid@M1!P4YCfiG(&T=KufejYqUXIv_pGzKu2^!XLLbVbVGOaKu`3-5DdjI49Bk+ zfsq)6(HMiV7>DtgfQgud$(Vwvn1<Q~( zIEVANfQz_LGG){#uBrh=%BhftZMe*ocF;h==(28NVO_ z5+V^2BMFis8ImIfQX&;nBMs6b9nvEgaw88sSop|`d?julvqHCT(&ID@k|hx53Ai@1c# zxPq&=hU>V2-*5|W@g5)W5uXq#Bwq(aL29HyTBJjIWI#q_LS|$^R%AnV z#}5SIv&x?k6u}T2ArKOw5E@|+7U57kEMHsHMH4hdGc-pFv_vbkMjNz6JG4g!bVMg~ zMi+F&Pz=Lx{E876iBTAhF&K++7>@~julvm zRalKRSc`R7j}6#}P1uYr*otk~jvd&EUD%C1*o%GGj{`V}LpY2hIErI9juSYEQ#g$? zIE!;Qj|;enOSp_HxQc7IjvM$5#l!K}36w=S)I@F6L0x>pXMDjQ_=<1%jvojTo<9c= z6u}T2ArKOw5E@|+7U2*c5fBlP5E)Sr710nKF%T1pkQhmj6v>eSDUk}Pkp}6J6Zug9 z1yKlvQ3OR%48>6bB~c0mBCr>QP#8r}48_p`Ezt_C(FSeN4(-taozVpoF$t3~1yeB% z(=h`xF$=RX2XnC*Td)<|a1Q73953(^ukadg@H^h(9p2*uKH?KT;|u=4SA4^F{6LV1 ze0?yDe->*F=3*Y^V*wUo5f)|9UGj%yL7**H?hHco8@76Kgg&e{)4Us{qwmi`#ta1@C)au?RSk^)c^D( zjQ{)Zas6(qf3x3{6!ULKYvR|A*W3@jyRE+|eM`SagT{W>w2A#UBl_C$DbCqgL(}@1 zzdo}&dzbRF{Sw{p7U8Wm#rD}g>k3-_3c>5CzJ9*Vt^GFny7<4XFXZ)WI#tV``@OQ?{p>l@Z(RyI zVMZ;R^L}TuaM>xZc$7xo){|$*Ve{#0^ewj)2{26_&+fp@;*@%hW+1XRu+r0f!*jm-r+cvi+cnR9wHEW6=G-DfA zG2g?M^s3JFy@~CMcts{=@`9%*;B^`~+`F{kp!a=qNHd~Je{WXOG~R-2KiPSSj+orR zuA05;H<|0FDw>@wmza0ohnpCQQkm6#BbyoBR(mgQZ1j>(`s96?mEZJ8HPeJXP{Vdl z8{Eb`6w2S0w}AiV-X}Y%b}oN#+=_m;tabbzahKb~?KAj|3zzZ>R;upD+K|$37JQ6N zFkrFwI>kcMCuCLg=0Gab?p+-7BXu1fy&qYfP=?+}ks@r1vOgDQ|DBOHR^xplS_n8~PL)!$?N0{}a zPnrCC-?hOkTXTr~adJF}$OGn4kiVH2g#MiZv*L^EM_ z7IWuO2UB?KB=hrv_$K}@QOvcBL(H`=z0Bqf{mrnl>5a)2)$B?X#}tj<)C}!4)2yn$ z+U&2q(bOnE%yeqI&~%LP&Z|(Yph?qwviH2>JTFSOBVGi%&?|W{i#KR^G4D#2>R#sK zMg4>8_`NDwO@B`CLjID9mHnn$iug4qhWB#^d2i2E3hS5e+1Rg8tfk-RT3f&FkS6~8 zCe8h-MN9gLQ{J{mFUIqqBueaGXmZFtN%Y2M@G|)EGF`CwSM;}ycbBr&CwBC0w8nm+ zq}Ba+le+jDI~Va&mTluVy->@K@F0~xwc0`(VfhT3v{?#&c*iRKxT)v8YoB_UD_iT> zqn%UPc)2f|VWnGmM|wOkE02XRN#=$#pW_F%q9 zewVK${gwMm`cK!C@{hM3VBZ!fX)C1LZ2LT}V^6+)XXcyBBjjcCKqU+PWI~y~4rH&W%stg_KWh$Q6yYnTvH|uk6 zuidub=5mt#-j>xX&6s1gP0RvYP1!ETOtR(IOsBno8xm=c_p{4_r4ZR=Y?O9)oXuYyq7ZEXz%UV zxaQKQ6sE<%Os3biBi_z)jl5oaGI#^}XYnSt{?$9zbd?u6-%hW0`cmGy-sQcZ({r1N z(I0s=K5X<-w7G2F*3E6QEzD!Kw%TJVzfEZp_1o_St1-vhI&G49x^b(iJ9D=8G)W@U z+M8=~jNNJrbZ+8@PL|v6f1hycPpjS_u zTd3++A>2t8Y8CGwW7c6pC@7lY{ zUf-yPyt{A5do5zt@&{{^d=^Z*Z@qKPz-Cf8y1a{`0-<{hPZR`bSE(@~5`1>u>np+#l4x zgP$u{IxlpXSho6=x29T~6Xsd}kT$~MkalX9Zzj{ZpX|${v2DH^&&{KPA5ERLm(91) z$IQEQ9n9EinN9fe6HV-8o6O3)15Kfg5lrfvam<3C6HToW8BDQo1I)=!Gx=*|L$fdU zMzb}}YI7>uLX&9aP?M@#0W%=V@7|c(v%KKmcyCYNqh9Am?K?KA-@aa*On?4_=AY*e zFnmTt@ZaQ=yZ`aCBM+spBOzC0@6?>>vrXAk~hTalo4}b+$L-@eeOquxO^|ov~(TZT_0K zCYU*qHlvAfIiA^&bet_ZGn!rUYNsueDyF@XWs=wJ+YN8=%~1AL%H(!UvvfB7gwx*q z*&|HC4yC-KA18X72c-AHWQ=Ael?!49pPubKxUt_mId+O^mU*06_RFtcv|=I5+0?Pk z{oU8StdFAGOfx3gDaDf7SnI;ty+=owk3moW*ViZWKYvaBymB+k$2{53R>~gl)5-ts zug`z-wb5rd|GQrwz0dpW*GBK%{`&O^JHL~+zd~DY&4j_;&~EQd>6NKX!DcbcmXN7U z;rXw<#Oa!t>6Nm0(FPUv3Z%^9Rlir!ZXcM{#w`2ZtR1n_J_tU}BwaM!g!-PzD|n%m zc|ESCDR8cqDbk~p*EfGmGp=nL??$>#-m|xZz1!_x^LjV6SrI3u$z3e9>6qY)$$O)* z$vYscmoQX%FL9w6Cik-J_G8#;_EffvUc=K>%*_vN&8b~6OpC-F|Lg0M<MmwU_^jsLps8N_EAPEhlLvXdmT&Yj zM;l-!+_N^pwczG;iqiIDrx~`uh=ex$yjqQiKX7MQ)Rse!HRlaG7t8ie{JOz z|2dU6r`axVdCa`t!Xs0>U5B%p$hW$hhppF{gT*7;dF$VL!53`s@~<1{jaZo2F592m zHj2{M?C)0Cq+eOw+je`ImpI~}|N8o5{pYXApH~`%iMS(EhUwYP_dNDbzkZUiG4Ola zzxvt)z9#yNHSl%$?>_s~XKMO-==U;xE&lqs$)7(j`Rms~pK}yxlGb|`@06E%$3!pm zmD#3Tj~8anim@i)%2(dOcwfBd{Zp6`eQJ4k7d7;{4j*oUy~<%i7F=fQEzE3>-`MT7 zuK&p-x>?3X9h2NdpIgmaS}~2c@5?E#d*(^r`Zuqvp+sqnl;(Tl1O$_sgiC+EifBpPs`}5D{KhKe_{kr2`jLVy5`v?B%=Qjo0 z_1BGm_j9Yyul3pT-+iY1o*&ca%76as^6!3*|N6O9;O9B;S<(-Fp7oiAKF?@V^t4y= z%yn;P+{otW$5STs_z`Bw)X`qGSw&3!GLubQt#^W!U zjs>HcOHbB#8+N?#8gHFxPKPaPG7dgsnpT_a?Y;4fjoW*HIeVj?xBA!s@6pw2=Kucd zclLk&Isfy@n*~RAv>X+4?SvHD|LNyH?Vo=B^}UQg|K9WGKezSs|93z4Z}>6&{C|MH z2A_1zpXY!5S_D3q{PX98|LSWI_&R*y>+l_cuSeiBrf+vwc=K*YF%>_S^6t(^>E#Sk z+AQr`z-&L#*F^cY*1TI&%k1Bs$BZwN)7!VLb4!uOtjLQn)laD+feghFV9L0CjU zL_|VvR;36*JGQ#t{ zoCwf=t2`1SBMPD-8uZT~>farqf0slo#6}$G?`@BV`1l#WAOR905fUQ_k|G%bufP7g z@Bak8&+~WR*O|uegVQksGcgOZ@t=Ob=dZ6b{?+fh`kqSQ_uiY#w{RPG@Bk0-1W)k{ zFYyYm@dm%+E#Bb+KH?KTL%)~*fv@<6!0+op_}$;y?MmO)S2*5*u+47x54uKjRl9Kti-cE3`%%v_(6# zM+bC7Cv-+rUQ;wfbNuytGn-iZ>-ST(v$g{}u?xGg2YV6tUdsjMi@1b;_x+QeeD9(c zdZQ2eq96KW00v?Z24e_@Vi<SQv9fAHG$j6|6 zFY*cKziDv_r*Q^naSrEk0T*!z)A{?gXJ95~VK(MK{~XCY%tx;%{PCa<`l28DBM<)# zY7Yh$KEm?foeGEWh=7QQgu4j*w{!L1y48Q*O#fZl>HK@Z_21%{iCLJ9IjG9N7qc3w zqXr`L?|X=XsECF$I1BxIV$Nd<|2)`K=$|{Djt2aF#SPI2jnM>2_Fw zY>&I2E#wM>=+ADjnrdR3PWN%NWd3M3v zSbnjt$^B$K7TMClvilW!?zIWZ|8AZf2yI{f9?HfTS<2sdDTF_-;~(~E(j0!tI{WO^ z*-8EEQ49E?_E+(bmTBSV{nE~EX|%;2eR;zUJ5j`@_9NI42dA25^|JWG|48Z2o6x|& zyrPQ#<@Z+ptlPEx4ml&4o5AbZ{pb4G9b0~Q*>6SkJ70?CFV0`ik9|Ca|KNB|Z_mz$ z-fsnWn6rJ0`*Wf`wJAd;wZUH=v>y}C_0~;Y=H-6%t9K?-8*^>@2vg`rU(@!>0I%%j z174>!PrV9LPI#Xi|6#(++iqI6iDY6i6uPBR}kmq$9oD)$V%FhVD1( z;?*=WgQfSQgbV2(9{t&V$q~U1QT(}`{aYA6#qp^A?BrqmR-HomKi7`wrx_61?-3@p z|7u?pf5g&=exoKK{1p#+p$SP+Js{_naZ0h+qC`G*eoad*j_)~us^c5vbhe_ z=KE#&?UpCC?6`i#?XIZrZLY(=_{VNsvGHHT^^c{9<$stS!7n@`s$b*5N82>{4BI4e zE*ri0TQfaTGyZ>1w~H#BwpF^_vE4%*vROtyw)%On_ZQg3>6)6c-Ew)YT6o^F*rV*m z85Qiivx)5RjeX67adGXfzMH%qQ9}Cz6ISytg(~UC{uIw&c;=Hmc08r8Kkn0&qWUjG z=d$Y`#x;G;&GE|bjO9Q1T*Hquu#G>pLLJknQUe>eXkV|+={(+#J43xm!`pkwD^2rK zp19}TOA^l<&KAoo%oEq_?d_Q)yMMAFO&FWLQAwMtlxKHE4`H7aylzIlTwq@pnPg8c z_w9<^YwP*(61jit^YiGHa|-1Z{FrL z{p{N&wQc|75l#P*DgEa=%K4SrMDy#fiRj0Qx5d0WnZ;YV^0AG1v54Ow!vs_0T`v=+ z{W$MXyR}}B+KapaLx-3R^|EWtD z|HSlA|M<1owti(>d-i5?scK03s%JZUCjLFU|HFEl_jMQB+upOYA`P*ni}RUb;)?cI z?PfOd+tM~y-0*(bbg}%PKjQh>^)kT&wJCilL?lzhJDa&jLo*AucOtU6W98-tSuP-jjW^=YE zW!J9_We;utVmckkWhcfOV-IYZXOl!NZPTpWX5W9xZ7*jlZMTIxVpndeXIq_XXd`ai zZ?nZeWv_qRWViI&Wz&_bXuoDDWmmMhYU{+VY`cG4Yx>_RWcme3ZblRyWfDXlYeF@C zWQGl%YS!od!#o=_$1Ls~!tRVa)uj0TldXAsw8?SnjT!i4h&eL$or#^NhpDyYj)|D6 zwV8YGu4x#iqIsC{*gt+9>DSYtMjyO;IYXHI%i4Pb8V~Z8A0F-b+4zi}UwisBreC|C zW1jJ{b-v|AyH(Ol61lFYU(>Y?t?`m1+2utzlGSUts(`2efBOH~c+d&YZr$!}ZC}cp zST(<==jqvv6TJ6wH@fL9Y}Ve}(XEcB|6lt5*sVYm(===_lZ4NEW``T(Eoh&_OwJnH z%p5z%8*_BLck^vh)4otj6MFxA@7}5f-oP)h&F&EiOqP(7y*%D*Z^NtPCY4QOCKg)c z9l12e)9)YG%Ox?}U!*jri_P(h2V3ar_YnQ@=#OjShPb9)*U4U|wrv}=uhX(olR72; z^#=uRbxTsa^T_f>UdD8z{^|3AbbMZ*_x6AHo_;JpHV%Q$YxI6t?|uL7y=vfn>Yv|R z2HrdB?+w)Zt`5Ae?})$ty={N}`_%rQzLyESchTQd_Sg3*cUilK`v|;edBpq}e}3=s zoa-0(@7}|_=g0rk_c8yw?_nbGUL^27CN*;!q(wTUM+Rg>CS*nyWJNY)M-JpfF62fY z{Qv!as5I|$%AhRDp*$*}A}XOWs-P;Wp*m`yCTgKJ>Yy&_p*|YmfAT)73;X+^FZy8s z24WBfV+e-gSB$_&jKXM)!B~vLcuYWL-dj~cRa8TD)I=@RMjg~eJ=8}7G(;mbMicyZ z@BLQtl+LKYeewk9+px01o014&w-p;uwzO1Ww`%&f;Iar@YMi6*&1R)-VZ8 z@4|;n_oxHRoA-&#mnr?d8k;kCbFRixHbGgu2 zukYmPUfE?myu)5yZ`r0z-slY>Z1B>x%-u!{{&7#%kmJ0G2~T(m}9jBA+^Wl-X-aLi*b~US4tinm}bi393y%sOL@fZ5q*@-IHM74kNYkoRsyS~_O zdya^08-McsU==g@3odoAchX<6b)HA_=cF#}w?2~D1h3q~j4R#SCfl0C9_XCj2L0o- zH)=vEb7eyj|3$dU{=7bA{GMg=`n_u8@C#*2?3ZpB)lYMvu%EwdQNLEBVt(((h5Wry z>ieIXR`s*QspQA5U(}EGx|v^bNPT}%x3+%&AnpAPp-T7(Lp1e&=~35@IHA3tv2ktx za;s1FP^js4#c!MJz%<$Yk|_q+ZkH1KJr685`Z;S?bdmY8sb6jCnmxf+sO-Oi~lOzH1i_s-_%oZT-rBbz^K$s^lo{6$+b*>5)2(NzA7JxTq; z+hh4*zwz2AK?pzS$6)@5X1i>($rtRjUr*btN59)*@k99?DowOS#+LWbKF#UJd=T2t z(J_^OqhDS>?}MOz(DE&;z9t!hR5q(d=Ja+Rsp932Rmcn8GmY1O`YZ2L{O6u2H`XLi zJHbpmoXGAv5Zg{%ncmBrKD9S1QZKu)&j1^L%mn-S;#j+K-~@Z%#vq&J=m6Vn_b3}K znDz8?TeV#nlel?Mv!+89Z}W#$CS8cEw&v2bc45VZrsTjAHbb1dHuCn7w%gq~HeJW~ z{;D-`{f%D=`48q>fBg8${+!)a{l{m^`gixm_kTSw(~jD-(Mwh4xCs{PmUpIkUaxz~ zL8f4WST;h#A+~&kpnk@xzxZc*RQAubZ{goQP~NX`b%!Z;C&%^e^?v;9sj9!(U$VwmtZ5g8eaN+&}&}LS&6<6Fg0BQCSirT zUdLrkY=-p=^G~nWYVtjR!1rAA8Y?-U8>c`@q(W+>L0Y6kdSpOGWI|?SK~`i# zcH}@#N%A9;}v`B4A`Q3!=m1VvE{#Zdw!Q3|C|24ztWo_0a$g(Fl#v1WnNl&Cvoa(F(2625r#}?a=`p(FvW=1zph%-O&R* z(F?uN2Yt~G{V@OoF$jY(1Vb?l!|^LdU?fIiG{#^o#$h}rU?L`AGNxcEreQi}U?yf^ zHs)Y1=3zb-U?CP^F_vH{mSH(oU?o;zHP&D))?qz1U?VnRGqzwWwqZMVU?+BAH}+sJ z_F+E`;2;j+Fpl6Tj^Q{?;3Q7rG|u2G&fz>R;36*JGOpk%uHiav;5XdFE!@T(+{HcI z#{)dXBRs|vJjF9S#|yl~E4;=V{EoMHhxhn^kNAYo_<}$172oh3KM*7g-+w?*1VeCy zKuCl_XoNvnghO~lKtx1BWJEz!L_>7MKup9!Y{Wra#6x`ij9-ud36ThikpxMR49SrK zDUk}Pkp^jz4(X8r8IcK@kp)?i4cU=HB?6p)I=@RMjg~eJ=8}7G(;mbMiVqeGc-pFv_vbk zMjNz6JG4g!bVMg~Mi+ENH*`l2^h7W8Mj!M=KlH}{48$M|#t;m}Fbv197=e)(h0z#; zu^5N(n1G3xgvpqKshEc8n1Pv?h1r;cxtNFfSb&9CgvD5brC5gLSb>#Th1FPtwOEJs z*no}Lgw5E3t=NX`*nyqch27YLz1WBSIDmsVgu^(3qd11+IDwNmh0{2Lvp9$IxPXhe zgv+>stGI^ixPjkr6Sr_1cW@W?a32rw5RdQ}Pw*7a@EkAj60h(YZ}2h=G`hh1iIL zxQK`N_!++-0TLn+5+ezcA{mk+1yUjvQX>u0A|28r12Q5LG9wGJA{(+J2XZ18aw88s z7+Cnoi+sqB0w{<=D2yT~iee~^5-5pMD2*~Gi*hKB3aE%msEjJ;j4qgr|LNyGi@9eB zmg4{9=REH?PoM1szK{I>#%C~r?=|cD%zyXK1^)H>%YpAF|9|!QiM~Ir&q=zX8@i(h zdZHJ4i^TvPEK+DY5c$a8Omdx@dQty&r{O!c}Y5?M+Rg>CS*nyWJNY)M-JpfF62fYcrdW= zkr(-p9|celg-{qpP!z>b93@Z^rBE7WP!{D-9u-g#l~5T~P!-is9W_uBwNM*%P#5)3 z9}UnDjnEiP&=k$k94*iitxyggigtF^Ot*jV+B+bC04*!N?v+lN69|6lCg z30Thi`Y--wN=1_t5h5Z(REF<;-{z@8=1dtPl}P4UGGxfmASx1tQY1r2A|x}Ji6Ugo zTuAkQx6W^!|Nig)-ut(I=j?N?bFOQz>w2yAto5uO-=69FJoo2w-*5h1H&-3B zn(>;`>ilhN6IK;p9{!;{+mD;YTCt(L#Xp1-SGjOzj42zc;}|?E*)8k=C%=8fD_-Pr z>Vv&p8kWpY7DjPu{Cakquz^3^UBvy9eR;NOC>tc7<&@}0>=$x}!}1cjQ|KyQFyS4A zSJq^$>xEQ!Sd;7M8gW^JW}Kc=lcyR!poG(f^y9nz`4P;@|2r$WK?cE8p1#J$(BEs)_0RpFH{HOP(^gob!9X;VX~Ic|~>; znKs!(@?3SrVM`;4ThUym*tM3;?;XW>P$T(Xswr1f(zv>%z6@LKAa9ekC1BMxp0vJ{ z4|ho7#Yd;}{jn>#$>pYUv`kYDPe|c8oX6TXYKgMAjd*O1=QkdKJfX{Y9`$+|58q`c zV=C%Nq-`Y!L^hNgl8Ci6Wyuy@Y2n$Pe~x$O zX&okW;+2M6+jls-=DG2(DR1a$3nPA$VaiF@jo74v8fWD8;GnCuc>l(+oafM(i+oi{ zwZMvcIoY6xus|6xqB)IUr9sbozE!@zxTY+c{z}>ByG=1#ykD{RIHF8ck5m@*%~Z5b z?o|#=iB_Bzgez*p!ju)$Zz+8*YEb`Y`qarWOG%xqO$qf2mC+q$z)Q6vb{!zvhZbz@?y^|<=d=G#qC|XvSV+S60$gjO3fb9oNM>Vu)!WW8uO42 zx6B~_)d}=qaSYW{k0<@hU1;W=MpSUujLx3vK%K8yl5Tcq`Z3p)-Y*zHN9vBCM%0mR z`wyYEYLm%(Y9JLK*harb`%ypF0Mct5N`3>TQtGUgbhg?KGHrH>RH`~K$=GLQBvnTG)zJ=uZT7w6!IZx@g zZqVvh#++-CM)N9uQ@ukvJaS=kzG@RiN8g{JLB99M^llQ(JFu4=uN@}!hWDt}sq56= z^BUb=d5e~WmQc!=TKvnQlvbas&SN+Iq$z6poLR3vhb5h->?MVi9+kie?=G>`i<@kF z@&lg@eaTK*)umsPS8VnA8!uU}F6Z04=D3-^c$ZaeiG7^Fk^7?g)bHoKeA@}up0b4U z99z<_?Zau;=dF~`WfcWIJ55blZ=xFLC(z#MePk&b9&v=d% zbWWtqouOpyy`6e4R3+slo}=D+^f2BLkBK48Q6EEZ+pM6G3HCH!|11@HhLiM2prM+1 zbR@oj?w-@)bC0yRr@uKrEci&?VYU7^S0s(iB7?FLGBeymWxXFzPmc&%uojQQ7ZqAJ z@S`%mRFw`iA51?BEy*FlmCkRRP4i35sr|j_6t!j@^?Q~nUYO6YHXo`cgx9S z$qafj>k9pv7)#4j&Qb&IkM!L~o&CQVv02|Xe6n>*E;ac|8as@+pG7)RS{^x8#FJs> zRm#Wn{aTOnv}om5rPZxZO8Fv0ix*hZleLD_a)ljzGZ$*~u|8$kMbW3r88lkInCw5* zWYgdmbbb2)N_f4EvTBFXi#}&*VPz4GQ;gYhT2uZu--1JHRgmBP8`M7h97QeZhu4P< zO&elG$@Tk?<6dj}b*CqlERUe!;l89^%GCDO6zcpfoXpz}rXP8$DeBEp8os0*o$5S> zM%FG?>^?nJQmVgHJd>JGyD_>nVxR@(dAFhJt$r!zzCPwoX-9bBj$K^u`W3ca^?@tR z&vR({M=m>alQXa8a?t1;o>RA!$DMq~=UqN?o1nL>*5)ohar(&}rWbRa+)BRPJ)hqP zK4;C|DpET9JLiR|2p@RI^}`SI%J4+~9Djua9^~`oBhNUY>^zri?c#*TD>-oa8cvG3 z$g=(zZ&aFbk%lR&ceUlG9~AcQK7hYxdhyKo<=kPME1&#f&ug6B*wt_u$KCA8>sE~A z?jIL(Wy>)3AKR2GMs((@gN%9PK5Nc2>ddt_4&gKTHF@)gCVbG%o?of<<1ODNavb)g zS(e1HPPYww=e0K%N4oHW`F*%_+z%=pT1=a_RMMZ9d-ykEd0*p?>v}(H!S-$2a%qq; zpBb-1>l}tD?%4|!ucA?O_kKIF*qTXUy2&)*(+*1XFI8T;B>d4s{pEwV;y9-r#o33^ z4x3wKw|2C$cu7Z^`{u3k!Pu1N?72xD4!7n98>g^V-_1NbJe?;wKIZVo1NrDLa}M?% z$<@bB;b6DJ6j`XjA#vs$J9jL5Elr{7!MS8o5~mPq{`GejC|y0ZIKP=8ZE(}$lSKnq zTQ`Odhi56F2c}CGnl2Y-drI^NFFC$)q$G|TEjb#aWl%Fu*^COm*@n^5ylA{U?mSM~ zyd5J8XAcqYGcMwN-$hz~A0|8WhKk{cO|{94z)Yqlj08_r#_LJ zD0uBH8v3GyTE*QV{p}y9&+js_@d{Bsj!9HvBiHifX(zZwO;x#a%23+5)s*Ke4{*#L zO$jv$E&P|BYh2IgKrY&EIGzAf^PD{0880(_B;PJ_`#j7SjwCuCep4` z9hn@ZB1sPdDVwaQLoE+7*A1hXv=&O~@5!Qadb&J{bQ9HG<7DoDNiu2m3~}z=Ug|#U zCgpX9$lUdPW%DbRR9`E(T4S1wiJvM-$&)0}VzPYy?J8GwhKr}gM6vf8FMX%^Nc>t~ zF+0^onsj0Ll4dXJCXSMrf%Pf_63@CU&O19uyoRy7u5bIteRc9;FR8x1w+vt0N-W#d z6W^2lrAx~`lI7W3mQa6rlwl@bU-hNiQ+qjtHM4lriyXJ(GTWL=VaMZ`so`YC4U1}V zuapW};E_camv<$q95*~u?_TSj-?|HR*7YoZg+YA! zlHO46rnVA#(M@hQ?kQ%~n#nfHzGDAun3QiCB<9}zM3r2n_t`-*5Hk&ihjo+&v+d+g zUR&|H+(wEIkldTtUGgVrNpBBrF`ca?{V!*g`944Q-$;*g-pJ5BA^y zj?e)*LMP}93J@>|bb+qW4Z1@Q=n1``H}rwN&<~uz8C;-041j^)3WH!U41u9A42Hu9 zaD$OB3P!^i7z^$&4#vX-mtH74AS5@oPd*% z4yPakPD3V~fwPbW=ioeCfNZ!3IdBOs!xgv+*WfzbfSYg&a^W`IfxB=I?!yCk2#??~ zEC!y9-D@8CUrfMWOvpWrimfv@llzC#I=!VmZfzn~0$ zLpfAHC8(f2t_o_P4jP~dT2KwDgEr_u4bTNW(1)5(3k<*zjKCO7pf;F79WVoPs0;PL z0_sBpu!M%t2pWSGG=ZjI4b7lA*gy+t3AWG*T0B+JikffFpE(j?f7@g8~E$ z0$rdhbc62D1A0O)=nZ|KFZ2T^a0VCX4+CHzxWXV93`1Zj41?h?0^DFEjDpcH2F8Lr zjDzto0VaY6OoGYa2~)reyuk;if-g*i>EH)5z#nG9ESL>*U@pvq`LF;M!Xj701W1JakOawa01iS59D-Ch3`gK79D_7C4kzFwq{Au5fYXo(XW%Sk z!8te&7a$uhLJnMl%Wws*!Zo-KH{d4Rf?T)_ci=AEgZuCR9>ODd40-SboD{;yiA`LC?S{Pmj3-`h|6*J~nw?ic-M_KN;{o#S7-&N0PTMQZm_ zlk;gB(qe$R9K!e8b&YCC-VzPzIN%3Q?T0;%y?=33LMi{4_mSgGe{tf?uY7%9S9vW6@zea`nWQ?7fv`&_@Wf@9-N}2A+(%F&(xLYJ@CDItg&n_Gm^!|T5|uHrr2D2!s>%RVjrTWWJi>;eOz@h-KHkL z4Xeq{3nsGK)j*<(4CR@ZnGAI^mN{iQ@?ltY>G8CNoQgG;?$LE*YfL@KIoUu4+Z)SO ze-kO&W+Hv<8q2wQS`wG9DjR-OvhNga2`*HTtv))k)S5)X`^ksat4PXp z6?r;MOJ-fGA=Rgs^S*s$+!nv*q&=$A*g-=g7t{~~swMlAYRi~`b)@?lUCCRjFVjP` z#BGMI+Ia=Y_cKbo34`OsOf_=U?#YxFRm-{EkgD zU+|iYcO1RoJ})}_g}=m9uv$U^w@)qO+HHQbzrhDKU!x+gJYH~LO5*I1*V*dyGY-Ff zl8=`pahs@Ee%f>sKOB|LrnSCt)pyR1nT0&~a|pMLd(WAQnOy6rA$tp(ORQlJ2^&a~ z=99`>s(<6X*RAD3fq@i{f6A*hW4OPgt*mold3~_A++HW*njXnL)zM?w(b;~yt|MNa=S*p%118ec`VRiVz zhg`~=cZF1TeWn7-a(ehHm&$in&@@X^PR;#9wy1A^7}(` z?x6t*rR4l{Fh@@x#*sHha?tDq`g!daxpa)Ca@$Yz%C|R1+YaNNH4~}za}C}cf0laW zmC=~{{n_iQD_?ZKN*&gfke}*sp0GEZSMGG=*y;AXHXwTM9!}w~gwj5Wmj=uz);-eogvEe&A9_GBBFRQoba|t2*;!ZYqZk)v(96PgI z4rTvlclb@dx){AQ5Hr)-QnRy(T>q&rmROhDcGN)h`ss>ig}O97rZ3%DMY`A&va$9H zPM(kVuk}y)d+0|#Xk;oQx>b`Yx_YvyQ5iGpH>!EhIjOa_Owm^r^`alVqo{_kV+DV* zzRIUZqPJJaLcAZT$~e^h(&qW_+_!cdbl94Yx1Pnu=JiVgTB0(^Q0i2)k@??jWUYpotn;cb_50b#&+BUPHlvp8n^a9!TveBW zlRt9ysC;hJrG$rf(U%vdsCU&fmAT0^<-BnjuUK@Er`*24L)I1XFWofWW|qfJBhxwH z*)yKM?>x8elh3w~F7mkvFL+O@8$9^NC)OBrjXj6_WY-~^X{Guq3Y|BNqF1b>l9cVF zG#g3>jeMxa_bKGdo4Hxf5WX;L4ac_G#DyN4xb2%@&ZAI%=^V-n0^akd(C2(UrhprL ze9qHqzhNcjBMBFtjE=?{e*^Ydq)o@?xd30J8A2X zSLCkwgNA!WQmp1CTJ|8H%!kI(j?vGl->km0Y+yIKq~}bv%6rky1H)*VS$|3iZAZ^GA61h*mvu$Y+fbT)GM27)esV;*rZ`P4XI`Kw zCo2uaaHP6;~LQ~KPi;2OC9XV^CtI%*@;Y|Z72Q7wsT zQd3$kw~&C}t)!(PNhWs|8@qb)?1YtcoLN`;SeVLe2O~K=%}jinX^Z6*T?voVlL>px zrQ&h}Nph^@`gtmnV^GOYR%(d*JS}lGSCN~k>SCzq$^j2uIsDyFI*&7zxgT zSM~@l;+eOTIr>ngy?*8qU5nBFllU+rFmZ^Uu>gi$t0=*P8r)cjeq&Ry?KIX}XYDM5D8` z`EcQQ?9X_hizY1Kw~uyn-h{r~|F<2tswb>|XArlY6v)ku z*71no_Plg?Q~u!EowaTa;z!oA(Z|1*1R>h*;God1FLbr2u;3||C`D>YO`JaI^4u?F*j2m z%-$oHvYzfLHk}yCj_sasbeDYIomIgmO)`0sPcZMVzk)SQSM!e>E7@%FHcsxnk&oJh zaLT|v+-2$^?o(XACbnhlKTTC;O`r77l&MuNw{4SA-lZAoItF(7>pJz;f7hx1U8hD3 zwW?nH@A~k+>%&f{r#XWQ^oId35L{sp42B^v6o$cY7y)iD5=Oyj7z1O$9mc_Um;e*O z117;_@PsMg1>WETQ^6Oe!F2G08Q>2yVHV7WIWQOI!9rLBi(v^Yg=G)`%OMa}z)DyJ zt04&1z*<-b>me96z(&{vn;`^3Aq>J{3q-(H*andh1<|k_c0dg5gjm=GyCDwZVGrzu zeUJc&upg2j84kcfNP$C;3Wwnc9ED?$2FKw9oP=~Z1sQM}GT{uIg)BG+=ivfm!$rt} zOK=&kz*V>g*Wm`-gj7C*1dkyPp1@PchXQy8&!G@rz)N@qMerKl zz*~3+@8JU!!$Ud3N}v>ez)$!EW$+uyp#m!5e@9)os#l__FXI2EUWb3S zp8L0EHvB7UyMMh0|G!e#{c~o)|7d;pujc~%yUzQs+0S0Jm;LYUU-#G*#fK;F2v-o@cVGtuK8!CQh>^U~NL4jg%!$96l-4&9@9e|!uV zbXdjHRhRPpA3HcCu3Ag;uCAp6vV&e(M$ppm;WX#& zU`kqZUQu`crO?tYq}|k#9Ji~{5T|6N{*dX^{9#M-X>Ch$)uz#>k%7wL8l#jY=i4cU z?VJ>Ik340kmH5bpG270q{}3*m?2JE{3L$sTMl2J z&-dcecz=y_?zt|B8yz^nZMP(G!mE?qKJNwx^xVg(^R~0Y_+++vdWug?&Ed@#Z*#`x z`#h=rIsRCl%-YF$+`T-X8?1Q9ZO+_dlgp3zb=(V%taFBQ&Si2%bOK*on#g0XB(vYH zY<6F|gBQ-no;2-!e0}t28S!n5JU`sqP(H9>Gfb4-_u?CzaJ~!$fz=IIYL4) zcf+d4O}0)OB+2JT$gQ&@#PQ$&x#KcOW}1zb*#q6hXYmlZmFq6``VW>*vpPsZdIy<% z&Oyp;$B1{+fwFzuXz8(}zYMrzFL8U?OVM`BUeM_+3(Va_$J<3zMz)u*pRL7JeWW}o zb(M>e_M)lP5VPL8%J#9{WTRd~xg66?f;Ki3{fyuIGPHu98vJA{?jld0)Rz{ANv7|y zkm408QZ`3TG@Lq0`|HLsxSk>dYnaN0+^<}x!5e;fm84&}g>+O(_>ImrR{EuKz|%b( ztGbij#~k4I2hXruyM3&6F@fFg9ORMTM)@VB{{ysytEc3Xd+BfjpW zNZvu7b()c>c}HpVL$t5ldfNWY!N(ysY?Zr}est5q-J`QM*&y_C=V z88y(0dL{hx>}$Rp+EXr^>L>nXE>b+Ki`4DVO*Rz`lp5E2$>r}Z;!%>$S5mLDebzI6 zckDdhuzbmV+hp^`ju-jO@5Agg@c?&8+40AF^P$K++`=k?eQzf4xen3%Vd8O~V3f%7 zUk0;AqbROS%itpy_i>K_5nR-=fZOF}a@O4^+;-|C?wj_3U$^+o#WioR(d|Rr!zGDF z);PrdXJ@g7elCkibx{g5WKwD#uiBw5t=>Q6W~guO(#m1&kP5yrheY*kC`MH0iNRjtFh=?HIUpu z3)%I~NZxm@D+e4KOL^nQm>=3$Tv`_57zse z<`d6jAFpB3+s@Ovtm2_Qp1io;G!7lIk$W6i#`Ug^;XtdlJZO9?j+xk+&3rrYxiwq#|B)iNdh>O%@R6hqM!D`{*0!^HQo9yUprcTe(FZe0pf z+JsM1UN`BY+|g~K%udWu9BrN`W_Bq`^nqYy>>R9dY%t`i+jls1kDB^p&8b^0K3ibU zKB=21cbgjN&aJ0hzoKYuY)%C}y{WX)Q)&OZoid?fsWRhZt}^*r z54y17t5W=Pld?Fw5&2x0PPQTbR9RGw?0j97^wjZ6q77zRk|m9gJ)%5$X-%;UH=>{6 z1U=99r1L*l(Bts4bo}B^n*N{$*Pru&MhE|(P5X|~UgOKO<@_buaPJ3MwXDXs``jXT zlM-t3GK>1PJw%n}$H`?@JOv$`OZ_ISqomL?bTK5J46=jBVVWIH>UNQAo}|*P;ZbBB zaD>duJ?XT2D19FrL@_hl)7&zBYVqBdR@c3uT%6j9D#q8My7%uWYu9g9u0GFJHduKp zzuxara$jU9J!d8<<0l3xrZYAwc5gc?sjdSRW8aI)<1`IQIC??R@4QWUP#C9FpY5Sk zmUp1c0we0{gFWI3R!6HTKwej%Oa#)gzr1*KdcE9c#?V z)o23k#qX47wFUWcf6gHs^vAy3zxTJQIfQwuC!P9Ra|oONo!o+|%#Xj$C#afNxD=Mb z-7#8W?B*c(zN>is-BaA989viTRq!;e<&-%Yd4c10 zD<8}J;$`aG66=vq$5UUg z&dl~FIBV==8MUF0SWOu%ul7!t!VRACPHn1$lmt=Q-kR*LR+DqaETFK~wRysuPzw9? zTCtjbSxHSUR(fpROM9nwegYHi;txg~Z=U$+qM?7W)0w_3zQr>x|pbKz{VcN1ruuH(*E z7IL5$axgW^mA8JHG}NTCA}!Dhs@;ZNqC0c*QHeCCehi<8T*FQJU@n1AHW%LLA|16% zq~lcV?O38n)4c;krR^}eQw#lh7k6@&frVHX-=Z~NPASeA-IcKuij>k4b9M?`OO88L zWl!>Io)C#-9#Ym_-mVyqYfASWvXmx6oRtG%`0Rz(TC}CNlG8j; z>3ryc61{hq5G*)ttd4T`V&G-kiaz&vE!zrh<GJjP(iwfQzRWNR(DuP`Fq2HJuhw1f6w4-Vi69iSs%QCWETQ^6Oe!F2G08Q>2yVHV7WIWQOI!F*T%3tVqq8ThB%0aJ+K${K>{Sg zen^63H~xhA;3HzQK1Wfl~MZKj9aY!EY#s3aEst7r!c~fjVe_CTKx5s1Dko12sSw z^gthKLM<==LofnkFoD`&3U$B?%%LvS0}H4R4Zso_LL+DlR?q~Rf;BXQs_%_9&;nXQ z)ja!F&>Gr6Td;$6&>rl;0UV(Nbc9aO85AI35aE{JVHgaD5#R>%!dWA5Ej8=SOQC783e#`2!s`|5>~-#2!b`R7S_Rf2!;)? z5jMeQ2!T)tgK*da5wI1uK_o;$G;D_*5Cc0Q7IwjIh=X|81AAc~BtRnUha^ab18@*h z;1Hz3VK@Ru;TWXBaX0}dAstRZ2AqaWI0I)P3(moLxB%I35pv)XT!t%f6|TW`xB)le z7UaThxC3|L9^8iq@DLusW5|Oi@D%c)0G`2fD1;aA5?(o_yEQ55kA3Z z_yS+y8+?ZnD1{&J6MjJ%{DyLYxoePy=*95A>lX)B*!A z1S2p86Q~WQPzTJw9O^o|04$*)G=j!p1x=tSSVJ>t4mQvNT7oUKg4WOm+JYT8 zfit*3Ro3NyRzvz{>PP>xb)u?F%0Kfc|EvvFWkvpF?WQU(@?TZAsmhhC%9Q*wL()bA z_ZzeXTWAG;D?73(H}ZdXttAY9W;kqt2-pf$HI_*Dv(B;|mv=x6{JomX9$Z&dci9IC z@L#RJglXb9;9pgTd5hcnXX`M3=4Ael)>`zm@LGgFYc7B0YyQvHTdZ)KRW+BU@Mqnn zIWAADhVu^i!3^++nJ^1x!yK3k^I$$KfQ7IK7Q+%)3dmO~({fR(TcRznc1fwiy> z)ja48!`X)e2rRs4FLQ^k%DoA>1h=i0#*H<*vu$`9Z%UtgXGC4>cUc)`#}9ZvI)m zyEThPWt`<|@6T{^%iEl^z>23is`B(Pb=bXAcOH@)$}KKWupaf|PCnOvmCrfVF@fEVH^2Xtj}NUTM{@LJapi=W;$6+NIYOoo~;T(X~`)&aY=mUDQSfsW+t#pBmCDV|Ciq z>5X!`eYkS#8gd_g#3;8uM<|;$jww#vQ$h^l!AF|+IJ|+;URq~eneZQq>$aPc*;2COy-xIDeage9rJgf zvZHlLFWZD>-?pUO3qoDphfz_258YiDLBmc5&=swLS-4eXp1$W-FS%@|ERrkCaO914=K$b@X(22pM;AqqyR}lryXy9e>=E zVl!LN+IB;z%lA#hd5KigJ)5{FlFY1^kVg3|sy}=fZ9}i4wc~l(;}J!>C!U~zJEl_) z2h7rY8H+W*nN;*sA#dkIGI*3s@$;i7+h;2sow$mIs|S+rku{_^(rqpL6N=yiyw9$bd`Ud?M$BOVs_8InQlXgI7e9(p=AKeCx<- zI_{H2Yc`eguP5i(*6AU)ZM~a={eSWEQf(RH`IU9NKk(QmA9>zB9qI59bGj_w^O&i} zxYmuWyv^tt=S0Wx>FgBhulbN}Ts=X%YK730)l0~3x)a%*v!%?pGpXR}R&s2ig_&_# z^ziU5I?&(-6(8}S(ZS@wls5S2$`jgp*3|eb<*k! z4e&Ti0h@Nxgmw35=nZw=T6ZH2+8R$w-7wE_a5Xv__f3iW@Joq1WI!X@wWZu2ODO;| z@CF}hO>>56vX;wT+OY5e-G3EN7fx=b0=JV?bv_tlRf}g0tixS(aDQvsqwwj)J;2_nxFiw414ujiR!0HOQ$xX6$4ypPAy+*Hnbn*h1Vg!dnag( z$7&kY+lMYiWRYw3OPZe@NME)@P*}_iIxxwY-&}i3I|^0!cJDKEU5TZ|EpjNjnK7TA zZ^P-aC1kpy1$Wqaj;2n#PrD=I=~`XP8FV^LpAvVHWsBd+{K5~)srp})*W+rCb5SFT znA3%x-m#&XPMG0W@RkM|9jC8qk+i+#D|&rPk4L0O(9Du#GPK-GyI<*Xt7=c_r^R`i z@*Hzu3z~Dr*n1RR`v--2UZl*9Jt$bWFB$AbZr`d#bQpWzrYz`7(bisM5!r(@I?bSM zZ?=%$kTg2jV;z~K45i*{!{}YyDEiu@6ZKAgrlg-PP|D_fR8)T&(%fDR=~RDYeYUAh zVPQX&PKS4KM$|#RbMYBpn0AXbUftnyUfJBU-&;0o`if_N_`p7v=ed3SJ$|e6mKTM5 z;^4T?e0mmUv#J#Gj8C6AZbUvmexxa0zu$7bxsQ41m}0)z^)*8^7Ga7O%2+RdzC$<~VVjSpYY`;>Cus9r={jK(>f& z!3oz**s^X@9@DrzU#$$~hlWcz*<(D9i(1CdZ}ecZ{L$RB;V?ehNnwli&G=1C=GD7v z^V5&b*r~7$_F*;R*}ApZWWfghX*h{{D*SDJ86Kzly3z?SzdHR74OeU(ug>d>$bt(BISgOrYQ%as~OchjXw zDU{xgNc+WEI(uglHNBgl%-b?Xamd|CTl9KRmQjGRa)k-GRZF9Z{hpCz{8nZh>PZgA zy%dwrqgWN^-P5NtxxjNe8}yFiUo-7Fs#Y%fQXL+vR-a$Zw&t#n^tjXHOq%RFll{hd z@ry)XR$pDL%rf4gL^j{0bh@2Kt4-5rXxAEitq?L*z)y@$%xx z1W}(qRw@#Q%grV3%Daeg<U9(y*pf}9c50kWD%_{W z7ixF*K7GEMqL{ReP#zi`=4x3rrA5Ah7}Y+(bI>=uA!GyB?Hj?(4u$fC;_4E8u7;@f zf4~(t(8qTwmERj1OG?u^ayG4rn9SD@>y*0UxUaTsH?8D#3oT@0WF^0Svqdq!)`EQe zSJAA7k+km96nd}QT1n6M6Q`Mz#O%fd34Y@z7kx*{f>2NNp7)TF3r=G5VThz2>mlK* z9c9tjX7Xeq_BdKk7K7OXrR6gZ$v2%U2Zv9SyC?l*#7S>?HFCVzT=0-lw;iO=O_Ax} zy2xE85}W$=GAGGVEM|3*wt8LV`72v_`m2w;{oGsTXWNQN2-d+?o5`8Yu5!t!mn0wU zDeH;{h+nj=Sbleu;!%d8ce$SUpIOAgU+?k;>svfXZ8ethjO;jXCt;5E`a& zo621`DXxu%$g(=)#CfrobnE6OmYXI^Nak<0ZLUazr?%X-K@OYu9;e4zZ!d5qk#9wR;Gc}w`RNwP3_ zn5b>+C+k){W zhSGFNXZ!1IY zVg|sY7P1b{j|lYBPVlcIU+0+0v8K($=ZmFmY+hedsEHiSZ7-^2o#gssMdr0{DPGog z(*9|8X_eGT{7&_jp^467J+g<)uk0*GTzkopGa?iF^p);CU1cu!7u8mZc#Y~M`@-7F zjSpQUb9Hwq!|TOlR$G~WxTEMtkxW9q@aa>Q67bkw?hSL2JI#m4an0c}++&m^g=0@^ z2RC`X&`G?*2TR}e_Hs(Msk|B1M*e)>PkW&d6$!+p^MdO|Pg4Sk?5^aCew1{dfL17IMyLe)bt7>2-57zV>(1h~OS z7zLwY42%VL7zg8F0!#!Cm;{r-6Q+O{c!Lj21z(s3)4>mBfIrNHSuh*sz+9LI^I-uj zghj9zmcUY21_7`f0$~NLgjKK_f?y4-g>|qVf?)$}giWv+LLd~vARM+p1Z;(E5D8Hb z4clP{#K2C7g>YEI0k8O98SPVNQYC9 z0jD7o&cIp7f^%>lESr-+p&@zrWsLZSsu>Ui`vDgmfaE zNf*+UbR(ifjC3bGh&YiTl0=F~6B*Kz^dh~9ERiGfqz~y!`Vj@9NR&u_qD%%56*7hqD^#&F3}_UWC$5bhLPc91Q|(2kCbuBQl;$ zAjZUmOeB+tDKR6H$rNHvrjlvIf=nkf$V@Ve%qDZlTw+PA$UI_AY{-1FfY_3SWD!|R zmJmC#l-Lso;z*o`GjSoyh%0d;?!<$5lI6sUcoQG8f~+LIWEELW){wQtkE|p9WIYKW zfh33olMoV0!bmuYAdw`BM3Wd2OX5g8Ng#blHfbPt z$X#-e+$RsnL-L3;lE>r;X(CTaGkHdylNaPAX(6x3Yx0J?C9UKgX(R8+2lA18BA>|@ z(oVjT4)TrsCykQ{#+n3kga6vRV8MLgU*`h3g)5yt@)=v z#zX{jOa=2x1#?S(Z(iwt$2tBz;~Y~$+c69~@nap*yiBMwza>Ih{!?deB0+oc(455* z>o%Oc{WU7beZiIY+VJ(A*O=bij^z&Tusr+&4s3117~dB3e%OpTCbT}UqXGA5HKEJZ zR;sW53@5yNj~foYz+ba9InR{1zkhH3#BUHEd5~(c7s>JUH^lh)&eA+$xe$ML zvJ0oRmptueS8g?=4f~#diVfqs@QSEgxLTzvuc_?Hw}whmZ9FNyQn5D=a+c-AUFEoy zWq10F(v^!^i1XC9y||vKJolSBkQZ0WasSvpJmlj5USHjt3+E{Cgd3UEckl1}{WvXW^x|h{D)75@ zUHMUyk9Z^PBRW*HqW^wT9(Y`mPZ{$7>xbOM6YE~!44J1`!Ec~e+B+;8{sz}Psl{T; z2iRKEf;nE#Fzl@ePl6YC^g7i+)GfquEqhTns}7euJBj+;itw3ICJw7=LZ!~?e6rpr z{J84?8u*7&jin6qu>`)M&X|ue*X8!c{kSXDbxfH32GiXe@oM*;{F{&l??turooAHd z$jod!kui}US3zFmqszyRK&tPy6Y!PY0oDWeprU;yGah=_PX-C=&C9o6Q<22It}Cf@`m&3 zMYo_u?>sC`tb}!QPeG$k1@ymH17ZW~;hKIEJalM=!Wk3b>m`KB#Nlw-Y6O(`Vc>Sa z4BAAOf!#}Muw1YZ%pJuc?5iwfUyuN=zOUG&r&2JbPzVC9D?pIFJUF|^L6Dv}zn9XB ze>IZfm9!SJ$X}9w`__doih6);e)o`5Ey~wld-9-Cs(aa6lDD0tns&uh!>wZ=|0JZz zlS2mZHyVoEqFsdB(ra@V)w}yhwH1e*?8c`Z?aouKi}JQiIeuVcKR%#AiYF~n;-eE} zxMrCm_Y@h(pB^5}Ylrv7PJ6}h!?oLRVa^Lk(-gu4-~L$d+zu{FKS1C9r-6xI0S=z4RyOx_mYQ z?I+e>*bEn?yn=H*T0zG-1rBfA47+<;V6OQLyt+&XC%h0w_gUxQieo99-7y_kyMF+g zeP=-F#Z4Ua{wC6i!p2#tI52KFW^^5atI`eetXm2?biaW`>(8RL#1VYjH40~6O-6%0 zI_PRX6y-)&;{d1A80wIUzON%`ecNcv6d#I<23;Jdd%eD`w+es`G&_mAnpU6p%s*JCfSOW!*fFI|taR$s92?qfWWdkw>M-(Zm_ z)#6JL<+q;qi@_z2g~j=POvQ+?Btb*O%+d_2<%CMfjc< zeR#wB3JiZxrHX@KG{y!_#pI9kvG(;$%#a<7+8;Y(je-*H71ZgorkZrL zo;acEGj^*L;~6Fr->(N(rik;sUxoOj<{n&8@iV4h?ZY{p$Ma6|d{HM^KJ9jIuGOy> zcT82{VupIWzI7vKH%Ywu6&b`6u+fSs#9gfQJ&wV152A|wYjnT) z3^hH^;)Uwtw3kjhx{kPrJI8y&-PIA0@H`c=E^Y)vkyu#nwi2G^&W7v;Pgourf#Rz1 zsI-pO%Eu+5JQ4LrK0@D(v~Hm5Gi-lF;|dS&p?uIQ)XRB+x+$-4 zg5q`Hmd#L>p9PvM3kjJ(K6hKt}9_$qI|Ds zcdo7=#d`;I<`rkV@cW~Mc}$ZW?-C`=Z8E!ZC3@b@-QJE`=VZjd^_-sNoW3L zlQ1_o`G!U(K4NanXL|n9K7Q%F`2q)NzMk$sAX${}Qxf9Au?qZq{m}bZ#m~^Hajl=kY z(35>I!9^BRKQ%(U*hHqGV$HrJxU#VhGO$u+GstJA!?jbrU{FOSyt>sDgvx1I@U#Kw zk;t*PwFEY8>4LKi$D*e1W0YQS9~Y)n;B4_4ytb(rdl>J+IOk$iRXC1U#G7z;L@hoz zQ-Q%2oAr7U|R^VMP8{ACq`IQ=BxNeUP-sq%?Zz3cy zX_6Saw0wZ9QZa1n5W&6MRIt+rNgR_q4<&;9P>kL$D`NvNt1cDyE&7JTx;(%!3U~0P zMGPwPT6DY!= z-}z5aXHdjIqw4qS3=01IFCSO`+fPmB!kCzliDVKnC1zwYnL^CTR5FcNkm+Ow5wyiD zGMmgHbBQIfBJ+qfu_5!x0%A)Rl0{@OSwif{QesaWh$C?#&cuZ*Bd)}axDyZJNtP2Y z;!S+W3bK;;l2v3iSwq$mKeCPlkU$bda!DcCOo~V`DIr_PR#HmJ$TqT_>>xYIE>cc* zlRacF*+=%13Q|c9kb~q9sUrXFAO3IuFsC=1am0v>CliPv2lK7HUWHnhs))GImj`)-HB!C2xAQDVMNGJ&-;Ut1Yk|+{QVn{5B zBk?4GB$6bOOg4}dl1kD@I>{iJB#Ue$*(8VLl01@6Hjx5SNH&uqQcOz77P6I;k}|T5 zY$rR&PO^)Xlig$w*-Q43{iK3ak^|%*IYg?+VRD32lcVGqIZkTG338I0BB#k2QcKQ~ zbL2d^KrWI?IeL{pZCx8^9ts$|F!w+T4FZX%}@acjhT&SkFUp;D`7amEFHC!OYp#!EWBNu zimweTQB7heE|uGW7awfIsU1tvV@nX;cv?bp>5kD}F$EZ*z7waBi6i z-i}E`f9DcRSI@z?=>@oS^IUx2#R(;$Gdj&5hHGuZP~0RR8^?^tgk@B3DEm1SOzed7 zwVNSrry`#AHo>{hK^A1SvxR z?cJ@XNOM(PWU%1;RJ1-2gTq4O@nOtzT$!1J5j2nMqj)r)caOk>Z!$2kS1~4UIf`?I zPGN7IGuW|u8|qBY!<#(=vHrv+ys>Ded;Q3SXBr+ z7HtN%IXQ4MKMJ%xY+&*3bhxn07A~CF1m`b^K%==bh_xBR@n@|}SoSy@v_(>jSLu3L(t$3igH zED`&~??ai~G%Q(Dh{|RsP~NW)Z!gKfIaU>D_az>`3hl+w8L2qBaRXKz-;S&6kKnUo ziC8|W3eD1UF?{a^>N|z z6`#f)!z-6cap%e{*zw{ZD&!Pn=N*Tz&Y>6s*5{$SX%2dQn9a|MSn?B=3wcAq0$wI* z!-p=M$rV$q_zU{^$a4$%>n97j&^asa8`4a}*Id>Ev`+@3H?3~7B56$4+JK6I0PZn^Y?L&C0 z>TvG6%ABvYGUeOWT5=G#io&W4X+d zG2FZG3*MWg$W0#@@|;UMQNdvomh3OaGYR{#{aYQDEjWWVlZ&udS~-T5m0=yNck#Mc zgVh#yFhT4o4tZCN>hJF1)DxdEMrtfHjW2{F<~rcrSO680NlfE z%Q{Q=un%8H!K9vLFyxpyaP=ZMuuOs{JNMvCpv$F8Y2Vr_raYPUU%uRXB7f^^z$*#yDiV5ydRHu8^V2^b@<5jz$046aHS%7euehj z9ced?kG%IB8x>lxpTa8?9rYHcl{cbn=ojpu^CkN7Io^|;#*?Ba(;hy?{Ady9=|jeG zi7ylRowynNbJbKXEmVVwACKU*qxbRP>Dy@Z^%Pp(-S_?dS8r}E&TrU-OXip1OsYZn zWorhG9-W5Mz7*q(@XdHTxd?3{_h5Xty%_mr1Ac0W#^zzEv<{>Y&-FZjHjOuML|Gj^ z+4Kx67C*s^jB8kXeJ92hoW+Ln9Vi!7im#22V5M*a%C+7?W!j7AY+)BZM?;kNSak_I zmepa>*mHRLUI%(LwczFQyZB+sJxtrsg)1NG%G(XEq3iU{-0zta-$L~S(>_-5RVg4i{rHowZe_~$|qMY{CXJ=cucc{E1Y?x zj|;yW=EBwLmhqSGw!ye-`(awPEv$O59AayR!n$wPFnr!wwnn{?Rp@+Xb=@8?9oG=n z-X(@@^4Y?kJ4wLH1;~2GS~544;Y_~H80|iq;N&cOG!VDNesjX{Lk{hg@g*D+-@9S; zvv9_nWUf^-ki) z$<^pEdnfjw+P7OTrJ&`fnQV2Z5iDlIVwQG)0n4o^VN?1Kfh{*m*<-edIZb%TrZ3fE zJ^O5D`==>E+Wu*9Y-$X6I)pK!)7#inwR230c2H3i>kVO6kJ*j8H{tNqZLlUS1T^uAZY zt5OCvi!{(bqCZAOC4*F;F5D>-1O2>MP?R0X9xt+B*RGg?zJ(qPwXS2al|C$^Za5p< zX$|w~9Lt7WXki}VuE|uUra6Yb#*4OFAfw9}er9kHG!@L2&B%TL|Ui*q-qe=Jjram%HkqbHXv$YkLSz z$n1vA_9sAU;0;j8{Q?G~x?_&iThNia2>VBug2>@W$lkdHlusRkM>dhL*1`vxd+S4% zbTSkl-UHh!?ciYFOmLXG1G>ha0K<(VLGgq$Z1=jyLK=HQ;`#~Dus8vZTWw>yHnmLn zhBK>}xse5Qsbksk(vVPZ${tNhWcuS7+i*RCy_ea>a@7v7n^o4VMJ}Dmgl}fm+fK2( znPLzuc7dJl^pNShO2V#S0~nmu9kqQQK*xa$m>fI`I`K~6D_+M!4(?{#UfyFf-&M0N z(MB-;e0P|zFb~91ufsGe8vl!a3p<--a2V~+R5RHdywxT^=(jvJ{hb`B-Z5pDyUu2_ zwkkrcVHtD(5(&Z*_VE5_2CTIA^08mywRqu#q13zd`~N*}_o))w89&NlSR~M=aQ^de zKA?ZR7NO5|??@YYPd<>3Aos)X5v(ndadU z!P@IlWHd1#;Ut1Yl2{T);zY33K>WSk-G?q;(#v(K)yTWi^wr`CK-}eGSL(BonN7tAp>1Wl`Zp8_=DjTH`m!i8u=L zh8%%cEh8cGd~aB=Y6puJd&}w*y&9p3TZX0O}tM;Q8tCY~Ep7$6Dg~{qd`fKMTSB((rh(8kWCK z!ija2DA6|t*B*1j0atqAgS%%z_v$IwmDvvd`$Q3>AHl~xlflL!6U4i$fichDvmuiU zS!=2&%+I%n)sqcDK956ZUj$zrL+G+g0>X#reQ(37v9lm{>O^>FGaSxt8v^b#=3M#V7-TUv*A6=z;Gq|evE|*n=!a-HVE#c#!?*x^Cu>T#`rf$tLpi^>jU5Qv*mK z3Hr$i4^&9{cWW0ACo7fiTt=8XVWz~hvbqxVkJxCX~de? z5NSEeZlovaMJ|!cxWHop=7_Gt?5E4oygCMV zT(HJR-iM(rOdRbuA@&at#lA7e0sE^!nt>9`Nho3o?)TVUCqFn7b{AG1D}|8@+`;DP zR5)ln9_C3pKvQ3Nm}sp*N{jsr&>1ceiQ zA$dpu0%4WfUEz@D@blN+{A_o#?7s5iSLvWy*HF%j@gDc(td!r(V z-M0h`Uo8Ze%xmyo_c$!GUk+z29Uyz$k9!OeIj)DhI7;(Qt5H3@jgM2cw-G!K$t=c(<5*Z@2kPX>i0Q8se52L$t_b zxWE1qi%)*fvKlrs+2%$zQb?E0_g}z9Jhx(xn&sdvul;^}l69T2RX76#_i;s54W?3^ z)bcr@7_-?0B}xr&tMCjQ+(!#<=osKz+kTj+B!i3Ps-bn;X((l9U@Nu3jQq2ZeDpfh z_qzxK&L4(rcAvntqB}Z#{R|P+;&^cINst~_4iMl8TRt5gscr z>3EEB2K7w}lasJHm{ok>*o{mgL z$dw764?}7`vN`6T*t{BhwrT4!COAI9aUSyi#7<59#6~Q4VdECMGQs@`?z^DkJ#*jn zo}Bt6njwNLS4 zZa&MI;Q1$bJc7qH?NBQ-9O>~>P8t52Z1VFD(htOZ&neg19e->eAfT(XZ!#C zpX~*o>wn~t{|#B>KmGIj-^w9{lt(s`B2r9B$QJVB^Zu{-B$zTv2ni)&zmr$SQD!kB z}-kzb@KtH_X^q!;|}j>wZ=^UyW=Ssl4fZjfK|(MHNh*(8VL{!U(UqRiw>T*$KD$xj-Tp)`q4SRgaH z>d$<)^neX{4b0hTD7rm;553uY2r@Im33i`hLe4PUv%n5Rj4aV$@dP~XkOr^oI$`Pk zvDoEAZ`@N@1A9(Ng2iJ!5Uwd?*Kb~BJ=cXmNy67-ZM9l68cd^)>j zHj?EHS7UENE#U5${cLTVCkT$)-7^&Ce4wfupT>MY2B`(dp?^pa&hMOnhjzH*+OA75 zATIz9Pg##fS;qKLYAQ~!^}?PLg0Lia0P;youvK~~$``7lljtHWY1YN-S&F!JM}M@f znUB?<=HsAMD=@u63zO!oK&zu3l<{-=oVIAi6-`mLx=c1IlF+NOt1qbxrLv8=z*hAC|9rI5> zUoklx5om-LYP+G(jx0E~y*F6Q`34WoVgO8Uv;3-JmRO<>(<&QaM`Sj) zgq^rM>w7yGoOgve=I20g`xSXcaLRH!JF>?C=bT@T!omqyni+y$JXT=-s~PCJZW5ls z5ESd9fkG`yF*V#C1B?dYZHL8J9k2jLeN@2%JC)G`M`LPVT@35yhcywt_^@0B9hGUH z$EaxBR%3_CFdw&UipH^>4Ds9}2b{j2VR4HyM$y+EgPd^GIEFq{3-Q3ciD)%^9a?}X z22WT;<6P4*Rwoz(_FAKXN(7$VIu|7agTJ41!MVRS;tgaTdkVD{ZV5P!f8-YDE+Lc4FV~+G}@q# z@G@95-2+Th>)8#pTP(SSv5kg|365Lv7-mSfL8m2e;b5E>43S?B(@pNM=fiKX$(;;X zoQ(k!JYK)J^J5bN;Cyr!lhexsD?_WTC&`WSx=L52v zJYiZ*14~=jz!v0>U=qS3Si_wckoD{(Oo;V{F{1{NcBkImRHlI8l2W+v9pV1xGy zxKiv1)2n?zL8O6YCER5pb4Rm=y3y?1+UH=K_Z;+S%qFw5 zcunLNG{d1s&9LTx2Uyj(!zOxPGTd;RX)Z=~OouVS>qO8Fg7$D4`T~S~J)uv;ZPvbq z{gm@Y{2c3k^L^}-4c~L#*%vc@lktmPlc zYFjCs=U&k7zWfupZZl=OqCb%D7E#7q z{0DMgAIfrl$=}O+H|ck7{ej$Wj z1x#As6#5&KK+k@M!Ho7YoRVM3UQS)X2G|ENq4_?HjR|CZ3If^8ZVGg5?hbis+W~fY zqwi=pw2>KshaL|_{|rNvt9D1V>4UNMkt(LIv%{Jf3os}_9%Vl-#CIzkQ16Knwzt~T z+FEsd?bs7b>tylJS{rPYvqagMOHlcg9L`Ibhfm{_v9fjvE?Xpxr>jCxw9m9oXn3VpF{mMrdV9f)fl%A;=dLJTo+z&o_I+kA>W&UzMztCxl2 z{q?!1;TMm^w>DtM)-c?3D;Z0@L(x(w8Z)o>VTx-yKI;~a4ta@K@jjgPZ`y!Y0)sF~ zIs=vNMB>3c(dcQh2FEsLqs_LM@8?x;e%+RaWACh3T$Z7VhZHq%u&x?<$3=c`i;$#E z@Wg&Id>Gmjo&-rjeP1b9+m;V+i|8Df2eaBuK}^stg7$7nkHWweG!|*Bj!(C1;*8z} z5F4-=j_;HK(`UUvGBK3R-yO;X&yUj3Xq0hJ#dTLT(B!xd-Z)bL&)N&Y&ZQ?Td>{k4 zexYo~^H3&u%!0>$Y;+X1Tc)AHIV~K#R1af)il8dD5HwCoL!i7g)T|3+-^K(p!DACV z&H$Mh{3e@<9VfN0HcA&o{7OLDZ8N0Il!V}^k}#{$mswl;F~PYJoTnxJark&!67^MT zqvSCieBG-Edh2Y4t*SjBFj*XePPj9hKHe1RI;~@F=|pw6r;}*l*6vV`ebg z+C-wpM|J#Use>&No4|H*Aw=f(fD9#ZuMr@(Kc|~56H{_4@1^&p4#grRM z{zP_MLiy3|Ph`k`ln)jDM3$_l-@W}OGUX=9l?8t?Te?%e^!NiAQ=4+86V>C_)z@c} zRo5|IKZ7ZDe#Z1wTG+F}qOkb$PFAo<1Ny!i4Fy#zID?CEFr@1Euwfg7!0gIcW?}H0HN=~PNs|MN zk_uwwVvfu}bIbSJE#C_eI<5k~#O{Ze*B8Nx^HU*n(+qesqZ)>63xPQz?(ojz0)!1X z3mqmE&|{YrPKlrz(Y;T@tb>Da{o4ER_TV1Sn6eKZ8;jvcTM2Yq{}@yu5vu#V2lHt; z(0-}|%HL)|=8EB1yj2~)CI#W`-OlLZ;D_h#XyVr}#04jfFn_HRzS6YE`9>>IqA8H>;6kH$B7uBd3@hWStQaI~>Dsx4WGk0&@{g1sj8Ty2LB zKD=UjpVu>|Biig%Vj*)mCkjp8wM;d8G?=z&gTMc7cKi-N?fYGSO zPWE=}6cArx3y)`2fY+FPpiJYOs^>kSbyVIDt^&%u{67r;p490Yq90u3!wt?C^tFRPqw|DwzG4;jh?=SOg^1|&w| zOOsH1l9`3!M(HRsj^_6Fn~Sejp9YoeGtgOj1n_U8K-_x^lN8y;uBEH8Cs`UyaJ~iS zK7M5c)}9Z?E9cTsW*TMl!rACJYBnnMKL*WOC%{i%2NaEmz@yE%OiQ?sB~qWa#UaY? z)045xFdeJ=OvAwHnRqquFwHfnhCzvHP+Y17ukF%Vm&lFGW_%bHor%ITXE$JvOX=wH zz#R2WW?=e|!w}r>D0H5tO7&_qAbLRxD>|FTLTQ~B91q3f0jW4ba|1q;pNc96r{b!h zYN%aM4UzP_-4AI%-Skve(U{6c^$Eo@B|+E`nT##|30OSX9AED>!^s0`DE}S>vnRSR zGFAsHe6yHoNG21!M)iBI$9nxR)EFIyUt5x}Y1|Z488HP9sGb7p&>DE8JrZVa8w%S$ z6fj5qd?t7u3trEH=iA7&p;-Sm8Be~Mis=S4hhzF^czm$rr+hl<=Q#SC@56Hozvokx zoPoc|r!JIFf8@_UlQ{)*$A6wTF36bwiTU!!JZ?dT{Ihel1@o`}n-giB|6g)qIepzt z_K>|~AK6b1l7BWs#!`-qBk?5RpUjk#DOXM*=49%>AY=BUoTxw)i4yr|Gv`~njaKrG zw2^-_gKnW5x|NiYGO~?qC%?|q`*qy4sXcKZj>L&LlV9ie{W`w=qu=vK zW>usdszmw|Wio)MkU!cl`XkFW(BIr4cga2Sfc(9&@*jPsKk{uMW!%lAh!m3&vW5J$ zIf%cGssHFx{gHb;Df=!bUc{UDkQL;w&0YL4_Acmi735(ZqD%CM!tDj@{*w@v_hJJZ z`XZBk^S;1tl@_qn%0w30^$44@ZwkwOQpS#-Ze*^LU$S>!L_ksW9G{L=t3*l;DA*`s}0{ucn(0frQyeHfhhluZjR;n#$ptcDD z6ot^Mmk7R@76l`(#=#A{kFPSxT!mU-o-~SXsr*Mcx?u= zI~B#+>ywzjdNW(Db(d{d-@=Z%RWiH#6ItcexbNr7@5LQ9Rc}Aj9cIr~Tnl4YM;0^3 z?Y7M9>>Aczrj8A)yuj9-f6c-l#InjQCCqaEC#E!OBt(r_2ewOHLFI`W^wO9IuP03c zo5Q`~#nygMIkJ%rJ8+a0x2u4Nm<((Pdc`)$=|krk)}VL$E@(vDfE7ZsVbm@m+_bD1 zj-GCZy#mJ#aZvL71vvSKLVEpUcorT6J-r*iw0IfxH@Xj#kJy9T zitF%Vi`DnXE;t9KYaLPfmK{dKZNSSS)W1BD)?hBQL&5p#dMN|1DW#%PuSC3)Lh}wr z#o#lqG;EO2!EM*H5ZcS&qHQS@`fq{P{WQ@yL6Ij3Rl)>JfJxDh{VW}@f$B$O;n!1aE*IPR%7daCSz zNiy5uVuwCN-P8f&eur3@X$1?MH;vg|HDiM3g!2j~%-Ld(yXsSMX^#vv70yMY9(m}t zWCI=wPeHGndbpnH81xzneGU(Ueaov@#@r+9qVjYGWiy%J91G61p6^1u z)ome8eUe1;GE%U%DG!HFD#YrdOkC@lfflYq(Eq$X?#$c<+rMsy7C7aB1=eC5dRfI`h&`>t z7v6#nD*4EV=VJ0uEtIm+#%nE`VWsdExV?K2#CB7MM*~Zl;lQ0tx7~oHIU)<0Jq_2F zSYTdxBpOYQMVI_y+;*-6<*oCuIw=R;{MB(1^}XtL%YzLU3&7Q@FIZP8!&ixXChS$j zLKf(<^x9!;=CJ9QT0ae=^TN?gk!nGhZ^rBWHlxptY<#Ppiw%~l_})wdZ#Qm)Q?|LV z=c)```p^rW?#N`T4RTrHJyq6gxHkLZHybr=rsLKTVR+Ik6xUhgqs^rp?0GR0PaVm` zoT-D+Wu`jr4c`c^RyojDxF<}SFAH0qrm;quEY_5##`blei$@k&;@yoQnDQbV$KTJu zX@j$|c_#Ih7o_08ST*c^Q4Jg9b7AxJJm}^t3-<41VJ02Rr<6=KX1^*kYEWZ>_l}jy zwwR@0jjL(z$sTEu*g7`_9s6bC0rv!4#*(m7TN77>tKp-^1(2dr0P~q5$W$wUYqxwB zcPE#rAJAiR7j>B6eMj(m61=V)`Fyk=5rzG1((vS?1e_eNfev?Q&$XQ@px&c|Z8RDA zQ!XFxCEugnChku;R+$VS zDr6uTME=!T`90m{2lA18BA>|@@~_U&J19r*B)dpC*-iG4e^s`2p?tlJxDq$wLH<>F zdm!cIL1ZvdCI4*xzE8Iy$lwpjBhpA7lYdnv-%7c>l$4Qetsvt;WL%u>dbg{914Aya59xj2?3E^}rYebd<8Yk{m& zlM$;b7{<~AX0fc}Zp`fAD0a)sfUQm#%J!8WV}8a5+3}+%*v`x`On<{x_JNnPmr>%N zus{-0_x6JL;6rR_bP}_=RKOI=L}0p353riIj)h+dWhG88neUP>?6LezHuM@)hQPcQ-yyA16S*%ekYh?j!{m|)5Ou~-kHkh&_!?l=!(-?MJ zT#H?d8Og+xtJ$Kq{md?!Y6@G5!^XKgnN?<2FrHP&R*vipv$HbUps#K0-Pb5)$eNj| z#u_$gd;>FzcV#Q3FED$>8O+4-3=6ND#Pa$cVlFEw=g=_;j_u-gFNo~B3g+(UiG6Hk zQ9rpa>U;$7>2by&7s!uRteIR6d%DVH}mLi2zg_$fykw}0J${bN(Ga%CZ^E-t`B zZ*ytBK{npJ5P@OgVR+3&9WQknjCB#!5Eys}`VN@~0e-W=FiaTEZ~DsSmuIn_<>{>5 zp0NWl2H)Gcxzi%BO(SPvXGIsro@$j5vfYPJb$ZqnoGya{(?M`4d6(Kt1h z<_YxD#?;=&!PmJ4Fw+LQy<7n5O(HO5RcAPIB%4`j=Q8Cd$kt|!``&JX_L~uJ15PLB zL$hC33?3+o3)G{rlVdbiWp2dBs(FY$g;=n2w#LO_+e3Xc-KmQ=dY**Fr!`>h zvH;}fEC7qMonW(VXBc-foAs8;Wu{WdzG#j6-mZc+&X->bHt9AX<|K-NC%R!~Nhp5q z9D!TyGttN@8v|lW(f&j+uA=z~RZ_`l(J}-_yw<}#-A}^mOUI!tV?LzESwpU!2n;F~ zhR3@zS;(7A_QYol(-a^3{rMz#Zb_7Tfq0b@tnVU@KHA-}-ZKO*U81=~ zE~{BFlzkWw3{KXoA<;}0Z&*oSMP(Su-3rDH2ePo|)ohfs*ny8am0_M({R z%bErMP0PlP8^J)_U*QSp#f zFc4>_so>Ds4S2RW3C%Tfuwoio-T1xVbG}eT9s4!s&!L?Eds+4O*2espZ~1%U@&9a2Jw{peIH@5g$VqaF zoF+f775;TC&hL%y|JpbEd$~1@vTHiYAekhKY$QL{A^)p0>}<-hbI4p`Nvy~`B3S4A zV~z8_I?oQK+g2rNM4f05P4ep+>R;C!{g|Wr>->XX`+|Qj-?r0zd?g*^8xf`~`s@1a zU)L}FI%nbc`ip-r>+Yrd*hlu03i9vDzV3g?zn=7UIq@RiCv$u3e(c9UP%-v6Wh-oIw*HI%E@5=YI z=QaI*t6%)*j6IBU_HeT4raoJGbp)&b@PKV8eacp{*DTW$ndgdh7}PxnMpPQ&eLq7? zUCyw(R}Lr#Y{Ul_^YGmCd^8zbjOl|*Ft#iY<&1Msp(Y>gL}Sp}BNk1J6LFeO5%w8x zh)QJ!=(zMHtm*O;rhRM#FMozR^b$d6Rvg^wITUVx&;hl{I&eKL4o8< zW)Ks^j_>tjsxGJ5*2}8w#8-88VDb%iF!Ua)$xMN|B^i)tI2JvW5Lbj}Va9`O?5vT8 zA7B&eL}j67c{VCjR`L>y!st~aF;sjsPSI!v_xsIIF(3gxcT0e+1w){rQ6Da8H88WP z>ulM8Vn_Z)6(Cx9aDz%{mY2xK`8hvkFruv2U9 zv$M9*%>QW&t8~|8Sg6OIzfolw_Vw&*VLek-&wv|~Q{i>PSnPCdH0tk4$FRL=cz*jv z45{9TS@M*{sxvToO*kfahGWk?Be2iGk+^S96P!EK3~zPgq099I*zKqfqRB&{b|S6+ zd3=Y}RYtM}E20@**J9n}beYV~A#AL;CUu20v9UD|SY&7p>_3|U+mDaI=jCH?yh$q7 zUrEQd(2cl$Z!WeD%|RiljTnC;8pC-c21Sj*{n8_`-^yno?fwLwUxysst0iw zbwDWnI#U^R{r^#S*Kt{G+aB;mMeG*4n@}-9$N1T;U||<_Cw7q%iiiS&q)2y5hhSkB zCMI@w%R3hLa9>~U;oQB?j&t8XzMr|)v%$621Dj|4=9+U%8fRcZzFwBpU}kI5cI-o2 zJ9j7dBOmCK*9&sJ;KSNeJ$YbOPc-IU;B78&o3S5T&AjpSr8my^^TUyhgVH~_8&;t^ z;g_O^vAW%nzdxTp7u@H3*Bw0mzz*&*wjI0bwdd(=Ptu_SQYX(~9X-$8N@{ka$?NnW zivC`P%f9?V?QOK_?04xbh7*puLk>V^kpJ)uzaujmgQGbi}FIN-qG zo;Wh6r;J6o%fr&{^9QowufDeI6w!u{>(=upU@1t}}e?CnZypmdZOr?%vCXr{N z8t=KR%9oRZx!1v9?)0iJHcsw`xW?Yt+0P4es|CTmr#~KkjlnY8ctrGY#piAN@XdyB z(2nsk>K1p|bDt;lwPLN|HvD!>OI~)mHD9=!M9B-&NjG6CJ*+c_E?u5WTTd7f{iwh_ z+E?V|KB3&$FpR$p8;B9p2B3SyLCg(1fbg^sR7(rQtE!RE-x7w?cKfk-*nT8e>4UW% zeXz#;7WXl{&*n~6oGZu67~Yb9Zf(uu#wSt3lvL9BHkleZO{d7!Q_1S;OnSOSjn#B3 zu!VOp?|L507i5m0Rh5Al>Enm;GklO{8w$;fL0Fg^jvEL^7a7OWWT2aj2Vq?5(ht2> z-sLZE9`NUr);u-DmRD-E<~6I@a+Y-}SzJx0xkfW3OU$JAqYWq}YyxevRN?INWw=sj zf9_LOo)1+WC}VpDpx0+#44rupTla*($UPWZnjwg36oOg}obcp;3qsro`_}ittB|`K z>h_qoChXw6<5E{-dOL1t*Pfl$r_u<&o7Y3?BMYxtFVFY@7b+!u}K z`k>|hAgCn;;9TQ9u+d;VFuu$CBkg#sQG521zJ|{~*Zy+9tM@FT_jnO1u_tMDdymzjd5Q@jmI2?x|zt zzB*3Ci$fwoB#OWK-r7X&uT6!SFc%iWQfwE$_g=fJ+;4Xi-9-;!*TRV=cXg#F-G}p+ zq`{mpeF#ThbfJso-f`sqH{58^5>#lm95!WFAa&;(UL*aME${o{#o0iVdm4fl1;NOR z@kiDuc_!W|6#L$VBBx6fj%!3=^6OBH4|l@$F8eUx$`~w~Ga7Y{8KU7VH)tP~I#oVp z@gXdddoBv)`#wRu&Z{(9I85c!(#QI9PFdc)q!ec_{z&mZ47qZ$KkJfLzAsilM9ViSZ9 zZv)Z%M3Brm3dW2_p@@xjK>N#kVd^vznOh8yd9^%_%6bhAEu*+*jYzhCJA)mYP2&%t zmH1qc8lS2kNqzQ*(8Q2&47e%Kb>=#2{Qgz8jVY9Z+lG2+Z=<$N9PyuY&c$zwD0;!*HqK7B<(yEZ5+^G5xp7{M4 z2X%YNUE=3rN}C0kX5o#F1HAE7u3PI>05auXZ~2Ho9G1SwyETH*N3MU~W(Vx3G7=m2 zj)bFYdF;!ofG^`BdBNCd_BcA7TkoIA%@Zne!SKqw?@l<4%8I1OZewX+h9NC2zn|># zoJjTDApWQ_nA1-`;D=Wq^IE?-_;G$d60dl{*Yp6+t(NsVJ_TWMrC^*H9*ix6A~1MO z7{2Uv#{R^;I5ukx;@*x#`p^nEZmkAYmoRo;AI1;%Pv%FRCv$zBGCbO(9JfEKE=t2IE|);+Fp0+{zI8GQga@syN+46?0n$aP*EK8KXU#Pc$;* zk%OMnB)3mw7PODzB@CZ4-k!Bx~gMNQ23jgXr1D7oDq3 z#r@^eVUt}NudAveXPP@d%kbpsPrz@=^<~S%b5ygetZx}^LV+vHB%gUv`PNb!{KHVb zx^)QWsXgMdYajBf^$XG2aUq=R24i@3AT(ymnj9xWQS)OA+%HDMLM09FL(;Hlun$)0 z`r%CfDHu0xCUPE>LH()apxMNW_igs#S;qai#@D{g30KHx;APs;(2~px%;;pS2bJ02 zLDv08a23^IJa6p_erxoUN1R-W#a2r&!!{5jjRG-od<60rhr<6_B>LZu#KcGO2pydW z=P_QG*6RRzIZZ_6Bh%2vUIl?^6aX!)9Kgy{^HxJ4Nn#3fU0#C{f``=tPS>S&8PolpZ4#$_rE0f|CdFs zxFW8KYvQ`NA#RJJ+Ejm4e|Sl`;Gkp!U*RYGMSuttMRlQY8 zwwNR4ilTa3e{^g}Nqy-h<%Uj@9dtxz(M5C>-9%AcuRptw{eR05<>g+!f~Y7eiOQmi zD5@X!XZOGVZ@D5Q&ppFJlio?Ue1d-X(5q4{AHC94dl z(YiyZ&G*vWib}EP_}%Qe+m272+QIRazf-sSRiK$%9`i4(g}3@@B)F}>aeFoR_YHyC z_fYtaOoVw}B0_4XVbz-u?8-^SJEIKzSet@bYo#?#$2tF0959N*km|{(GA9z|+oLi0 zVhk<~O~B;ImiTzU66u#ap!+8cl)BOuw_jOdyw`npnsu9BF5bbdJ6Q9kXXf11>k2oS z*pPdTt;6|wvE(r>loHk-q$fkFvY*}%a$MSncDr<^+;d|o;e{bJEvw4f%~biwsy!SZ z=D=-wRmY{Isu=KfBh)8ufQCsZX6*{a-SJ6qut>z*tLfM~JRNIdQ&F~g8th)kwY^C| z#f)&MZI49zI1BjJmUF$(1rvJcVBMXk?ELx>ANp#~Rj1o=*?#S~1d?45+(UlL$0=hHnm4E?`YVCzo{bT;maV|}`z-jL@U z)aQkap>bgUKnMOjLZ5UGetJ6R!8^8Cxy0XRk}U*N8Q%pxx6<|8iiqp zRss?|lVrVm`JKzpKz8L+L?29tW78B_^Dh-6J)>Y>ItmA?ZpTL_3*5cY0WI!zLilUx zL!S76ZP|t`Ztviqsg2lYa0@O_i={CS5~z2}0Tf>_oH|eFM@dhcM;8p&aMH2O?6vFzS33NYW53LU)3!zUwl5T(v7zYx zQ+}7{CBv?9CU%)0hS#hUaH*1wfm>v)z@~@MG&>O$%Eh7L)a@uY!3vre8X?K22_~qX z=8TMs{C2-Fw+P$B2c%wc$oc}RP}4zbBD>OuQ|;)BS5N9ZlxfnFI!@;h|+@gr)bZBDt5tSS34 z(Z@GLnzyb|i)J^-w9#@NVX=az>bzj}{jb^GcqZ1=orOIYLUD9XFse>SLQDBu_49Bh z+-=jbEaxN!CLD+5q~l0!cLco?Qn5QA87JiD^IU5?9u(AvPSwV;?qDWwplo(Ao6pM* zEaE1QZjo8WJ&Ibim6qHwp+Opb$){Ows{Q;f84b8YpZ2Wd9TV5`6TD-$z<2!KWHy55 z%*MOW5M;ax!lc$oXuatWoabcX&EQld2It^M{!u)ycMM~4v$3XX3JUB}u@jw)>FY-snAN}6E6(pG}ScHgB@$ZhY|FiPe zJjq=1#R9QV{JUfE|E#>#T{2e>p)2&nYoXLq`FF=M{ku7Yzp zlVcwjCq#}YX+G^=m8(qtk*&<6H5Znmq`A0%Ri4t7ETboSie94l9Ns_cc}__=>a!g4 zi})(OiIV33{?X?;CFQ3K$xxZ%u*ec6%^ChHbCaE9r(MEc>=wVyJ^sDfsh8v@5^LtQ zp;nKBX`uN5TJG0|%Vjm;gF5xu>W({kw036SIrgj)R~o(}zq3Y#cf2Nl2cOIsCG~Pf zNL|Fe(97S0J4sBjvvAZa9L{BSBT85pOK_akC=uB_kHAE`-3QRs`NO zh{lw|hp@@O4b#`V<6ebHXtsJHPP$HjZWlsnb%8IH|IviiU-c*3xlBiEbf;tk}okicyXU4I*eQ$u4ImP2a4i22hTNu+u&*6~KpB_cnHrL`J14)x&r9X(l3)+~LN*@^F+Po{2eY4qm# zaMDiEr?X)PX?UYRaiko*lsNO6$nr%>M`!EsdHnQIG{w$Q~o`Slay>Y#l z2gb;=&xd9cU_9>$>o)ns*{*i{W%6D&8`+S*+c)FZQWGa>%>nY=s6&IGM|(oH%LqVw zSr528*L+`<@2G6!<;TtWhF?BUdGn0Ja{6LWpMhA>*%8gv_uyng1iD&BBEmTao2JBK zgGm}9HzwoxjBLzxK8B-qK2rOM7$2N?{`gIxD7@v-~Wf^FA zG80DI{Lt)p0P0pT#L&ItQSQ}snZI+9+k_hPx?!vM)Tqk5?0$Lq9kZbd)|OOyryXh3 zvZd}RmH1Ax3al~QjLS!x@Gi9nJox=Xu06Ux%&PT6&iXxAP|Fc3za^kun`qcgh{o+l zQJA{m{Bu%{eM+1bXT&*CR8#2h%0L$X$U)nswG!6CMikW~`nz%vNfu!N z(OdKpeZ}9MhrY`(e~6!=K$Mbv{z#BpxCGvJM)o)WTZV} zuW%GjLaEdA?`9>I?}g|s##C5L(buL?pOY6UY~=}>5s*$*f(+?K^DewiU5igubl~!| zlUv5v@)75D>{0(dYt_EVV>NrAUB50kR#692>*ca%6C0WPY=c+1u~12j!$gfk*x7i8 z%n?n;tJq9jvd_easz+o_%L%j!K8p42<6!(E4y_M+;9UbxoE>ujU*;#{?BNke3etz& z=7+31>jAg2yTeEN>m%a4DaUG>@XU{uS#x|vsbyN8A6(zW!?x|G>?CK})wv_ReW5{n z%eSL2O-Fi=XH52Mm(c^y>!hZUOLtcF-~xxPJm~!%-af^FYi@hO{^Rm_v_lU(8q*!$ zW$t#L1Z(6vg~MvCjB}cjf(+wSj8aR7)7uQ#OpU{o?QvL|;|j~GZqUsciknY{;r;9< z{IcOA9@)j5Ri2u%=ZmV`x@Q$05a2GtP@@ET1P{3H|^1?#$TRt$44(@9DNV8YNQ7zM{5kovqrN;;W&IT3>rSkP&u0fL+v!F zeUpmDm*ZqYbsY4&xk7ikE9R#TMeD`GFw*Y{U%2^{&vi8CxLk9dQN9{q`B{zg8hcWF zPcQ15--YU5=}J9iZNpn>>uAA^t5mr`9*tJ(&gvEP7(X1?wUHx_X!wN3Uw+1qx?-YaFZ?ft1PN(0`u-Z_i|W@JmOGZW@MPjE83Vcr1-|1Owh^$Cv0D4ur(@I8G?<^x zLanujk!+HJ3z>;n*-hrZG;l}Az~Q(TJQTz0+~Ov_`P{q8Hm)?(gq_kV@a3A7_-@QD z>NLoaI_qiD!ZX^`zN!Jmm`|W)7gK5Jlx$k<+=~0oX~%rkiv17RaNdvW?ELj6cR1b= z;}_}Rb%HInr`h0e&rr0i6$aA-*~pkH_wO%HqSX_5u5jWUa%&vNnkZj59QJ|Nz!B)y zVgwAIp5q3`udv>YwLJRBCN`F5r8@1^*nfhx%q_R2i7IXB$uW}gR0FADY8cIlkE6ZL z4fxH@rkts6!Lw&ra7MQatp6yNU$)i2xVPFU^~nYXWQ$e9qtI((2rNFHK=OrbOd59? z2acb@44o^mJ(Y_rgCN|P8Hly34UkrDB-#zkVSay_>s?>XXO|lD>0_n%tYsNK3=@iQ zvZTB(I<#z=E}gw`kZyMfrb^>#vueY7Ja6bW)`&IZv5}`Z{>gcM(V#8#QZ*3nY=f}% zws_Vz77Hpwz+dMyo~=KQkhyu-m7I&nY1gr1!c}}~9ESBRLb0u#0a`6IfM%&<++o)d z9_}usg{O(;s?zZ#j zJSZG3s;CkJW~SCMe%2G;gJi>B)@$a)bW@SGElK~nd3<1+(H+Ip5pygA96$FGojZ%cWh zZvmO6{2=YCR^;4P=K0m?M}6a%jKU&lYKsW6No~v(H5&4U`j+f8$C8(7o#nc>FLAVy z7QS!QLc{v9R@_BfTz`EC3oFE;)7CRsbUX*f?av|R;U!#XosBYGPT|!UALvZ+!}Tho z@bbxMluNwI>7_35lHj$xb@UpZ`o0Vw3@Od9x1)+xcaoOs2#s2)`D`SO2t)~Y8Nr@m+)8j41uu_&q=ReUb}UzN4a$}yF^bzWQ$ z7sVx^)R!tgzrLh-LM4sgEB>6Rq>N=N$J!xw3Olh&*o)%x?Ms>~RMMEe;?I~$%2xd( z-}Dy)#6U4f3>L-b-=$lAsiRdi$NyiA-79+j^lPT- zBj4Ls^b`F>tad*d)J=~nw(UxmKi#NxPbcbBy(~W%|ASP5-&37YyU0Ul8gFhtk=63! zxk;61#;6c(YB840A2)?%y(TF8$P`wqOmXp>35-MQVMcU3Ce}^H@FQu^-II+K(np?{ zmW)fSQ=ru$9TD?l(QCpXXx~V}mZ4dAJ!BWUYuF?Er8Y+V)IvmoHfFDIfZmE@yz@ym z=jzPoEvj?4(W+Topr6hA=6$3~_1@5uN{+Ox(H^>=WKWY)U(vL)?THOr)3Y_hD17}u zdKD{kT6{d|(Y*4U-%^!7M9k)6O=j>(({x_vpTzxtwt#+UbKH(M!Q6VLn06=x-CIWC z!K65Z7#+gI%Lyo-lZ2l?qtL)S2J7=}(RJ}oILrD_WpgzVe)R|sjXA=@UeDtPQ|9rH zKoy>O{u?DHJJH(#j${?niAJ^QKzk!bkV;(xYJbt6n#+0|4r?l~wyYV}b;Mkrb$^~@ zp$zU(`Y>CbXo>IZTET9$38q{yfuU!hoL?XgnaAQ;vshTZJp`MjhoBJ_1(O+3*r#R- zyNR|q*-8U>{WW1@eS|~59p&B!=W*+13)sC$8E(P0M%Qs#x3OBTA9t_ygGCF?)fyfjmqFV`7LB#nVeg+3GT<5pn`u8 z>U@^^NOG^ZD>)W}q(W3?^90mf7>#Z>qmZ6si@Kw25z$BLJT23}xhAsS@XjOLVbok+ zuzjA??N#BcA4{{XiX%1ibfSv&I+Ct?r^564wQV>aWbN6P(#N@zUN2ADsI9{8_vHJu zrf}<;Q~6uzc&;0n$R9Q|#aZiS__W^?tKXPlz_Kvh@D0JmOUXE@lYq4i(=b@Z{jIx{ zf{klqq1|p5#tqqthT)p%2o2mFkjUjmrSkgBS^TWQY&Ns|Nuy2`(CKH^)Y8YE&OT{N zZSys0*l?+*VbYbfw0F~@4UVMp{uM2a`$Q4%_4%CYIGLw(kdJQ(BF;<$4_8o|8tl-`Ya|_ zb%Fkey|^)73!Uz3p>IJ1n|zLCE88hNVd!)o{`5I%+0^e{z0Hu8BK-kTvN#cH7mfFN2DcaEW?SL~c68PlmXr6{iT>b52ZXElV9&0|Q{>{uN zq4qYq?Xr=^#crcE_s*03n#;GEIB~PiF5FZ_)|&CDiu!ZSu(7TM+Bqe| zuTd)M_P>PWd*|`W;TnF%=3?cE<1(i1D9&7VLk~T7v~lTx8*4ivS3j8zEmOE@z$C8Y zJei~YJ|9i!(^yk_Q0*#dUCE`jTZrqm@5P3(uAJ1$h5LT0hG9Wf zap0pVW?7lTDBlV=9^fS_y*RX9O{8VifYwS=Jg_jstLCYA`Y{o4PM2|}$yH1-&B2^L=TKP&j;^Se zg_a)9xECmON1{3)%BK^O8)owM1(`gh!c1;CbOz5Vf1l2`zDJHpHuPYFHCbHIqAm{B zbn(JVT6IF7UoZFPixq35<9ag$-A+N9o~Q7@>syr;?`egvhw$O zOa8OMzuhTY?S9QwU4P9{#kWt`tEN?mwC~>dyLOM_xk`DCrPSvtKE|%38V3K{Jf@Py z*Zo;}>Ajrm2k}vS5}(Bv@k12V{rbBzQ=;UiB#|sqM5-vN3HE#EI29jrSJE@6f0dWk zNnTq2kKD9T+D&4!*dmJRhW*~TPQ}OGmGmsCq`WjpGSXmCJU5My*G39`VIW3{(PE4k zEB;gYsflElrlOf>F8)>g19IyiOV8aToKpB4e`%vF_bjN>5pV6cgay6!c%w&Z*f5UTEpSjc~HM4 zOAU}bHBbx^gT)XrRK!I0powcc(k-L?RBy!|iXUV{UpH6gOq+6iFmxkFS<9S+zH_BU z>o=;IaE@Q(9phaCyW?luPN?;|J@$P}BV~C9@+Der*d>*Ka{i<*mrB8-@3)Yhcc_YKZfTWkbyv zt~4l$1N^FC`l>Mu?~zg$>@k%ee1nG7zd(VDM{w`fyC~|SE!9%BmU93 zk$?DZq6+rp(Xbs^Mh&4IJBL!|TcI>#X&A|(25fw^fjnEXVwZ_lyjJHCzn}GpcP#^k z1_C+ByPH%{n<<8tkAXlTUYl5s3I{Q1etdx{p*kN!|>?mCa8sNMkPO)+i|b~ zT|D?OR5I!!5TdHE00s8T@6e(>Yn6m`~tR&H-cL&mqKO$+){V(4Hx+b599 zKMbKQrR(w%-}-#}kOjB3-_94--sijBA96t*hH6tFI!$W8Ufzw#a(|w&B^>Qv#=)#h z99Ex=(6<$91EAwmm5$$A$drdXws%io9Y@b)N3C zmdmW%#*=qnWSx~axb}`7I5tHO*C+2rDbL;T9vlhR6H%Bg^Q?xiIRx|h3DB;afPqK+ zF~%=g`sz2Mrp{(qgw%y+cwNj;3FKh!2(Eu?6mQZtwRLCK{dYj91s}FnIAU+}su>b%4Wg z?N}15ms`uJ@mr_Z0jJ)`{?=R>%X{J?r0ZiTj0 z?J%G1aA!<3?2m_I_35KfPfvr|gf!&ar(k!*K=kqo!pa@n&?9dfc7)bI9kW_6$dmD( zrQP_R(*W+fX)y2He2abt<cAQ>y9}ig4+}Q6Yoas_H(z zdC;9t)U7RRwAVueS*x#E#0~^^koijeVsNra4sInKMZ8W1LS@d*$Xc=R@Cb%;`Zm;Q zWrEgatD|mW4b1p_kQ*)YX7zpjIm)*`#~WQG$4Pl)J9{043|vWxqsG#u1ry0`;&F=F zaFSNI5I;K5o4cHK;!9>O+^cPMxZkLOwmocM5^0M}i!_|JO2e*z9Mt%H92+lZz&Se| zUw*_PFFX!+E1O{F3=`OXuZG>%tK*iRF9!zs@!*dAIeqW|e(!OGwi#U`rL}0iu5kO- z+x4W|Wx8aFiS%0aJe3-Fij3|0^4s*@yswWJKeTh(lQkV>-e1i)T$TTqD(jn|tCtBpUQ~g1LJb&958#&f{P}bKKrTCJ zpgd2!N<-dUFFX&Wb;{jLVd)$Hd*9e^HR*&bqM9x4(0P}uRIU9e?s;t}Z)qOJ+b8<* zjj#r=Rj(uCRd>Q7awqn^O~77_WQ@`{j55`aKy6G4hHIoC05J&J5raLmOwi+|3C<0# zh_-$e(Y0(SCpQe?p}PlhR?r}xvH290IeUo)%`>M^cT=h)bGO3AKBMk2Q@Dw195*=E z0%|Yqa6LO7868t_Zb_2V7m0@9hOJQkma8qV3gz!QuZUpfZ}^F|Ls|KI-e&2!!oTBM z%dCFQTiuFhtY7zA##brKTRXM06N~4qG|5}%B&!tFh5Nsnr@qQLeiPq?lC6G<0#Qn` zjfyBO%7~)cawXM}C_bmDq%nRaJ&*cl*(yzrn=Ud$rZ_B$YRr{XJL0d-Ra+%nZ4)NK zRG0~KVIj7Qq8fB1)spy6<*RX$u?)p{F+ofelf+~(MNAdb#C)+p6xFgTsRl*yxltvJ z5iIGsRq@=_LUK<_(Mq%yZA4p9RMYP7%3e3*m^Ve9xFv3jJL2!oV9t`m_6Zl^D)tLE z@y}{a{L$xDCFL-E$zld#lo&0>h_Rx0jfvuOqkivmtN$&BRhR5jL(~+tL~T(=sEc|+ z$z{dsO%$Im^?RRX{coAC9KsZIOB+sL>rJnUTnxt}y$Tgit_t%qWCLK7lO)Ks> zIGR?MImm4^Jh<=Z@^Bki7RG0OaO^`T?x8ymk*#MT#ls&tSN-u|KmdBWO+z2=7(7@U zhiQ@l3MMC@XQxD@O5NZ_rH|m&fuk5E^D7412P5%RFgkl@qyOP0=s02#D(tU>GJDEm z^!)-p*ljU>oQ`12uuzT~G=y)h=);Hgd-1SJ!Mw%$KK-n7olZ0~r>N~Fd2nG2=7)c#vQc)Bz^TqT2371 z$46tVbvz!)*vJ89F?d`)26LVU;9L1XGzeOS53g6@;q5v|Td!Vtp31&*-b!0FF_K>% zisEy&vLN~0(X5=evR~BNcYjA`Uc9F!))us2gJt2lE7zcGE3YftN~>Il^4gdWODJRe z26`TLnlx5kqf_^E`N8ns+|b{f?JE28TIVuw&8di`HRobp;(S~*3V`0E0F;xQb8A)_ zn)OM*hH?q0hFGY{v)rl;y-~^29~#S-!OC|f&Y+geSF43N&HcFB)ex>QW(Zq9)#vNm zp3$nnm$cDv4J9-(p}Ct3=-HR)G%F{Vj?YLT_Zuzwn_EY|e`62pUUX$+zvq0$^a~rl zoC5P7GvTEb2$SFdd7gX%Bi(cGG$0k)dy=qdoV>3$tya-pFr%$mAOVc&cnOaNz|{GiIm3a&}@-_ z8DkG&OeIfbK68VE?;^NPS&R?ID0F@tg-ecvqMnCj?xf^M<#mMebA@ z8$6dTZqlY!nPyaQQ`Ti^uflU>&eV&W8##KeDX&dB!$&5a;|N22Tn-r{b<+c|T zd?7%Wd(AvgJxb@&pzm|&T;fc+)lL2`Tr#7HKRW&PDq zHlloCYro8cmF)*xJ^Az$U4Ct($6q&}qdNK*XzA(MG`QRB|8Dayw55h*OU^CKXmGl0IL2-Mx$0Km~D|M&mJ=|Vp0ay z<{yH0PAJ+}kvX3ROR;|AQdC}|CTlHKC_E>nJ-x%5Kbm^+>;*mf`IMfloU`)!oss8g zRG*79rT2WQykJh@x&7MCoUTXbk94AXhxgMpH3zynsS00uT$b-wuwm|D!L3F;;X%f? z+3l?%3>uHaQ||!e<^{meI1#6xB;xJ1G;G+EhLgQd;o63i$WIEv%hI8Em9-G%HZI1r z_CNUX;<6Z=!$_V#E1w~QdWJyxyqNTLVc}=T%CLgM&j~ZN;KI+0 zyMy&u`FzM4bGGoaq7ASAH8*zuH76F|u3uBVFgHd{t(sIkHx@{4EUFdwpL)jjTQgx< z$z!UboKO?xMFmk&R1%d%HBmzpuQ~X4<;5&HcD6Voj*4UAxHu(>*B$&%W=G3^sfQUKY%er~rqB}FLPr$UN&K^)6PA=!@5(Xn ziTfg7JP;4XBk@%H(Q%d~JvS^Vv${)e^$?!IOL&U|!cY9&*>#-cS3@ygOb`>rBr#b` z6aUF9TUT=1&&Q9n}MeV!ZJt!@=3swK5NwxId>FOak9hNmYfT*3RcziL-b|=`2=9249@tT-JbWiWUP*F{F|y`qm8rz6U_9AObnrkub=J zl6i_T&~u7Hhi{3vSs?)LO(eq}Uk$s{D-iXj9u_>Qg{k?WoH;Or`@inXn>~n4-dvP9%SGy>d6|@bW!wFPVc|aA zA78kww92*o+Fr5kOvf9@`m+_>WF1crQa3HjPp*~YxV*XC#cu&`IGM>`_sRG&gQoCK zZ;q;6O>tzQDFW7oVPCT_XfKIE`C5_4pB#`=Hk|^% z`&MIr?rJF4sq7cEI_CAz&mwBy~_6~`zSq*>^c}yQLDTs%D&Pn->ZC|vfukud)mKv7p*_(NDV_@ z(w*@?DYWNg4!Avo2Q^A&m)ultxV|LINF^$jwP^Yh__%=l~lX0k-V|Z-aD4zQ?j=!C)it1X`apSTH z>gH}kWt%9Z_Krl=Yk4r}b_M$nrNeV?Dlj`1okzsLK6F3ot9YQa$2|PhT!iW^YM@47 zEiAQl;>P1$*(9?I&(_xEN=pyZjPPT0v#~B!J!~FbfARp`<#s+oN@JORFHic}({hB6-wU0s7f+!s2Tr70Gf-9{KW6;P(l7C# zBH-Z47oPvuc`L2&#J2p?vK_zCPN0?d|LeS!R=F8fAZ6 z*aC_?KVACUPS9q7?P3Ky;=UfxJN}0g@<2JbM^oQ9@S&M9U z0`4D4z`o8>2h~>kF_N!fg{C~`)(l0Z2BGNqW(K_X&c>NeWnizW3iAqH(tqd9H!rs2 z4~eb0xW-eF8mB_@o6TM&&y+@RiS)#s%su(<#X~;q9!Y! znKiYKkn$Pn)P{cTKj=}s&*0bng_=zY`wvdV)cPO&2g^$TzqKy^>anUXp z(qB+rD18PsMJ-WV)Dh~Uu4o_{i6)|{D5|6RS3PqssSn|V96Lvx6iR=>X>mrJ73aix zaY^KgtKyotE{f`G{@G)G|JAeU-`l_7ApHq@gwoI8D3rbiXYp%)!+zO!6Yj!8c!~q! zpzss^B0vO+AW>A$^Y0o{{9B)S|B-%(rPAN9Oep;kD}>S~u}b{2eu?$+`UbI4Y!aKr zHeo8vg@v#b+l7@Vsyq5uJzFoS&!U6$5p)!tgwlV}S#%LyMK_@)h{wd`bDPxqkm+&v@^s^VI*dW z*ilN|D>7pH8dA3gwmJNO8nZN(oXi<3k{(u zv_watBf5yLqMPV0dWhn6hDw?n`)7?O_^tgc&*j`+h?hd?b9pWPS-;CidHs|4EWU`Z z;)f^@rKJBuMU)n0L|IY1o>58ja7!9P{(Jjl!sVC|B2p-QGtuJL{+W2$KO_=FqDT^{ zB3)#NOmSFbiEN?Noc&jGeoGps{(Jjz#>;Ugh>2p7m@KA7cR?O;8 zDj~gO?qZOv-|S1Pdw7w>j4t#esU}xxSC#v2*v4Ag8`*K^T5fW-B0s%zoNIo_=9KfA z$RD5yXllT*eKs%XZjPsm%+S1n7pkqt{Es3l8rVi zf}uMs8TF)Ys6!)n^h$R}(v0_29}LBVTK(a^@dNkU@Rmnxd&x7pGHUc+#S1UY zXQhn_DZ|6;R0{XQjDFCSpy`GC%Ilj}EFtB;mA0Nu%C^#a=}aNz>y+0`7mcJX^M+85 zxCn|^9ZFFe>O7{P7O${2<-21{xKGGM9%Xu(ze5Xt8#J-^ktGHjS%TsMF=>n+S`_#r z)HeXlEu_tiKx=t!IBaGVG9BFD{KXAl1{tDC;3)L9{mi+mKJr8d6JBtC1Gnm0j^m@t z7M{Cu4a&Y@>CL3Pwt9y#Dcee`ob#`3RH6Y*)Eh<4uOey3i70A#R-JdJ*X2byru=4! z8MmyQ%c{Gt@XC5xcw1H*dvh!?^owO-TW(HSh#QDF}`qnz~s*y==Ft_ePw%oib>)A^RcFd+co4`oF0^8 zWnZ~2<(iB3m2Ks9L>n>`Q?=AZ8W1WUmT@QWQSSOsSj)VHPf+3YEBng(p|p4G z12DTy0K99+`w;FA<^53hi`uF3bL{9CfR(qUK68v4l=ne-kCbiYb!A&=_xl@Sz#~H} zpZkeX?=vg!hw^?EZp-V+w(`Bo_bFf3`1m$fH#T9Vb#Jc9DQ8p*_m%fUc^`}Rm2KtU zQvMy~>y@v4K6xW4|9xT2&7^EAt@6GVwaULy^xyT+n{tK@q-~Y_sg-pQ*~%K8+d5TY zjm(Yg(`gI8ICPF5C7kE2=z*?VJfI(IC(*t}t_oOk^E-g3UuY6G`RFU2RlOBbH6a*fLNk;e?^HuUCP%e`!(-$Abr;!)cF2>nlap)E?zC5%EqNR==^HVGG4=K*H7?9 zsT1X*R~zfK>fyeICA!SCgqwaiEWU-JYol{eIdmNH>r-**T>_TKdKJ&&g7M?o9`y0w zgWwbTXghl}IwU^fPk}GF>xP*;H+WuQtG)XpZ65oBlzrtIlx^j;rE{kgzHYnFsBl|p zmFp<_nu=00&Q9Bb=C5(4vFR^p`n%6$-D@$=y|tX1JkDb6wZ}L~#thZHtuA%GEpe@x zCG2IL#8`s}ST8??ud7dCWR$EGay<?eT)(>STI*TUdp(Z!-fQ>XZ6~<7k!9V*>*d{<7@yf@lP+5OcpdxH^#;~8ykuTT zaMk~O90R^|iyD3}->Akb>*}8eQ z+OF*~x!gT7xQ7M~baU?XcU9*vbE~^9b^Wrea1%3aaZ6UOaOW?saaA8);+AY%rde0D3CdoBZBi|1uB33io_KD_tUe+dC`{(y;^b(J{D-|=l-J=J( zONj@$>R;$t)XR0hz1G1`FZX(Vmt}5pqLps%$IIO#m6o`7RxWmZ56*C1@=W*ZbLXD- zI!24qu1?M4cKx7}mUU~MMqYQ_*w`*xb=J5d7yQr9F{0T=hxof?Ui3KwN7poHR*p5S z96O)GZ>uugTw6TUoV|6!#47!xNxP<{UAVo4oxXpgUEg|(jg~5l%bFpJ+ot16_uwGc zy2T>bJLfOQ#rpgNT^oL6nM>bxrR(*^a(}$+pF6tB9qz7ofp(bYMxUSNkB{}~BhR^> z-AlVQu}<5@@Beaqtn`6+zYiPR+_xIrF^9e|Ifh>_952U@W*<#Y_)N%alE0SEo!hpS zL9=q)VWkG2$L~2l*6dj}+Du6t)6UBn-G1|Zdzuign>+H$c+1$miv${v0 z>gQ7H-$knyPj;^!p6&WvUgRd7SnN{W+U{yT_@1j?c(+^7W~&?Y@RWqQ<*M{Ta*wE~wLp;I!nm(s%!RiLh%5j91&+<9^ zw0=3wkW~}SQ!V4#nsYl^e$Q#xd9&qro*m7z``>Rq9@E$Vt}}hq+y3{OLEl9B-*NUQ z-tK>&d2!fo|GUi_pS0Rh!|?N?`F#c7uX_Wp zS@~J-USDn2@s(zcJ2q-iB43fauhacjAN%Stf8B0Z6xZ#}>bl+C&u9L7&lCGwe;@xx zU6V_z>sk*AuFa(vT%XGz!Zo^#(wW4gBD2UMvWe{C36WFe61hbl5uOQszke@sKiBRK z>gV`Ka1HN};5yzBard>n3{U^`u`oS@lDmW zylH}KeKQ2t`(}x#uKCT^{sIvx7K%k;saP&nidAB@SR>Yo@T}{9_VWe)4A%nR&^5mv zf@^}k1lI-oh^Vd&4$}T$F+>a%!^B82T8t56#W*ouOc3Fj-S_+VIREH1!@|1G_N3t2 z;ZuU^hebtH*AR=TaaZB70(REEPridkCi#Q^#_;%~U# zuGl30ovu$d({;$^g6otm1=lKDi>R(wzO4NYqNC^}UJw4*S#de6DVwZSd>=Ap# zesMq?6g-pux6e=fS6xf3um9}^f@`Xc1lLuYh`X}JmF}KaqDyQA)a@gLtH=5C{M%ni74!04rPTRgy z4%q|k_SzQBhueN%8aMgLqHfivgWa%H1Kme42Dto}pK|eAPIcd&o$OZTn&n<^Yx$gOTyIilgUUMZ9zU&Dp?fqs<*~~i%59Tx9c!!A7-Q$J`qt)H{Doc6+Pd^} zj4POOgnRPbFjsE2uJQdi)2+)q(>;A*rrVTswmYz4f%~$=Y**pxY?r=8Z};i2H}ssl z)UHa(RE}fenDIp(dDF7@YP=B^T_!){u!*g|K%^S()X>u&v| zODQ*oyUjO;yL^}CxUXNI`PD3kNB11x+xwvl zdVBrNL#bV@4^lfk$4_s9N3%~(%W-d7_9qk=W6{qfPi}W?Om6WUKfMYbO|6hmZtXPv z4e=ds_cvZ^rB8TPYJ~XhVy~Gd^ShWs>GqqCPaiPv4$oz?X3AqzZyjSJI*zp?>wjy< zKYPXZ2~Xcx8}Bgg`!v?IEHuJxNj$>QH+)$0RhsLp{{FE3J2PEGrJ0U?(MvS@Xx0r+ z&vMWGG}G;!JKL3NKil_>zM|Pj^I1NJudW_-9^Koov*xFAMX#pvp1#rV;L&^s)FGeT z^-V@w;%_|trbWm2A(^c*`2mZkZ}d8NG&Ms$xlg6+XNW&MU;q3`v(n$NQX|CY9dB>C zecI6sn!DR1Zn4KKt)0nEx%If+KYXN}5c5qtt=%PCwee-!aYKH0=x7nQ`Tb$8$D1Qv zgY5I&%0Bbl?)EF(n$PFCnlD7Sl7nZvZvE%Dt4AVSi~e2Q?)bgjo<_-C<9R9kanTcW zWS>Fyhi1bqYq3uf+Ap&t@t&WZ;|(57Kllv!Ad|Q^%wS}p7Ect`4cW*(jhKG?4j

&*NVn@o}e$!$cgly=cegKg6jL+nSXPuq`rp0htcm(A5&|F~OUahR)=e~7D7Pxk^> zUg%E0vdul4aGl$s`_c-1InTZQRHVB$aK7v6I=c3QbWD-)UD_>){4sEx_~+j5ZrNK| zzK=y0NfgaaFB#L~Ikvl3Vt0x)HpK7jY+}%?9M|3J-rY4#oN9GVmzk@~il`lEk6^a<)9w@xjbzG+RK;~WIy47Fr z(id9f*0+vygLW@;$s;1&+1TCP57S=vYlrM{+|(ZNyyrO3>?LaPhDCS!th+@gne&4= zpXsK-^Ye3z!K1@xiIdyDWka9ecvB;}assY`O4| zJ#apQJ=$WhJ^tVjJNwFU+jGK6zb1a5phM>_T*wt~JX-G*9PQ$CT!Fy0y@K`Qk5YlH5JKe(BksZtSesu4&@9{&?vLntgPLSN^z%Wj{~; zUKYJ`$2GGn;<~|eob)DmG`$P?=Hb$o7cc`M^+H<=7CLf8=p{_{b^W2iCMn3cKP53%TBzN4fpuMmze%ewL#P zT+2R7T(J$2u3`IM`oWqi*>cym`9jxtQ>4pP?U#PA(l_E)-t6x7?d##jjg04tCyDF( zL%-1Mqv<7|33)H&>Sc*%8m#{>OE>Iv%iL~$-QYQXdWL4D-yxU0WG5Q=++v-Zdd*6| z?p{YtYhqq{qLFF-_;NER!!l!MXR&PuXSV6a4zYJq4z-Ct*kk7mJZzV&F5+J8Qp8nw zaG;CmHN-X1I}C3;Khq^YGtbSwG2eX`ZJWEUd&SRb#`VDb1+G)6POj;hPVTW8iCm`f z3H&j0{Al*kAzo#*jzRke3U;&T*fV3=RaK)|JjcOtqgm-)$R#hs)ux8r4oeyvG%Lq_ z_d5DYbHnea@kgyQ{H}VS^yB{b(gHV!`rlDc&Dd-Cef0fKMg8xlGinX+zlRRdoRr^5 zn`pku@1GAutoOf*4vaR>|Grrz>no1mA@`0?>W>r6@0R#AKlky!XYzaF^>cA7o}ZWF z3m(lrIsC54evAvv{O_Ht98XyJY>3}=ef_E5UQ@r@ms*g^Utd2K#r5@uG4(sWo@*4| z$MK(V{roXqPtGd1j{dmdT6zu<)%Ene+RrEQivpsccv3tiiV7pFaN-&9+xLas>+_lZ zi0kdA_4A$)Tz5Y!xb}WtM0NfBEA3wrm&MoO8}XgECVmjt#gF2K_(??do|6CDb9es} zuFo&lb@(NM>-5V6*Xmb@sIJ$q)Bbv~L2MN7ip^rH*e-U6onn`GU;Os{D*x#7g8vHF z^M~uY{RqKz{ZWEz`)`VxMTD3m9@4dE-XC+X&*A!` zuKPc)pRttS`hOY04B!P3)f}L*_N$1hqME2KYKq#TuBa#Kiw2^h_*>6k{&$%V{H&kx zwqQ;WP1n+y6~qux%?sjbKfXvH5{g73sdzx75Gh3}ky@k?|H}KAfA1V&wSK-ef_cI^ z!AxO;xO=Yfp8RI9MQjz@#7^HJhFfm+=5F^FE<9*imJD0G!R__G!iDv~fisB-wIYnvhml0*f z3!gp zh|k2o`%L5|%|6-+W+Uwd^N|iBsu{^^+J9Yi5nV+$(L?kSeMDc;PxKc9MAM~@nP}UG zm~jUOng_F;FlE~9H{bQyWe%qwXtsa;LA%Y9L-rb~CEhP(RXRU56+1a~vmSa)XP9JgoTTsJ-4e0Smf(Qbbo-Gf(SqhE8+ zoa>Sgo#*}9&*!^BKW_J){r5%<@_JeK{$3|~D3ja2@DYcPIQx(r@?u}_`5ZNfZ)@|W zCFke7!!0^p^2D}7wuBZxu4Y_2;k$vqdNg%HKDl+{ylTi#)4i=hvsP@>^w*UdAwJ}( zY^KG|$4sdvBhBJ{!%c_8m(5ob&zlMxi`!BKi`h%1XWF@u(`>?7@m>3;W4q@v)^=N) z)pEy@PjQ(~PjVXuN4OcK=eVD%&2atq&vWS)&vEBl&vhI-J;JZsFv9PheR!DHUFv3b z=dNaQc#fAI1&?N*oEt4BTJ{@em|)SlB9qybo03>O$4PI3M^h{0lY1gTA4B}BGCd5M zm41Yk8X+F{k!+?+)5p!jPmeUM9vS7=L8~sC#O=QEK1GM(_QOpj>q>x+7hUF@23 z9G-sB%iz)Mlk@nKBmMrgY$Ls%^K539?rdg-BL!8_>Z%nkr=iQ#D=kQIm z{kJ8v(W*UQ@$`!x2al#^$R~Hjls<-d)7yOvnw7qWl^P-ba^AB*-tYUw_~4~VGDga!_sGbSl8r@@22&N@6K(hZ&Hn?C|uN?`}o z(?xCOxbN5*gQnXtJL9-U1LC@&Gb^|(#jCq6uS|1;KAY;2CZ6X~mY(afUs~eg>X|Kt z^*0vh^gd{gpWdOfX4X5l8xQwuj2|C%*WS+PJ;z9of=BZ?K0`jauMZq;iN}0-yhX>) znZTymlE~sYM*0#wnwlY>+$V;-Vu-Ju*4?04=|xzn5#pVC_c#4^4m72fo-{FcpE1=p zJZ9gEozu3fHBRq|d&}l7AJbKQF}C|I|8uU)u2Sy#hBI6>JKZfmx4^YYIp596|E?SJ z+dkiWdV*#z*Ny>RC(Az2>xwzjxtG^uaCnZFUg5)Ms>K;--*{n|WzBjg zrcG<&dC#%YkKoaKp3jm`?vxmf4e_Q;+88t|JqRl`LVQW~KBnL&ea+8#51UUa9yhP< z&un{4&1yRr8e?BSF~;7!c*kx!7{itNyrjD{w~TvQv(PK&X1EEv7iqQ<=?YiV^F1@J zcdNE8axvp9^v6m+@Simq?DrntgHx9|dUm+iol6e&`qH9gZr+LH4$pDYm*COiv&6}*da$1*zN%4wiyoi& ziaB`Xn!$6t^d@*THA6nRUtO>5^GiNc$7@!46jo~RdHl>By-n)Z`JTTl z*Omd6`1;oeTC^GbwfV8;6@#ZA^e}idHA6nR={D8#`JZO2?=>qu3@bJGJpRD+zGg(Z zz9#+K2TcAKKlc4%owGWhtvn^K-I{B>{ki&hOF!A)b@E4>q~_1Ib=6Al{Ip;C#=7pK z=`P{q+4`Hn#cpE9U;4&MUx{y?zStF69qG>JUhIk=UhMlwU(xKN={cVXd1KcO^YNBj zM>urSZYkXSJINfLKG9n=E8h#X@Z>eC-QSWMH~T<~PSf_fiCFcm!P6u98a$ePa!wVk z>+?>Is_!)`{R}Ig<#YHu%ln!=-}f~|?`$*M$9`zarFzo#ZL8;`-Wp|}T==Gaz3ta} z@5py{!qTd4e(5Uir#0i@=KXOdV6ypKs*IImU8sG3VwL z%X!AQt~LBQ#rQsN`SXjS+kQERSU+s7BT+Sbe7k<2+KbK&o2Vtc~i2v^# zEq~s-=VrgvtveR-bF>TRlm8#jm)WB^T6h=ZpXqN+?sryJNVA~Af|*$n!QAX=5!LMM zS?w1S#YG8GQj`*9#0#RFC@(6AiekOkAU2A3#U^q0J5T)= z8QV?m-x5EI+v1Lhp;=KZ5l6%o@kD%)K>YSym;ar)>7N<(ye}aabG?N5v=N@4dV8zq7di|KHj~HH&*kGq)*%ncOtNTyBPlYBo1l z`}4$nu|PzM#bT*gE>?(@VwG4e{?@y5{;V^*8k%>#D45;V63p-Fh^S_GjkMobG!acj zGtpAC7B7jmqMc|jUKal;v%SQcX(bWN_>u|ce91*rv%a+2e^8_o>BU3h5s^t`7Fon& zBCE(Ie(!Uf@8wxW|Ed|_cK!T21hc?hf_dO>5!Fm^zxEG^gW@Ccu{a_=5y!;|aZ;QT zpNa~an??0Lq<_Y~kYH{&L_{?^9Hsry;!QC|j1?2a+hUTKEZz}Q z#8iYQL7KE$WE6qJd~6nuw;N znP@Irh@;{YaYCFFzkTP_zv3BDf5eP2t>$MB3TBPz1@p!XBC45VX6U~*%>p9_zl)qRk5%>CBsy|{Dc~n2&CxV&ealu^jq=;%Zc~<-9 z#CdT+Tohl5OX6$sjrdkv5#I^k;r!2jF4jN#w_Nu-x9qNCc|$P2>?xRG_7+jiF$ZdY zkQgk6h@oPH7$x2mW5if7PK+08Kg(f`ZOmrcl^kZO#2IKzL|-%Yp~pv>VlA_KVlS}ut3U3h?91v>Z_MJ>Y@cQK7wqR+Ro1&vwJxtV z$EDTZ(cn)knCB9H)75+SH|p6d#NMmC-s>XM=D8m_&i6iL-UV*m(9PcSIr4}<`qogt z_d%XPUN?OtjXQKGmBX)_lH9ec+5cCMrVcfUllxxTftLJ1hx%Cbdu4B#!MSc2{KWF# znH0}$MO#JfIeSX0VmAqz6)1|BlD>e8$e*6bH%^vfFxw`#L^G=RYX6s|O z&FNy_n=%Wl+jN_&+R24B+6i^n*yy{myA5+5cZ;qMcC(rcbd~k@GJCE?_}L(Gk7$$s6(9G z{^#PNSnRfWb+tlG?;&_JwWvd! z+_?!y`*?$IM|r*e+=H%Fi*yc8Klwg_M^lq}#K}!oVx%QLX5vVT9`jaoJ1J2Ni>IG_ z2f?GM8S=^9{d`?ReA%_S2F*&}!%B@1Uz-03voL>7bEMm7^L2$c4gJT5wPNL4=F?d} zo0|_+v*puNxAdLw1kFC0wbr%`_F$Whc6k2mE={-Wj{fugpxHX1+Ffs`|SytJ9&wVOQ8jedEa!_$Ahzu?i-q#ki{KYn<$ zk3X4swAZI!deF_D{Gh|rf4;xq(bS|KadP{Y9bt(_`)Gtk?|&znos>Sh#nXSjv*6Lx z4Ef|1h^%dhSME~Bpjr8z!s@^8|A}w;Zm5~ve3Tj6_~r-8t8lxT<$&s8943UH#k=x4YY1zxLAKgFG^FzW4Nk zUIvfmb9{z;a`WUH?&GVFhBk~9uaFX(0PXlhcAIJtFoZJ2n@_(LtaZpMff4z7OuUY9?Sg8@>ef0jzIXecLwka-|m&;x;ceWI< zD;iiEyY@1h=ITm&KL4Zc(#0&UPMO|rO@Tgs&E0Q-Yq5Kt_w)|U-iL|Sdp&LQ8n4GK zjdUAUFK~GJLQnDGGcm^xbRB-sEK}?9=*e8~bt$~32lOy_G@s|Q{2z!!#%E>pFB;RYAHTA0kk_wFOyJ_DOYHC*KRpW`%|1B;kG^Kv&zPsP zMOPel##DXyg28j#^eT8XwL(6*qc1z3zvhfyohi*qufj?VK97IzR3B6L{BN4 z_0LSiHe-*xSH$K>IoF;_zQCqElFnVOo53}1HP}6xX`o*d{-jeyD%J)64K#;^Y>;G0ew{&*0J2 zq#ki{%eH#O5>Hj{6^nlV>Jjti`eO!9U+87ZBCk>?WZPDDr0j^Dr#A4y)wt^UQ6{}gy!j7_N(a~>!963yxvi9sC%N( zQg}0ZqYLa95Sm09Wi+NMUR6=Q#0g~yQN$a zpTE7sQ(m*ut}|?(cieAIAL0v)23(>XXm#vzMrhezL;azm78ZbJd(ln z{N|T_veIwj%`**lb&lw701IknTx*H%Fa1WdkLEkzGa>I?y|ak;i1?8X{nLPjuA1Jf zfv11;9L>u26>`a&vUsS^-5YPD*9Qm1bEgW#c6fS6?}JCPPfq0uoh|#vtG#Z~wI-c3 zXCF9X@brv62aoo({wJT@w0o@2f8fohyk@1(VWkG2$4|}F%bc&=+iV_s$TUBzf4(1h z&Te|7xE)b;ragaTwmo_!qbpS65jXSeK5prWzV4@5k?x62dgrNnNI%i+qeJ}6s&#%p z+so@5+D?jew^v3wJbj^$XjbY_15e)DI|ljOZ7GL%y?R+E-#BbG-uzviS44_`Cb~bGyO==KKC}zQ(y5zV*ASyyiSC zSJ4ID(+Bz%JeoXmIA>#jP_+SGbN;m|T{7?K1N{pgO|6hmF6V5-yKa2NqB$R{Hu;jC z!TE~s8NCZ0P0f%`F6VN@-x&YA*R1p|tn@O(@0wHR`|WJ{Zl5i+^>gZj*9!d~bLvx? zQ%BPrF*>tE5lh4taYS4Z)w@a)Yd?udD*oO(NdA%M9sbcX=;w4?&kJVJr3LfovLdRP zbS3Rq5%olUu~}>pf5lmJG|fPx3ue+W1#{`xBC6SRLhUCOX~l!0x9B7KiT+}MxYu{Q z{-f_;x!>nA-tXUk-tR1WpL(=kFq1wgm`i^wqMA(~)BXu@QG70HXde2as3~fTKl0r! z_xn7@`~CaR`<*#2RR0zUX3t9m^XFwEsu}be?XMGC#Ws;uv({|luR4Qnu48W@m_@e| z%%j_gsAkd~wBJc|7jKBu;{Wyz-_I4lm-pQKo@Y_s@86ost#=Bp12=F%Ajv*|}g zRP*V_wVy*25{1PiFrHx^ON zu3KuqwdgEf6=8OLM*45ft-nz0OTqi2@8`Wnf5w^h19TJhw zKCmQ>P1b0Psrcn!`(mDcmi4sWQJb=GVu$~@T0(bXOb?4^KUtese5^p?_FkvCHP2*}HFz{NsYjgL{AZh4;={T&(Yx21 z+3%LDH|dM6HF)|$FM~%@GvtR{^2jN4)|z2II=?>He1X>^>qHuKQ}c-3@_0szM<=;7 z+WX>D-}KtnOX}WDp3LFtC%q0H%|1ERqV@E7+3WQ5y7_ zciN~~K3*!b`YwGU(*jpp&y&N`Pri@f(bS|KadO`((a*;peX*a{G0(?z*{a2Ic>2lr z5j>ij)FV!=`>B~F9({Uqi(a#Ky-C|@gTd2JzJuV=)C~C{mppQQu3*flTGscQwR^nz zX4p6L&8PVvw)xLJZ0R$-N3)OSJ0cg~Jkw~~eeP&oYaeZ^CrRq2xugzHpZR`*M^lSB z#L3P3UJsu?DM?SSFJ+tS68}8M;psEqQ}AeNQja*f@jsg7vO1CdPDl`powfJer!+BTjDlsZA~MPR}*7=!bf) zGb3ZHH+cHYcN09Cnjt^rl1I+^%z2EhQ`p2vG}~NGI>(HSc+gJlnBGpAGsu>jGTff2 zm&i3NpV-kidW{}3;#F5;OgFzyuDQU~{b-)|^oHIBkLGiHhJ131%v|E*cl3-_^b2;8 z`}U^Zqa{yo=xy+5YEq9lxl^L`_VG^(YBnl;rNJHBrd@Q0r#JLAcr-PsN1WVe64&@1uy){ibc%9(G4qi{qvDod)7U}Txi2mZkXI4JD*`0Z7tz)e` zbg65tcP!!Q2R#fP&FB4R6(=`Sme+iI#&_Mko^Dv-FnBaIsYjgL+YQV5 z{OB#JcwJ=r0yDMq5`(87^fP!gHK|8D#!`o;hj*{U8tOS7#1DV9$?Nku zR=UJZmU~Yx=wI+?^2ph_p_|{o`F&@v^PjkEbH8)N;^_fB3?5A_>JTUQ)o;rB{HHUN z_PYLuGtI^s5e82W=wa|^YEqAQ$R&@Q&99F&rK(LZ4^>QH7sp9#v&HRgW7Y2E*EZ2& zxG%HDa(McKW^YWK?p|L?-^J^Q(Q91Fy{jCazR<_u(c!bi$=y|Rt&eA_vd-&#_13z9 z8&^9#{h_bHqy6`w`ozgC*sq6=zj&vc*EgOzZwpSmXz}!i{sxbxCiRGud+ddhKELY8 zQeIC>G1=6c@Q%ULANm_Snwr!j9&*Ver|FF>rudg*{CXwcIP>+P_%_M22`%gQw|aY> zW?vthab|RP^kxj-KYEO2A06U7;`Q`7T5GS|i zl;u9&y81G&Z_Zrja?f7l@brzo2al#E^@x*Oe@bs3pSh*C*XU;2f z2h^ktkpC*vB5P5zD-BL!8{FE0^{8335H}^`?tcO=R7P22bzkeeh^%Qjd7Z zC6AnFF>{+MMV~N@?P!xd*BDbQNphQKMN)h7{a!Yn>uKNoDz1AzUmQnI=`WgnbcioJ z*U{%JkN=88$23b_ik>SRo<7l6G%IzefhX_b6q|hRh@Kn0Zmsu-wi}_|%F`=)96XwR za&G9~CG5A`qyHaE7jA#m{xI&6#nU5t96Xv@A)nj?g)92})mdKfdPm$@=2X=g22YRZ zaqwtrQjd7ZC664=9lt)C-*B#&KHXb}^G25>wdLIKx$1rWdE(PU6F7RwxgY0&_?g8! zd(AoB(=RXfo}SRd;L+rf!}%Zkae@brY929Ks@$Pc-`clyj-bMyRn&&hwQ zR~LTH&&@|(O9$zd+5GTbc@u@g1?&sOa-|F-C^LO08cXpmgGhF89NkmeSOgtcxixeWINF`E>G$PE| z(@Ccn8N}lvyBID;ic#Xfv-EqLr5{(Xn5UlyVebBg^q1n2 zxGsJatu+U3BVH11MLW@6yevA1j-r!zMZ6|n7hObG(M@z0f3+F z9+6k%6Zu5}QBZ_g{gcu~#M9zA@w}KOri;Jwtp1FSpLzXRaZa2U7sN&Jx%fhSDZUby zM40P;BmJ%TPW&uxi<+8O*Alfw9Z^@*6ZJ&{(NHuJjYSjDRQ%ch{`~jO_NVKZneWdO zv&3u>A?Ap=VxE{U7Klg@?gLmXy+kY%8^yaKgXYqYh>RkWcvNH-S;S)^tH>rE7uiJ) z@r1}J{_KCJ{(EQtt#r)H|J#U{L|f5Lv==Xn4x*#zBwi8WK7rSyUl(0Pe=$JZ%RK?# zEAIz!UHm9+h@Zq?;a-4(nqzZ6Kwhhu+#~@ul*vwhxr4>w-s9llsKTt@?0UpWk+L zYOlXdQPJ$rR@UGrbt!2Qy_?(ykESN|h=*MA$jQ31p&3x2w#jhhoT<>_Gv8}^j?X%_ zk!3GcgE|)d?e|x0{nJ-0o<7s>;L+@plVn?4$NuE0tsVOE$=R;xq6mklfAl_B>-zxUjOUdO9g!wflG#o*~5{SO{ZP3jR3x#W?P@qtDrL7~QeEwT2T z>H7V7?|pyO`{4N=$Rnr6l(Lp#M7K= z>(HI{&32!@J=@{wFW*V@cqPw;4JQja*fqvAF5@f#PLdcExSPMe_gE{mtXd_TdXsYyNJ*{9L#FwK)z?-{^JlXljOh za+}v#>f@EW&-Xe;%lYo5n)4iujxZIZ(0_r00M>*M9io20QS8$3Ov?|5oaC&Y=d|Jsq_=C!v=`}Nf2gC=^n zqu$eJG<)T;l(Og?AH87FZ%sUJx19ab;^`rM$A`~UEKt`aiP^}pHZ8rt4IeVkd-_F> zgGcjuK1)8isV;2x@$a&(^SaB&k*<~gh7nJ{=y&jFYEq9lxi1Z>>f;||sO5FN#p~?e zoSQ73e$nsX(bS|KadP{eNZ|8F4M^hkfmJ0;)$yebp5D>#;L+5i9`TS%9y!Y|S@TA@ z;-DOGS~Ea&&dTgS?YxrPe1uSf=5%6dc?^+^P36ug?r9Y;vqE zV(|2n?<06LHK|8D2;3o^K9-(3oM?#^1TF)rY7}> zliTuIET3QQlh|IrT%xc^pQfO}(^tNi;L+5i9`TS%9y!yNl{8PRC~4Ym*=5S!+3x$# zcY$Uf9pZ-)m$K~NURuhclYDdB=FD-_;^`~j1)7!bG31h$_Kn7l+$qajIP|*ZS?!`GOhOd+a8Pc-^IlaPcQi{f=5$}I>gCM{(5a6Pd@HNuVas2 zY>!==XYurs?;?0KHK|9O+>5c|`TVY%VtM^)+d`&D>%s<4FZnKlM^lq}#6vE5)w{iOeBR=&HCOWuaQ z^&PoQayNA7G6N&scX<~%JUylV!K2wHr@-xPet&a|%$fmwXq&qp3w5 z;^amot>fcA_pasjtgFlHQ>&L+JiX+*2p&yM>JcZm!ipq5|N4peUcdK&H5F4oW$^Tp z?;?0KHK|8DUuM{9`How@{wm(dXdN)C&3Javn{*$@N`cb55M^y-4rr9lZ}8P0f%` zF6Yt2>tv|oHRr@r`YgA2dPnbrM^iK8lgoKD@%4?9dd>NB@uJTfJiVj$!K0}e@TGd z@8xKuW9EL2CZefmAzFzx;w2I8^Jp*4{T%e+Fhs7h}QISPt71>0% z&m)KQB=L@zBL3d<59TRnzE~h4#X_-2{Mnv+aKHCze5GUNevQlGYjH(f72k^=M7WRR zhBWtO-0M9V1C={S3>HJgP%%vW*`8_KO1|+^6xe^zXSJ z<5}HzP)rmTB}7T_ocJr;htX5V$-Nl8MIX^$3>1UK5E1Ut7%u&__*PsIf9v@NKPh%o z+!BAb=N{beeHTyZ{s8X1C@PG2MidhzL`f0u$tWc~N6ZuR#R3s27K%k;u~;IOie+NC zSRq!5RpK9ghxh$HzyJ3>BjJAUySSob<=%^{;+nWFZit)WmI(J`+>z#K|zt8>uSKm+3MaSD!bQ9f0PtjZS75zlG*J7YF_fXu+{S&b?-;OQf zh`1u2h%XX|gd&khERu+%BAIwVBo|S=TRg4y@8`MykL&Zl=NSt3d*4J!{qJ$_#Pgz* zC@ac|3ZkM2_f%AoUM<#&b>jc_et>O?Zx=hnPO(e8FLsL$#2)dX*emvl{o;T)D582t z`BCkEB94iFiZ*NX?D*&5^+Rakw7F8Nkmc+?wv?3U0c)@^~7K0`3v`ZkHlQ{ ziu)wyiv?nlSR$5*=y~vHYK44qZ=LJm z^YNye21rhzUTkr(bS|KadJDn6yfvVojJ$rX`jw;U3boOc=|{GgGW=7 z`ozgybveI}SDKK|>sh9^y|k)_#nV6fA3U0x)FV#rwIZ_(@kupj8Z;|?4l6Z6y!kgT zn8V+cGpyB~J!4wc_{@9yNY8^ulSj_Xt!*v)iKn*HeHd+RnH|wwu@cc8p8nDE;L+3y z`Q)x@*VE?@S)}J)NH;k%&wVypJ;tkl^gnnsHK|9O+)0BXeEd>|2(PnUp5clbdr*ejm@5vw+v>3-q>&CiJ#=`bYnRM^lq}#L118Wws$+dFyP0W~I+z zrACOy`mv08sL~6DHT&D2nye#Edru$fdGKiR$cfkJCCmQT+1gt4p2pE!wL#Gwp8nDE z;JsF@kWcQ+?fQFC)9VRN?_o_h-+TH;&x1!(Gvt#yx%@2B6JpH5pcxq9Hc%wTr4SUT8%ra+_<+F`}o5x=6PNJ_-t2W z@+^m^XY@RHG&QM5oZNa5IemQ8_`F`POx?xCx!v93=^s7EQ;RypAMHNXuy=a$41;E+ zw_)XTA^zP<`Am{rg$?W3Z}ytgF%Nl9@8~oBl|q$l&O$XUYpgzcZov5K-qRm?8a$fM z@fq^TtzWyHBmQE6P7eK9-6ig$2NyX!{h_D9qp2D4$xYk#Js)5E#u~3XubAuJ-XG!c z^oRZikESN|h?85c<6}NvrPAYGCmhqx?!3^+;^`Ir4IWKR>JcaRt-Nm=;)ma#Y|yOq zG_2GJ@ee2FG8M}gFs$pI+F?qk`M`U6%YImiZOBx?5|8&u1&bcM>vLP^^Gg;_-{^Jl zX!gmee5a#hKUtx+4&A)i3Rh?7GKZ&M^f-7lwL(6*Wml~B@uAZ#S#%6rb+QuegP z(>wYdJeqxS(r)kM*x%fxi$fnfyV4b0xYpt68GQ~OO|6hm?w8ws$-g#tt=HGuFLXO& zE^&BzM$dysQXvAR`)z+{I;Bi_4fG>Ox)u;yr+NknOInfe-o>cC1>5V3KqSi>eu#K>d!5n z-qGja(d?7c_M?{^`?)T6bm+Oe^<1L;D;%Dl(dXdN)C&3Jrp&$4$KT4h+UqXaXS*o_ zA|0Nd(evQZ)TAD9a#Iy~!pEQ5meuQTuePuaKW}XD^o*VdkESN|i2K|$;|%ek&x|$= zrCI51Sg8@>oTDcGyr4f<<(zZvq5a;|Kl&UznmlqiKV|<=nM(e=m2=G$HNUfX`bV#W zM^h{0lgs%j@nNZSZ<93VnxB~^4p0B+dGKgzhJ124KPBG(yA@t@uK7^W8Q#-B`X4-+ znjxQD&QFP-+mgd;&OJY<(%RzbAN>y=P0f%`F6XVpU)(>&pTn}!=de;E#P7Nfq2S&3 z9sE|$`=Xk^520@q_aUs)`y05w;9l=7$fMl6BA>`F3W$QDkSHvk6h*{S;%QM-7-5AI z&xmJ5F;QHU5GBR$eP_Zy`<{Yk`Wc!F?k#93xWAyai0U4Lm$lzfbQ9eL&w{wu=Rka^ z+^@tXaanvVz7c=6=Rf@Ro`H;-U1t*9JCIp$|G;A+s(T2Y(0(paL_8(9Kj2>P4Opw( zbz;5PAU2A3#lQMp2>05Pd@Hy&;5)(n0oO!S_Xzx?{aYfgX4~-u^Z$FD{ZCNt zTjFgoQA`q(#lQL;2LFti|8D)<9|&gu9}4FG`$Sat036c(5pi0a5zP1Rb+%tgxs^o~ zQB_nE)y1FT*$Tg%>G##o-A^#vA0U|T4-!$$_(y1elz3ZA6u)PlA6IkOcp|G3qzjW3w1Clt)q6N@C`xAXNB+Dj!eicF%VXf4`^mqc69PP7*fr z=pu39Up<n3Uf}+ThXD4EZ6KJaUR8ZDeLftLxX6Ki@EA_x#{J zeWItqqsb%ZpkJcY*WS8}p{5mmp}8PS&-+3_woGq;fSoU|E9AMF98zpz| zcTVo`^oO1XkET}0CpT`~kv_l9CH-?K{oIo?UHr%O&xbtyp})bSsYyNJ3|t-qRcU89bUia@Luimi;Lm`dajWo=M!O=aM-*J)w`mqp210 z$zAuuFrT08;s~$5I5FF;d}o%!(-Zm_Jer!+BTjC^BERI9oIlm;6H|J*u1kA4JpG}k zcxq9H_`|DLS@sG=thMM>nNOK@1wJ!)dO{zA_gZyAe#j+{oK)9~n<|N4@awiE=S;Js zUwKb&=x6X~^2nLhrLARuMDtfI`r=~=+{^j&Ze)4i6ZJ88dP=R3Pj0g8gM5DcVtPNi z^te@XU6q3o4o^?$Y4B)jQja*fiRUf%@m8%Of6)tjx*3UjIXwNLr@^DCNj>6Klv{h# z5=;DXv%;cNcQ|aiEjVWI^oO1XkEUkG54q%#6F=3n=JjWb`SntpVj@v|`34*3J3RfN zr@^DCNj>7^#^1Qi$M@`5>GfhgGktht-FG2Rf9P-UXlhcAIJrf~%(KKV#fh}&t_eRh z^5GvzivmkfENpXhDyX!6K8pZg`te%&!IS@cGG$F@BX&Ee?} zJq;dBt&mS{-fbfs@$=(GI&_9IOWY0p9)_ns^f!1kHA6nRgVaCb7x&HedRWHZ?x81o zdQX4oZ}4bphJ13b9Gqo|ujxG7qLZb2-&}6|zQNNUdKx^Mnjt^rl1I*i-#=r{6)Nu6 z7jGOkL-QZ-o<7mr;L+rfQ|*IRmi?zcc*&yQ-Wk)4s}s%P=?^^(9!;%~PwwExBYl3t zej~iT^vXilJJ}M4r$6*Gcr-PsN1WV>wRXK6p8n9^;L+5i9&vJW z9GPv2+i5c_x^K>%Cg0@k22X$JY4B)jhWwCA9y#?}7B`c|KkHYw>a@AB{S)u$6TJ-{ zO&&S3vbM79cUsrRqN}ut=Mrv-&u}{odg|e^NpH4kvvq<8s$?NTkEl zANm_Snwr!jPHw6zvwb{HQvG{P`skGIZhDUH4o`pRZ}4bpQja*fU57+k;=^amwdgJr z_L7|}!SgMebFRT9_ZmF?p{K#4sTuM^E_vkKH5V@Q+gb44ermnC zelFZAin;K5&4roq-s^n#KV`1lLC4H&x0859bQZ6Q*Tn0hi|8u431+{{aqo48`;&5S zid*7maa-IG|LSM=-|y@;r)H1LZ*z-0BCp6N@{0nZpeQ5?izh`9!JPML!QA#=7S|y<(r(FAj)%d2jt6J*&N`pObm*&*HYYBcf>r8C}E>F-0s9Tf`A@1#{i_ zf;sKI&S>W-cdnQx=8FX)QvBZc%l{Fx*~9udna>^-pNM1PxHutBic{iK5$3ndV()bh z+fccUL}SrJG!@Onzv9{U_d9>}c_(7$e4tabmofAl?#TM$5eQUT3ZUDKpkG zI%ejqFNkuYyr>{5ib|rgs3NM0Y9h>IUzFY~wu)`y@BK~mKIQBe2gE_~k@#2~5{JbR zaWC(S|7ZU#^zWUiM%OHmxoS)iOT-p&L|hS1#1{!fLXk*>`D;>X=Bf8OOC71)QDU@s zQ;ZQ~#UK5*&A)esx>-LnbJVS3o7gUPh@E1Wcwg)mABa67%v<+KGe5o8+3AbQ{b#)Q zy_M?R&$Hiu`?t!!cV;?R|NG2Mhl*ihxELWuicw;;cvFlKV?~&+PLNKi`Cw|1M*O|M zM}AZ}nMD@y*#F1gS%+7ZWL+P3Z>({54*^1U6&BosLvVL@X&^*Mh(i)IA-KB-r*UZ9 z-Q8WkwW_E33wXKzi^!$N(~eOdvDJ0!IJe7W#i>4Rk&F%yrO>U=xT2o52>a6>J0B zfn6uv1^pw~4fcX#;5ax5PJuJvI=BIDf!p9Ncm|$>m*5q617c^uH3q~3@j*h63Va9B zfV3bz$O&?RJRmQ~4@v+B;0Q{AGN2N00aZX%P#w5}2A~mW44Q)WpabXxI)kpDALtJT zfqZ*ruG_bW8h=miO;Xy=>}ntr8wlzvfg)-Rr#Ihl{` zjE$ed&$NG9>T7h2^$%5y19uet-uu_o*pw5r_0-JC{A_1zHK#--K9f^?qxJPhl69)9 z&_6F~GHd1h7ilrzoTh2@jZX;tR2sTDoPg5zdAHR~BuI?Wstw|L|%qr>(% z>SS$8YI=?V$IyCe=3*YUGq%&!8798Tu?V9xM^DseV~1&ajseHedTQomKDIMr|3B@97F4=SO?))f1;-6cyK(er{)+lAKMwb7tf~Ie(~l6qx(;N zrK&Z4t>`%(98c@1nbXEIw&kbfCO+rT6h`+O+(KL{xCuSSj^k-PHFGi_+pp~QkR6RZ zg=OD9X;ir^xmb-q?ccFq33vU4C$GRdEy-(As2rbD=dfIORgflQz?4(pJQb` zHR~A@C)0Ej7ZNhl=mlMh>unVsG(G#xakHM9xtNFTjCFbzVdCe_jWoLPzA)W#K&YnY z7;xO^nTvVYUNTjXsT=ns!02MzAFKS2o+*0vn`31?HS;hB+Zo#{Um_EKb7K;tqc+x+ zTtylQJ;#XSM$cT#vny3M$q>|ESbn&aP>nv2RME5l94qUoS=R)|2d68n zkL4<+>Dh0NoAuPp#XM|hY=V#o6JIax45NE=n67`wIaSkh3^;DqQ!^*?v7ND9TZfqT z9WR57PO;~%8d%_=qURWJ46UbTPUd4fW2bt?HSq@@$2U4SZDna*v4+rdyf}u|Q!^*? zvAwrrX9-K%QCOC{8e1)F6Hn1|TsVf-Q?s5i>QbhPG#riwP0~K}ePucaRJ2^Bx$AjZ(JvDRLc*Yh9Ut;1v zG+bhIjaHF*&w9*7@Ei}0r}fm#$$V^Q?ADKAroBV!$ws#yc3I_%yrAeg9vn~WshN}c z*v{CJF+K>}dltg~96@h7<|G4$l@)r99mmspYUZ@@9r|~YamP9d%XUrP$@m2yjOVy; z46UbT9AoZ0^;fJvay&p$Kf0b(*E*kF({nsHhSpOvmyKs^^AW%F-NBao45&^ z0*qdlGq*0`lugrfJUE8dQ!^Lyu${5x<1IGvD)%y@m;E$X=MRk3^c)Y4r}fm#$$V^Q zY>zhKrv2mkDMssq=hf;9=M+81gX3vEHFGi_+Zo%yF}HzO%3l9v5HrDI8nTb6hxv)>E^dF%!;AGI6)!gc!Z+SYJ&&g6 zcyK(er)DnZG3|&gx_O?7Z?Jcv(KGSCZRLB-*7O_?j;Hn1%*lLgXKeC?A*Q{3mN27t zH@>dE`*cOob38bn)>E6D$j^4h?%5v0#CwE)7V5DHD$6KcLFhSl97F4=nUne0&i5+y zrK2hN-s5PdM2eo{!ZEa-n)Qs~`xMsSn;T{{-*Y&(&ZFr$b{tRZshP{hGuFIkL41x^ zvyJ9^j%fTpB|XQ3<7quLb21;>8O!%6Y=3mn-)O$~czyATqUU&UJgui@P8-iyzGq>3 zx=}IAdzc=Tstd=AV@J(;YUZ+We2-(_`|y1aJ@4u5y*}IMdEaX9XW2&2`!sw1#x{E1 zqu6^Fw$byNY_HX9qvv(UUXR#D&$-pkxoo57{9)%6w$bx7VqZIKqvv^G&kwfIv(N04 z9S4?QtPhv^ay|HKov34bvpziiAFK~Q#QLyz3jA+4@BzMH0`LR=AOHk{AP@{fz(g-4km*sfS(8c*3SahMQlCrpZ*N+Z(S?qy6?BH`6j{|VPcR3Bn8Ppa*zU~1mF5Q z?f=QOUas4I>zeIZ#GV6x<+WO_yMF7M>pH})2Y-dNR<4_V>zZjF#P$XKz;FE>@IQO4 zl%Fll2)^ZWrFjvT5B#S;Px^b-I=OE7t!tK-5qkyvmDeh{?)a^1juD8B1T#Stm<9fw z->d%mdzAmowZ>*xKWhQpz`y!_?ZLje-nI|y2M54Ga0na*KY=6QD6ngCC!p=R z+-Yd8&7B43z1Tm+ZEWpD*t1=oOG!@CJ>*YWN^b1m;4xDOtHhu{%-44#0ez^?VZ zfVS&>uc5i-_ZGYZ@4*M~5qtulK@6_7fmk3mhy&sRyFQoznrnoKKw^*tBn8Ppa*zU~ z1a=KEHMCtvOb5-i#P2}{kP&18nL!qi6=Vb1K@N};YU3bg}&9%n@pdcs&3WFk` zC@2Ps1G_d^656g$mWJjUr4uL%oPhuZG$;qkg9@M`s03Uz+-Zx%Sx%GzTq!8)ykyf!3f6Xbakb_Mijk2<$p(7ig}Pb_3l( z56~0z0=+>W&==UX)B(_TJ#{cN*HnjsVPH5I0Y-vR;0G`oi~(bTI~WH%fG6+*-e5fN z0lr`Y@B{uJ00e>{5DY@VL@)`2f-n#cCW9$pDwqbQgBc(KM1q+h3d{nt!5lCb%meem z0CuoNr<%fSk;608EN!5Xj@tOM)82Cxxq0?}YI*aEhKZD2dt0d|62;770< z>;ZehKCmAg00+S#a2Wgqj)0@!7&s12fRo@9I1SE#v)~*!4=#X<;1akDVtjljM^e8L z-_iGly7~S`Mt55CQ1aY(X*5gLvz#|8mb!H7v+;dhVk>S#&vN4CCGv9f0#iPGTSetc zRYB1=k6TtvZ#zenf2FuzS}rUfY_6?Jl&z`g*%$WTdTQ1)=JJSFCa!6k7e?><-cyI~ z^3e3`1INI6YUW}dwllWQtqCUniDR(Q^EY_w!$Z9_J^R2hu%4PZnUC#^b;+H?w9h=3 z(CA&=TB=s-nk#ztmt$Z(HFGi_+ndE-C9eZk3Cr6XYpbI}>L_~li(_CtHR~C3(fO5$ ztC0lj#Lxv3dg>eTJT*Q0!||}5nz@*V?Tl@Qb!4{d?GucianoB54)->m{o#06PtBY* zp0Vw3B{uDI>n1VUCx1&7=T=Ka&%Sd!tfyv9=3{&G=@n9;!%AVfeM~LYG*N9u&wgev8%)#y1-pbj}#7rpVXY}yQwJ^RRh(=!+I99TF_yfV%bmTi(N z6_KH$qUZ6muhvtuo-yx#x@_VeY`tOhnwuVa?HvzI&pxo<)>AVV^RS(AVl^Ra!g z`!snUIYn4jPwS{E-zlx=*)NWP_0+6q%)WN#Ox(^Y=Zqe`z*9GB?5XM5AC8Ch)Xc>^ zY-jA?cauzf$y}3+-nS=6rymoj>DeEShxOFV$$V^Q?4@ckO}opMSVm`XE~mN=sHo`K zcaDek)Xd3zZ14X$RBGIrEG*N!ETobRE~4n!FOGrr)U0PrpS|ZyoXh2NMh74A(rHh6 zX?pgD<6%8Db1@Iw8T%knn2C>*Gu-F{>x1>lypuFN`@`|Do|-wCkL`?o+A)S{f1T;G zqQ2BaD>Q_k7vtJwo>#14Km~>^%nz)@S z&l!FFy|>QS%uCa=KO7J1shNv;*v{BIRl-bsx|g9w@4FkUGtLdx^z0AE!+L7wWInbt zw%CCfroGFN7)FYN*$t4%$lg_ z*&mLF_0-JCd~9dzE9cLO?OO|eQq%|TR#3UeS5)-uJIBL%YUZ@@`3po!&2`g+rHbpQ z9`tii^z0YMz<`DodTQok9=0=f@A^;^pLt^F z&-#p?eo!)4)3ZMu59_I!llj>G8nGT8F-?22@-dBGzM-0m)1AVl^Rb=x zdX4%=2}|C)bwB8+=-Drhf%Vj^XAJN2SYJQYZKHY5Hf@Nzre}XR9@bMcmyKsE@AKF` zq6!Oedah&v!0r{Y#i?qc`tSP za4K{Ecq~H-qy3u3QHA=%QuMdl##Le4lNimCxw#$Nc>l$FlecZt8@*{|8lyuZld1Y2c3zQ5u76ME*i zCHKc|=s6#AuIlX>&*+ZJ;~CwvR4f(!@~zM_4|7{j&HZs(wsVf->;FxwghqF$lfdXf z>tm_&vH$8G32U+}e5sY6_&hlj*B`do>aYT2SsLeD(RZ9O&j$8Fip*C5Z+ z-8!z(7iPvadS~j_vSGz5p=W+ua(~>0p64~sN1m6|gSsU!n&+%T)sI5YJj`u9HTP%Z zM=W?LJV$wcrhM{Qc<%DNqi4zUCw9H`gv}@KX|>~eqVPrtZCQyi>}Ap&t1pHx^rCcS6^?ppNr;aqECRo z`g*$k-12g)ldt>>t(V)+6?erNc=x~1dbs^=n-E>)rNqx%^D-Iq+9s&$geN z4aeH_6!2GHueNK{ZLkjA?*G7gwEf&EKXb~@n>v7!z!8)Jr9m0s1j+(uAV2{P%7OBr z0;mWo0T=M)Z`}TwpDneY3*~1*`FYUi;05@re)e+$)*t!ZwE-Xq{CB6u_pFC z$N(~eOdvDJ09>f_xx9C;$qALZC1x0*ZoSpg1T296(9n2ugv{ zpbT&VWq~sgpnwMDKzUFBR0NfP3#bgLfU2Mxs19m?nxGb_4eEfppdP3XTtNfS5Htdf zK@-pvGy}~+3*ZJ?f>xk4Xam}UcA!1z06KzBpfl(Kx`J+?JLmy=f?l9E=mYwKexN@X z00x3VU@#a0hJs;WI2Zv&f>GcHFdB>jV}Uyu2Rwi$@B-doJn#X&U;^+1{vZGZf*=qK zLcl~Y350?$5Dq4TDPSs?2Bw1%j)F5o`j{U^CbPwt{V7JJ}g4o-lR;1oCw&VaMv95@dyfQ#S~xC}~FzNvCdy{;zpJfo;xT+SIi;Otq| z)9H%QELqQTf7*xY?3FvlAIb69Y(vj&BhvJg!-qS{$+vE%qz{;rO0n)%-js^^rSn=f zdB{pdA6;&#dNnZVFP_?N%XY>#zTQqV{$$2BnmQt5kUn-hRMUI+ovK?tbo<3qGpCJb z?52WaP5a(-V~pP5T~^;p>!j%eJC@dKkBv5-xtO=)>Va~;dq3f^v!p*%Hm#yQ+A_7G z&K$5w^@_Pc(eoJDFYBr8wrpo?&n%rZ+jrgQsHr{iyuB|zqfO6aWWTJZW= zrv1R)u||jQ7kw$rS<|yW?4$M6%*lLgzq@Xr)LJ~q^n)e6uVY$8y>)Y1MLntCCUrkX zw4&$nvX9nNa|~=eV{5GGsM+q6x|60J|Hey~S?;CjdA#hS_0-I1;~Cqip1W!9pU~at zrDH{pzayHSePe&Er)Ey(V|%Y;1H}2@0Miea^f{fEDSkf2S5K~caixo>zcP%zwJzTX=(errON9(CM1~#6tK?mDvwlD0}PE+>?_Sel5 z`)hh0FZ*acHFMf{#(E_lZ`zCbc^lmTpOIZNqKKwv-`Gd%shN}c*gnytrd*y-+w_Aa z{ZpryiaK3XOhw)L=4`d1+gwG@<7FSMr{);gc*aKcZL8Vt_^73({#?gj=lTxo`S3hm z_R)H3=CtvQ^}Fh2+OO6eZ}g2KMRd^R!kV6aV}GruW=`f~`-2|UQPWb)@dLA$PXgxJ^ z+IYr>JA0Y-xei`N*PG*@lP4>o>Df2-*LrH^WInb}4y`BcYE?J=U`f9*b!t(cOR59&vr?{qP-`HR4shN}c*dCa#u{fM;VEVz5zNl|PMSbC797UaG)&f;C z$y`Ox<7I!Xr{);gc*dS+(@wKJRqr;MI?vl6-RPLVrswgpkJeK&r;TUq!%z7C1jHXo zG2ZA?w;lALz9o!j-`HR4shQKp^L}H*GerMW-hy+z8=lQlh$mwmLJnmKJeV|h=)_Qug;%{@w-5ssRDVn3-_ zPt9C5j`uXY7pS@@wz;2~v@E94BPTyrB^EzW^e*Y2sdDu{8O@USKirOOyno=e*Wp5Z zqa9AgH9D8aClxXKxuRz-=C_`j`{cH4=QW$xzW1Ht8$I+ve52dvc%jz4f2ru1-&c%K_5NKkjOINq?{Dduhq#4av8_zk2uiqur zJ}T-lP2MZ&O!c3tjvPFnDVqCR}~s@m1;nxbb;TXKIkj^{PcN1m6|KSsPZ=PJ+HHd}8g zdgft1>#4av8$a#fWyN!p=jZI?cNEWEo_F*tdH%TFxMnolsrf#K+flQ$^^E0tR%`bS z#dDD74?Rns2YfF?&30<$VGe4Rtmk_w{>}LJYCP_W`CIbuK+lrnIsVL5quEZ)Jlu|& zrLAWy$Nj>I3+8Xa@uX+Tafy6#%4oJzGY@l6v$XY$<@gQycwTXAIXBR=dZNxkMa$mN`{Dapk`B~uxpdn}k8iOXFDQE_o zgBHLIv<7WJThI=)2OYp~{f*$?`uSjf*7sXK=bHhs8Nq+@^S%76?nQ73Tn1ObRd5Yl z2RFb?a0}c8_rQJd06YYbz+>=Re)snGe3vpmYr6?VgUw(I*b26R?O+G^5$pzgz+SKq z{MO%@{jJ|+%+JaW00Y4wFc=I0L%}dG9E<{g_UB^@V$G~DC<2OtVxTxE0USU{P#Tm0 zPM|Ds1_FNT@1*{o&$Zsf{%(Og;2wAao`PrKId}p7%;6M2tuXYWL>t9^^`cJQOy}>cO1@FN}5F2Yl|H^_m=0!u z2rv^wfw^EF`0wWx|ND8x{CG}Z02Bm;Kw(e>6a~dVaZmy{fRexwlmewe8Q=uU0%ssV z0S(H5@}L5!2r2;=P#IJKRY5gS9n=6dK`l@l)B$xtJy0LGf(D==XapLACZH*32AYEw zzzwtntw3wg2DAn3Kzq;ubOfD1XV3+71>Hb*&;#@Yy+Ci!2lNH~Kz}d*3 z1;fB_FanGOqreYfG#CTM0(USDcmPk}1-!v{-~)WY1mFk!K>!E@K_D1}fQeud2nAsv z983mNz*H~|Ob0VS1c(GPK@^w;W`j9kE|>@Ag9TtASOgY>C15F729|>rU?o@uR)aNQ zEm#NEgAHIK*aV`%X0Qcp1>3-OumkJ_yTFfNH`oLAf_-2=H~3Ix1 zZtJO;%f>TyYw%bTf3lOO(aqnw>pSDdX?h+n`(Qmab26Wae^6Qu%qSyUQMNgEN7{wn zHJ-=CK3Gr9IL17fKV7kYbBP&>de)sLx_srPnx4nQK3Gr9TsEGuK~ZB({K&3jjdsX5 zPUn2!uIYK~?2q--%*lLg-#5J!9_o}9mSg0$w2X-dOz=D|_JN-D9nMTs)ai>&SJcUB zH`UeeHqrDv1|GNd)ZE_2Gxo)Uu_iw1$XKIeR~e@VJCD=!JYM#Jp1GJOWBRvM%>sG^?XnO9K$7($_x3}?(9d>D)iO+n} z-RMC}#_KisJQF>Sk;hHXT+GvRP+olJ<4LJE>zq*Y7AAde5o5mh7 z$I6nv#v4CH{qb{vqJCM|Rp*Ry)%4sSkI{N+_S42QHcJ*C6F=jux6#A51nGUpgET#l zjmK*}HFGi_+h;u3BcmMmo8w?fe|e&hqMqV8UQw6d*g%KItf%R@KOUp?)a-+eXKde9 zJ|=!1)^4c}?DN;Dd-!X59vhF>dTQomKDIYsu}9X{`_UW+OZtvG$1CdOHGLGd`mUjF z(50cK=l*z%)>E?&HlDFPs`!}rnB{$pj+*PC-!1pn^gK2mqxICx$$V_D7rI+29oS=z zgC%{d%|41c)*CNHohV*itp?WB^xU60#=m)L_QA$8_H%@h(&*=P~Ub5tz z@p!GLW=`g3dzYp^$$)PA&2g}#Ki)4;QP(cur>I91tgq9C*VpviACJ*`YWBg#Gj{bQ zKNG*y(Z}eHZeBWlsF$YavGI7Vr)Ey(V>_=wlk?{@*Ck$47VJ1`Jdew2wzG}b9oDV6 z>aVDIEeXw4ThsG6clF^tmtzNM`sXG5bz1a`nkBDy+>V~t6VBDGdgAk>(8rqMbJ5Vp9{cNz zTLX<}F6OkJn)|fzoZ~r{_88}9=KCXE{EWV`JWyX78K~)*)0W&Hx1s0U%lWRXtqs)l%){K)Q*(dZmhGG;IWIjN=x_9Zw|++R9^~1{Kuyp5w&eb}4L#>E z&LI_Z2N<3AioemkXW{({J@YWP_0-%Sw`Du$9=`5fZs9kop^MJK_iRJ+eu?)x^vrKd z?$5??p5SXV%N;*6XLMT_V00s2KP?l3G(Gb$pY_z-AGc*YU)y|Lg*NvyI$zHTM#r8S zpt~RN*YwP9OYV=`(DQZ3*Fc^_0Y>lh^EY~Ny#QTs7Uo%a=3#E@skuLH%XYqYc%B}d zGQsG0sr`)})-y;~!}n#=GrujlKW;E>ENwkwd7dpF9-?^;^8BG^$@75s zw$yB=W*+9CX32WqBlB;@zt`n^SR=*Xl79z!mK@JGS#S>x&30<$;daz4Z9QW-?i1F9 zX#Pz&p7bm^F0)UE7|nKS=3x$MmbRX;98cF-A!a_{+(6HguWyb4HQT9~hdHQOvi^(p z1g9_82)@>xvJW!r3Ge>FdP4tLf9&^_a&6#S*9Cebwh#EN>j8YWp9N$E*+6!X1LOp` zKyHu+U{D43Bt-ra)XW!rY+`B4btAXG1yqnLqzxBEHXT-+9^XK35 zn{Rw}y$Y-b|LXe;w<2a6_&vXw#%I&R!3glLetXOdG2Yv6|RVB z02+cu;NSVpEbUU>R5rR)CdY6<7<_f%RYm*a$X(Xs{V<0b9X8`^~8Tevcjg zu6TBp5F`SLK@yM@Bm>Do3Xl?{0^fnuAPqUe8B|Z2mC<*2n0bO7=(a{U=j!gVIUk#22;RPFbzxx zGe8801T#Stm<48oIbbfB2j+tXU?Erp7K0^VDOd)UgB4&USOr#tHDE1R2iAiPU?bQB zqQPdc1#AV|z;>_$>;${Ok6<_01NMS_U_Uqj4uV7AF!%`^0Y||xa2%WfC&4Lj8k_-V z!8vdqTmTorC2$!O>>8?X2ZZT9^FlRs=VT#92So(yI1Pf0X32V%x8qFI?UGM2zFYAy zvkg7B?KOVC?A!LEuylPIsgpA| zHT_+D|5nEOc&-P}9E|IC^{6;_|0FCocbTq+^qr#UnTz|io|^THsW_~SW_^L$tu%G4 zRvtPYz9)^I`{RDCr)Dl2pX%gMsWj=Bu*_R&x>~kvx}s-Z9)tDNtY^%i#%(m~bB$`F zsc(+)(6?)PXnO9O$6!4*bJ_Ud#z&-of}_H6#*k^s{qQtJ&%8Va>#14KnA@G(Xx3-1 zfxOW3HsgEj7J6uU?wiLz&m4^Ni{3AXXB`%npZABUkg`)0J#%rt)>E^dF(0pjsqeP;&>4}Fp8Ml|t*2%#8}I#SgZQV|EG%7``Kh)I0u(*-@))eAW<6t)ziFvi zzqDK{P2FOmw|-a*&z0c0Zytm7)XZh$gPL*}d!mI-J3s?3>v6g~6u7_6seJ!6uq zwwm?oW=l<7yNS2Hkr>a<;JI%egZ0$RW#cOiT_rd3t`?U2Tzyq6FJDE^ygUZ$saek$ z=e_MT>(gIsr>XZ`9j}i(@YeL)H;=)3YUZ->RVuHM`1Mu@%QDl(s|LHh6+QFv7_6se zJ!9%^X{lL%@M9}YJ-L~melf>a({tZE2J5Mr%f>g^x><%iST8IiR`{ziFD58@=H)S1 zPtAJ9ESc3pv%cTnmYTZRG#|ZVr>~~xzIhDRQ!|&1=Nz;rakQ}H+|t^|Pth|kkHLCs z)-#545$lV2HZgNkMW69zpWHV!>#3Q;#&PcA9CNr|keSCioeVL$)SwXE{w01#5dPi0 zaJ}epsL?Dr?{Pb}abDt_QFVi#(WQz97+q{}us*OVSkp5X^ILB;_Q`G8&bfy3K%S$1 zM!#6)XSCboV7;|wu%>5zTXKKghMw~VU*Cz}|Ez1@^E3Khkq|vKDp=Dq4|7{j&HZs( zwsT(K>vzfpf1{7q_cxl?l4e(fH9hm&lKbN}^nAVZwHUY}z-ZMhz-V53c-^6A9_F^5 zn)~CnZ0Bp3udk-h1C7q!F3@OR_jui+XMS69f82(iuSdRC&N)srI`5P~qZ2Nls?!Y$ z)AY>4+}2Zbf83Vse2ww^565#D>MM0ajV`$W&uGd_HlF!e&yxGIaeTe-T%L3-(7bkP zHxD*Cwd-VEweKWN&pga+JvH~oZQ0J(0ACyBYlRzKYX3x|W96ExM^y{g^vrKd?vLBh z^StKy$n%nV#fvbbdCrc&_qx$D4|7{j&HdT<(a&+7;vD7q*?%^EpAY9Q&pUdSJb%t- z{#mn~n)e^vj+&*dXDrXNtj~iq&q1C)^elNE@E(Pl?bOV}9MmjX&wCyI&G`2UtQw~I zx8&b}o+ZaKahsq2Hf*P69&Sg?($+JUF_j@AEeMzoT!E>)jvlJk35sTaV{t8~=dkW%e1_XgmiS`v*J^v(Lb4;`vr> z@Oz(k*=JmQzQt!-zxR2TeTK#7SA2H$-{)2T{oRE!cqZTk$^vH~KmiTPf%2dNs0b>cGeH!X1!jXeU@n*k=7R-bAy@#v`G_R~XM@V^bvgP#N$Jvc_NPL8!$*0W?i%U4gZmVN!_xMBMz zm~H5}ZLVcc~?wiM8JvEQf#y`A}OZp7X zEi7Yxek(aozcZeBc?{N5GmbI2F6>sU&sS`ZqQ2U=yFTR9UDI>lJO+B^U|fQcPi54# zmu6e;hngkpOZC~V=qongrKsav?W~7i=&I?Nm-*?rU&i%!xGOPsJT%*~q|cr-T2Vj0 zwnb5Ao!LQ`DBelaGavI>PtE<>_&G^0OUR0ACJ#&c2G3S2>J-D*De7t4@cki=+i7~{ z=02>a<}uj#kdfyls_$8ohb8^Hj;rvQ|FhDd{Ypjc)3}SSalE6ZXKwDpdTJhnjlXjA zoVa8^Z}PCDKe1z#qVBq9m7;cS(MLCF)JxMdH}_#ZHIKo@UtE4hCdN8#^01^IIdr9> zz7V=XQCF?mRjYzMH9d24AJ$Xz7;Jp)eOINz@Jl8SOZwuc)+p*1k5(({jq|$d!hO4H zdgkUntf%HN*m%Ca;?%uj^01`mYma*Hht=k_*!fad&790l&3bC?+s5&=%GcVcet2#H zz3=G+qZ8iu*GurfFZ8>Y`RZsF{2m50OTNx+EMK2|?Zmq5XI{HrC;W__mCR4C-ihy& zfM+h|x1O5&`4?$5^aHNf+CPhEfW`l#97&*=Us z{B)+G6Er>Z+mid^HuOB-d9L0b5M*@c9eCaZUG;>oe%ZiZ(=!iqTTjjXaa*?Y9Oro& ze~X{dyW0gAz01>2FWKg&>6z1(+#k20=XuTZk>@3K@;5)9qdaG`&GIvzd6?UJYVOa* z?_VBd&QYG9(^~{-p1VBn=vngo*|00fXtq=HddlsnS=xHW@;ti}8Kij*^8BG^$@75M zTxzzP>oD>#2Q^F9^BT>+8UJ1<2Lx#TE%|q#XUXwwusOhJwo~(XxE(c1ThCaIyZeMd z^Ecsm(zE2a48I&;G~20}hdHQO+Iq%v{O;ZiH1h%H26~o!eRB+`*-p(o%t6hP^}jrS zY2UHmpswxP_Gs<+c>KZN@q$LslI;xG8|Er@C>FC=mNTeZXg7Nf-n#c zCW9$pDwqZ$!Avk4%mH)3JTMZ*1(Y@#MFt))W8l~5@PH&$u(G*Y!wj8xA`RaRXc#wg#!qgC}Ex~n%49c6sAsp9&! zvJAbhr1-7+5|Xa2?C8^9zJK&tYRvJF?XHhxuX{=LV1=W4o(21i*;ESTFC))NI>@0V zc|_rUwEjhJ*}Y|u?CiNxe0JZIs);kIpm?{%{mv7awlJSc(jkFrQ9Y*`QTeRo96C=v zjv6A1UMbOKA|zS0NLeYvcdSXWmvwreN38Yrn)p}c&*#zpRCC@b}Yo#pBF z!g7AeP8sO=S>BiFA)P&5OSU`xB+D9C*}23;20W{$+8(N`irjNj{SP)#>o>TnbA6P` zJ+`O%JaLpNeXo&<6WCGq22_$o<3zSQ){z5)8c1q)cZvJqy|fM~rlieli42RY28863 z5#KvYrz{sGO`nxgWl3*2)Of78MCVhU-j8M8^jqTCIis3+?X09MkW=l9q2>15!P2@- zgw*t%E{9$X|DW%l|7CtC`OBQ}rRW$Hu0Ff1EU_tV)ZfhyehB<`=YZe(+UM)OHeT~} z0AK(00Ox>4pcSZvxu7;^@C|dq6}+auo)_+-?jCpyo`Qd8p7@OIVqji~31WfRAP$HN zer*o@IKeLYpt%)?c8uNErPr{U^o z*`_M&Y)zGTa4m6slUtI5Wg zx_{SRh7{f?u}YSa$U*z0&xiy{*NCIqIqs1Iv-8O-Z*O_Dv8PO_JVa_2>@N4BD#@Gd z`DC%GEs2&EmnWZwN`Zx&WpUSNX}IizWE+=Nt(jI+)w+~hH47@D4m4?}avsd1cK%RB zRmh!8<=J{(e3uoJIvm(sTBE9tXm zoji@@ArXVMTo_zM61cm`>;5HV>#P;BV_OmxJGqyvjh|IHe3&7rYgAA@RSR|4t*F{t ztA~1*XpEY*y{+oftF~%9b%ffUv6s5C#aWK6nl2yRYs>s{&1G2Ka4DKTugvRLOdKj; zJW>{xO=q3tQiU=y^z}yR{y2dO_T4Kd!uCknEQKX@)@l;#W>1Oj-&by)E+NJ0){*{o zM@ozG*_2-ULB<}BmW7|UNb9HVRPUHY)ZC)RyREs@tS0s@jb*ay5N18CSfJ zd_SY0WGd$@Z4Pvi_uWF|V5ZIDH~*zX=6x>He_Zzu<|~IUr>S4GbIcj)W8|t58~V)t zyZLG{qQ1UY`L+9$-#S0l!W{JV{L}z-U(Qjj;p1U`iVu>33c$`=^`Tt>=dUK91#kmn zzqr5o`rhUe=9|la^VwB!4O|DmHn%-M+e7eY&vEvC=pWq+{nojy))(`eD|G9>&2#rq z-Uly0Ud(m*!IyKN6MR`9pggDmYT&-<>-(s1%vqDc6fhM`1Jl9RbL1S<%?1D4b7e&F zo|1HmhrArxS{__2EoBqB%AiRLC9=yHIbOAZ+R!t$y7AOkVtJ2L9qvt3i7pOOPYyRw z9k1q5-xtlU4j=PT>p!`xPD|ZY%uQr^hnoBmUbO0 zy8??#qUSB-Y~jYTe!8;^ye={~dW?+xVWH&tyk8Q0I4+r|MMy1tC-5HJI~A@oN_N#A zBHfNvkXRo5rDLbblC840)J!p1GW3`zZT1Y5llRNX*-zEvV15_Lcwv}?AM7QGkIk1J zdG1J>8ZlMUo5j?J8dcQg&qGz?`>j>_RejaW@_{PjdN;MI*C>@Y9ezitUnUiqud^gt z)hhb*lhPo0juC`SSvmBU~M)$eiwH6n12tnn`^PrvIR zNg7U&8ZL3v!^30bbdo~KW6vTvGcmhz2yCQ$)8|nR!v?GOdnc(|J4UJZ$3z`DK2Dv; z@2e*E2$LOIUdfV|5%RdBNX!g#MU}oUL!J+kTl?H3V(M6_yQi*r#Bh`hPr8X?KwhbR zq>xR?TvlvtAQ6|!%ErWF<$Q|+(lcOz^x6_3 z@3xB^mG-iy^+1_BVWbR-*H;oamXivLD@$76;c_8gsO%c*BU7$bmeaTncAwHmJ}w#| z%{woWJe#Vjr`?LHpqnw(mb&-k{*yp;WkO$d;$Rz0x1i^E}_fem%!uz(;?$5lZ{iEmm z+L+VpfV#lm+j8!A1Fe9)2Hb_V*MW!7&w#xi(Boxup1UfJ|#r zLY+(VT2`g%B01lUR|6JDs9Z4ztBa}YsH*$Zsk+6Js_WyYsYR>#`RB`O@;rI_ZACmo&{;M;`SWE!Ui@ihu2Pl5XU5X;W&l#2GhQ z?mcpmpY~6XBzdD`RxR8^ru37}IjT$V!n5RZDsMS5VU745Tqfxf2TR6~6>>IbT^V*D zO6m^`lxN>BlS@|?N%#mqX)~pU9AD5;W`uQ>iJ2!z@Cpa%H#9(c%{wd;hQ?MsHfL8^ z4z^d95_VD!iT%~UyT0l}uPJKtk@+f3YF`yxe2Qv)aEuzx--mqVFDb%9C1L0kxzf#F z?hFi(!TYX>%Z?>7WNBID+App8w0xL~TGU^CNK!$KO@i;lZFU$D+tTbp zN#!u~k(4@&BVeq{Q+Ea$;WrHQ?|@$)byhPE|$84l9< zdZ;A7?KR1J%&@DHwM#lO6a z{h~dJ%~J{2ZYXj6<@~?9p56cIdiIZ=i~iR48@!g)0RQZI=8E=zbxnJQm`~s{h=J=- z9PssZE+Oi^zSfmToxR>whOQ32yzbS5|MEQzuYHZcm)E~$@Lyj8-SK|sA6)}4{spgt zd zcD>YS|MHqy9q+IB9_!2J)S&3i1(;;mDIyG&7M12?N$q4QMjq^>HJo3mQk zb+#;@=`3@@S4+R^=j2Y8*s4#pf~xb0(W?KnBC1O4B{Jwh4|&xffokZ}Lrq$pOKobk zP&`t_QoCCpkth3lOY2!9#H&k1DU(_x^TYmf^uP#Nez%G|E)*%<>g|)HKc165bv(rX zX(4G+?4z7Z5G4`G#!1BnUebG?$i^)G^739g>2kb|G*8eoF24=fFg2%7&Iw zyXKG5V9HVa9mW|T9^g5~ZbduC8URkQu8zv4{MoYnmL9${*8ENVtDMP2-lPYNvtDu>p zmR}yP*3THGqKieT<}GKdp5B|(&V8Fy36IrkRpHGlWt`dS?ut;{Uo1@#!_|5 zSCTks%Sxx6!^9&^Z;6w{LmF2;BR~DHTdqy4A|u8`N||njq)3h^nVaL2oV=-Ih>MRb ze?LxEANQA9?b^$RQ3+L&@c1h6Oh5V1%}w&$Y$GRvn#;k)i=I+$wBob%hNg1%XyTjhyA2#l(+1A+*thj21&ZI z+vUY}{69+e=i*!NvwZjHgG}sk${dr^iy5*cQ%&jNJ6V>s-yrSV1xV}f$BOT{k&^4f zOgS0qBqfT3$m|o3q+Rln>d8YNRi&g>OQ$AL$>MKTP0~iI3;0{O$SjpMc(y7~bc@On zxE9ZCmx;VwAuFrRl>s;L{JZPD)kbA4_*q-+0QuEu{a z;@w!JD%VT4Hn_}^zq>vsiTU&TC9lhNt@6*h9yh^tw>fA5zJ9;i4t4Fp6Yv!9TKyb+ z03X4Z*X@|Nmc|CZcKuF*wxr$o%O1la3&C1}2f-)IBUE}Q< z?KxcA&jY^K{UfgPf988#uI<`&-GAp<=0CfxH^eo%F=zr>0AA-?f-m3mo`dK0{sOoN zu7iJd?SF)rC&1nVJcs7{qwG3+)msd`g zg2UtKJQt6s?)!4-m7Qbhpbr5m^P8?J%qx>xIqIEsdp=lQS<_UNZ?#4xKR8E~O&zIH z|HA4_7Z0`cT`d(b;ElY?T2HYEpJ==k_UI;K7u1yvRm;o1U5jPq&~f53>xKlCYM^$GsH%=W+%2w& z^QzJ_TvW)5I_k=%q{?j+t`}!N$oAGb)U)LHy`O+%68?t(^I>-g_mn%CC$)@b* zD*nVD)QqOJ)adyW)u~l;)x3GzRob%a)bl|R#VlTOC443ciq(wv5u>?q4D+n?>ego%_G&Lz4O)gligI# zYnfC!hgafL=8ZgWQb$ee)>g_0s$6={CYRW7e?Bj;|FkojphidPdCNi$=K ze3%nM75bb_9gl7xKO_i|;&TUy`axv8UzDsYw?T#$x+wcz?2r-x46 zg^ct_q%vF@Ek`T6$))F0q~pU|^2y0Td}|g{F-!H9S%bYKQ*>>~Shb-voWD>qf1D>y zr`O5z%;P0Iu)aKBTUC`l;;IrfzbVyEE|!hc#!0)8<)y=n1Crt42HDU)nQFMKj=JSm zMY(;-tM*>`D32c}J1tVa zn_59Ctnrp?@1kY)#?R6&bADA#3-;Rn^u?xfPFl^^7+%txQSTiue7K zDle7KNr%XRjD4hHjKOkuO@KJ`=p?IW9~Gyfb=2^yqt&S<`Bc2t7v$)u^=fYL4ps8h zJQcofl6pGpJN>L?T0OAL9;u#alQ`wrCL3>WltEGWf7(vT)Z;EyRiP4|>SndM%JWII zYH|L}7xyUxdbI5|;O}ox{#J7%_DZ$2^yU)IvzPzfeM$!0r~IeyQQUCf@vZkMFA)0@ zyan&Td+=-bF0pWb@z3sG5}`dY_@nP*>L6!b@Oz$D@P6hD?p@A;-+M3fXRpovZ{NQ( z!ac>mx`#Q7n6K|+E}`xk;Qh=Ea1(sXea&OU{o1|FE3~}^zvmvOB<^(_!Eb#Q^5wlw zFz#U>jWxtS6b#T}zw_XRzni~sL zvxQC7t;uuMhcg1Exr?POl`L-$5B!q^fw7&ZBN*_h6YQXzW@@TV~YWYV} zLYsJH)p@F_Q>Bwy)Xr3~zmGCsk)o>H=%FSi#;R7kBUQPw!_=(@dz5Ye=5*}sC-vrM zFUs1wg1XIEPbpd9YFUki%Fd_@qk-BtA~`q%rz7_ zzXa)Y%v87U3{wVsebuw4E!EeN7T7;^x?0&hK{cv2UDfP9UQL?UTg^POj=bXX$#YdN zTD!OzRd4o5>Dlg4zIB*dRh_SD)ecj~Jq+l6*f4tY8f*AmO{4vH<4DKUfv&%vK|M$K z(96Z9ba0*>J?cD)1_q{3KW8)5d&xw#cXOV4yts$bxs4nV)_rLc_)(qyq)$IE9>_zm_V_QUDSHR>B=*?vuaqShq~0#MClu4tF+`k z6y6%^CKuPCG0xl7h4C1e+f<7Ssy`s7)FNtmyefAe`HYr%E>x|ovemo5$?7u33QXRz zM0G0pQtf}#jV{+*N=9j4$o+PGHubB-;lm??g8nob`qu}n*FU4f`|q{uroH*!#6`Y{ zE3%Qh`D0z>e=>*Tg5SXve&=#DagrPSS*+xP$27mUANWH61i~;F4nZ&if*}M(LMVhm zI7C1sL_su+f*2SLV_+=A!Z;WY6Ce)aApsI$A|$~im<-7<1*Sp@OoQn#17^Z3NQK!j z2hw0Jq{BRz4+~%+WWXX=44JS5mO>U}Lk{FZ9xQ|9kPj@IU?XgT z&9DUupb&~+D{O=9umg6&F4zrwU@z>0{cr#d!XY>eN8l(NgX3@lPQocT4QJpioP+al z0WQKNxC~d|DqMr>Pz*QVCftJCa0l+fJ-81K;2}JM$M6K6!ZUadFW@D-g4gf{-oiV0 z4I-k?bDR>IM$KJlc zb$1juo70mYFGnn zVI8c84X_b5!DiS31yBe@uobq!cGv+sVHfO%J+K${!G1UZ2jLJLh9htkj=^y_0Vm-U zoQ5-S7S6$WxBwU75?qEWa22k>?;3^X-2Nuqg4=Kh?!rB|4-eoWJc7sY1fIe(cn&Y% zCA@;y@CM$(J9rNt;3H_x^BY4G(9|@H;LqwBE%Df2t8M(P=lyB;xpN^M=D~be01F`l z7Qtf3ge9;PvLG9BAQ$pr87zlc3Py}0H8*GOi zuoHH{ZrB5RVIS;=18@)y!C^Q8N8uP8hZArTPQht7183nJoQDf=5iY@HxB^$<8eE5B zxB)le7TktAa2M{ueRu#5;SoHBCr|^mqnc0)YC|2U3-zErGyq*_2zsCojlcjJLlZCr zBWMcEpgH_yp2iNh?V&d~fFtyQzTgD?z#0D5e9j-ohUOqA^m|^xGF;cpE%--|5e?Nw z{|Vs`0g(^|(J%^PU^I+@u@DR6U_4BKIEaS?NQ8-y1e3u1YM`=iRgxCj#Hj@nCQ^dU zXLUvEG>u;Ji01zYq&R&$s$FrbYL6Vc>zbz&jPWp0`wV!U?mDXMS)F=aE>^2s4U`HC z{iKyvUs-b4R)U(hk#PU!(y7FIX43}p(W$GPZ`4RmuP-6*%(t;y!D>G1xrs-(f8v|R zMb^F_D)s}c<$Qi4>3zSR3{Gk+27Tgr`=fST$+-*XTo}#Qd!+HOhFjU-k*;*mF_hFk zEyU|%RY{%NMVe;Rkn@JScc|3%K67@0F*lvIltDPOw;i_fA_()Z$6>D7IVT$(aU z%zF)&rs*TZt#ORxJ{&F1S4PRK+rwqej|fQ!iID(rGav>#JZe_*D;d5jEpV$8VJN$c>WmK#@t{N--%Zw4zf-y36y%FDXZ^HGm zD{}U>N3>_fE;=&q6lv#wrV%rm^IQ`Lw(ZxKLKeMKiHY55^ZB{t*C>(PW^bXJBkIw! zfdi>Y%~mvoZ!4{Li&UG~%j)n1f9d$xOC}ESmG@48vN_FH7PcKBcT)$8yzrJHZ#U^= zI7l(}22J-124rwx`?UxTD>-=XsQ zet$`icM@&uUShSpm-IW@Uy95{%6w`gKh68lvR-AWt7&^mXrxW)!&fS;HtW@h8?kCu zOGi~T)?MZm`$(L#o6MfvUp&lxsy2)lR+`hDlk!2&vr8 zOX|O}mSMhKB;s~^aV_B>hv$39rPBT6TYOKM66-8s)ji~Td>?7DvYTugYbjfjqUBhA zv;=$|C7~5Y$@v#i68tSnbl*kDx%Uw=;A^PdycQ~Hqk^S|cd)G58zc_%f}~-iVKVAu zpsao8A-BWbB|6eYZq;{@MICJ9Y@&rME2<|>NhY$qN=Yenc+HPe^11wu4cxBBDL!d@ zoHx5^akW+sy!KUDZru)-dxa1@fBHglg?mG;XXf)d}rG zgJMS0yf=}w{f94AwjD_UH>|nR%o}8~EQ|Ep%%Y#Xavy4-83a6FUxCJyJ#XWR3RiYBb3AITfLuH$!y z3fM93JufJKlWXeNm#y!$Wz_~#Sr*hmnl`YJ18us?Wp8gWx#1#Xw1jhU|mCMJ6mG1UDq)fJNH$2+dWa~@9(O^RR^dQ zw=GopZ`ahSR&|%-4`3l6?7$ z@f1FExC<}znZjRfdvHMerQG`H6<&FtX~Ro%x-zjhxpx~v9Y!XQxp8T(yml4E@0-9S zPg?PwK0A1)Rw_4fdd8dI=}1eR&*~}W;N^HG(c(!Z>3w*B8kSxE+&9F z2RFOFJ&c}#YrbmdIw2VQWvnGANcl~=w4WnK5KQuXp?wqLcDN6g;N zC2*`5M;l1D%Aa|KM}5(IVjw=}ZDh2qkCZyzRV+?7k%)o&K z`z3ID)0$$`x~hzs)h%j63UWw*sc zeh^wkJcCYfcY}HS>iaT|jy0Fd4XnhYLO#CK`!AUU;bj7(Y*DJxfp$>HHK5>zYp*LT|2gJUIUR*alJ z6fG6(|NMKd(c{r_xlF8lb~WTOq3`Ho%~Mol^O&3-?x6PjDsZ*y4LPf86Tazh&vBKp zUX?{ERks*NKW+#ekPn#KY)4lj=Brr^E-Q7mIZgNKLniC$P(5qx`-ktZ?uP;;?1ZmW zb?}p&orj8xZGd$3aF_Ydy=AW1VA&qvBH!kAl*oAwQg4W(j5*z1rhVI`7EjQlmbG2z z-KL@9G;V}63mhWjR}7GHd!41dX)kGE-cxdJ_Yv)m?Ih}lNa3tiDmbeGt&X>&O;^HH zgOk28x46FqMZ3xFy1r7>*Fy~M`OA{tF|w*CT5`um%8rBxnYC|(Xw8q1?I8fwqpp-~DMt-?k++ptp+Lk?q66}{zK?Z7Y2jgk=-dXg(brYS5^`P0$7m;b* z3zS#aOnlb0l`hWCGNHbQjJkuivnD{+UH6orl@W5uCrpl>@sI=N4zhh!2SG_ey416g zE9U)V^#Dt$o!dvQb@q_JJZJg5q^I=Mw~}-9qh&$aQ8FMlT4t4rmPZmM+BT8$5ZaoC z$=c^Z(s*gG^v(&E61UJcZ+XbsIe~J(ZYsnZM=G3TKbuoryWM)$Ua^9oBU3tvi}xeEOUrs9WSx(l+v6RZ_WW_ z#_-QOiTv}kH8)GD#NVdJ)3`_bDU&zSmAvtEcB7Exwl?H(is>xY7ueoqBz-&LNjnbC zCvD5e)cLb1|9BV7N5^T)=BveAIdc`4+0a<79=^`(!yk$d5fCTLd5)~0HkDQ|A zfnlU)X|T4w_f-kitH+otl{ z!jW=#Zm=}FJ50_U@Ry^@Jtd3L|8%gG!*N|@f3+^+MqOl`MHksw!s=Ih4gBOJ-4?s5 z7}p1?MVaU7P@S=A)jN!(+xSWaHZE4<$8}M4t&K=)(==uB;fMONBZ)S(|3THln6(^V z(#Mra6lbpZ*vcu~vZ+6RsB6Rn8)dS*wBamENAmUSOxcAARG2=5rj1)g&tpq-jXu^K zwlj|NLuPZwB|G^>pC_z|bv3c=e#b$-;@X7SF27>lBU&zUc2?hC{etGc-!boW+rGcz zT}|AoiDNbKtme6D^}qBXn!ZHSzi9fJVP4VyT2%Wh*M=25r|1~HcH`=&Q2$e!eiP@T z%geInvJdJBe_Tgl5$bP?VF_sF>t?}UtI28Bd+Ldw(+ljt9(scVID+Oi`hpYm183+D z17IMyfGZ4w!7v2ez#Tlm6THA1hJp|Hf*<%p00hD?7!E-&0)im~MnWirK{!M}Bt$_p zjDi>#4P#&|#KJfj4-+5`;voSNVIm~KB$x^*Fb$@|444VCAQfiA97uz?kPh=;J}iKR zkO7NeF=WCLSPD6i3wf{%*24za2%BItY=HtOgd*4q+h9BFfSs@lcEcX{XWi^?8=t0) znoD))3>NTvy!}7xXaB69{co?IO+YQ|Z>^#IZ>pbZ*75sW*XCM>I+7=%LvL_!oq!zhS>(J%(a!hfb_HVMz049PGB zra}r#gXu5>X2L8;h1oC%(qJy6!+cl(3n2skSrhyF*TlZzef9 znZAXFnqHu~muB&|JrlX2dp{0$$!8bGul&>I4O{t5;K@$6NNWl4)$S|#&DR6m>+M#4 zdgT^R-daj-Rcj{U^BPLVIYXIUv7YQ`eURrC7w~oWd}f_HeErd6-gM|P`>$vymXjMw z{P&P%JFwv@$PZ+ zschRhlx$U>XWckVzWR@-CLFJ_FA(ZHHF%U1 z7KBTn(Fl1vCPe0#21?_=D2baACOh>arOJm<;;B7GYNJlH2Rg#k4QJNA{!0Y=hl;Lcyh2EU)r3;6)T4FQimw1dnQaCp`LfEVU(2m z8Y4qpN6V*t9ZqdJk2v~1bqQ$BIqy60o~Hx&y?cM&aIra0n;yp>t1ae{-@;_T%4li1 zBSJoXkCN=1(J~=wv?Ns+D-Qd{%JnTfDQnYkntv*Zwix~--NoB!w_6@vt=XE|4ys7I zVlJ!awJXr^sF$i!?{}(7i?_<8?RJ%St}=Bv+n(}Dm87ek+R&>bdNi(sHkrR`N`1m3?M!#+vbLXS4YiZ?qdUv(i`6A^&R{86*he1tSjgmW-KFhuJGo@#FZFNx z(~i|{^kU-x`kd)X5!Q~huWkTsIn;<&w79IYG4}o8EJs?jx(A&uZ$)?A22ihReaX<% zf!6gB+JLS57Vc6s_NSsMMIC5NsG^)X<;i(yS^AWEOFe)6L+z-pL-jgqlhw{PbTX?A zE$Zb-)hxYfNS74ydznI+Pv+AsT1a(&t|3lYPgbTSIJQkWZepUx@pJS!#n_*Re3-%; zQjYVGw<~!4z3-gkQeILzw~*MSP37U>x>E0HJ(<1SO~yvp%lQO%i3qnB;UgrXrZK%a(43xEF(Ze=Ox@Bv#N z_ll-)^CVhbq7NA+RpG=Ld#P%dx@;R?M4#e)xX37v+s>QLb#60niK-+QLP|=F>Dzh! zz`L9kQA>t()0MubtIHAJYO>h`^{`1S`zDE0t=m^x+qlcmS3~4V)j%ngf!goh5ZO^2 zBJBr6%D4OB;+7gN(j!s=+D6LW+Y$1je5j2794<>AhRT;`p)$`PRKBepDW7VMkgVZ8 zVsg_<#+M6{XL{Ds@0gSHjYV;-&{CG&Y$oM&4aHT;irH9gxxD8Xr_{W`%NOME`le|d zINP6}st~q%{EP-o(&bt^t1&k`h;^p(D5zj6r5u<`3Cp(9(E44-XJ!ey^Q8(I)U+Xw zQcWpwg$dd3U!p?8D$DHrc491@#cqwr*-jlr(`S}3x036IHd4={oitjf3Bs+=!hQhHxJ#Q_D| zIBa1am)FhVoVXm0b{)w}%cQVvdwiEwtIe%~Jyf}RZB#^mf2E80p#^alRiEp%Xzmmb zD&Hkbm3%x$l{a9DUvEHbbsnlxC!E#tsk2qJt;wpLYC^UB*HL!&8MJ!+cr|C<9Cfe3 z9(5@8EWHf-XrRZtTg{|Fk#nf>_C-{GLRE^lZ%$o|F$Xs6g^DN|LF=9e($4-Tl+TSMwd~L% zrL8xEBq#`Tnx6dn&I&fYsGK`Zqj7yQscg=Dm1ksD87{#|{FXWn~C!np3 zmMf9ba=|uS=C>a!P3jd=t*>8c?({@j(%PSNDio1L#ccXwcTsirEkkQNU>$V-3baaZ zm#V({mCC>INj-j4nVv5Ep{7kXrJx(_$Tq@^>?1l;8XMB;m1d+JT9qm9v_FWk&U*_#r-2zgBIsOFW~h zn>M7hN4@EwaX&hiz_b#_c-bBH)HBMC#ssyc0#^&N(y^fK54vFOAw?z4%;}UU9;dZS;n*@IW%k!qEDKKa+q81B@M~Q;F{G}%_iHAfR+z|vxz?hW z+(C}`_m+Jt?WNvJH?f=LCh3j*q9uZA^V(TQf*3aUkA8u^4_d0)UzJ=>-`Np;H zmX{qBD$CtP)g&!eSGu{>6#s@EGVo?!dBEKyZaT??I0uQ+bCX7ELgbaVzqFheD5+&f z%DyrYVvjK^6*1n!N-tEpe;X;D_?wy^3X+{Tem2B8%Wli=5>)CY=T+B{(d&%mb?Xsa z_e?rZh-k=(x1Lk*f^C#tW&zo3??I!^RHWtWO{w*j#p;Ngh2)yHm!_#ze)Tb%cXg7r zN4rVOm>!6gE#+CflJvo5GX7&zamsBeK@U4hjh>eDrm-XCg>$&F-zjm91^I0*%Qadx z=978Rl-;T-yZ3OR3l*nOyj~N|$=XX3eH!xf>CITX^LpC7=7O5Fr7msVet>c}C()8t zChFjblYF#aNg2H@kB8sgj<_Y4_gBm1+f`C{{Oe%u>s*7?ZfDXh@2NELtR{Yay}S0W z*!BJThOCKei!bYQVPWTA{e$Md-*N5X+ZMlKT1{-KiB&Z*tLC}db~?YFtLalT{fws1 z2_Nb;GBU`^!(LO6`YZokOz%RuwM%y?RJ;Doys_SxPd^lOC|}U*apDhuxzEXP+}7-M zG6&M&ukCsAyZ)7l=l!mMY4$kzy}yZOZ#S#Elg7{`1j`1TtHs- z5?qEW@OuxGmj8GC*x&2w{Izw!|7@?5Kjuj_d!GE>@5BW;PIvGCPw{N77t3a(Fu6qp7xU?!x(Y|!krvJzIoYS8SVuonK9 ztNpY6S2S}UG&$Sta0q_y$8r?ckHK;H&&-Xui054b%^od(%=!MceD9y-bu~F#O}_Rq zJORy^cg=Wr&G>fB*!EBG8NR?*_?^r9f$Kk^1ja>|gi=r%%0O8t2j!sxXhB7&1eKu* z{C9GJe{DU$zg!E@60c(g-N71cz!rKyPv`}9U=O`v5Bwg7-UWFl1p-~68(4xBbO&p& zfj`Snjlg3eFcLx`48kD_q9G0DLORTY`LF;MLI!B|+*u5numqMu7UaM)cn&Y%CA@;y z@bB%>^AY!dg3s^;zQQ;74nN>0{6}je{%;sFZk}$hM$TTYO5Md8M*}O+gPNZ7Bw-jW z4K6{83;a~GO0B50^+Z)>S-5JgQ-j=1lBq|-6_lRwlF|p1VNdIRG-YrnDm^4kHC`U9 zdiStb_Up_^>)k!t;yy@)RmfD+t(GhE?+ew2Uad)ccTeiFYZ0ZqK1(?nwK?y~ASxSI zo8BdzR6p_zc+j#rw6WlmnqO?MyqZR-7XqFFl|vADgN|4}TSDF<;eO z7N-Kdz0~-Z-KcEy)6_q}TjeHZs8Zirap$8Q>Cw58+-{;bof>qLzIgf3>xReF?dG{E zcUosPag~qCHJhyNukTMAbt=#zk3!WS)8D={n?nyRTT`bIhtxTn{_5nHw(9AuD0Q`P zp8C>pqIznv3-3h-I_j~AnjYM(t|m?=pBvL?$&9^N=e`jqMD8X1Vb!=yfh&8iZpz+z zUi>`hJb!!qgv%!`V8K2c?+vG^?#m)nd3&q@>2O+Izn-slt{Sg)Xcth=ms_Z4*km%Z zxJt*Ho}}U}$LYx}R!tAAP`jcHsQ$(<)xz*7IryEY(S54%g}5JN(%+QdkL=4u_v86p zjUK#TE##R7o}5&AF*_Sx<-zUdbMMNj9GE(hv+WajVTZ|FVrCTI&vIrN-J6feH`W?> zjSZ{X^QdWE_|{Tg?xb^)uO3>;Eq1NsMfKCU(<>)Ff5(N*^fvHiisD?Ku57q4nZAZZ zaHmciId|bBRqucq-F|vbUHIg$I(h}D`strl%#c_z={20rW`9ynZTqVBmMxXfX?Im^ zb1AZs?P~kcu2i<~UV7n|Mtx74DvhI7t<=NiOO)-11huvR>q>XBR=eU?sMg=ca)y^L zU-`I+!;enpmPeMb!R6&#>E{$0+h99gTKR%reqKb`AD7YSie0f@PZ}*x+(=dYu)XAd zJ-YaPwmMW+k8G0yDQtIH>eRTH%GRDsR|myYk4c}@5a+LI@;OKHdw)hP{=hVU_D-^I zcaJ*1_)fiU52NeJmFb?>PPKRO88yweSlzJfrg|C2s!8Y1sg85^s_!)yst2a7s(Rzq zSVv))>T$NW@;*65&G5)qkG?-qj`=Iq$Ws$l_?-sSX2~QvyxWg=ZF1)BXSMnBle>Jf zp&Q2?uEJIFR&l=v1JsmGzN+H+>FUAf&Z_^z*2=Z;wCdh;2wfj%MIlGGsq?$+8GByv zqBifT{oOJA_Sz^8>GD!-nHEeRUOfBtepahFQq6AER`s#>p~7wZ$THK48#)_v)D9=Q zwDpF{;S;oOYO+cw5kl=>=1|YeUSt(>nx2oiKmpszQLBqxX?xkGJat10wr*CP$w-eA z=NzNxoc6TMGD*3lol&hbTT$xMEtH+A&mRw`a8$|nJnW{f47^@n0(EN2KJ91h+pvhW zih8LZ-e%O{Qzq@RT|=2kQPiosHjS?{M=fE@9cgZ_I$i9m+^f!2mZJ-m+3rJXY`{_F zigiU#AD#HC9TXR5@cVsJxj09#e#KBW%-zh^6PNSl>=mrPwU9@*Pv+3DNo*1s$zx}Q z@q~AZi|^~QSy)frKXnLqdR~_soj*^5&y-=Cd+m7fxP{cdK`EYO)tW=CUz5vqKVF6N z)(w~XGaH+-zIQdwu5gx~HCj(&9aHGVS8IwKInp=G!z*mWe-N?$jL9WOFJCoh{P=$p zuR8wUc-05-;Xf*7t&Nzo4%7vG_{+5*|61JnXR+pA#*>=((G>>4U>E{!@Ru>A7jFMC zuJprwzhg^HT=|#rWDIVPhA}V}V&RW*WjyXnfJB%GNiYfiEZ&@s$9~70vvB=)+&LfD z|DLhupT(Hf5zEzpnotXBLmj9K^`Jg909|MZdY})DzyKOU6EFlLXbR1sIT*tq#~}>C zeSaKd@Q;c$t0At_hW~2J`CpA6eefE-;0OK?0D&+JhQnXRmp^g41Y)m}Pzp*z87K?o zzzo_$CoqT3U;)45Qo?nH|7v`ynOpep#ibFrKN5b&r=xH^21dge7z?p54#vX-h=X`Y zfE1VkGhr5_!fcoWe`~Cpjeo0&cXJ^RmcerP&&0of8Q+$uiuW1*-f`@IrmpK(>#N%P zbdI_*vkr~hHifcX<0;Bqi|xwTaE<*(s8JPD^2K*!)d^-aZ$x`~;Psq-_{8z|`Ez-- zD{3=?hH+TVO8V-zlP-V1s9qVISD_)rYR1OXbo^&3PhL1wUAK2u_Yiv=nrW;i=>(`f zcM8;vm>AU~B}+ND?^MQ93)SriEh;YfLT}#9;|C3vsIzTavv2k+`f~9K?fx=^5@&By zsWt~x(dR)lFQ)`md^$sAUv`knVT~l9OKqt=-C9mut0&Vocb5IZ4l-`c0Esbjmgt{N z#bB&Phj)+#8TxY6>?_w=Q9-U774WAL z3wV2{mOQoRaSp#+jI^e^LWme z7SxwuZ&Ml5P$V@boAiml zY#MREHX|P5F^e`ox~)2F&r~Om z(>3-g-a3P93#L=zI8%PxqaD9-7@_FGTUG3os;Xw0sG{*%NCgXJ6rKYEoJUc#6Orm z$JkI5Zr>%HhHJ3Ft%gB=&nA=P-YcTMTJR9CDXY-HCmIlTCZlXQ9DCtg$hc}Vzur>1 zc`M0nu^sEhmJ_W5ySSgvJ$|?UJv*zGGQ5S6>>lOKaR+Wv=VqJuNAY9!uib;pvbItD zva;feTAyc;lkCa1l{Ec9a=h3R^VRg^-V!IF?(5ibTT}iSzex>vkV2v9O=;?+ZL~3F zG9SKwj_Z~#=5*V+JoRCB*4z4=N;PXsuUAwer$rfRV9BP`Y9rQXE!jqOFS~(_y`%W? zW@BD@FPZgMKjxj~@;RzrD(h-rwxPW;lCQ&{mwi7BjUG2{5}&Q2`0g0NQNme6*TeP zG?)&5Yn=Bxhxuo5T|R#H3RnrN;2Hc`p7W3KT`9zOrJ)Rzg>q0HDu5PLgi25usz6n! z2HKzl)u9H|gj!G=>Oftn2lb%==t4u#1AS-&2GAIqfFT$`Q)mXw!5B=S1+)ZHXa%jI z4YY-JU19XH=U=E$Z0=j?#0tSJu&4*?Je!(ccB!3YS35Eu!e5C-88 z0g(^|(J%^PU^I+@u@DR6U_4BKIEaS?NQ8-y1e0JgB*PS#3MnuRro#-F39}#-X2Tpv zgSn6n^I$$KfQ66&i(oNi!V*{tS&$7mkPCUR43K3vR<5xC{5-K0JVj@CY8m6L<>G;5od2m+%T+!y9-D@8CUr zfRFGAKEoII3g6&6{D7ZO0_)Y3gi=r%%0O8t2j!sxXhB7&1eKu*RE27w4LVRAYCuh> z1+}3L)P;Ib9~yuzGz2}+helukjiCt`f)O-@X3!jr!30`>A=aodf~L?6nu9TzKnrLI zrqBvnLmOxd?Z6D$LkH*xoxmJAg9UT}1q2KNU7;ITf)#WJYp?-Z=m9;U7ubP4^aclT zgg($0oS+{#Lw^_m1HlDcVGs<4A>an?-~pcC1>P_ee83m{z#jr25Qf2U2!at13?VQQ zIt^=~=6*2aM-6syo8)u6{7@kK^*GKC=A^J{)PybcFVid2JgQ!D0~bv1%vKpu6dD&# zUy}`a@|yy7Z56979O#6--M^_7nTI&_;c3ovIl?0kh4Q%(`*|}B;EgH!>61xYu6ZPx zyCh@GRoq)X**uMp9o)?g{7MOO_Uvgg1^dzNRBKCbP&X!zqCIadu}9Mj6&V_=T4(6c z?uWY10}mM&P59CWY%R{x%Hz5#ydNT&nPA1>RQW5Un{BQ z?j#5M43deZddeZ6UZT~oJ&h?|sw{iisYRtXt1_=z(i696>TxiQY8qW5uc(&1pz;Me ztkaFEKJ=n7)7DY#?<+}bR9#MqX~>f{c&WWla@3RJlDuPXJ6>`iiqp&IlG9^n`e1TP zMR;shu}`L}o#XSB=j~23=*TXz%Xgtl9~#TV^UbB7d0h#Z(Ma~@H&iFVI$~Db zP>wawk=)f)<$+cSxgK(l*E#Oz8+WRTo3(+w9%LZt-9PY)4bQlI#se<6Qd5RSG?9Te z#?r(06ULEi$^Di``PI)GoH4b&1Y}i}Dj$1E%e{RBXV;>yGgzXZJBZO|M+tB>kh}T~ zWOkoq4lj=9Q%4qX-=kZ&#if0`VEzLBHgO&AdbEOW_SW>2>D_Pk&g%tGhImw#|(smg{rHs1Brk&59b2sm(*S&rze=J1Z%DOBo$k zbmrwpH@ zC#|nGkj1Nd%iDVW#K_EDl9vsY`fj(lM)R*6w%Sk@bk-Mcl*4ZginvmX^W3DzA$H%< zTYi+#m#*Eva;q?~-@&GPKH zR*SO+PE$*zmGa(+TrS-7>gYznR}Wj{UUlk>N5 zw_6K%&7x(hQ``V5dS8u~IpbH_{)ATCYDG)mgsaldS5)M3d&M2J=i)akJiF>? zJ|4J=$LTHRrtNQG-2QfUi9baZGqiYh%p1Doah9}i@1e}TYiQEvOzLR7i5B!-PV1X2 zC(i{B>EX6*biULrn&Q2k%t~a?T-}9K@A3@lBkQTY{#WW-bbzd;6;st8+o-K^9`)ko z^yBCv8an6a^__iJ}hCy%={$3B~$joL|vjVkb7U45?nyeXe9Uxja0vEar=qhcGRt@IaO%d zhg7FT?l|6`*WC5wVW;DGYS+Hpy(p5a7P+y7XClA#N#KO4eYt6Edv4#(965(>-0`qG zON&W--NS;NxEpt_HkkDe1o6ru^a-~t`9M@p&U@UR$7u2zQMzpStQxmUtjdvbmH61{ zO1$c-2|qY%#HPE@j=ef^QSGv+JeW_tkIbaD)8c9BizIrGy@XOj(kW>8WQ3zqZ^r4+LRj>S7 zy=ihBd$?AoPfk}<+>CO++LNYT6+M|k`+sE6mQypRu)`oy=c4J(?&;L~dk765noPI- zXVUP9yXeS}tX1;Ouj%U*>t$->xsEWY|!AS_ATM)1wc2 zpQyx?`^wuVn8E_bP?=%&RI-9TwJ7^iRcZcEy)LIi)0$Y2^~GRPCF7_~;6U2jB$CdR z^`!EqmQ*3V5lzfu>bbTB>1FHF3cCWOnru@ivTmtTtKX_66ZEOd+s0I}PcI6{??<1; z%%F!@@4mci0u9NSOjS-N{QCUbH4CAGS5nA6IhXEyTtFRT5~+QqrkuClmn)9e>b9CeQ*!ZEmBFmju-t5Ra-G}myzSFtjczw=Hbl|$HI&sA{SfA}n zIsQ8SFx9YnPZvjhp<0GlXi|>`Z26;*>OB5Nwmp{-J>Nk*avv?!&Z9$lOX+-OCS7z` zO_L#x|iKEHT103 z0vhokgZAZYrNIGH>G8@8dJ>mPMVDq#WK25E_>R4ln@=P6xHLMPK9BlXZ=#kHGpT;c zlV9yYb8MNLbfS&%{eQj3n)a-DP0g`4ZGQ#I_iXU%eb&6+n&VQ_2Wa|(t@@>Y^$nWO zL-RRnKJS^&SE`#8=l}XVG@py6O={YvrcG$t#t={cp)V{jT@@vCj9m$*mPzK6EIVcYmKnp5DC8!Kl zpej@YZP0=0Py=d0EvOB3pf1#d`p^J$p&{sjJ~RRYXberj5R9NHG=t_~3?|S5T7oIG zg4WOm+Cn=pgZ9t?IzlHfht6ODT|fZ=gFsj429{t2-N71cz!rKyPv`}9U=O{)0UV(Z z^aUsA2hPwR2EagY0aq9VgJB4`fjfABCwPH33#6tok!bC`dNiZ3bVG2xz6qp9nVFt{ES&#~| zVGg9hTu6s`Fdr7cLdbwcuoyC72`q&y$c7xqg*;dW%OM|Dz)DyJt6>eSg>|qVHo!*M z1e;+C6hI*q!B*G?+hGUngk7*3_P}1)2m9dw9E3w~7>>YEI0nbz1e}CZa2n3QSvUvh z;R0NQOK=&kz*V>g*P$40z)iRXx8V-lg?n%x9>7C*1drhfJcVcQ9A3ancm=QF4ZMYS z@E$(ENB9Jv;R}3)Z}1&{z)$#R{^tMx`J2397RoxWJYTwK$_cZlQ&5N}-N=8ZHciV@ z-AhkbSvCRGI$ED+P3_7jlqp+oSVv8p9;Ihp4Jp=q2sNmeKqr5^qB(s%c*p~DHk@S1 z5$z68(%!|CRot2O&d{cy+WpnT+Zk&3s&KV7XR}Id^jbA6+|O-49psFA=lJ`Tr#Oc$ zBj0Ks5-a@QK4cuLd9 zyn5bgE_i-}D=ZD<`TwWAJCEwIZU4oeXp)pjC?!HNm1I26<1h~m(m1AnJ%v03l@5Hb#RTTBjYB9iPwAP zh}GK+v4&Tjo;tY5pm}|y;fD|OvfCs2>>f)u+w7rkF5hvV;WOnQd_!%{zNK~(4e8FU z{iOEe3BAw@k}sl{io-VTMD_cR#mzlqL5Q{j~2w8f}ZZM>|3v(roYdbZ}lCtv^yq(|hOB z*z3h4y>cn5<#*~=UxiCdDrkz|7YbWZN;~RJp@`0&)T~=CYU>+H^PBc22Pa(DzYL=z z=#%F+A&i1gtR&fMIn}Fhq7Unx>1ebwJ&6gU3&o%0lG&=%YfcyXvZMnw7&V>31Ef05oCpTlULu5qzAveY3Hor6j+IMp`ER$^F3?I>^X=M^F7f=a5kmC zolox*H28>@CcAD^#XHK?_}!*T@}62wDFbSA0|#v$)l-XiKG5SYUcYGJA2ql`LmiIK z!D0lHuXH3%g~zV0q(_G3^xEb!MC z1zjR__RFow#g?_X=wU5ZGt}kLp*Jb_>3!-LdYeu?x<(@7EP0Pkr84x$b^3XO23*F2@1cwSn`w4bG!1gxPX-ZtN&UiFDrp@{ zLT;j^97Ao4wo+ryom9F_h3;IbNdw=TQRo?C^15eAOElGK#ekM%GPoK=O;sVMO-(2^ z$eUhkdDD-Op|ofJa#|D~NgI7f(9<*n3T;=PhVS|*!>+uO-;Ru@4HHAitVt*8lF*vk zm#WeGQKd4W+7=3&5KT8vj-ba2EQrs4mJweoWa4r&>XbH=;`}1%eOweR>9>l$c#45Iu{H#(S+BOi7sl9$@(Qc*-*y1CkoCI&gu%)P70{P8L( z@OnbUoo-R#`_t4XFQ3lmWmS#e>v2i6&McCG;|@{cujADH8g?wK@R1|UL~&ymnpN=6KYUgOhLo)=+ThR zqmq>Pu68D%agW3ksUvTE)qpZ7u9X~Ld+136=a^JwPsyN?2PGHEu`BqvrfQBVnG6V;Fa`^7 z9DZMe|JARKPmW1VGb?EkakSgtUbkPxb^GsY_P@7=`0uS7{#Rdb|94(vD{FRtUqk;_ zuATSd`;@h=|GrNC_jU3-TqpheI{Dw%$^TyG@c-|14mLTfMO?iU(ey#Q=rlWBT(?UX zQQi89pKIzs^c2Gu4nR#XOpY=+EVn&4Bil^6Cc9huNzWhM zrH^SxS^tld(xg_3ywd-;v>VY|*4o!eCgir46$|5J)Z@dl-R8%#)!uB`CEiEQ4h@zy z`&<(z&K?$Lo?42E#a+baO99kg^$#+fWQ~16T2krK2K2J7JGJ+$Lx*=Zq^oOe>1Mbi z`BjF{+finu)-Q-MyE)LADW){>+P{N|e04DJ92DrO0=+sBXefdG2RhqDB^Uv7|`4 zIyRx>F{&K5{uZqtP(lrU{G?DVHC}m3i$6`(<2>hDtP`fsy}s7uLhG-z@2w^;45%Py zR}J>FHRO{|8gS6|25kPRCfn(jQX4CEHoNtMMsHH%Ravz;UDn}y7xdV;R(1ZAS%<$h z(&vm}s+^~9$PrF8d9KGR`tkWb{c3xLg18zT3PH&l%H+XYXyzDl?k1dwd%k5B7BAu5|@P~4D>RJ$^P+Ac~XVYG=x+)SYTxo1gl^8tFD9YsgaMbf6? z#ngBEQtD)^#?!)Uu>CT1R%@-n`^@yXNn?G!*wBFApH{hOZ$YMg3S zhi__Wv30BpuS!$nvOG;roM^z#e#X4RtQPk))8{em8gNo^ZC2@~#U_Pn+$CCrr{Q~o z8fx?L@%kK7YQS!Lyt%K1CvUN`tka#pwi7(8oH%cOTfX1X zl9#_0?DG+y-Ohy{MtJhQ?cRKSZfAC`=)`en2Cz?idw$x+olW|CalyuBY^&d#6Ki&7 ztq=BmNY{%Gj`8Gx@IhR0kobDO1^caT&XxgfctAB%4tdgqUFutL-K~Atr$!gkBiac-QOz7BwDj- z{2JsK@=w{ zCWE0bsQuwADs1tbp8CI|n@Nw!EbJRaPya%XFPGD#x!QaO|HfI`8tkrFjYmIH;|Z+C zmd=K(QR5qR?DvB@-cjQKQG+ipDWkF#PwCmqQc5r{Bz=|l6z}(f`mg;+{VIP_=^x){ zKdzbg+NpAk&qwMWYsmibIvn~@gFiL?Kx=#cq7_s?N*F4nv$`BHMG?s*k@}T5GId+x9T2{?bC6mAV@VNZd1?hi$UFpNqrFQkSzv{zdgZDx@LO19R z0wfSH^n%{d2l_%k=nn&6AlQKu3KljxCy(jfPe0@K}LjokiAvg?2;3nLH+i(Z&!aY#l$-fVOuOHMCeElip zLLNK=OZ13p4N9-5w$KjRgB4gq2e5&T@Vk#xXZ&{;=my|J(=Qch9MR^gVy2chpU|1xo+_yKoP(;dgJSmUz#}5?aHb`w5ld zo>Dpd?Yq!>ur~cL9D$>741T}goQnTG3+LcWmrinK^V4EN+)~kc_*S{#&IQpZAVQw< zT`fa8o)i1upnv6@yQG@wM`nKBbhKVesxv{4Qhn3q#3oH?jrL~p%A6(gm#-F+Tic6S z-4BTGv+jttz50s4Df5N%-7Kly`LWy_7%u0PpOjgXYDvF_W29!^5Sh{?O{%@RAqVBo z63N@m<>kc*;(m)hqL)K8+EH7VR=v0@MY}BNmKQG7IvkQ?y}rq1aay##u|NGXa->V? zn`!;r#gypiLax)>Q@^vtGHmH|@_xLG=H)M>d|E@*>Mx;P12SK9ln z8wI#J(5NR5sppYzG&IM7!mb(7opm);3 zz7r}*fubPCO=L{`CgLWHlg)GI%Cnt*2xq(YV#kj4(y&#!Y!QOzdM|3A_wN}|I)0S6 zea))Mf&g35Uv;Ty=&)0S2DTUFAL7Nslzt+wUjm&yA4cD`W9jXuWNMM&O-)SZkZg^$ z^OLqpkHlh`?R8PkC|)J~21!}Fy^-`9(OnLBn>yW}zAHy)*;I;Oi+>15xkw&Z`cqci!n%1;OV-nxD4R5? zD{KF{B8s|Oi$^NGh4Y?gqD{a(L8V*7B#Vn;&iVTyvShA!cEC%VTD(%+t?ML=i^hu4 zdkzV=6A5B&_99W(a=&m$FBWgKmPqfi#&S=x9%U4`(mU+{(l)3??S^~PlPmc&xmqHX zO-b7v8pd0LDz=`TB<@RFVMZVJyc?;M#TZp;HlsT6+2M&`_P5sBE#_`}p4at-=mtv)teTFyHyhW3vZ*1Mg=ls2xSqVlA8 zniDO0gk2NUW3Gx#hRem2eW^kt+ftnRrB43a18IAULh0S54>fHaPQF<&G|ei7imoTn zB=xoIq_IedwnD05TrYnEcOnr$b~zF7MRn%D8M9>E4JQ zjPsODFIT6W`Z4lwbyXQXYNISPFO#85tf+jfCnfY4O-(MhrT2NRRQchq{CrcFYHkdd zbG9bQjQjoNI`u7L-3c|>zs)Z(2x}%E4e}BXb*2cnj}7H@l?7t|@^G;}u9F;ly|>)- z-Bax7I!FBRiRI{7+r-KjzOwNsUr~H%tLUyDFZLG3iMA%gWt+VYvY^mPzU=)#4C~bp z>l^0_)7VsDWI9;*X$6YD^BiP$tq^hMYmBJ#sH>c9a7f%K$`%doPm&X>Pmns7dWz+{ z!$d=k0MUBXNin3cmMoreTeQ{bB*R|}69r4LWX;iFIey*@lH zc#iVBUbRJ?)d@O77w8IqRm1kcpY?>_wX9Od{<(hrbIt0GKl1=j@B(j8>eyl63&UXq z_`yi{N9)^(_`83uai`$-q42M+b^ofS)k9rb2lSyX)B^*k4~EbH8bTv50%K?lCSVFp zzzmu~Gcbqd&;nY5E4aZB7z%%{#{E~-uNJ5gTfzTs9s6IcN9W6!6|TW`$buX2f2wxQ$Ip5WFQ5Qk!aq_^E4B3RTDix6)XTl_ z>%Xcd{&UYQRrGJI4mCgx)IkHZ;LmmMpZl%;qqXm!`;98SMwJ?O1M1no?VB0*cWT_< z^=#)_L;3j3L2NmpEBDRo! ztPj`JAI7=4KD>UK6LUdFo>f?%YrpNp)4O30@Wmyv^QDF4q@hmw0b6CzgxRuf;w9mK zHbQ(d-XrIaSs};i)|7Yc%w+DE1To>;E%8=f6|r4k^?xVn+v~>^I)&%Zv5&{FE;gP&KsMw<0Z=z3_h1l$+K3`oT(dV z+O1rgWARaL@6(_5zOj)<-)aeQ;9x>__v{9b^BARqm4;Dm1yaMnNpVvq;BA6(c1g2 z>{T2o+eI45y56zk_+)i?v{4ti<9&s6+0a9}9%k9>k_O3;T-5)?LT|w{@#;gSjCUy% z-*t{l)uXOrU%0>MtT|0M&BXQMvkBtmM+(nS`md-p&*0y57S6$WxBwR+9WFrzT!w$9CjIk0+rL+L7UJi>f+Bbgzw6Myy{D_( z&;8rlvk$)37y3be7ytvo4(!1J9AOYR!C-I(7jOkP7y?7V9X!AjyucfLU>Nwqa2Nr8 zFcL&C#=&@)025&nOokAc0#jicOotgT6K26|m;--6D9nX z?1Wvg8}`6n*a!O|9ugoC4!}V;1c%`WBtbG9g=26WPCyEz!bwPjQ*av2z*#s4=ivfe zgmkzB8E_dg;R;-ZYj7R1;0D};TW}lhz+Jcp*>E3n-~l{@NAMV)z*ESDJa`8A@El%1 z0lb7lcm+l98s5NLD28|N9zMWFD1lG#8A_oH%Ha!qg>O&+mGB*Yz)$!EDtP`-4OF2z z)BrV52My2!EvO0FPz!XRHt2#L)B$~{3-!PN>VqLPfQHZrjKCNgg9(^I6EK6O& zIkbS5U;(Yb5?VtWXbbJ2Jy?M?bO0OZ2)57(Izt!e3f-VP2#`R)&;xoxFX#<@pfB`; z{xARrf*sg{131DUaDu_$3@+dbZZHIff;)JCCwPH3_`opmh2by){9q)E0)H3{0Wbyv zAqawDER2Kkkb`F&58xp@g2(U#ogP9T;;w93p?8b6Z;GJs>}tH+GK2bei6P^p&$KXCn{DU4C${M$ zO*;G`ZCj)XyUpn$$*_ZHv?xLhcKRe1y*MD|&YmTHPDgKv#X)lCazpuM_Ehm)eTZ1s zuB%w5A1P9v_ZF=KeEEWkGe2tX$|2qSSo2svyc^-ojSKs6Fnaeqa<$`}IfJ`}N@>i@w}Xy{&8! zdQ>F5v=hNb2|~3&H<>tdrgXY`9A%04U0w|AHOZzhUe zvwUQyaYmffs5L*)F=wqXQ#SH8uVLW2_8zS5NYhYjXwX|-5on;j<} zHDsTCKuZ@reh|)!v4i3@#1!hJUgPNeAb~*cpYCyFSq2hblU&9tKA1jTL`E}h!Pi-_=Ew6bG83f*cgCqH{D zpWU4$3|6{`W><1WdfpK+>1QoDb94-~s7R!kfIBpH+gX~i?HtYe`hv^t3bW&~L3xUdbIh0KmtM-+n|8{f z@hjxHLHp$M)Hqp~dR%%8xFqWjeJbr&f0M&H9+oSyf9a^c8uYBwS&8l`a$4$c=`kx! znlC#h2i44#S6obKbh#lt-l0v|nq6uBC39+Q*NE5=!v1|@<;KRAGVPX+bTn!%PgRzS&mBsH_J?1h<*unx|Mmp=bI3;7 zbHWxmY2!-S#chNvZRsTK%{$1rGaY50#|F};9emNfICE9!3aOD~LSoEt@>G<#Fgjjq(rW+3_8>`IvjgDCNaJN3_F zdUU!exu#i@|M-41=35UMmS;^jem0`qHZ3W&gBE%3uSv#Jb!pIQU8=paDRtUvLn-~H=$#uwO6BE(J?tr$utp?ENxNWuvU#GhB{& z7$aAYSs*K1*2>+DVx)ilWwNL1Jn0{{THgA+Ti%-#Cu6ZEwDepnMtF%OJ8@5s=mf6V#^%_fqo>D$=){{n0vc-Yi+hU1>x@=OYCzlrA7sWR(i?)Ye ziUt>TWsP&IW&0jmWV55ot1_o#?-Ke}pKlW(4fCf+v%T&zcF-#MC~2)+^J2N2HF%z! zqB2tcSZOQMbgksr!7XLvy?Sz&hpzm2!cb-p@|UrJmU8gJ>awJ5x$p^ZEbsTWlb&OT zO104=rB;%ybnk8{*L=7loZYHRs{xr}vg!xXb?mg@a zTFUgb-K6{HCh}frL%DakxxC%rlNd0)G4@2w7xSMS6(_%?2&;>(^7gXc(tPm(=`=G; z4qUuie)%y@F7Ng~$E>!?a#?Nl0%>Z39!ppD$${@z%YMU0(bTcc>DLW&+Hj`{nSZh% zz0^@O)_o2I*4scUX04~0pO;Z@TOS(e*PfnZeRsk}2WmzQN%zS+8T016JkB*JW`r5# z_3lL1M^?zd9$#e5(nb`t^||h!>5yp?&c%zx!Ppv=pnw}w^Yp=3ZA zd($JPa^}R|QW*>7*ei2EIp#{%l`JTk(Au&`Jf50YHBQQSDS1&ct7KOb`#&jTr{r46 z_eCfZ!q2=kn>d&J*XZ}~;1N(c=82>x(KmFfw@9D3eN&fHLC;CV3_4L6tZC~gI z{b2wM1Us+?2XKTz-~@xg8C<{>++YX{1$XcOPw)b7@PT3A3&UXq_`ygR1^zG^0$>aT zLJ$PQSQrQ6VFFBqNiZ2gU`PtM8Il@gf*}h)VUL^uEk;Sd~#Baj5ia1@TgaX0}fkP0Uu4Nk#nI0I+l9Gr&>a1qks5@f(-$b>6! z6|TW`$buVi6K=t6xC3|L9%RFP$bkp&5FWu}cmhu$7xLg4 zrPhUG^3E-5GMUkvsvq*FULSPjqsH6h8trbfVB0164n2L^#df8L1u?>C&`{Ce@vB%- zbW(U;4;8F&g_^3=;LzoGPFk8t9*Os8)Q=2`>v{(D>3b@k`;xwV-bXg^Pw1)ne%fA| zP6ZrG-WLkVZTEh^_uo8-5~cSTR@Fu5+X zop`(K1C{J3r-mQYct(dGRJu=vCni-;V3P`p9`cczU9QGusx|mxj3&?hSc5%IVK47G z8l3m4CO=bEpL1WzONZ;Ce^4Huc;%&(sF{5a{Xmlf7413r^MtZu*2|=}JyIMoK)@U!) zofb>oP47|LX`g9QqY`qGg;eyjgr?uCq+gr!sb|B3lyc96hCEy$vUX3DPu^M!J-=~s zgV8flxBfdBUE)lxZ;EL5_e<15`z`gTtttJM4A-0mnv@WrWfj`DaYwFmGrz$;n%Lx z)q+&IleLrj^-m_<`pNXn>^!waFP_KdS+vMIi>w!&q}>CO=y_Z=Ess1)QF`a;^~nRY zrCB14*^xjCzMQA-$q%UOlRVn8?lJY5{h7A6d`q2gKc>LoVyYkijWUgX(xo{ShA#}feKXO3Uy=%9ph`7&W)}R{CN&HGV(^a{JffnbD z(&TkhHTjiIElya5`%s5!bGI#@=uR6oZd+ZO?K@RtZ6g)NvpTMPRzibyzEHF5ujD^N zg`-+&aKtBkZ>wrt>*!~ivHmkfU(x1e#cG_KQ$~x|RA+PT+U#qf%l>b5d8=-1b`MIT zURyKBb@g#Fo|H+Se6wllg6otWolY*Zu2bLfhsZY}nIa}<(6h*Fsy+BBeRa+tpPUrB zu>UMAu6Y_gvG-6$_F;N57X6jRUM45Ai*&Er2Xga;Iv?cK-guI$r(e{nsWm1>dGR6S+kaX(PxVNum+0C1Bd6N&4>KW3EjT>p- z{T*cfVry0Al}*00 z8aJc!)pY2!tqS#Dpia#;`jTy8Q`#K$RhG`FlTM#KDvRH?b}F|yt$*XDX|sOB!W)a%``MGFugW>aAB$Y{xYEVSIybpMFAD?;j>B_v=+-Hs?(~ zWj>6gx3iPcALuCUP>Ui_^oa)KzNKo|18T@ARd)2%#y!L`(zf|QMO(j<#)B{PF7_wY zIbKO^Olt7(fSUX{>j%v$E2HQ4N~qlC1=T7jp}57L$#~-@TK2wzrs|cES&dSv?)sLN z4Jo1FmtIhhk@-}+&3kHS{hU-=ej(MGc{I%B3aQ4X)AnA;)G;WP>dGVv`EiDFiZZES zemYrP%B0*W_o!9(n^bx3HNBggL(?;hY3sFjbXa_%PI#~K;oxlQv+5PCsqu(p%5%!- z^NbQd;+(WCi+0XFi~ehgq;~ir`8&R#(l+^38BjjQ^xB51JS)e#U%x-9=AAO%EHbP~ z)uvI^aaNAEGVhi7ubc;zdHG0paMgGy8BoSvb(0&_sK26WER2eDsxO3?}E@xRr5v}UnQdx`VOTFlIKfqFQxTp zld3E#nN)JFCdyEiPh=9>d*7H>z3G_`+})0e&zNMu9(!h5#4?fe-}2Fc!wac$feaVG>M+ z5SRi}VH!+_888!O!EBfVe?TbAg?TU^7QjMS1dCw_EQMvT9Kv7)tb|n%4iT^#B4G`z zg>?`G>meF8z(&{vn_&xVg&2s1Z4d|BVF&DlU9cPWz+Tt~`yn0@AQ2A0K{y15;Rqx_ zG8~0ta2!rR3Z%kGNP|;w8qUC3I0xt90$hZ2xC9w+88YDtT!m|J9kSpC+=N?j8}7he zxChyAA9COUJcLK^7@ojW$b~$32Kn$DUO)l7ghF@)MerKlz*{JWckmuQz(**7Pw*K^ zp$y953w(udPyv3kv(?reHW8~y;^a;$kB=wh$l#Be1%e8rfWT0D5SrKzo z8pR!#onvfd{Hau#v`xrxiz71rV@LTtHck#P>L$17CySAuljYU%H-upuf7$fa6RCc< zKo*-zVRx;Ai2PxUo;z)*sUFr?Ok6;2_T%Y@hBtjxZANce&Y*4+ov3bh11dJKr8ie} zDHhi*JGGk8y|II6vDRejGV*|Yr`3p7IC;?!&tMwoY)*%LlBC@UmLuEuk`L-$6qT)S zi&y=8L_afs5sXYR&bLZNK-C15y&?hM-GwTc^g99HBurnr-OSqrSArElxHa z+fUj&KPqgRdx~e*FN$HR2jspUy`*vdX%t-3oUT4;Nk!G$)BePta`c*7)N_?NZ5#Af z9=fB$54-F0x|3RLKfD@OW~%eOyw6l8?jEV&S$qA%^?1bf27IkoBX&xu$u3=M^4{P| zvblclAi3@s(4AbYk8#H;it2%F6Qi=BqOX-+J8*XjQ{L`=t53S#qwYBZ}g`PdfEnPzobY{`I+p%QHD{0B~ z=``_;2Q}C}l!lxfNHT03cb|4rnj9Yfu^ z? zVwzmPKI+tqpnnIRorbtHDz{tMbG4TAX8~ z#UsYl<#W$;I4DPlZL!DE>urYo@&S7FtkhugtI530ru?f=)oR&1Nm@jS8n^J6Z;J@XPuws9CjSt*t)Kyr992{eDqedIL5L*Qy#b)oR~K z__gHAzI8cow;l)lYQ|=PTj)~7bjc#0>@7c#&Wt>&f8{G}8K}y-Bel3@Q9axf(c#orhTI_w|E}zs{A+|d zCzxySXWUEa`Nwy1@y(}!T`Oro|3cc+=q(MO`-&VBzELL~RrWM0r|)^c=<>jCq_?($ zdRCOs>aXbalc>YnjT*4&3-s@K@R44;dPzzKl+Sry(xNKQ%CQdHZ(B9*l=;@Hqdi{^ zb*?(j%JEj_y)yrm^MEoh?L&K2jfau}W$X{;_F#=O?W)E?Irhq2P>#8hbtMZ*CgyhV z|(Vk)x}|PRX^B@4kzCc$TAIRd$r~g>v3d&L2wtm3i> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/textures/deepmind.png b/rofunc/utils/robolab/formatter/mjcf_parser/test_assets/textures/deepmind.png new file mode 100644 index 0000000000000000000000000000000000000000..1586759c0c0deeee5bb45b548884f590643f8842 GIT binary patch literal 2976 zcmV;R3t#k!P)00009a7bBm000XU z000XU0RWnu7ytkO2XskIMF-&p3jrZ4v8Z{$000X=Nkl4586+Y*_W!{^8 z@g67MoqZvILKadWp@BdNh^9m!C~Z+uBU(XeC4^d93ALnBH`)jlA*!Mvpfn1oBrPEg zi<6K*tak#Tfz65mG!>B z1k4uzA}~Y(AOf$ItMyt|m0JS!PfA{ZQ++T&KrnofB1Y*H;Eh3Y3cxA%mCO_ z>#T4Kxx>g6Kv!7ZzOS{yZP~fG>QrCi-P1wcB!+-6V*t`OA%F_Eux75!C9zx-%W2U5 zi{TZ2I#uQrc5bfvcX#}a|N1q9(w;Em!Vr2Q+IwGw`(ygd0N8Q3=g~dQ3ku|y@2YAG zD7zbj93p(lVwm*zrpW*Ll9P^{B!oS*ySbqwqUf~i!CCsRxvko?g=cuOKNVBV z^_8|MuE6$xv^8`@OoCr*oLlXdUOhfY2ng3s5TH4re%c;4DSrSD?QVX*DZn9Cd!)yf z6`mbPwhk-TQv1v6&>7N>btm!zu;WPI;jS2msGGEPk=JSA-a0Xi*IxZg(ln%;>`Ube z;GZp_myh=`1Oh;WAFeJv&>RV;jM>v41P;#*DP3W0ascgN@V2%Ar2G@}^4l0=e{Pt+S zq7#m?xoVFE09ySD;&lWdrkH0&VHg1rSIxaG;n9i`L5)|6t7bwsuBQb6j^P)6MY&|v zBLMcdg}WlkSg)s2yU-uiroem}ICOp#m- z#tqdV3y(Yiyn8Mna%}v+syfLW2b7cc_bza)uCV1C5OHylWo4Osx<7S#AQ?y)LY}LE zKrI1nagoT9nt668nIX?21e1nK=5onlPp&G=UHi0?9BL0g_hIX@5^38~_YGxMGtW%J z5L<#O0I*=n=!wB73_^A%OY z3XfOjaxZs6DTAH!Cs~&G+!9E|RbyGHm9jYU(h{pAOp9kMF0yS|REP{)hm*Iw@}F=@ z+p^F(KB8okxMs4pP}VxDBdoNC)Jm^t&7$RkB5C@m>A9~|kU@yh7f~vIbu^OFzrNVX za?5#|39K)sXB*5j{Oz&6V!Pmx`HUtwH-F#FGz(UrLj(X0F{T*z?>cQ2*!n74E(mm! zSTLn$8!9k-?_3~|(l^g{YvUL-0u)&J=>rfL&T)$AgpCMCE(TsW&|2dW3vK+Q{;U|p zRDGghvcP`X(6hWuuJKt$hiU>~GsJ8-h7R${L~sK4;(@kLT7#SF9FyiyMJG0CpxA#g z+!xcft?=>e>J|91_$G%x-G32*R+h?>CO9VYlV~y!*IxXryUZ!vJlAH7x}PyajYY$x zsB$%9KhhpL(HpJviIxe~6FFpFX%bTt7`}7Hzx&+qw&lJ;JD*k?0SLgK(5DYTHK;eL zjQ{+{`4XeF zz8C<2GDlV$u?mbWFSbH%)5tUY!k^su##xDH&#o_7QY^!!ks6MbVeV)vEbnq-e6L1Xp2n^z}qJW54Hp+ zh%&=TEu7K|tz1SjMg%^YV;-3+wF`L!X@sb1eB<4wr}nkoTyA@2U9rStTR_QI`?pRF zJh7)~;)Z23r6)AQCbEoOeG88^kujNPiwoqu3L*qBOnR$vaM>#-8#=hIJrqs;}J&MDi1C3Dn{PE$TRGXsN4Q_e$8vAUux)zC^@x{ zIz!5xe?Ily_s-`yWvW5x{lD>2>lH`ZDyz!ur4BKWe^yGj;5)<0j)v|RKkd4s+P!tL zZ&kU&De*GT1P;?ZCDkzFs@WM%y>hH)*NFj%Pj6x7Xt79{JfOhJrMogC?)$S_%bwiV zF7Z<&I0A<}hle`CpSA@#WL}wbT6l?P0s|sQ=*Dnd8;Gk&U=_JMw$?e61x7@s32bae zE_bH404@R8Q01(2S^DGC%B&nB$1x%ZrSxD@PjAE$LHZ#u26-L}u!)>3u#`?F5gWB; zh*0Gg#`|<`W5lWg2TcElE&z!q+!yc0?TERcV%IIw5AmB`T|ho5WTX{ z9~;x&w25pB6fAi(N!d3>PHQ19GU>3nu|sWGb|sjkGasovKa z(h@4A+b8pV;#^k-&X&1gdwyNnhDw(*OPiC1Nl&kxD+}ycR{{`-U{RrT(;PW78_0H- zT@Tc3u5+8$d>stKTwUSbzPkKacQUD)rb*>);pQyb!^EdmUjJJ4-F2Siwe^QNZs~)^ zmj#l>dA|aP3yY*Xs%#UmZZ>ht>Gk`nzrU&&;2Omxj^V2hEcD7kLwnpXX-T1Fb-6ro zcFpO`+=15cqkEc(fMJ^5zzC}$p!C(q%at!iDC8(EboomfJ8tBMM4CY#etX5Hdhfmq zk%5@;)mnSGbMi_n*F%5)g#PgE3yp(`5wDn00Hz5xfxY(Nf~`x7j&>$`qT1c{4qI-G z`#g?aY9{Ty5Pa^V_JM?EVK`F&G?Qw)@;loWubksJ)DbVX^L0K;?xbugCwE`?q;uEF zp}1zySf%m>Km;6v+p9f$9$6~z*cI01xrBU`nc~softa?xCA90*;GvGNz%dJhyZ~qh z>6&r>(xPY9mangJPsi`4d-%IIs=j=*_pfLCNzE`!GHDV3X^dm*3ENSrXRR) zrjFk?4=2wJCRzfiuCOu?QwL&dPectSH6SRm3soLzj#I4h%1cXZYvwtf7JjB8@Bab5 W53`zqw>t&^0000>> import pytorch_kinematics as pk + >>> data = ''' + ... + ... + ... + ... + ... + ... + ... ''' + >>> chain = pk.build_chain_from_urdf(data) + >>> print(chain) + link1_frame + link2_frame + + """ + robot = URDF.from_xml_string(data.encode("utf-8")) + lmap = robot.link_map + joints = robot.joints + n_joints = len(joints) + has_root = [True for _ in range(len(joints))] + for i in range(n_joints): + for j in range(i + 1, n_joints): + if joints[i].parent == joints[j].child: + has_root[i] = False + elif joints[j].parent == joints[i].child: + has_root[j] = False + for i in range(n_joints): + if has_root[i]: + root_link = lmap[joints[i].parent] + break + root_frame = frame.Frame(root_link.name) + root_frame.joint = frame.Joint() + root_frame.link = frame.Link(root_link.name, _convert_transform(root_link.origin), + [_convert_visual(root_link.visual)]) + root_frame.children = _build_chain_recurse(root_frame, lmap, joints) + return chain.Chain(root_frame) + + +def build_serial_chain_from_urdf(data, end_link_name, root_link_name=""): + """ + Build a SerialChain object from urdf data. + + Parameters + ---------- + data : str + URDF string data. + end_link_name : str + The name of the link that is the end effector. + root_link_name : str, optional + The name of the root link. + + Returns + ------- + chain.SerialChain + SerialChain object created from URDF. + """ + urdf_chain = build_chain_from_urdf(data) + return chain.SerialChain(urdf_chain, end_link_name, + "" if root_link_name == "" else root_link_name) diff --git a/rofunc/utils/robolab/formatter/urdf_parser/__init__.py b/rofunc/utils/robolab/formatter/urdf_parser/__init__.py new file mode 100644 index 000000000..c3ed66a75 --- /dev/null +++ b/rofunc/utils/robolab/formatter/urdf_parser/__init__.py @@ -0,0 +1 @@ +from . import sdf, urdf diff --git a/rofunc/utils/robolab/formatter/urdf_parser/sdf.py b/rofunc/utils/robolab/formatter/urdf_parser/sdf.py new file mode 100644 index 000000000..c44d9cd39 --- /dev/null +++ b/rofunc/utils/robolab/formatter/urdf_parser/sdf.py @@ -0,0 +1,310 @@ +from . import xml_reflection as xmlr +from .xml_reflection.basics import * + +# What is the scope of plugins? Model, World, Sensor? + +xmlr.start_namespace("sdf") + + +name_attribute = xmlr.Attribute("name", str, False) +pose_element = xmlr.Element("pose", "vector6", False) + + +class Inertia(xmlr.Object): + KEYS = ["ixx", "ixy", "ixz", "iyy", "iyz", "izz"] + + def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0): + self.ixx = ixx + self.ixy = ixy + self.ixz = ixz + self.iyy = iyy + self.iyz = iyz + self.izz = izz + + def to_matrix(self): + return [[self.ixx, self.ixy, self.ixz], [self.ixy, self.iyy, self.iyz], [self.ixz, self.iyz, self.izz]] + + +xmlr.reflect(Inertia, params=[xmlr.Element(key, float) for key in Inertia.KEYS]) + +# Pretty much copy-paste... Better method? +# Use multiple inheritance to separate the objects out so they are unique? + + +class Inertial(xmlr.Object): + def __init__(self, mass=0.0, inertia=None, pose=None): + self.mass = mass + self.inertia = inertia + self.pose = pose + + +xmlr.reflect(Inertial, params=[xmlr.Element("mass", float), xmlr.Element("inertia", Inertia), pose_element]) + + +class Box(xmlr.Object): + def __init__(self, size=None): + self.size = size + + +xmlr.reflect(Box, tag="box", params=[xmlr.Element("size", "vector3")]) + + +class Cylinder(xmlr.Object): + def __init__(self, radius=0.0, length=0.0): + self.radius = radius + self.length = length + + +xmlr.reflect(Cylinder, tag="cylinder", params=[xmlr.Element("radius", float), xmlr.Element("length", float)]) + + +class Sphere(xmlr.Object): + def __init__(self, radius=0.0): + self.radius = radius + + +xmlr.reflect(Sphere, tag="sphere", params=[xmlr.Element("radius", float)]) + + +class Mesh(xmlr.Object): + def __init__(self, filename=None, scale=None): + self.filename = filename + self.scale = scale + + +xmlr.reflect( + Mesh, tag="mesh", params=[xmlr.Element("filename", str), xmlr.Element("scale", "vector3", required=False)] +) + + +class GeometricType(xmlr.ValueType): + def __init__(self): + self.factory = xmlr.FactoryType( + "geometric", {"box": Box, "cylinder": Cylinder, "sphere": Sphere, "mesh": Mesh} + ) + + def from_xml(self, node, path): + children = xml_children(node) + assert len(children) == 1, "One element only for geometric" + return self.factory.from_xml(children[0], path=path) + + def write_xml(self, node, obj): + name = self.factory.get_name(obj) + child = node_add(node, name) + obj.write_xml(child) + + +xmlr.add_type("geometric", GeometricType()) + + +class Script(xmlr.Object): + def __init__(self, uri=None, name=None): + self.uri = uri + self.name = name + + +xmlr.reflect(Script, tag="script", params=[xmlr.Element("name", str, False), xmlr.Element("uri", str, False)]) + + +class Material(xmlr.Object): + def __init__(self, name=None, script=None): + self.name = name + self.script = script + + +xmlr.reflect(Material, tag="material", params=[name_attribute, xmlr.Element("script", Script, False)]) + + +class Visual(xmlr.Object): + def __init__(self, name=None, geometry=None, pose=None): + self.name = name + self.geometry = geometry + self.pose = pose + + +xmlr.reflect( + Visual, + tag="visual", + params=[ + name_attribute, + xmlr.Element("geometry", "geometric"), + xmlr.Element("material", Material, False), + pose_element, + ], +) + + +class Collision(xmlr.Object): + def __init__(self, name=None, geometry=None, pose=None): + self.name = name + self.geometry = geometry + self.pose = pose + + +xmlr.reflect(Collision, tag="collision", params=[name_attribute, xmlr.Element("geometry", "geometric"), pose_element]) + + +class Dynamics(xmlr.Object): + def __init__(self, damping=None, friction=None): + self.damping = damping + self.friction = friction + + +xmlr.reflect( + Dynamics, tag="dynamics", params=[xmlr.Element("damping", float, False), xmlr.Element("friction", float, False)] +) + + +class Limit(xmlr.Object): + def __init__(self, lower=None, upper=None): + self.lower = lower + self.upper = upper + + +xmlr.reflect(Limit, tag="limit", params=[xmlr.Element("lower", float, False), xmlr.Element("upper", float, False)]) + + +class Axis(xmlr.Object): + def __init__(self, xyz=None, limit=None, dynamics=None, use_parent_model_frame=None): + self.xyz = xyz + self.limit = limit + self.dynamics = dynamics + self.use_parent_model_frame = use_parent_model_frame + + +xmlr.reflect( + Axis, + tag="axis", + params=[ + xmlr.Element("xyz", "vector3"), + xmlr.Element("limit", Limit, False), + xmlr.Element("dynamics", Dynamics, False), + xmlr.Element("use_parent_model_frame", bool, False), + ], +) + + +class Joint(xmlr.Object): + TYPES = ["unknown", "revolute", "gearbox", "revolute2", "prismatic", "ball", "screw", "universal", "fixed"] + + def __init__(self, name=None, parent=None, child=None, joint_type=None, axis=None, pose=None): + self.aggregate_init() + self.name = name + self.parent = parent + self.child = child + self.type = joint_type + self.axis = axis + self.pose = pose + + # Aliases + @property + def joint_type(self): + return self.type + + @joint_type.setter + def joint_type(self, value): + self.type = value + + +xmlr.reflect( + Joint, + tag="joint", + params=[ + name_attribute, + xmlr.Attribute("type", str, False), + xmlr.Element("axis", Axis), + xmlr.Element("parent", str), + xmlr.Element("child", str), + pose_element, + ], +) + + +class Link(xmlr.Object): + def __init__(self, name=None, pose=None, inertial=None, kinematic=False): + self.aggregate_init() + self.name = name + self.pose = pose + self.inertial = inertial + self.kinematic = kinematic + self.visuals = [] + self.collisions = [] + + +xmlr.reflect( + Link, + tag="link", + params=[ + name_attribute, + xmlr.Element("inertial", Inertial), + xmlr.Attribute("kinematic", bool, False), + xmlr.AggregateElement("visual", Visual, var="visuals"), + xmlr.AggregateElement("collision", Collision, var="collisions"), + pose_element, + ], +) + + +class Model(xmlr.Object): + def __init__(self, name=None, pose=None): + self.aggregate_init() + self.name = name + self.pose = pose + self.links = [] + self.joints = [] + self.joint_map = {} + self.link_map = {} + + self.parent_map = {} + self.child_map = {} + + def add_aggregate(self, typeName, elem): + xmlr.Object.add_aggregate(self, typeName, elem) + + if typeName == "joint": + joint = elem + self.joint_map[joint.name] = joint + self.parent_map[joint.child] = (joint.name, joint.parent) + if joint.parent in self.child_map: + self.child_map[joint.parent].append((joint.name, joint.child)) + else: + self.child_map[joint.parent] = [(joint.name, joint.child)] + elif typeName == "link": + link = elem + self.link_map[link.name] = link + + def add_link(self, link): + self.add_aggregate("link", link) + + def add_joint(self, joint): + self.add_aggregate("joint", joint) + + +xmlr.reflect( + Model, + tag="model", + params=[ + name_attribute, + xmlr.AggregateElement("link", Link, var="links"), + xmlr.AggregateElement("joint", Joint, var="joints"), + pose_element, + ], +) + + +class SDF(xmlr.Object): + def __init__(self, version=None): + self.version = version + + +xmlr.reflect( + SDF, + tag="sdf", + params=[ + xmlr.Attribute("version", str, False), + xmlr.Element("model", Model, False), + ], +) + + +xmlr.end_namespace() diff --git a/rofunc/utils/robolab/formatter/urdf_parser/urdf.py b/rofunc/utils/robolab/formatter/urdf_parser/urdf.py new file mode 100644 index 000000000..a3af5d6cf --- /dev/null +++ b/rofunc/utils/robolab/formatter/urdf_parser/urdf.py @@ -0,0 +1,592 @@ +from . import xml_reflection as xmlr +from .xml_reflection.basics import * + +# Add a 'namespace' for names to avoid a conflict between URDF and SDF? +# A type registry? How to scope that? Just make a 'global' type pointer? +# Or just qualify names? urdf.geometric, sdf.geometric + +xmlr.start_namespace("urdf") + +xmlr.add_type("element_link", xmlr.SimpleElementType("link", str)) +xmlr.add_type("element_xyz", xmlr.SimpleElementType("xyz", "vector3")) + +verbose = True + + +class Pose(xmlr.Object): + def __init__(self, xyz=None, rpy=None): + self.xyz = xyz + self.rpy = rpy + + def check_valid(self): + assert (self.xyz is None or len(self.xyz) == 3) and (self.rpy is None or len(self.rpy) == 3) + + # Aliases for backwards compatibility + @property + def rotation(self): + return self.rpy + + @rotation.setter + def rotation(self, value): + self.rpy = value + + @property + def position(self): + return self.xyz + + @position.setter + def position(self, value): + self.xyz = value + + +xmlr.reflect( + Pose, + tag="origin", + params=[ + xmlr.Attribute("xyz", "vector3", False, default=[0, 0, 0]), + xmlr.Attribute("rpy", "vector3", False, default=[0, 0, 0]), + ], +) + + +# Common stuff +name_attribute = xmlr.Attribute("name", str) +origin_element = xmlr.Element("origin", Pose, False) + + +class Color(xmlr.Object): + def __init__(self, *args): + # What about named colors? + count = len(args) + if count == 4 or count == 3: + self.rgba = args + elif count == 1: + self.rgba = args[0] + elif count == 0: + self.rgba = None + if self.rgba is not None: + if len(self.rgba) == 3: + self.rgba += [1.0] + if len(self.rgba) != 4: + raise Exception("Invalid color argument count") + + +xmlr.reflect(Color, tag="color", params=[xmlr.Attribute("rgba", "vector4")]) + + +class JointDynamics(xmlr.Object): + def __init__(self, damping=None, friction=None): + self.damping = damping + self.friction = friction + + +xmlr.reflect( + JointDynamics, + tag="dynamics", + params=[xmlr.Attribute("damping", float, False), xmlr.Attribute("friction", float, False)], +) + + +class Box(xmlr.Object): + def __init__(self, size=None): + self.size = size + + +xmlr.reflect(Box, tag="box", params=[xmlr.Attribute("size", "vector3")]) + + +class Cylinder(xmlr.Object): + def __init__(self, radius=0.0, length=0.0): + self.radius = radius + self.length = length + + +xmlr.reflect(Cylinder, tag="cylinder", params=[xmlr.Attribute("radius", float), xmlr.Attribute("length", float)]) + + +class Sphere(xmlr.Object): + def __init__(self, radius=0.0): + self.radius = radius + + +xmlr.reflect(Sphere, tag="sphere", params=[xmlr.Attribute("radius", float)]) + + +class Mesh(xmlr.Object): + def __init__(self, filename=None, scale=None): + self.filename = filename + self.scale = scale + + +xmlr.reflect( + Mesh, tag="mesh", params=[xmlr.Attribute("filename", str), xmlr.Attribute("scale", "vector3", required=False)] +) + + +class GeometricType(xmlr.ValueType): + def __init__(self): + self.factory = xmlr.FactoryType( + "geometric", {"box": Box, "cylinder": Cylinder, "sphere": Sphere, "mesh": Mesh} + ) + + def from_xml(self, node, path): + children = xml_children(node) + assert len(children) == 1, "One element only for geometric" + return self.factory.from_xml(children[0], path=path) + + def write_xml(self, node, obj): + name = self.factory.get_name(obj) + child = node_add(node, name) + obj.write_xml(child) + + +xmlr.add_type("geometric", GeometricType()) + + +class Collision(xmlr.Object): + def __init__(self, geometry=None, origin=None): + self.geometry = geometry + self.origin = origin + + +xmlr.reflect(Collision, tag="collision", params=[origin_element, xmlr.Element("geometry", "geometric")]) + + +class Texture(xmlr.Object): + def __init__(self, filename=None): + self.filename = filename + + +xmlr.reflect(Texture, tag="texture", params=[xmlr.Attribute("filename", str)]) + + +class Material(xmlr.Object): + def __init__(self, name=None, color=None, texture=None): + self.name = name + self.color = color + self.texture = texture + + def check_valid(self): + if self.color is None and self.texture is None: + xmlr.on_error("Material has neither a color nor texture.") + + +xmlr.reflect( + Material, + tag="material", + params=[name_attribute, xmlr.Element("color", Color, False), xmlr.Element("texture", Texture, False)], +) + + +class LinkMaterial(Material): + def check_valid(self): + pass + + +class Visual(xmlr.Object): + def __init__(self, geometry=None, material=None, origin=None): + self.geometry = geometry + self.material = material + self.origin = origin + + +xmlr.reflect( + Visual, + tag="visual", + params=[origin_element, xmlr.Element("geometry", "geometric"), xmlr.Element("material", LinkMaterial, False)], +) + + +class Inertia(xmlr.Object): + KEYS = ["ixx", "ixy", "ixz", "iyy", "iyz", "izz"] + + def __init__(self, ixx=0.0, ixy=0.0, ixz=0.0, iyy=0.0, iyz=0.0, izz=0.0): + self.ixx = ixx + self.ixy = ixy + self.ixz = ixz + self.iyy = iyy + self.iyz = iyz + self.izz = izz + + def to_matrix(self): + return [[self.ixx, self.ixy, self.ixz], [self.ixy, self.iyy, self.iyz], [self.ixz, self.iyz, self.izz]] + + +xmlr.reflect(Inertia, tag="inertia", params=[xmlr.Attribute(key, float) for key in Inertia.KEYS]) + + +class Inertial(xmlr.Object): + def __init__(self, mass=0.0, inertia=None, origin=None): + self.mass = mass + self.inertia = inertia + self.origin = origin + + +xmlr.reflect( + Inertial, + tag="inertial", + params=[origin_element, xmlr.Element("mass", "element_value"), xmlr.Element("inertia", Inertia, False)], +) + + +# FIXME: we are missing the reference position here. +class JointCalibration(xmlr.Object): + def __init__(self, rising=None, falling=None): + self.rising = rising + self.falling = falling + + +xmlr.reflect( + JointCalibration, + tag="calibration", + params=[xmlr.Attribute("rising", float, False, 0), xmlr.Attribute("falling", float, False, 0)], +) + + +class JointLimit(xmlr.Object): + def __init__(self, effort=None, velocity=None, lower=None, upper=None): + self.effort = effort + self.velocity = velocity + self.lower = lower + self.upper = upper + + +xmlr.reflect( + JointLimit, + tag="limit", + params=[ + xmlr.Attribute("effort", float), + xmlr.Attribute("lower", float, False, 0), + xmlr.Attribute("upper", float, False, 0), + xmlr.Attribute("velocity", float), + ], +) + +# FIXME: we are missing __str__ here. + + +class JointMimic(xmlr.Object): + def __init__(self, joint_name=None, multiplier=None, offset=None): + self.joint = joint_name + self.multiplier = multiplier + self.offset = offset + + +xmlr.reflect( + JointMimic, + tag="mimic", + params=[ + xmlr.Attribute("joint", str), + xmlr.Attribute("multiplier", float, False), + xmlr.Attribute("offset", float, False), + ], +) + + +class SafetyController(xmlr.Object): + def __init__(self, velocity=None, position=None, lower=None, upper=None): + self.k_velocity = velocity + self.k_position = position + self.soft_lower_limit = lower + self.soft_upper_limit = upper + + +xmlr.reflect( + SafetyController, + tag="safety_controller", + params=[ + xmlr.Attribute("k_velocity", float), + xmlr.Attribute("k_position", float, False, 0), + xmlr.Attribute("soft_lower_limit", float, False, 0), + xmlr.Attribute("soft_upper_limit", float, False, 0), + ], +) + + +class Joint(xmlr.Object): + TYPES = ["unknown", "revolute", "continuous", "prismatic", "floating", "planar", "fixed"] + + def __init__( + self, + name=None, + parent=None, + child=None, + joint_type=None, + axis=None, + origin=None, + limit=None, + dynamics=None, + safety_controller=None, + calibration=None, + mimic=None, + ): + self.name = name + self.parent = parent + self.child = child + self.type = joint_type + self.axis = axis + self.origin = origin + self.limit = limit + self.dynamics = dynamics + self.safety_controller = safety_controller + self.calibration = calibration + self.mimic = mimic + + def check_valid(self): + assert self.type in self.TYPES, "Invalid joint type: {}".format(self.type) # noqa + + # Aliases + @property + def joint_type(self): + return self.type + + @joint_type.setter + def joint_type(self, value): + self.type = value + + +xmlr.reflect( + Joint, + tag="joint", + params=[ + name_attribute, + xmlr.Attribute("type", str), + origin_element, + xmlr.Element("axis", "element_xyz", False), + xmlr.Element("parent", "element_link"), + xmlr.Element("child", "element_link"), + xmlr.Element("limit", JointLimit, False), + xmlr.Element("dynamics", JointDynamics, False), + xmlr.Element("safety_controller", SafetyController, False), + xmlr.Element("calibration", JointCalibration, False), + xmlr.Element("mimic", JointMimic, False), + ], +) + + +class Link(xmlr.Object): + def __init__(self, name=None, visual=None, inertial=None, collision=None, origin=None): + self.aggregate_init() + self.name = name + self.visuals = [] + self.inertial = inertial + self.collisions = [] + self.origin = origin + + def __get_visual(self): + """Return the first visual or None.""" + if self.visuals: + return self.visuals[0] + + def __set_visual(self, visual): + """Set the first visual.""" + if self.visuals: + self.visuals[0] = visual + else: + self.visuals.append(visual) + + def __get_collision(self): + """Return the first collision or None.""" + if self.collisions: + return self.collisions[0] + + def __set_collision(self, collision): + """Set the first collision.""" + if self.collisions: + self.collisions[0] = collision + else: + self.collisions.append(collision) + + # Properties for backwards compatibility + visual = property(__get_visual, __set_visual) + collision = property(__get_collision, __set_collision) + + +xmlr.reflect( + Link, + tag="link", + params=[ + name_attribute, + origin_element, + xmlr.AggregateElement("visual", Visual), + xmlr.AggregateElement("collision", Collision), + xmlr.Element("inertial", Inertial, False), + ], +) + + +class PR2Transmission(xmlr.Object): + def __init__(self, name=None, joint=None, actuator=None, type=None, mechanicalReduction=1): + self.name = name + self.type = type + self.joint = joint + self.actuator = actuator + self.mechanicalReduction = mechanicalReduction + + +xmlr.reflect( + PR2Transmission, + tag="pr2_transmission", + params=[ + name_attribute, + xmlr.Attribute("type", str), + xmlr.Element("joint", "element_name"), + xmlr.Element("actuator", "element_name"), + xmlr.Element("mechanicalReduction", float), + ], +) + + +class Actuator(xmlr.Object): + def __init__(self, name=None, mechanicalReduction=1): + self.name = name + self.mechanicalReduction = None + + +xmlr.reflect( + Actuator, tag="actuator", params=[name_attribute, xmlr.Element("mechanicalReduction", float, required=False)] +) + + +class TransmissionJoint(xmlr.Object): + def __init__(self, name=None): + self.aggregate_init() + self.name = name + self.hardwareInterfaces = [] + + def check_valid(self): + assert len(self.hardwareInterfaces) > 0, "no hardwareInterface defined" + + +xmlr.reflect( + TransmissionJoint, + tag="joint", + params=[ + name_attribute, + xmlr.AggregateElement("hardwareInterface", str), + ], +) + + +class Transmission(xmlr.Object): + """New format: http://wiki.ros.org/urdf/XML/Transmission""" + + def __init__(self, name=None): + self.aggregate_init() + self.name = name + self.joints = [] + self.actuators = [] + + def check_valid(self): + assert len(self.joints) > 0, "no joint defined" + assert len(self.actuators) > 0, "no actuator defined" + + +xmlr.reflect( + Transmission, + tag="new_transmission", + params=[ + name_attribute, + xmlr.Element("type", str), + xmlr.AggregateElement("joint", TransmissionJoint), + xmlr.AggregateElement("actuator", Actuator), + ], +) + +xmlr.add_type("transmission", xmlr.DuckTypedFactory("transmission", [Transmission, PR2Transmission])) + + +class Robot(xmlr.Object): + def __init__(self, name=None): + self.aggregate_init() + + self.name = name + self.joints = [] + self.links = [] + self.materials = [] + self.gazebos = [] + self.transmissions = [] + + self.joint_map = {} + self.link_map = {} + + self.parent_map = {} + self.child_map = {} + + def add_aggregate(self, typeName, elem): + xmlr.Object.add_aggregate(self, typeName, elem) + + if typeName == "joint": + joint = elem + self.joint_map[joint.name] = joint + self.parent_map[joint.child] = (joint.name, joint.parent) + if joint.parent in self.child_map: + self.child_map[joint.parent].append((joint.name, joint.child)) + else: + self.child_map[joint.parent] = [(joint.name, joint.child)] + elif typeName == "link": + link = elem + self.link_map[link.name] = link + + def add_link(self, link): + self.add_aggregate("link", link) + + def add_joint(self, joint): + self.add_aggregate("joint", joint) + + def get_chain(self, root, tip, joints=True, links=True, fixed=True): + chain = [] + if links: + chain.append(tip) + link = tip + while link != root: + (joint, parent) = self.parent_map[link] + if joints: + if fixed or self.joint_map[joint].joint_type != "fixed": + chain.append(joint) + if links: + chain.append(parent) + link = parent + chain.reverse() + return chain + + def get_root(self): + root = None + for link in self.link_map: + if link not in self.parent_map: + assert root is None, "Multiple roots detected, invalid URDF." + root = link + assert root is not None, "No roots detected, invalid URDF." + return root + + @classmethod + def from_parameter_server(cls, key="robot_description"): + """ + Retrieve the robot model on the parameter server + and parse it to create a URDF robot structure. + + Warning: this requires roscore to be running. + """ + # Could move this into xml_reflection + import rospy + + return cls.from_xml_string(rospy.get_param(key)) + + +xmlr.reflect( + Robot, + tag="robot", + params=[ + xmlr.Attribute("name", str, False), # Is 'name' a required attribute? + xmlr.AggregateElement("link", Link), + xmlr.AggregateElement("joint", Joint), + xmlr.AggregateElement("gazebo", xmlr.RawType()), + xmlr.AggregateElement("transmission", "transmission"), + xmlr.AggregateElement("material", Material), + ], +) + +# Make an alias +URDF = Robot + +xmlr.end_namespace() diff --git a/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/__init__.py b/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/__init__.py new file mode 100644 index 000000000..bb67a43fa --- /dev/null +++ b/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/__init__.py @@ -0,0 +1 @@ +from .core import * diff --git a/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/basics.py b/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/basics.py new file mode 100644 index 000000000..638ad72b0 --- /dev/null +++ b/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/basics.py @@ -0,0 +1,91 @@ +import collections +import string + +import yaml +from lxml import etree + + +def xml_string(rootXml, addHeader=True): + # Meh + xmlString = etree.tostring(rootXml, pretty_print=True, encoding="unicode") + if addHeader: + xmlString = '\n' + xmlString + return xmlString + + +def dict_sub(obj, keys): + return dict((key, obj[key]) for key in keys) + + +def node_add(doc, sub): + if sub is None: + return None + if type(sub) == str: + return etree.SubElement(doc, sub) + elif isinstance(sub, etree._Element): + doc.append(sub) # This screws up the rest of the tree for prettyprint + return sub + else: + raise Exception("Invalid sub value") + + +def pfloat(x): + return str(x).rstrip(".") + + +def xml_children(node): + children = node.getchildren() + + def predicate(node): + return not isinstance(node, etree._Comment) + + return list(filter(predicate, children)) + + +def isstring(obj): + try: + return isinstance(obj, basestring) + except NameError: + return isinstance(obj, str) + + +def to_yaml(obj): + """Simplify yaml representation for pretty printing""" + # Is there a better way to do this by adding a representation with + # yaml.Dumper? + # Ordered dict: http://pyyaml.org/ticket/29#comment:11 + if obj is None or isstring(obj): + out = str(obj) + elif type(obj) in [int, float, bool]: + return obj + elif hasattr(obj, "to_yaml"): + out = obj.to_yaml() + elif isinstance(obj, etree._Element): + out = etree.tostring(obj, pretty_print=True) + elif type(obj) == dict: + out = {} + for (var, value) in obj.items(): + out[str(var)] = to_yaml(value) + elif hasattr(obj, "tolist"): + # For numpy objects + out = to_yaml(obj.tolist()) + elif isinstance(obj, collections.Iterable): + out = [to_yaml(item) for item in obj] + else: + out = str(obj) + return out + + +class SelectiveReflection(object): + def get_refl_vars(self): + return list(vars(self).keys()) + + +class YamlReflection(SelectiveReflection): + def to_yaml(self): + raw = dict((var, getattr(self, var)) for var in self.get_refl_vars()) + return to_yaml(raw) + + def __str__(self): + # Good idea? Will it remove other important things? + return yaml.dump(self.to_yaml()).rstrip() diff --git a/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/core.py b/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/core.py new file mode 100644 index 000000000..2d9c3fe1a --- /dev/null +++ b/rofunc/utils/robolab/formatter/urdf_parser/xml_reflection/core.py @@ -0,0 +1,680 @@ +import copy +import sys + +from .basics import * + +# @todo Get rid of "import *" +# @todo Make this work with decorators + +# Is this reflection or serialization? I think it's serialization... +# Rename? + +# Do parent operations after, to allow child to 'override' parameters? +# Need to make sure that duplicate entires do not get into the 'unset*' lists + + +def reflect(cls, *args, **kwargs): + """ + Simple wrapper to add XML reflection to an xml_reflection.Object class + """ + cls.XML_REFL = Reflection(*args, **kwargs) + + +# Rename 'write_xml' to 'write_xml' to have paired 'load/dump', and make +# 'pre_dump' and 'post_load'? +# When dumping to yaml, include tag name? + +# How to incorporate line number and all that jazz? +def on_error_stderr(message): + """What to do on an error. This can be changed to raise an exception.""" + sys.stderr.write(message + "\n") + + +on_error = on_error_stderr + + +skip_default = False +# defaultIfMatching = True # Not implemeneted yet + +# Registering Types +value_types = {} +value_type_prefix = "" + + +def start_namespace(namespace): + """ + Basic mechanism to prevent conflicts for string types for URDF and SDF + @note Does not handle nesting! + """ + global value_type_prefix + value_type_prefix = namespace + "." + + +def end_namespace(): + global value_type_prefix + value_type_prefix = "" + + +def add_type(key, value): + if isinstance(key, str): + key = value_type_prefix + key + assert key not in value_types + value_types[key] = value + + +def get_type(cur_type): + """Can wrap value types if needed""" + if value_type_prefix and isinstance(cur_type, str): + # See if it exists in current 'namespace' + curKey = value_type_prefix + cur_type + value_type = value_types.get(curKey) + else: + value_type = None + if value_type is None: + # Try again, in 'global' scope + value_type = value_types.get(cur_type) + if value_type is None: + value_type = make_type(cur_type) + add_type(cur_type, value_type) + return value_type + + +def make_type(cur_type): + if isinstance(cur_type, ValueType): + return cur_type + elif isinstance(cur_type, str): + if cur_type.startswith("vector"): + extra = cur_type[6:] + if extra: + count = float(extra) + else: + count = None + return VectorType(count) + else: + raise Exception("Invalid value type: {}".format(cur_type)) + elif cur_type == list: + return ListType() + elif issubclass(cur_type, Object): + return ObjectType(cur_type) + elif cur_type in [str, float, bool]: + return BasicType(cur_type) + else: + raise Exception("Invalid type: {}".format(cur_type)) + + +class Path(object): + def __init__(self, tag, parent=None, suffix="", tree=None): + self.parent = parent + self.tag = tag + self.suffix = suffix + self.tree = tree # For validating general path (getting true XML path) + + def __str__(self): + if self.parent is not None: + return "{}/{}{}".format(self.parent, self.tag, self.suffix) + else: + if self.tag is not None and len(self.tag) > 0: + return "/{}{}".format(self.tag, self.suffix) + else: + return self.suffix + + +class ParseError(Exception): + def __init__(self, e, path): + self.e = e + self.path = path + message = "ParseError in {}:\n{}".format(self.path, self.e) + super(ParseError, self).__init__(message) + + +class ValueType(object): + """Primitive value type""" + + def from_xml(self, node, path): + return self.from_string(node.text) + + def write_xml(self, node, value): + """ + If type has 'write_xml', this function should expect to have it's own + XML already created i.e., In Axis.to_sdf(self, node), 'node' would be + the 'axis' element. + @todo Add function that makes an XML node completely independently? + """ + node.text = self.to_string(value) + + def equals(self, a, b): + return a == b + + +class BasicType(ValueType): + def __init__(self, cur_type): + self.type = cur_type + + def to_string(self, value): + return str(value) + + def from_string(self, value): + return self.type(value) + + +class ListType(ValueType): + def to_string(self, values): + return " ".join(values) + + def from_string(self, text): + return text.split() + + def equals(self, aValues, bValues): + return len(aValues) == len(bValues) and all(a == b for (a, b) in zip(aValues, bValues)) # noqa + + +class VectorType(ListType): + def __init__(self, count=None): + self.count = count + + def check(self, values): + if self.count is not None: + assert len(values) == self.count, "Invalid vector length" + + def to_string(self, values): + self.check(values) + raw = list(map(str, values)) + return ListType.to_string(self, raw) + + def from_string(self, text): + raw = ListType.from_string(self, text) + self.check(raw) + return list(map(float, raw)) + + +class RawType(ValueType): + """ + Simple, raw XML value. Need to bugfix putting this back into a document + """ + + def from_xml(self, node, path): + return node + + def write_xml(self, node, value): + # @todo rying to insert an element at root level seems to screw up + # pretty printing + children = xml_children(value) + list(map(node.append, children)) + # Copy attributes + for (attrib_key, attrib_value) in value.attrib.items(): + node.set(attrib_key, attrib_value) + + +class SimpleElementType(ValueType): + """ + Extractor that retrieves data from an element, given a + specified attribute, casted to value_type. + """ + + def __init__(self, attribute, value_type): + self.attribute = attribute + self.value_type = get_type(value_type) + + def from_xml(self, node, path): + text = node.get(self.attribute) + return self.value_type.from_string(text) + + def write_xml(self, node, value): + text = self.value_type.to_string(value) + node.set(self.attribute, text) + + +class ObjectType(ValueType): + def __init__(self, cur_type): + self.type = cur_type + + def from_xml(self, node, path): + obj = self.type() + obj.read_xml(node, path) + return obj + + def write_xml(self, node, obj): + obj.write_xml(node) + + +class FactoryType(ValueType): + def __init__(self, name, typeMap): + self.name = name + self.typeMap = typeMap + self.nameMap = {} + for (key, value) in typeMap.items(): + # Reverse lookup + self.nameMap[value] = key + + def from_xml(self, node, path): + cur_type = self.typeMap.get(node.tag) + if cur_type is None: + raise Exception("Invalid {} tag: {}".format(self.name, node.tag)) + value_type = get_type(cur_type) + return value_type.from_xml(node, path) + + def get_name(self, obj): + cur_type = type(obj) + name = self.nameMap.get(cur_type) + if name is None: + raise Exception("Invalid {} type: {}".format(self.name, cur_type)) + return name + + def write_xml(self, node, obj): + obj.write_xml(node) + + +class DuckTypedFactory(ValueType): + def __init__(self, name, typeOrder): + self.name = name + assert len(typeOrder) > 0 + self.type_order = typeOrder + + def from_xml(self, node, path): + error_set = [] + for value_type in self.type_order: + try: + return value_type.from_xml(node, path) + except Exception as e: + error_set.append((value_type, e)) + # Should have returned, we encountered errors + out = "Could not perform duck-typed parsing." + for (value_type, e) in error_set: + out += "\nValue Type: {}\nException: {}\n".format(value_type, e) + raise ParseError(Exception(out), path) + + def write_xml(self, node, obj): + obj.write_xml(node) + + +class Param(object): + """Mirroring Gazebo's SDF api + + @param xml_var: Xml name + @todo If the value_type is an object with a tag defined in it's + reflection, allow it to act as the default tag name? + @param var: Python class variable name. By default it's the same as the + XML name + """ + + def __init__(self, xml_var, value_type, required=True, default=None, var=None): + self.xml_var = xml_var + if var is None: + self.var = xml_var + else: + self.var = var + self.type = None + self.value_type = get_type(value_type) + self.default = default + if required: + assert default is None, "Default does not make sense for a required field" # noqa + self.required = required + self.is_aggregate = False + + def set_default(self, obj): + if self.required: + raise Exception("Required {} not set in XML: {}".format(self.type, self.xml_var)) # noqa + elif not skip_default: + setattr(obj, self.var, self.default) + + +class Attribute(Param): + def __init__(self, xml_var, value_type, required=True, default=None, var=None): + Param.__init__(self, xml_var, value_type, required, default, var) + self.type = "attribute" + + def set_from_string(self, obj, value): + """Node is the parent node in this case""" + # Duplicate attributes cannot occur at this point + setattr(obj, self.var, self.value_type.from_string(value)) + + def get_value(self, obj): + return getattr(obj, self.var) + + def add_to_xml(self, obj, node): + value = getattr(obj, self.var) + # Do not set with default value if value is None + if value is None: + if self.required: + raise Exception("Required attribute not set in object: {}".format(self.var)) # noqa + elif not skip_default: + value = self.default + # Allow value type to handle None? + if value is not None: + node.set(self.xml_var, self.value_type.to_string(value)) + + +# Add option if this requires a header? +# Like .... ??? +# Not really... This would be a specific list type, not really aggregate + + +class Element(Param): + def __init__(self, xml_var, value_type, required=True, default=None, var=None, is_raw=False): + Param.__init__(self, xml_var, value_type, required, default, var) + self.type = "element" + self.is_raw = is_raw + + def set_from_xml(self, obj, node, path): + value = self.value_type.from_xml(node, path) + setattr(obj, self.var, value) + + def add_to_xml(self, obj, parent): + value = getattr(obj, self.xml_var) + if value is None: + if self.required: + raise Exception("Required element not defined in object: {}".format(self.var)) # noqa + elif not skip_default: + value = self.default + if value is not None: + self.add_scalar_to_xml(parent, value) + + def add_scalar_to_xml(self, parent, value): + if self.is_raw: + node = parent + else: + node = node_add(parent, self.xml_var) + self.value_type.write_xml(node, value) + + +class AggregateElement(Element): + def __init__(self, xml_var, value_type, var=None, is_raw=False): + if var is None: + var = xml_var + "s" + Element.__init__(self, xml_var, value_type, required=False, var=var, is_raw=is_raw) + self.is_aggregate = True + + def add_from_xml(self, obj, node, path): + value = self.value_type.from_xml(node, path) + obj.add_aggregate(self.xml_var, value) + + def set_default(self, obj): + pass + + +class Info: + """Small container for keeping track of what's been consumed""" + + def __init__(self, node): + self.attributes = list(node.attrib.keys()) + self.children = xml_children(node) + + +class Reflection(object): + def __init__(self, params=[], parent_cls=None, tag=None): + """Construct a XML reflection thing + @param parent_cls: Parent class, to use it's reflection as well. + @param tag: Only necessary if you intend to use Object.write_xml_doc() + This does not override the name supplied in the reflection + definition thing. + """ + if parent_cls is not None: + self.parent = parent_cls.XML_REFL + else: + self.parent = None + self.tag = tag + + # Laziness for now + attributes = [] + elements = [] + for param in params: + if isinstance(param, Element): + elements.append(param) + else: + attributes.append(param) + + self.vars = [] + self.paramMap = {} + + self.attributes = attributes + self.attribute_map = {} + self.required_attribute_names = [] + for attribute in attributes: + self.attribute_map[attribute.xml_var] = attribute + self.paramMap[attribute.xml_var] = attribute + self.vars.append(attribute.var) + if attribute.required: + self.required_attribute_names.append(attribute.xml_var) + + self.elements = [] + self.element_map = {} + self.required_element_names = [] + self.aggregates = [] + self.scalars = [] + self.scalarNames = [] + for element in elements: + self.element_map[element.xml_var] = element + self.paramMap[element.xml_var] = element + self.vars.append(element.var) + if element.required: + self.required_element_names.append(element.xml_var) + if element.is_aggregate: + self.aggregates.append(element) + else: + self.scalars.append(element) + self.scalarNames.append(element.xml_var) + + def set_from_xml(self, obj, node, path, info=None): + is_final = False + if info is None: + is_final = True + info = Info(node) + + if self.parent: + path = self.parent.set_from_xml(obj, node, path, info) + + # Make this a map instead? Faster access? {name: isSet} ? + unset_attributes = list(self.attribute_map.keys()) + unset_scalars = copy.copy(self.scalarNames) + + def get_attr_path(attribute): + attr_path = copy.copy(path) + attr_path.suffix += "[@{}]".format(attribute.xml_var) + return attr_path + + def get_element_path(element): + element_path = Path(element.xml_var, parent=path) + # Add an index (allow this to be overriden) + if element.is_aggregate: + values = obj.get_aggregate_list(element.xml_var) + index = 1 + len(values) # 1-based indexing for W3C XPath + element_path.suffix = "[{}]".format(index) + return element_path + + id_var = "name" + # Better method? Queues? + for xml_var in copy.copy(info.attributes): + attribute = self.attribute_map.get(xml_var) + if attribute is not None: + value = node.attrib[xml_var] + attr_path = get_attr_path(attribute) + try: + attribute.set_from_string(obj, value) + if attribute.xml_var == id_var: + # Add id_var suffix to current path (do not copy so it propagates) + path.suffix = "[@{}='{}']".format(id_var, attribute.get_value(obj)) + except ParseError: + raise + except Exception as e: + raise ParseError(e, attr_path) + unset_attributes.remove(xml_var) + info.attributes.remove(xml_var) + + # Parse unconsumed nodes + for child in copy.copy(info.children): + tag = child.tag + element = self.element_map.get(tag) + if element is not None: + # Name will have been set + element_path = get_element_path(element) + if element.is_aggregate: + element.add_from_xml(obj, child, element_path) + else: + if tag in unset_scalars: + element.set_from_xml(obj, child, element_path) + unset_scalars.remove(tag) + else: + on_error("Scalar element defined multiple times: {}".format(tag)) # noqa + info.children.remove(child) + + # For unset attributes and scalar elements, we should not pass the attribute + # or element path, as those paths will implicitly not exist. + # If we do supply it, then the user would need to manually prune the XPath to try + # and find where the problematic parent element. + for attribute in map(self.attribute_map.get, unset_attributes): + try: + attribute.set_default(obj) + except ParseError: + raise + except Exception as e: + raise ParseError(e, path) # get_attr_path(attribute.xml_var) + + for element in map(self.element_map.get, unset_scalars): + try: + element.set_default(obj) + except ParseError: + raise + except Exception as e: + raise ParseError(e, path) # get_element_path(element) + + if is_final: + for xml_var in info.attributes: + on_error('Unknown attribute "{}" in {}'.format(xml_var, path)) + for node in info.children: + on_error('Unknown tag "{}" in {}'.format(node.tag, path)) + # Allow children parsers to adopt this current path (if modified with id_var) + return path + + def add_to_xml(self, obj, node): + if self.parent: + self.parent.add_to_xml(obj, node) + for attribute in self.attributes: + attribute.add_to_xml(obj, node) + for element in self.scalars: + element.add_to_xml(obj, node) + # Now add in aggregates + if self.aggregates: + obj.add_aggregates_to_xml(node) + + +class Object(YamlReflection): + """Raw python object for yaml / xml representation""" + + XML_REFL = None + + def get_refl_vars(self): + return self.XML_REFL.vars + + def check_valid(self): + pass + + def pre_write_xml(self): + """If anything needs to be converted prior to dumping to xml + i.e., getting the names of objects and such""" + pass + + def write_xml(self, node): + """Adds contents directly to XML node""" + self.check_valid() + self.pre_write_xml() + self.XML_REFL.add_to_xml(self, node) + + def to_xml(self): + """Creates an overarching tag and adds its contents to the node""" + tag = self.XML_REFL.tag + assert tag is not None, "Must define 'tag' in reflection to use this function" # noqa + doc = etree.Element(tag) + self.write_xml(doc) + return doc + + def to_xml_string(self, addHeader=True): + return xml_string(self.to_xml(), addHeader) + + def post_read_xml(self): + pass + + def read_xml(self, node, path): + self.XML_REFL.set_from_xml(self, node, path) + self.post_read_xml() + try: + self.check_valid() + except ParseError: + raise + except Exception as e: + raise ParseError(e, path) + + @classmethod + def from_xml(cls, node, path): + cur_type = get_type(cls) + return cur_type.from_xml(node, path) + + @classmethod + def from_xml_string(cls, xml_string): + node = etree.fromstring(xml_string) + path = Path(cls.XML_REFL.tag, tree=etree.ElementTree(node)) + return cls.from_xml(node, path) + + @classmethod + def from_xml_file(cls, file_path): + xml_string = open(file_path, "r").read() + return cls.from_xml_string(xml_string.encode('utf-8')) + + # Confusing distinction between loading code in object and reflection + # registry thing... + + def get_aggregate_list(self, xml_var): + var = self.XML_REFL.paramMap[xml_var].var + values = getattr(self, var) + assert isinstance(values, list) + return values + + def aggregate_init(self): + """Must be called in constructor!""" + self.aggregate_order = [] + # Store this info in the loaded object??? Nah + self.aggregate_type = {} + + def add_aggregate(self, xml_var, obj): + """NOTE: One must keep careful track of aggregate types for this system. + Can use 'lump_aggregates()' before writing if you don't care.""" + self.get_aggregate_list(xml_var).append(obj) + self.aggregate_order.append(obj) + self.aggregate_type[obj] = xml_var + + def add_aggregates_to_xml(self, node): + for value in self.aggregate_order: + typeName = self.aggregate_type[value] + element = self.XML_REFL.element_map[typeName] + element.add_scalar_to_xml(node, value) + + def remove_aggregate(self, obj): + self.aggregate_order.remove(obj) + xml_var = self.aggregate_type[obj] + del self.aggregate_type[obj] + self.get_aggregate_list(xml_var).remove(obj) + + def lump_aggregates(self): + """Put all aggregate types together, just because""" + self.aggregate_init() + for param in self.XML_REFL.aggregates: + for obj in self.get_aggregate_list(param.xml_var): + self.add_aggregate(param.var, obj) + + """ Compatibility """ + + def parse(self, xml_string): + node = etree.fromstring(xml_string) + path = Path(self.XML_REFL.tag, tree=etree.ElementTree(node)) + self.read_xml(node, path) + return self + + +# Really common types +# Better name: element_with_name? Attributed element? +add_type("element_name", SimpleElementType("name", str)) +add_type("element_value", SimpleElementType("value", float)) + +# Add in common vector types so they aren't absorbed into the namespaces +get_type("vector3") +get_type("vector4") +get_type("vector6") diff --git a/rofunc/utils/robolab/kinematics/__init__.py b/rofunc/utils/robolab/kinematics/__init__.py index 4daaac452..98b90b69a 100644 --- a/rofunc/utils/robolab/kinematics/__init__.py +++ b/rofunc/utils/robolab/kinematics/__init__.py @@ -1,2 +1,2 @@ from .fk import get_fk_from_chain, get_fk_from_model -from .robot_class import RobotModel \ No newline at end of file +from .robot_class import RobotModel diff --git a/rofunc/utils/robolab/kinematics/fk.py b/rofunc/utils/robolab/kinematics/fk.py index 5eb48b9a5..0db47e8eb 100644 --- a/rofunc/utils/robolab/kinematics/fk.py +++ b/rofunc/utils/robolab/kinematics/fk.py @@ -1,7 +1,6 @@ -def get_fk_from_chain(chain, joint_value, export_link_name): +def get_fk_from_chain(chain, joint_value, export_link_name=None): """ Get the forward kinematics from a serial chain - :param chain: :param joint_value: :param export_link_name: @@ -10,14 +9,16 @@ def get_fk_from_chain(chain, joint_value, export_link_name): # do forward kinematics and get transform objects; end_only=False gives a dictionary of transforms for all links ret = chain.forward_kinematics(joint_value) # look up the transform for a specific link - pose = ret[export_link_name] + if export_link_name is not None: + pose = ret[export_link_name] + else: + pose = None return pose, ret -def get_fk_from_model(model_path: str, joint_value, export_link, verbose=False): +def get_fk_from_model(model_path: str, joint_value, export_link=None, verbose=False): """ Get the forward kinematics from a URDF or MuJoCo XML file - :param model_path: the path of the URDF or MuJoCo XML file :param joint_value: the value of the joints :param export_link: the name of the end effector link @@ -28,4 +29,4 @@ def get_fk_from_model(model_path: str, joint_value, export_link, verbose=False): chain = build_chain_from_model(model_path, verbose) pose, ret = get_fk_from_chain(chain, joint_value, export_link) - return pose, ret + return pose, ret \ No newline at end of file diff --git a/rofunc/utils/robolab/kinematics/ik.py b/rofunc/utils/robolab/kinematics/ik.py index ed5ea61d8..72d01b435 100644 --- a/rofunc/utils/robolab/kinematics/ik.py +++ b/rofunc/utils/robolab/kinematics/ik.py @@ -1,58 +1,59 @@ +from typing import Union, List, Tuple import torch from rofunc.utils.robolab.coord import convert_ori_format, convert_quat_order from rofunc.utils.robolab.kinematics.pytorch_kinematics_utils import build_chain_from_model -def get_ik_from_chain(chain, pos, rot, device): +def get_ik_from_chain(chain, goal_pose: Union[torch.Tensor, None, List, Tuple], device, goal_in_rob_tf: bool = True, + robot_pose: Union[torch.Tensor, None, List, Tuple] = None, cur_configs=None, + num_retries: int = 10): """ Get the inverse kinematics from a serial chain - :param chain: only the serial chain is supported - :param pos: the position of the export_link - :param rot: the rotation of the export_link + :param goal_pose: the pose of the export ee link :param device: the device to run the computation + :param goal_in_rob_tf: whether the goal pose is in the robot base frame + :param robot_pose: the pose of the robot base frame + :param cur_configs: let the ik solver retry from these configurations + :param num_retries: the number of retries :return: """ import pytorch_kinematics as pk - rob_tf = pk.Transform3d(pos=pos, rot=rot, device=device) + goal_pos = goal_pose[:3] + goal_rot = goal_pose[3:] + goal_tf = pk.Transform3d(pos=goal_pos, rot=goal_rot, device=device) + if not goal_in_rob_tf: + assert robot_pose is not None, "The robot pose must be provided if the goal pose is not in the robot base frame" + robot_pos = robot_pose[:3] + robot_rot = robot_pose[3:] + rob_tf = pk.Transform3d(pos=robot_pos, rot=robot_rot, device=device) + goal_tf = rob_tf.inverse().compose(goal_tf) # get robot joint limits lim = torch.tensor(chain.get_joint_limits(), device=device) - cur_q = torch.rand(7, device=device) * (lim[1] - lim[0]) + lim[0] - goal_q = cur_q.unsqueeze(0).repeat(1, 1) - - goal_in_rob_frame_tf = chain.forward_kinematics(goal_q) + if cur_configs is not None: + cur_configs = torch.tensor(cur_configs, device=device) # create the IK object # see the constructor for more options and their explanations, such as convergence tolerances - # ik = PseudoInverseIK(chain, max_iterations=30, num_retries=10, - # joint_limits=lim.T, - # early_stopping_any_converged=True, - # early_stopping_no_improvement="all", - # retry_configs=cur_q.reshape(1, -1), - # # line_search=pk.BacktrackingLineSearch(max_lr=0.2), - # debug=False, - # lr=0.2) - ik = pk.PseudoInverseIK(chain, max_iterations=30, num_retries=10, + ik = pk.PseudoInverseIK(chain, max_iterations=30, retry_configs=cur_configs, num_retries=num_retries, joint_limits=lim.T, early_stopping_any_converged=True, early_stopping_no_improvement="all", - # line_search=pk.BacktrackingLineSearch(max_lr=0.2), debug=False, lr=0.2) # solve IK - sol = ik.solve(goal_in_rob_frame_tf) + sol = ik.solve(goal_tf) return sol def get_ik_from_model(model_path: str, pose: torch.Tensor, device, export_link, verbose=False): """ Get the inverse kinematics from a URDF or MuJoCo XML file - :param model_path: the path of the URDF or MuJoCo XML file :param pose: the pose of the end effector, 7D vector with the first 3 elements as position and the last 4 elements as rotation :param device: the device to run the computation @@ -72,7 +73,7 @@ def get_ik_from_model(model_path: str, pose: torch.Tensor, device, export_link, if __name__ == '__main__': - model_path = "/home/ubuntu/Github/Xianova_Robotics/Rofunc-secret/rofunc/simulator/assets/urdf/franka_description/robots/franka_panda.urdf" + model_path = "./simulator/assets/urdf/franka_description/robots/franka_panda.urdf" # device = torch.device("cuda" if torch.cuda.is_available() else "cpu") device = torch.device("cpu") @@ -125,4 +126,4 @@ def get_ik_from_model(model_path: str, pose: torch.Tensor, device, export_link, # p.removeBody(goalId) while True: - p.stepSimulation() + p.stepSimulation() \ No newline at end of file diff --git a/rofunc/utils/robolab/kinematics/kinpy_utils.py b/rofunc/utils/robolab/kinematics/kinpy_utils.py index 5a2ab5a74..c5f6d3687 100644 --- a/rofunc/utils/robolab/kinematics/kinpy_utils.py +++ b/rofunc/utils/robolab/kinematics/kinpy_utils.py @@ -9,7 +9,6 @@ def build_chain_from_model(model_path: str, verbose=False): """ Build a serial chain from a URDF or MuJoCo XML file - :param model_path: the path of the URDF or MuJoCo XML file :param verbose: whether to print the chain :return: robot kinematics chain @@ -27,4 +26,4 @@ def build_chain_from_model(model_path: str, verbose=False): print(chain) beauty_print("Robot joints:") print(chain.get_joint_parameter_names()) - return chain + return chain \ No newline at end of file diff --git a/rofunc/utils/robolab/kinematics/pytorch_kinematics_utils.py b/rofunc/utils/robolab/kinematics/pytorch_kinematics_utils.py index 598006c23..14f35b831 100644 --- a/rofunc/utils/robolab/kinematics/pytorch_kinematics_utils.py +++ b/rofunc/utils/robolab/kinematics/pytorch_kinematics_utils.py @@ -3,22 +3,20 @@ from typing import Optional, Callable from typing import Union -from rofunc.utils.oslab.path import check_package_exist from rofunc.utils.logger.beauty_logger import beauty_print +from rofunc.utils.oslab.path import check_package_exist check_package_exist("pytorch_kinematics") import mujoco -import pytorch_kinematics.transforms as tf import torch from matplotlib import pyplot as plt, cm as cm -from mujoco._structs import _MjModelBodyViews as MjModelBodyViews -from pytorch_kinematics import chain -from pytorch_kinematics import frame from pytorch_kinematics.chain import SerialChain from pytorch_kinematics.transforms import Transform3d from pytorch_kinematics.transforms import rotation_conversions +from rofunc.utils.robolab.formatter.urdf import build_chain_from_urdf +from rofunc.utils.robolab.formatter.mjcf import build_chain_from_mjcf # Converts from MuJoCo joint types to pytorch_kinematics joint types JOINT_TYPE_MAP = { mujoco.mjtJoint.mjJNT_HINGE: 'revolute', @@ -26,120 +24,29 @@ } -def body_to_geoms(m: mujoco.MjModel, body: MjModelBodyViews): - # Find all geoms which have body as parent - visuals = [] - for geom_id in range(m.ngeom): - geom = m.geom(geom_id) - if geom.bodyid == body.id: - visuals.append(frame.Visual(offset=tf.Transform3d(rot=geom.quat, pos=geom.pos), geom_type=geom.type, - geom_param=geom.size)) - return visuals - - -def _build_chain_recurse(m, parent_frame, parent_body): - parent_frame.link.visuals = body_to_geoms(m, parent_body) - # iterate through all bodies that are children of parent_body - for body_id in range(m.nbody): - body = m.body(body_id) - if body.parentid == parent_body.id and body_id != parent_body.id: - n_joints = body.jntnum - if n_joints > 1: - raise ValueError("composite joints not supported (could implement this if needed)") - if n_joints == 1: - # Find the joint for this body, again assuming there's only one joint per body. - joint = m.joint(body.jntadr[0]) - joint_offset = tf.Transform3d(pos=joint.pos) - child_joint = frame.Joint(joint.name, offset=joint_offset, axis=joint.axis, - joint_type=JOINT_TYPE_MAP[joint.type[0]], - limits=(joint.range[0], joint.range[1])) - else: - child_joint = frame.Joint(body.name + "_fixed_joint") - child_link = frame.Link(body.name, offset=tf.Transform3d(rot=body.quat, pos=body.pos)) - child_frame = frame.Frame(name=body.name, link=child_link, joint=child_joint) - parent_frame.children = parent_frame.children + [child_frame, ] - _build_chain_recurse(m, child_frame, body) - - # iterate through all sites that are children of parent_body - for site_id in range(m.nsite): - site = m.site(site_id) - if site.bodyid == parent_body.id: - site_link = frame.Link(site.name, offset=tf.Transform3d(rot=site.quat, pos=site.pos)) - site_frame = frame.Frame(name=site.name, link=site_link) - parent_frame.children = parent_frame.children + [site_frame, ] - - -def build_chain_from_mjcf(path, body: Union[None, str, int] = None): - """ - Build a Chain object from MJCF path. - - :param path: the path of the MJCF file - :param body: the name or index of the body to use as the root of the chain. If None, body idx=0 is used. - :return: Chain object created from MJCF - """ - - # import xml.etree.ElementTree as ET - # root = ET.parse(path).getroot() - # - # ASSETS = dict() - # mesh_dir = root.find("compiler").attrib["meshdir"] - # for asset in root.findall("asset"): - # for mesh in asset.findall("mesh"): - # filename = mesh.attrib["file"] - # with open(os.path.join(os.path.dirname(path), mesh_dir, filename), 'rb') as f: - # ASSETS[filename] = f.read() - - # m = mujoco.MjModel.from_xml_string(open(path).read(), assets=ASSETS) - m = mujoco.MjModel.from_xml_path(path) - if body is None: - root_body = m.body(0) - else: - root_body = m.body(body) - root_frame = frame.Frame(root_body.name, - link=frame.Link(root_body.name, - offset=tf.Transform3d(rot=root_body.quat, pos=root_body.pos)), - joint=frame.Joint()) - _build_chain_recurse(m, root_frame, root_body) - return chain.Chain(root_frame) - - -def build_serial_chain_from_mjcf(data, end_link_name, root_link_name=""): - """ - Build a SerialChain object from MJCF data. - - :param data: MJCF string data - :param end_link_name: the name of the link that is the end effector - :param root_link_name: the name of the root link - :return: SerialChain object created from MJCF - """ - mjcf_chain = build_chain_from_mjcf(data) - serial_chain = chain.SerialChain(mjcf_chain, end_link_name, "" if root_link_name == "" else root_link_name) - return serial_chain - - def build_chain_from_model(model_path: str, verbose=False): """ Build a serial chain from a URDF or MuJoCo XML file - :param model_path: the path of the URDF or MuJoCo XML file :param verbose: whether to print the chain :return: robot kinematics chain """ check_package_exist("pytorch_kinematics") - import pytorch_kinematics as pk if model_path.endswith(".urdf"): - chain = pk.build_chain_from_urdf(open(model_path).read()) + chain = build_chain_from_urdf(open(model_path).read()) elif model_path.endswith(".xml"): chain = build_chain_from_mjcf(model_path) else: raise ValueError("Invalid model path") if verbose: - beauty_print("Robot chain:") + beauty_print(f"Robot chain:") print(chain) - beauty_print("Robot joints:") + beauty_print(f"Robot joints: ({len(chain.get_joint_parameter_names())})") print(chain.get_joint_parameter_names()) + beauty_print(f"Robot joints frame name") + print(chain.get_joint_parent_frame_names()) return chain @@ -372,7 +279,6 @@ def solve(self, target_poses: Transform3d) -> IKSolution: def delta_pose(m: torch.tensor, target_pos, target_wxyz): """ Determine the error in position and rotation between the given poses and the target poses - :param m: (N x M x 4 x 4) tensor of homogenous transforms :param target_pos: :param target_wxyz: target orientation represented in unit quaternion @@ -567,4 +473,4 @@ def compute_dq(self, J, dx): # dq = J^T (JJ^T + lambda^2I)^-1 dx dq = total @ dx - return dq + return dq \ No newline at end of file diff --git a/rofunc/utils/robolab/kinematics/robot_class.py b/rofunc/utils/robolab/kinematics/robot_class.py index e1a3facdb..b9c37d233 100644 --- a/rofunc/utils/robolab/kinematics/robot_class.py +++ b/rofunc/utils/robolab/kinematics/robot_class.py @@ -1,13 +1,26 @@ -from rofunc.utils.robolab.kinematics.fk import get_fk_from_chain +import os +import numpy as np +import torch +import trimesh +from typing import Union, List, Tuple + +from rofunc.utils.logger.beauty_logger import beauty_print from rofunc.utils.robolab.coord import convert_ori_format, convert_quat_order, homo_matrix_from_quat_tensor +from rofunc.utils.robolab.formatter.mjcf_parser.mjcf import MJCF +from rofunc.utils.robolab.formatter.urdf_parser.urdf import URDF +from rofunc.utils.robolab.kinematics.fk import get_fk_from_chain +from rofunc.utils.robolab.kinematics.ik import get_ik_from_chain class RobotModel: - def __init__(self, model_path: str, solve_engine: str = "pytorch_kinematics", device="cpu", verbose=False): + def __init__(self, model_path: str, robot_pose=None, + solve_engine: str = "pytorch_kinematics", device="cpu", + verbose=False): """ Initialize a robot model from a URDF or MuJoCo XML file :param model_path: the path of the URDF or MuJoCo XML file + :param robot_pose: initial pose of robot base link, [x, y, z, qx, qy, qz, qw] :param solve_engine: the engine to solve the kinematics, ["pytorch_kinematics", "kinpy", "all"] :param device: the device to run the computation :param verbose: whether to print the chain @@ -15,47 +28,333 @@ def __init__(self, model_path: str, solve_engine: str = "pytorch_kinematics", de assert solve_engine in ["pytorch_kinematics", "kinpy"], "Unsupported solve engine." self.solve_engine = solve_engine self.device = device + self.verbose = verbose + self.robot_pose = robot_pose if robot_pose else [0, 0, 0, 0, 0, 0, 1] + self.robot_pos = self.robot_pose[:3] + self.robot_rot = self.robot_pose[3:] + + self.robot_model_path = model_path + self.mesh_dir = os.path.join(os.path.dirname(model_path), "meshes") + + self._load_model() + self._load_joint_info() + self._load_mesh_info() + self._load_link_info() + def _load_model(self): + """Loads the kinematic chain and robot model (URDF or MJCF).""" if self.solve_engine == "pytorch_kinematics": from rofunc.utils.robolab.kinematics import pytorch_kinematics_utils as pk_utils - self.chain = pk_utils.build_chain_from_model(model_path, verbose) + self.chain = pk_utils.build_chain_from_model(self.robot_model_path, self.verbose) elif self.solve_engine == "kinpy": from rofunc.utils.robolab.kinematics import kinpy_utils as kp_utils - self.chain = kp_utils.build_chain_from_model(model_path, verbose) + self.chain = kp_utils.build_chain_from_model(self.robot_model_path, self.verbose) + + if self.robot_model_path.endswith('.urdf'): + self.robot_model = URDF.from_xml_file(self.robot_model_path) + elif self.robot_model_path.endswith('.xml'): + self.robot_model = MJCF(self.robot_model_path) + else: + raise ValueError("Unsupported model file format.") + + def _load_joint_info(self): + """Loads joint information.""" + self.joint_list = self.get_joint_list() + self.num_joint = len(self.joint_list) + self.joint_limit_max = self.chain.high.to(self.device) + self.joint_limit_min = self.chain.low.to(self.device) + + def _load_mesh_info(self): + """Loads mesh information for the robot.""" + self.link_mesh_map = self.get_link_mesh_map() + self.link_meshname_map = self.get_link_meshname_map() + self.meshes, self.simple_shapes = self.load_meshes() + self.robot_faces = [val[1] for val in self.meshes.values()] + self.num_vertices_per_part = [val[0].shape[0] for val in self.meshes.values()] + self.meshname_mesh = {key: val[0] for key, val in self.meshes.items()} + self.meshname_mesh_normal = {key: val[-1] for key, val in self.meshes.items()} + + def _load_link_info(self): + """Loads link information including virtual and real links.""" + self.link_virtual_map, self.inverse_link_virtual_map = self.get_link_virtual_map() + self.real_link = self.get_real_link_list() + self.all_link = self.get_link_list() + + def show_chain(self): + beauty_print("Robot chain:") + print(self.chain) + + def convert_to_serial_chain(self, export_link): + import pytorch_kinematics as pk + self.serial_chain = pk.SerialChain(self.chain, export_link) + + def set_init_pose(self, robot_pose): + self.robot_pose = robot_pose + self.robot_pos = robot_pose[:3] + self.robot_rot = robot_pose[3:] + + def load_meshes(self): + """ + Load all meshes and store them in a dictionary. Handles both complex meshes and simple shapes. + + :return: A dictionary where keys are mesh names and values are mesh data, and a dictionary for simple shapes. + """ + meshes = {} + simple_shapes = {} # 用于保存简单形状信息 + for link_name, mesh_dict in self.link_mesh_map.items(): + for geom_name, mesh_info in mesh_dict.items(): + if mesh_info['type'] == 'mesh': + # 处理复杂的网格 + mesh_file = mesh_info['params']['mesh_path'] + name = mesh_info['params']['name'] + mesh = trimesh.load(mesh_file) + temp = torch.ones(mesh.vertices.shape[0], 1).float().to(self.device) + + vertices = torch.cat((torch.FloatTensor(np.array(mesh.vertices)), temp), dim=-1).to(self.device) + normals = torch.cat((torch.FloatTensor(np.array(mesh.vertex_normals)), temp), dim=-1).to(self.device) + + meshes[name] = [vertices, mesh.faces, normals] + else: + # 处理简单几何形状,直接保存形状信息 + simple_shapes[geom_name] = mesh_info + + return meshes, simple_shapes + + def get_joint_list(self): + return self.chain.get_joint_parameter_names() + + def get_link_list(self): + if self.solve_engine == "pytorch_kinematics": + return self.chain.get_link_names() + else: + raise ValueError("kinpy does not support get_link_names() method.") + + def get_link_virtual_map(self): + """ + :return: {link_body_name: [virtual_link_0, virtual_link_1, ...]} + """ + all_links = self.get_link_list() + link_virtual_map = {} + for link in all_links: + if "world" in link: + continue + if "_0" in link or "_1" in link or "_2" in link: + link_name = link.split("_")[0] + if link_name not in link_virtual_map: + link_virtual_map[link_name] = [] + link_virtual_map[link_name].append(link) + else: + link_virtual_map[link] = [link] + + inverse_link_virtual_map = {v: k for k, vs in link_virtual_map.items() for v in vs} + return link_virtual_map, inverse_link_virtual_map + + def get_real_link_list(self): + """ + :return: [real_link_0, real_link_1, ...] + """ + return list(self.link_virtual_map.keys()) + + def get_link_mesh_map(self): + """ + Get the map of link and its corresponding geometries from the robot model file (either URDF or MJCF). + + :return: {link_body_name: {geom_name: {'type': geom_type, 'params': geom_specific_parameters}}} + + If the robot model is a URDF file, it will attempt to link the geometry's mesh paths. The URDF format relies on + external mesh files, and this function assumes that any `.obj` mesh files are converted to `.stl` files. + + If the robot model is an MJCF file (which has a `.xml` extension), it uses the MJCF-specific link-mesh mapping + generated by the parser and processes different geometry types, including meshes, spheres, cylinders, boxes, + and capsules. - def get_fk(self, joint_value, export_link_name): + For each geometry type: + - 'mesh': It maps the geometry name to its corresponding mesh file path. + - 'sphere': It maps the geometry name to a dictionary with the sphere radius and position. + - 'cylinder': It maps the geometry name to a dictionary with the cylinder's radius, height, and position. + - 'box': It maps the geometry name to a dictionary with the box's extents (x, y, z) and position. + - 'capsule': It maps the geometry name to a dictionary with the capsule's radius, height, and start/end positions. + """ + if self.robot_model_path.endswith('.urdf'): + # TODO: urdf has some problems + link_mesh_map = {} + for link in link_mesh_map: + mesh_path = link_mesh_map[link].collision.geometry.filename.replace(".obj", ".stl") + link_mesh_map[link] = os.path.join(os.path.dirname(self.robot_model_path), mesh_path) + elif self.robot_model_path.endswith('.xml'): + link_mesh_map = self.robot_model.link_mesh_map + else: + raise ValueError("Unsupported model file.") + return link_mesh_map + + def get_link_meshname_map(self): + """ + :return: {link_body_name: [mesh_name]} + """ + link_meshname_map = {} + for link, geoms in self.link_mesh_map.items(): + link_meshname_map[link] = [] + for geom in geoms: + if self.link_mesh_map[link][geom]['type'] == 'mesh': + link_meshname_map[link].append(self.link_mesh_map[link][geom]['params']['name']) + return link_meshname_map + + def get_robot_mesh(self, vertices_list, faces): + assert len(vertices_list) == len(faces), "The number of vertices and faces should be the same." + robot_mesh = [trimesh.Trimesh(verts, face) for verts, face in zip(vertices_list, faces)] + return robot_mesh + + def get_forward_robot_mesh(self, joint_value, base_trans=None): + """ + Transform the robot mesh according to the joint values and the base pose + :param joint_value: the joint values, [batch_size, num_joint] + :param base_trans: transformation matrix of the base pose, [batch_size, 4, 4] + :return: + """ + batch_size = joint_value.size()[0] + outputs = self.forward(joint_value, base_trans) + vertices_list = [[outputs[i][j].detach().cpu().numpy() for i in range(int(len(outputs) / 2))] for j in + range(batch_size)] + mesh = [self.get_robot_mesh(vertices, self.robot_faces) for vertices in vertices_list] + return mesh + + def forward(self, joint_value, base_trans=None): + """ + Transform the robot mesh according to the joint values and the base pose + + :param joint_value: the joint values, [batch_size, num_joint] + :param base_trans: transformation matrix of the base pose, [batch_size, 4, 4] + :return: + """ + batch_size = joint_value.shape[0] + trans_dict = self.get_trans_dict(joint_value, base_trans) + meshname_link_map = {} + for link, meshnames in self.link_meshname_map.items(): + for meshname in meshnames: + meshname_link_map[meshname] = link + + ret_vertices, ret_normals = [], [] + for mesh_name, mesh in self.meshname_mesh.items(): + link_vertices = self.meshname_mesh[mesh_name].repeat(batch_size, 1, 1) + link_normals = self.meshname_mesh_normal[mesh_name].repeat(batch_size, 1, 1) + + if 'base' not in meshname_link_map[mesh_name]: + link_name = meshname_link_map[mesh_name] + related_link = [key for key in trans_dict.keys() if link_name in key][-1] + link_vertices = torch.matmul(trans_dict[related_link], link_vertices.transpose(2, 1)).transpose(1, 2)[:, :, :3] + link_normals = torch.matmul(trans_dict[related_link], link_normals.transpose(2, 1)).transpose(1, 2)[:, :, :3] + else: + if base_trans is not None: + link_vertices = torch.matmul(base_trans, link_vertices.transpose(2, 1)).transpose(1, 2)[:, :, :3] + link_normals = torch.matmul(base_trans, link_normals.transpose(2, 1)).transpose(1, 2)[:, :, :3] + else: + link_vertices = link_vertices[:, :, :3] + link_normals = link_normals[:, :, :3] + ret_vertices.append(link_vertices) + ret_normals.append(link_normals) + return ret_vertices + ret_normals + + def get_fk(self, joint_value: List, export_link=None): """ Get the forward kinematics from a chain - :param joint_value: - :param export_link_name: + :param joint_value: both single and batch input are supported + :param export_link: the name of the export link :return: the position, rotation of the end effector, and the transformation matrices of all links """ + joint_value = self._prepare_joint_value(joint_value) + batch_size = joint_value.size()[0] + if self.solve_engine == "pytorch_kinematics": - pose, ret = get_fk_from_chain(self.chain, joint_value, export_link_name) + return self._pytorch_fk(joint_value, export_link) + elif self.solve_engine == "kinpy": + return self._kinpy_fk(joint_value, export_link, batch_size) + + def _prepare_joint_value(self, joint_value: List): + """Helper to prepare joint values for FK/IK.""" + joint_value = torch.tensor(joint_value, dtype=torch.float32).to(self.device) + if len(joint_value.size()) == 1: + joint_value = joint_value.unsqueeze(0) + return joint_value + + def _pytorch_fk(self, joint_value, export_link): + """Helper function for PyTorch kinematics FK.""" + joint_value_dict = {joint: joint_value[:, i] for i, joint in enumerate(self.joint_list)} + pose, ret = get_fk_from_chain(self.chain, joint_value_dict, export_link) + + if pose is not None: m = pose.get_matrix() pos = m[:, :3, 3] rot = convert_ori_format(m[:, :3, :3], "mat", "quat") return pos, rot, ret - elif self.solve_engine == "kinpy": - pose, ret = get_fk_from_chain(self.chain, joint_value, export_link_name) - pos = pose.pos - rot = pose.rot - rot = convert_quat_order(rot, "wxyz", "xyzw") - return pos, rot, ret + return None, None, ret + + def _kinpy_fk(self, joint_value, export_link, batch_size): + """Helper function for KinPy kinematics FK.""" + pos_batch, rot_batch = [], [] + for batch in range(batch_size): + joint_value_dict = {joint: joint_value[batch, i] for i, joint in enumerate(self.joint_list)} + pose, ret = get_fk_from_chain(self.chain, joint_value_dict, export_link) + if pose is not None: + pos_batch.append(pose.pos) + rot_batch.append(convert_quat_order(pose.rot, "wxyz", "xyzw")) + return torch.tensor(pos_batch), torch.tensor(rot_batch), ret + + def get_jacobian(self, joint_value: List, export_link: str, locations=None): + """ + Get the jacobian of a chain + + :param joint_value: the joint values, [batch_size, num_joint] + :param export_link: the name of the export link + :param locations: the locations offset from the export link + :return: + """ + self.convert_to_serial_chain(export_link=export_link) + assert self.solve_engine == "pytorch_kinematics", "kinpy does not support get_jacobian() method." + J = self.serial_chain.jacobian(joint_value, locations=locations) + return J + + def get_trans_dict(self, joint_value: List, base_trans: Union[None, torch.Tensor] = None) -> dict: + """ + Get the transformation matrices of all links + + :param joint_value: the joint values, [batch_size, num_joint] + :param base_trans: transformation matrix of the base pose, [batch_size, 4, 4] + :return: A dictionary where the keys are link names and the values are transformation matrices. + """ + _, _, ret = self.get_fk(joint_value) + trans_dict = {} + for link in self.all_link: + if "world" in link: + continue + val = ret[link] + homo_matrix = val.get_matrix().to(self.device) + if base_trans is not None: + homo_matrix = torch.matmul(base_trans, homo_matrix) + + real_link = self.inverse_link_virtual_map[link] + trans_dict[real_link] = homo_matrix + + return trans_dict - def get_ik(self, ee_pose, export_link_name): + def get_ik(self, ee_pose: Union[torch.Tensor, None, List, Tuple], export_link, goal_in_rob_tf: bool = True, + cur_configs=None, num_retries=10): """ Get the inverse kinematics from a chain :param ee_pose: the pose of the end effector, 7D vector with the first 3 elements as position and the last 4 elements as rotation - :param export_link_name: + :param export_link: the name of the export link + :param goal_in_rob_tf: whether the goal pose is in the robot base frame + :param cur_configs: let the ik solver retry from these configurations + :param num_retries: the number of retries :return: the joint values """ + self.convert_to_serial_chain(export_link) if self.solve_engine == "pytorch_kinematics": - return get_ik_from_chain(self.chain, ee_pose[:3], ee_pose[3:], self.device) + return get_ik_from_chain(self.serial_chain, ee_pose, self.device, goal_in_rob_tf=goal_in_rob_tf, + robot_pose=self.robot_pose, cur_configs=cur_configs, num_retries=num_retries) elif self.solve_engine == "kinpy": import kinpy as kp - self.serial_chain = kp.chain.SerialChain(self.chain, export_link_name) + self.serial_chain = kp.chain.SerialChain(self.chain, export_link) homo_matrix = homo_matrix_from_quat_tensor(ee_pose[3:], ee_pose[:3]) - return self.serial_chain.inverse_kinematics(homo_matrix) + return self.serial_chain.inverse_kinematics(homo_matrix) \ No newline at end of file diff --git a/setup.py b/setup.py index 3a2bb2aed..35022ba68 100644 --- a/setup.py +++ b/setup.py @@ -1,5 +1,6 @@ from setuptools import setup, find_packages + from pathlib import Path this_directory = Path(__file__).parent @@ -24,7 +25,7 @@ include_package_data=True, extras_require=extras, install_requires=['cython==3.0.0a10', # for mujoco_py - 'setuptools==59.8.0', + 'setuptools', 'pandas', 'tqdm==4.65.0', 'pillow==9.5.0', @@ -47,7 +48,7 @@ 'dgl', 'trimesh==4.0.5', 'wandb==0.16.2'], - python_requires=">=3.7,<3.9", + python_requires=">=3.7,<3.11", keywords=['robotics', 'robot learning', 'learning from demonstration', 'reinforcement learning', 'robot manipulation'], license='MIT',