From df3530d7d3fff721e3a899145ddb13121d9c522e Mon Sep 17 00:00:00 2001 From: gjstein Date: Sun, 2 Jul 2023 17:43:53 -0400 Subject: [PATCH] initial commit for open source v1.0.0 --- .dockerignore | 2 + .gitignore | 137 +++ Dockerfile | 89 ++ LICENSE | 21 + Makefile | 177 +++ README.md | 52 + entrypoint.sh | 23 + modules/common/common/__init__.py | 61 + modules/common/setup.py | 11 + modules/common/tests/test_common_pose.py | 107 ++ modules/conftest.py | 31 + modules/environments/README.md | 3 + modules/environments/environments/__init__.py | 5 + .../environments/base_generator.py | 67 + .../environments/clutter_generator.py | 240 ++++ .../environments/environments/constants.py | 9 + modules/environments/environments/generate.py | 85 ++ .../environments/environments/guided_maze.py | 190 +++ modules/environments/environments/office.py | 482 ++++++++ modules/environments/environments/office2.py | 826 +++++++++++++ .../environments/pickle_loader.py | 127 ++ .../environments/environments/simulated.py | 266 ++++ .../environments/utils/__init__.py | 2 + .../environments/environments/utils/calc.py | 131 ++ .../environments/utils/convert.py | 40 + modules/environments/environments/world.py | 136 +++ modules/environments/setup.py | 11 + .../tests/test_office2_environment_gen.py | 133 ++ .../tests/test_office_environment_gen.py | 49 + .../tests/test_simulator_speed.py | 95 ++ modules/example/Makefile.mk | 24 + modules/example/README.org | 106 ++ modules/example/example/__init__.py | 2 + modules/example/example/core.py | 6 + modules/example/example/scripts/__init__.py | 0 .../example/example/scripts/gen_random_mat.py | 20 + modules/example/setup.py | 11 + modules/example/tests/test_example.py | 23 + modules/gridmap/README.md | 10 + modules/gridmap/gridmap/__init__.py | 5 + modules/gridmap/gridmap/constants.py | 10 + modules/gridmap/gridmap/laser.py | 286 +++++ modules/gridmap/gridmap/mapping.py | 234 ++++ modules/gridmap/gridmap/planning.py | 125 ++ modules/gridmap/gridmap/utils.py | 49 + modules/gridmap/setup.py | 10 + modules/gridmap/tests/test_gridmap.py | 141 +++ modules/learning/README.md | 52 + modules/learning/learning/__init__.py | 2 + modules/learning/learning/data.py | 54 + modules/learning/learning/logging.py | 17 + modules/learning/setup.py | 11 + modules/learning/tests/test_learning_data.py | 28 + modules/lsp/Makefile.mk | 152 +++ modules/lsp/README.org | 86 ++ modules/lsp/lsp/__init__.py | 8 + modules/lsp/lsp/constants.py | 10 + modules/lsp/lsp/core.py | 939 ++++++++++++++ modules/lsp/lsp/learning/__init__.py | 1 + modules/lsp/lsp/learning/models/__init__.py | 2 + modules/lsp/lsp/learning/models/shared.py | 39 + .../lsp/learning/models/vis_lsp_oriented.py | 158 +++ modules/lsp/lsp/planners/__init__.py | 6 + modules/lsp/lsp/planners/dijkstra_planner.py | 41 + modules/lsp/lsp/planners/known_planner.py | 57 + modules/lsp/lsp/planners/planner.py | 38 + modules/lsp/lsp/planners/planning_loop.py | 135 ++ modules/lsp/lsp/planners/subgoal_planner.py | 218 ++++ modules/lsp/lsp/planners/utils.py | 87 ++ modules/lsp/lsp/pose.py | 26 + modules/lsp/lsp/primitive.py | 117 ++ modules/lsp/lsp/robot.py | 163 +++ modules/lsp/lsp/scripts/__init__.py | 0 modules/lsp/lsp/scripts/shared.py | 70 ++ modules/lsp/lsp/scripts/vis_lsp_eval.py | 128 ++ .../lsp/lsp/scripts/vis_lsp_generate_data.py | 95 ++ modules/lsp/lsp/scripts/vis_lsp_plotting.py | 134 ++ modules/lsp/lsp/scripts/vis_lsp_train_net.py | 140 +++ modules/lsp/lsp/simulators.py | 237 ++++ modules/lsp/lsp/utils/__init__.py | 5 + modules/lsp/lsp/utils/calc.py | 45 + modules/lsp/lsp/utils/command_line.py | 121 ++ modules/lsp/lsp/utils/data.py | 40 + modules/lsp/lsp/utils/learning_vision.py | 117 ++ modules/lsp/lsp/utils/plotting.py | 294 +++++ .../lsp/resources/images/results_maze_dbg.png | Bin 0 -> 431694 bytes modules/lsp/setup.py | 11 + modules/lsp/tests/test_lsp_accel.py | 97 ++ modules/lsp/tests/test_lsp_evaluate.py | 145 +++ modules/lsp/tests/test_lsp_utils.py | 43 + modules/lsp_accel/CMakeLists.txt | 34 + modules/lsp_accel/README.org | 3 + modules/lsp_accel/setup.cfg | 2 + modules/lsp_accel/setup.py | 81 ++ modules/lsp_accel/src/main.cpp | 46 + modules/lsp_accel/src/subgoal_planning.hpp | 245 ++++ modules/lsp_gnn/Makefile.mk | 344 ++++++ modules/lsp_gnn/README.org | 38 + modules/lsp_gnn/lsp_gnn/__init__.py | 7 + modules/lsp_gnn/lsp_gnn/core.py | 279 +++++ .../lsp_gnn/lsp_gnn/environments/__init__.py | 4 + .../lsp_gnn/lsp_gnn/environments/generate.py | 50 + .../lsp_gnn/lsp_gnn/environments/jshaped.py | 191 +++ .../lsp_gnn/environments/modified_office.py | 847 +++++++++++++ .../lsp_gnn/environments/parallel_hallway.py | 342 ++++++ modules/lsp_gnn/lsp_gnn/learning/__init__.py | 1 + .../lsp_gnn/learning/models/__init__.py | 4 + .../lsp_gnn/learning/models/auto_encoder.py | 228 ++++ .../lsp_gnn/learning/models/cnn_lsp.py | 71 ++ .../lsp_gnn/lsp_gnn/learning/models/gcn.py | 74 ++ .../lsp_gnn/lsp_gnn/learning/models/lsp.py | 100 ++ modules/lsp_gnn/lsp_gnn/planners.py | 610 ++++++++++ modules/lsp_gnn/lsp_gnn/plotting.py | 104 ++ modules/lsp_gnn/lsp_gnn/scripts/__init__.py | 0 modules/lsp_gnn/lsp_gnn/scripts/evaluate.py | 208 ++++ .../lsp_gnn/lsp_gnn/scripts/evaluate_all.py | 237 ++++ modules/lsp_gnn/lsp_gnn/scripts/gen_data.py | 192 +++ modules/lsp_gnn/lsp_gnn/scripts/plotting.py | 114 ++ modules/lsp_gnn/lsp_gnn/scripts/train.py | 160 +++ modules/lsp_gnn/lsp_gnn/utils.py | 847 +++++++++++++ modules/lsp_gnn/scratch/Makefile.mk | 206 ++++ modules/lsp_gnn/scratch/info_planner.py | 73 ++ modules/lsp_gnn/scratch/info_util.py | 251 ++++ .../scratch/learning/models/cnn_lsp.py | 356 ++++++ .../lsp_gnn/scratch/learning/models/gcn.py | 404 ++++++ modules/lsp_gnn/scratch/plotting.py | 106 ++ .../lsp_gnn/scratch/scripts/lsp_cond_clip.py | 14 + .../scratch/scripts/lsp_cond_eval_gcn.py | 213 ++++ .../scratch/scripts/lsp_cond_evaluate.py | 319 +++++ .../lsp_gnn/scratch/test_lsp_cond_plotting.py | 180 +++ modules/lsp_gnn/scratch/utils.py | 207 ++++ modules/lsp_gnn/setup.py | 11 + modules/lsp_gnn/tests/test_j_env.py | 109 ++ .../lsp_gnn/tests/test_lsp_gnn_planners.py | 551 +++++++++ modules/lsp_gnn/tests/test_parallel_env.py | 85 ++ modules/lsp_select/Makefile.mk | 226 ++++ modules/lsp_select/README.md | 28 + modules/lsp_select/lsp_select/__init__.py | 5 + .../lsp_select/learning/__init__.py | 1 + .../lsp_select/learning/models/__init__.py | 1 + .../lsp_select/learning/models/cyclegan.py | 159 +++ .../lsp_select/lsp_select/offline_replay.py | 264 ++++ .../lsp_select/planners/__init__.py | 2 + .../lsp_select/planners/cyclegan_planner.py | 53 + .../lsp_select/planners/policy_selection.py | 93 ++ .../lsp_select/lsp_select/scratch/Makefile.mk | 383 ++++++ .../lsp_select/scratch/models/laser_lsp.py | 91 ++ .../scratch/planners/subgoal_planner.py | 545 +++++++++ .../scratch/scripts/cyclegan_data_gen.py | 84 ++ .../scratch/scripts/lsp_cost_dist.py | 137 +++ .../scratch/scripts/lsp_delta_cost.py | 210 ++++ .../scratch/scripts/lsp_delta_cost_gen.py | 226 ++++ .../scratch/scripts/lsp_estimated_cost.py | 472 +++++++ .../scratch/scripts/lsp_gen_nav_cost_data.py | 183 +++ .../scratch/scripts/lsp_gen_threshold.py | 118 ++ .../scratch/scripts/lsp_laser_maze_eval.py | 91 ++ .../scratch/scripts/lsp_model_selection.py | 195 +++ .../scripts/lsp_model_selection_eval.py | 173 +++ .../scratch/scripts/lsp_planner_eval.py | 112 ++ .../scratch/scripts/lsp_planner_results.py | 80 ++ .../scratch/scripts/lsp_rtm_delta_eval.py | 116 ++ .../scratch/scripts/lsp_rtm_eval.py | 116 ++ .../scratch/scripts/lsp_rtm_lb_eval.py | 120 ++ .../scratch/tests/test_cost_distribution.py | 53 + .../lsp_select/scratch/utils/delta_cost.py | 233 ++++ .../lsp_select/scratch/utils/distribution.py | 39 + .../scratch/utils/learning_laser.py | 38 + .../lsp_select/lsp_select/scripts/__init__.py | 0 .../scripts/lsp_offline_replay_costs.py | 166 +++ .../scripts/lsp_offline_replay_demo.py | 134 ++ .../scripts/lsp_policy_selection_results.py | 404 ++++++ .../lsp_select/scripts/lsp_vis_gen_data.py | 102 ++ .../lsp_select/lsp_select/utils/__init__.py | 2 + modules/lsp_select/lsp_select/utils/misc.py | 21 + .../lsp_select/lsp_select/utils/plotting.py | 92 ++ modules/lsp_select/setup.py | 11 + modules/lsp_select/tests/conftest.py | 25 + modules/lsp_select/tests/test_lsp_cyclegan.py | 86 ++ .../lsp_select/tests/test_maze_navigation.py | 77 ++ .../lsp_select/tests/test_offline_replay.py | 97 ++ modules/lsp_xai/Makefile.mk | 293 +++++ modules/lsp_xai/README.md | 72 ++ modules/lsp_xai/lsp_xai/__init__.py | 7 + modules/lsp_xai/lsp_xai/learning/__init__.py | 1 + modules/lsp_xai/lsp_xai/learning/models.py | 658 ++++++++++ modules/lsp_xai/lsp_xai/planners/__init__.py | 3 + modules/lsp_xai/lsp_xai/planners/evaluate.py | 397 ++++++ .../lsp_xai/lsp_xai/planners/explanation.py | 604 +++++++++ .../lsp_xai/planners/known_subgoal_planner.py | 86 ++ .../lsp_xai/planners/subgoal_planner.py | 467 +++++++ modules/lsp_xai/lsp_xai/scripts/__init__.py | 0 .../lsp_xai/scripts/explainability_results.py | 267 ++++ .../scripts/explainability_train_eval.py | 517 ++++++++ .../lsp_xai/scripts/interpret_datum.py | 127 ++ modules/lsp_xai/lsp_xai/scripts/run.sh | 84 ++ modules/lsp_xai/lsp_xai/utils/__init__.py | 2 + modules/lsp_xai/lsp_xai/utils/data.py | 132 ++ modules/lsp_xai/lsp_xai/utils/plotting.py | 198 +++ .../resources/xai-example-explanation.jpg | Bin 0 -> 1188555 bytes modules/lsp_xai/setup.py | 10 + modules/lsp_xai/tests/conftest.py | 19 + modules/lsp_xai/tests/test_lsp_xai.py | 691 +++++++++++ modules/mrlsp/Makefile.mk | 89 ++ modules/mrlsp/README.md | 27 + modules/mrlsp/mrlsp/__init__.py | 5 + modules/mrlsp/mrlsp/core.py | 439 +++++++ modules/mrlsp/mrlsp/planners/__init__.py | 5 + modules/mrlsp/mrlsp/planners/lsp_baseline.py | 63 + modules/mrlsp/mrlsp/planners/mrlsp_planner.py | 65 + modules/mrlsp/mrlsp/planners/optimistic.py | 29 + modules/mrlsp/mrlsp/planners/planner.py | 66 + modules/mrlsp/mrlsp/planners/planning_loop.py | 180 +++ modules/mrlsp/mrlsp/pouct.py | 248 ++++ modules/mrlsp/mrlsp/scripts/__init__.py | 0 .../mrlsp/scripts/simulation_baseline.py | 183 +++ modules/mrlsp/mrlsp/scripts/simulation_lsp.py | 127 ++ .../mrlsp/mrlsp/scripts/simulation_mrlsp.py | 187 +++ .../mrlsp/scripts/simulation_optimistic.py | 181 +++ modules/mrlsp/mrlsp/utils/__init__.py | 2 + modules/mrlsp/mrlsp/utils/plotting.py | 160 +++ modules/mrlsp/mrlsp/utils/utility.py | 415 +++++++ modules/mrlsp/setup.py | 11 + modules/mrlsp/tests/dummy_frontier.py | 23 + .../tests/test_core_utility_functions.py | 336 +++++ .../mrlsp/tests/test_cpp_state_constructor.py | 48 + .../mrlsp/tests/test_more_robots_frontiers.py | 48 + .../tests/test_mrlsp_using_true_values.py | 73 ++ .../mrlsp/tests/test_two_timestamp_action.py | 59 + modules/mrlsp/tests/util_function.py | 451 +++++++ modules/mrlsp_accel/CMakeLists.txt | 34 + modules/mrlsp_accel/README.md | 4 + modules/mrlsp_accel/setup.py | 81 ++ modules/mrlsp_accel/src/core.hpp | 482 ++++++++ modules/mrlsp_accel/src/main.cpp | 74 ++ modules/mrlsp_accel/src/mrlsp_utility.hpp | 194 +++ modules/mrlsp_accel/src/pouct.hpp | 381 ++++++ modules/requirements.txt | 26 + modules/setup.cfg | 5 + modules/unitybridge/setup.py | 11 + modules/unitybridge/tests/test_unitybridge.py | 78 ++ modules/unitybridge/unitybridge/__init__.py | 1 + .../unitybridge/unitybridge/unity_bridge.py | 194 +++ modules/vertexnav/Makefile.mk | 96 ++ modules/vertexnav/README.org | 36 + modules/vertexnav/setup.py | 10 + modules/vertexnav/tests/test_mvmp.py | 261 ++++ modules/vertexnav/tests/test_navigation.py | 341 ++++++ .../vertexnav/tests/test_noisy_navigation.py | 124 ++ .../vertexnav/tests/test_noisy_vertex_nav.py | 240 ++++ modules/vertexnav/tests/test_vertexnav.py | 270 ++++ .../vertexnav/tests/test_vertexnav_data.py | 55 + .../tests/test_vertexnav_environments.py | 39 + .../vertexnav/tests/test_vertexnav_slam.py | 1084 +++++++++++++++++ modules/vertexnav/vertexnav/__init__.py | 13 + .../vertexnav/environments/__init__.py | 3 + .../vertexnav/environments/dungeon.py | 398 ++++++ .../vertexnav/vertexnav/environments/real.py | 857 +++++++++++++ .../vertexnav/environments/simulated.py | 623 ++++++++++ modules/vertexnav/vertexnav/learning.py | 67 + modules/vertexnav/vertexnav/models.py | 230 ++++ modules/vertexnav/vertexnav/noisy.py | 267 ++++ modules/vertexnav/vertexnav/planning.py | 517 ++++++++ modules/vertexnav/vertexnav/plotting.py | 171 +++ .../vertexnav/vertexnav/prob_vertex_graph.py | 698 +++++++++++ modules/vertexnav/vertexnav/robot.py | 276 +++++ .../vertexnav/vertexnav/scripts/__init__.py | 0 .../vertexnav/scripts/eval_simulated.py | 737 +++++++++++ .../scripts/gen_vertex_training_data_sim.py | 131 ++ .../vertexnav/scripts/train_vertex_nav_net.py | 171 +++ modules/vertexnav/vertexnav/utils/__init__.py | 4 + modules/vertexnav/vertexnav/utils/calc.py | 198 +++ modules/vertexnav/vertexnav/utils/convert.py | 131 ++ modules/vertexnav/vertexnav/utils/data.py | 15 + modules/vertexnav/vertexnav/utils/topology.py | 124 ++ modules/vertexnav/vertexnav/vertex_graph.py | 269 ++++ modules/vertexnav/vertexnav/world.py | 643 ++++++++++ modules/vertexnav_accel/CMakeLists.txt | 54 + modules/vertexnav_accel/README.org | 3 + modules/vertexnav_accel/setup.cfg | 2 + modules/vertexnav_accel/setup.py | 85 ++ .../src/Hungarian/Hungarian.cpp | 395 ++++++ .../vertexnav_accel/src/Hungarian/Hungarian.h | 40 + modules/vertexnav_accel/src/Hungarian/LICENSE | 23 + .../vertexnav_accel/src/Hungarian/README.txt | 7 + .../vertexnav_accel/src/Hungarian/license.txt | 24 + .../vertexnav_accel/src/Hungarian/makefile | 15 + .../src/Hungarian/testMain.cpp | 24 + modules/vertexnav_accel/src/cgal_ex.cpp | 231 ++++ modules/vertexnav_accel/src/cgal_ex.hpp | 72 ++ modules/vertexnav_accel/src/main.cpp | 219 ++++ modules/vertexnav_accel/src/noisy.cpp | 290 +++++ modules/vertexnav_accel/src/noisy.hpp | 260 ++++ modules/vertexnav_accel/src/pose.cpp | 25 + modules/vertexnav_accel/src/pose.hpp | 32 + modules/vertexnav_accel/src/types.hpp | 11 + modules/vertexnav_accel/src/vertex_graph.cpp | 383 ++++++ modules/vertexnav_accel/src/vertex_graph.hpp | 435 +++++++ .../tests/test_gapnav_accel.py | 64 + resources/images/RAIL-group-logo-flat.jpg | Bin 0 -> 55489 bytes ...onboarding-01-known-space-navigation.ipynb | 502 ++++++++ .../RAIL-onboarding-02-visual-simulator.ipynb | 395 ++++++ .../notebooks/environments-playground.ipynb | 247 ++++ .../testing/lsp_xai_maze_0SG.ExpNavVisLSP.pt | Bin 0 -> 484274 bytes .../testing/lsp_xai_maze_4SG.ExpNavVisLSP.pt | Bin 0 -> 484272 bytes 304 files changed, 45908 insertions(+) create mode 100644 .dockerignore create mode 100644 .gitignore create mode 100644 Dockerfile create mode 100644 LICENSE create mode 100644 Makefile create mode 100644 README.md create mode 100644 entrypoint.sh create mode 100644 modules/common/common/__init__.py create mode 100644 modules/common/setup.py create mode 100644 modules/common/tests/test_common_pose.py create mode 100644 modules/conftest.py create mode 100644 modules/environments/README.md create mode 100644 modules/environments/environments/__init__.py create mode 100644 modules/environments/environments/base_generator.py create mode 100644 modules/environments/environments/clutter_generator.py create mode 100644 modules/environments/environments/constants.py create mode 100644 modules/environments/environments/generate.py create mode 100644 modules/environments/environments/guided_maze.py create mode 100644 modules/environments/environments/office.py create mode 100644 modules/environments/environments/office2.py create mode 100644 modules/environments/environments/pickle_loader.py create mode 100644 modules/environments/environments/simulated.py create mode 100644 modules/environments/environments/utils/__init__.py create mode 100644 modules/environments/environments/utils/calc.py create mode 100644 modules/environments/environments/utils/convert.py create mode 100644 modules/environments/environments/world.py create mode 100644 modules/environments/setup.py create mode 100644 modules/environments/tests/test_office2_environment_gen.py create mode 100644 modules/environments/tests/test_office_environment_gen.py create mode 100644 modules/environments/tests/test_simulator_speed.py create mode 100644 modules/example/Makefile.mk create mode 100644 modules/example/README.org create mode 100644 modules/example/example/__init__.py create mode 100644 modules/example/example/core.py create mode 100644 modules/example/example/scripts/__init__.py create mode 100644 modules/example/example/scripts/gen_random_mat.py create mode 100644 modules/example/setup.py create mode 100644 modules/example/tests/test_example.py create mode 100644 modules/gridmap/README.md create mode 100644 modules/gridmap/gridmap/__init__.py create mode 100644 modules/gridmap/gridmap/constants.py create mode 100644 modules/gridmap/gridmap/laser.py create mode 100644 modules/gridmap/gridmap/mapping.py create mode 100644 modules/gridmap/gridmap/planning.py create mode 100644 modules/gridmap/gridmap/utils.py create mode 100644 modules/gridmap/setup.py create mode 100644 modules/gridmap/tests/test_gridmap.py create mode 100644 modules/learning/README.md create mode 100644 modules/learning/learning/__init__.py create mode 100644 modules/learning/learning/data.py create mode 100644 modules/learning/learning/logging.py create mode 100644 modules/learning/setup.py create mode 100644 modules/learning/tests/test_learning_data.py create mode 100644 modules/lsp/Makefile.mk create mode 100644 modules/lsp/README.org create mode 100644 modules/lsp/lsp/__init__.py create mode 100644 modules/lsp/lsp/constants.py create mode 100644 modules/lsp/lsp/core.py create mode 100644 modules/lsp/lsp/learning/__init__.py create mode 100644 modules/lsp/lsp/learning/models/__init__.py create mode 100644 modules/lsp/lsp/learning/models/shared.py create mode 100644 modules/lsp/lsp/learning/models/vis_lsp_oriented.py create mode 100644 modules/lsp/lsp/planners/__init__.py create mode 100644 modules/lsp/lsp/planners/dijkstra_planner.py create mode 100644 modules/lsp/lsp/planners/known_planner.py create mode 100644 modules/lsp/lsp/planners/planner.py create mode 100644 modules/lsp/lsp/planners/planning_loop.py create mode 100644 modules/lsp/lsp/planners/subgoal_planner.py create mode 100644 modules/lsp/lsp/planners/utils.py create mode 100644 modules/lsp/lsp/pose.py create mode 100644 modules/lsp/lsp/primitive.py create mode 100644 modules/lsp/lsp/robot.py create mode 100644 modules/lsp/lsp/scripts/__init__.py create mode 100644 modules/lsp/lsp/scripts/shared.py create mode 100644 modules/lsp/lsp/scripts/vis_lsp_eval.py create mode 100644 modules/lsp/lsp/scripts/vis_lsp_generate_data.py create mode 100644 modules/lsp/lsp/scripts/vis_lsp_plotting.py create mode 100644 modules/lsp/lsp/scripts/vis_lsp_train_net.py create mode 100644 modules/lsp/lsp/simulators.py create mode 100644 modules/lsp/lsp/utils/__init__.py create mode 100644 modules/lsp/lsp/utils/calc.py create mode 100644 modules/lsp/lsp/utils/command_line.py create mode 100644 modules/lsp/lsp/utils/data.py create mode 100644 modules/lsp/lsp/utils/learning_vision.py create mode 100644 modules/lsp/lsp/utils/plotting.py create mode 100644 modules/lsp/resources/images/results_maze_dbg.png create mode 100644 modules/lsp/setup.py create mode 100644 modules/lsp/tests/test_lsp_accel.py create mode 100644 modules/lsp/tests/test_lsp_evaluate.py create mode 100644 modules/lsp/tests/test_lsp_utils.py create mode 100644 modules/lsp_accel/CMakeLists.txt create mode 100644 modules/lsp_accel/README.org create mode 100644 modules/lsp_accel/setup.cfg create mode 100644 modules/lsp_accel/setup.py create mode 100644 modules/lsp_accel/src/main.cpp create mode 100644 modules/lsp_accel/src/subgoal_planning.hpp create mode 100644 modules/lsp_gnn/Makefile.mk create mode 100644 modules/lsp_gnn/README.org create mode 100644 modules/lsp_gnn/lsp_gnn/__init__.py create mode 100644 modules/lsp_gnn/lsp_gnn/core.py create mode 100644 modules/lsp_gnn/lsp_gnn/environments/__init__.py create mode 100644 modules/lsp_gnn/lsp_gnn/environments/generate.py create mode 100644 modules/lsp_gnn/lsp_gnn/environments/jshaped.py create mode 100644 modules/lsp_gnn/lsp_gnn/environments/modified_office.py create mode 100644 modules/lsp_gnn/lsp_gnn/environments/parallel_hallway.py create mode 100644 modules/lsp_gnn/lsp_gnn/learning/__init__.py create mode 100644 modules/lsp_gnn/lsp_gnn/learning/models/__init__.py create mode 100644 modules/lsp_gnn/lsp_gnn/learning/models/auto_encoder.py create mode 100644 modules/lsp_gnn/lsp_gnn/learning/models/cnn_lsp.py create mode 100644 modules/lsp_gnn/lsp_gnn/learning/models/gcn.py create mode 100644 modules/lsp_gnn/lsp_gnn/learning/models/lsp.py create mode 100644 modules/lsp_gnn/lsp_gnn/planners.py create mode 100644 modules/lsp_gnn/lsp_gnn/plotting.py create mode 100644 modules/lsp_gnn/lsp_gnn/scripts/__init__.py create mode 100644 modules/lsp_gnn/lsp_gnn/scripts/evaluate.py create mode 100644 modules/lsp_gnn/lsp_gnn/scripts/evaluate_all.py create mode 100644 modules/lsp_gnn/lsp_gnn/scripts/gen_data.py create mode 100644 modules/lsp_gnn/lsp_gnn/scripts/plotting.py create mode 100644 modules/lsp_gnn/lsp_gnn/scripts/train.py create mode 100644 modules/lsp_gnn/lsp_gnn/utils.py create mode 100644 modules/lsp_gnn/scratch/Makefile.mk create mode 100644 modules/lsp_gnn/scratch/info_planner.py create mode 100644 modules/lsp_gnn/scratch/info_util.py create mode 100644 modules/lsp_gnn/scratch/learning/models/cnn_lsp.py create mode 100644 modules/lsp_gnn/scratch/learning/models/gcn.py create mode 100644 modules/lsp_gnn/scratch/plotting.py create mode 100644 modules/lsp_gnn/scratch/scripts/lsp_cond_clip.py create mode 100644 modules/lsp_gnn/scratch/scripts/lsp_cond_eval_gcn.py create mode 100644 modules/lsp_gnn/scratch/scripts/lsp_cond_evaluate.py create mode 100644 modules/lsp_gnn/scratch/test_lsp_cond_plotting.py create mode 100644 modules/lsp_gnn/scratch/utils.py create mode 100644 modules/lsp_gnn/setup.py create mode 100644 modules/lsp_gnn/tests/test_j_env.py create mode 100644 modules/lsp_gnn/tests/test_lsp_gnn_planners.py create mode 100644 modules/lsp_gnn/tests/test_parallel_env.py create mode 100644 modules/lsp_select/Makefile.mk create mode 100644 modules/lsp_select/README.md create mode 100644 modules/lsp_select/lsp_select/__init__.py create mode 100644 modules/lsp_select/lsp_select/learning/__init__.py create mode 100644 modules/lsp_select/lsp_select/learning/models/__init__.py create mode 100644 modules/lsp_select/lsp_select/learning/models/cyclegan.py create mode 100644 modules/lsp_select/lsp_select/offline_replay.py create mode 100644 modules/lsp_select/lsp_select/planners/__init__.py create mode 100644 modules/lsp_select/lsp_select/planners/cyclegan_planner.py create mode 100644 modules/lsp_select/lsp_select/planners/policy_selection.py create mode 100644 modules/lsp_select/lsp_select/scratch/Makefile.mk create mode 100644 modules/lsp_select/lsp_select/scratch/models/laser_lsp.py create mode 100644 modules/lsp_select/lsp_select/scratch/planners/subgoal_planner.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/cyclegan_data_gen.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_cost_dist.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost_gen.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_estimated_cost.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_nav_cost_data.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_threshold.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_laser_maze_eval.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection_eval.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_eval.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_results.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_delta_eval.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_eval.py create mode 100644 modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_lb_eval.py create mode 100644 modules/lsp_select/lsp_select/scratch/tests/test_cost_distribution.py create mode 100644 modules/lsp_select/lsp_select/scratch/utils/delta_cost.py create mode 100644 modules/lsp_select/lsp_select/scratch/utils/distribution.py create mode 100644 modules/lsp_select/lsp_select/scratch/utils/learning_laser.py create mode 100644 modules/lsp_select/lsp_select/scripts/__init__.py create mode 100644 modules/lsp_select/lsp_select/scripts/lsp_offline_replay_costs.py create mode 100644 modules/lsp_select/lsp_select/scripts/lsp_offline_replay_demo.py create mode 100644 modules/lsp_select/lsp_select/scripts/lsp_policy_selection_results.py create mode 100644 modules/lsp_select/lsp_select/scripts/lsp_vis_gen_data.py create mode 100644 modules/lsp_select/lsp_select/utils/__init__.py create mode 100644 modules/lsp_select/lsp_select/utils/misc.py create mode 100644 modules/lsp_select/lsp_select/utils/plotting.py create mode 100644 modules/lsp_select/setup.py create mode 100644 modules/lsp_select/tests/conftest.py create mode 100644 modules/lsp_select/tests/test_lsp_cyclegan.py create mode 100644 modules/lsp_select/tests/test_maze_navigation.py create mode 100644 modules/lsp_select/tests/test_offline_replay.py create mode 100644 modules/lsp_xai/Makefile.mk create mode 100644 modules/lsp_xai/README.md create mode 100644 modules/lsp_xai/lsp_xai/__init__.py create mode 100644 modules/lsp_xai/lsp_xai/learning/__init__.py create mode 100644 modules/lsp_xai/lsp_xai/learning/models.py create mode 100644 modules/lsp_xai/lsp_xai/planners/__init__.py create mode 100644 modules/lsp_xai/lsp_xai/planners/evaluate.py create mode 100644 modules/lsp_xai/lsp_xai/planners/explanation.py create mode 100644 modules/lsp_xai/lsp_xai/planners/known_subgoal_planner.py create mode 100644 modules/lsp_xai/lsp_xai/planners/subgoal_planner.py create mode 100644 modules/lsp_xai/lsp_xai/scripts/__init__.py create mode 100644 modules/lsp_xai/lsp_xai/scripts/explainability_results.py create mode 100644 modules/lsp_xai/lsp_xai/scripts/explainability_train_eval.py create mode 100644 modules/lsp_xai/lsp_xai/scripts/interpret_datum.py create mode 100755 modules/lsp_xai/lsp_xai/scripts/run.sh create mode 100644 modules/lsp_xai/lsp_xai/utils/__init__.py create mode 100644 modules/lsp_xai/lsp_xai/utils/data.py create mode 100644 modules/lsp_xai/lsp_xai/utils/plotting.py create mode 100644 modules/lsp_xai/resources/xai-example-explanation.jpg create mode 100644 modules/lsp_xai/setup.py create mode 100644 modules/lsp_xai/tests/conftest.py create mode 100644 modules/lsp_xai/tests/test_lsp_xai.py create mode 100644 modules/mrlsp/Makefile.mk create mode 100644 modules/mrlsp/README.md create mode 100644 modules/mrlsp/mrlsp/__init__.py create mode 100644 modules/mrlsp/mrlsp/core.py create mode 100644 modules/mrlsp/mrlsp/planners/__init__.py create mode 100644 modules/mrlsp/mrlsp/planners/lsp_baseline.py create mode 100644 modules/mrlsp/mrlsp/planners/mrlsp_planner.py create mode 100644 modules/mrlsp/mrlsp/planners/optimistic.py create mode 100644 modules/mrlsp/mrlsp/planners/planner.py create mode 100644 modules/mrlsp/mrlsp/planners/planning_loop.py create mode 100644 modules/mrlsp/mrlsp/pouct.py create mode 100644 modules/mrlsp/mrlsp/scripts/__init__.py create mode 100644 modules/mrlsp/mrlsp/scripts/simulation_baseline.py create mode 100644 modules/mrlsp/mrlsp/scripts/simulation_lsp.py create mode 100644 modules/mrlsp/mrlsp/scripts/simulation_mrlsp.py create mode 100644 modules/mrlsp/mrlsp/scripts/simulation_optimistic.py create mode 100644 modules/mrlsp/mrlsp/utils/__init__.py create mode 100644 modules/mrlsp/mrlsp/utils/plotting.py create mode 100644 modules/mrlsp/mrlsp/utils/utility.py create mode 100644 modules/mrlsp/setup.py create mode 100644 modules/mrlsp/tests/dummy_frontier.py create mode 100644 modules/mrlsp/tests/test_core_utility_functions.py create mode 100644 modules/mrlsp/tests/test_cpp_state_constructor.py create mode 100644 modules/mrlsp/tests/test_more_robots_frontiers.py create mode 100644 modules/mrlsp/tests/test_mrlsp_using_true_values.py create mode 100644 modules/mrlsp/tests/test_two_timestamp_action.py create mode 100644 modules/mrlsp/tests/util_function.py create mode 100644 modules/mrlsp_accel/CMakeLists.txt create mode 100644 modules/mrlsp_accel/README.md create mode 100644 modules/mrlsp_accel/setup.py create mode 100644 modules/mrlsp_accel/src/core.hpp create mode 100644 modules/mrlsp_accel/src/main.cpp create mode 100644 modules/mrlsp_accel/src/mrlsp_utility.hpp create mode 100644 modules/mrlsp_accel/src/pouct.hpp create mode 100644 modules/requirements.txt create mode 100644 modules/setup.cfg create mode 100644 modules/unitybridge/setup.py create mode 100644 modules/unitybridge/tests/test_unitybridge.py create mode 100644 modules/unitybridge/unitybridge/__init__.py create mode 100644 modules/unitybridge/unitybridge/unity_bridge.py create mode 100644 modules/vertexnav/Makefile.mk create mode 100644 modules/vertexnav/README.org create mode 100644 modules/vertexnav/setup.py create mode 100644 modules/vertexnav/tests/test_mvmp.py create mode 100644 modules/vertexnav/tests/test_navigation.py create mode 100644 modules/vertexnav/tests/test_noisy_navigation.py create mode 100644 modules/vertexnav/tests/test_noisy_vertex_nav.py create mode 100644 modules/vertexnav/tests/test_vertexnav.py create mode 100644 modules/vertexnav/tests/test_vertexnav_data.py create mode 100644 modules/vertexnav/tests/test_vertexnav_environments.py create mode 100644 modules/vertexnav/tests/test_vertexnav_slam.py create mode 100644 modules/vertexnav/vertexnav/__init__.py create mode 100644 modules/vertexnav/vertexnav/environments/__init__.py create mode 100644 modules/vertexnav/vertexnav/environments/dungeon.py create mode 100644 modules/vertexnav/vertexnav/environments/real.py create mode 100644 modules/vertexnav/vertexnav/environments/simulated.py create mode 100644 modules/vertexnav/vertexnav/learning.py create mode 100644 modules/vertexnav/vertexnav/models.py create mode 100644 modules/vertexnav/vertexnav/noisy.py create mode 100644 modules/vertexnav/vertexnav/planning.py create mode 100644 modules/vertexnav/vertexnav/plotting.py create mode 100644 modules/vertexnav/vertexnav/prob_vertex_graph.py create mode 100644 modules/vertexnav/vertexnav/robot.py create mode 100644 modules/vertexnav/vertexnav/scripts/__init__.py create mode 100644 modules/vertexnav/vertexnav/scripts/eval_simulated.py create mode 100644 modules/vertexnav/vertexnav/scripts/gen_vertex_training_data_sim.py create mode 100644 modules/vertexnav/vertexnav/scripts/train_vertex_nav_net.py create mode 100644 modules/vertexnav/vertexnav/utils/__init__.py create mode 100644 modules/vertexnav/vertexnav/utils/calc.py create mode 100644 modules/vertexnav/vertexnav/utils/convert.py create mode 100644 modules/vertexnav/vertexnav/utils/data.py create mode 100644 modules/vertexnav/vertexnav/utils/topology.py create mode 100644 modules/vertexnav/vertexnav/vertex_graph.py create mode 100644 modules/vertexnav/vertexnav/world.py create mode 100644 modules/vertexnav_accel/CMakeLists.txt create mode 100644 modules/vertexnav_accel/README.org create mode 100644 modules/vertexnav_accel/setup.cfg create mode 100644 modules/vertexnav_accel/setup.py create mode 100755 modules/vertexnav_accel/src/Hungarian/Hungarian.cpp create mode 100755 modules/vertexnav_accel/src/Hungarian/Hungarian.h create mode 100755 modules/vertexnav_accel/src/Hungarian/LICENSE create mode 100755 modules/vertexnav_accel/src/Hungarian/README.txt create mode 100755 modules/vertexnav_accel/src/Hungarian/license.txt create mode 100755 modules/vertexnav_accel/src/Hungarian/makefile create mode 100755 modules/vertexnav_accel/src/Hungarian/testMain.cpp create mode 100644 modules/vertexnav_accel/src/cgal_ex.cpp create mode 100644 modules/vertexnav_accel/src/cgal_ex.hpp create mode 100644 modules/vertexnav_accel/src/main.cpp create mode 100644 modules/vertexnav_accel/src/noisy.cpp create mode 100644 modules/vertexnav_accel/src/noisy.hpp create mode 100644 modules/vertexnav_accel/src/pose.cpp create mode 100644 modules/vertexnav_accel/src/pose.hpp create mode 100644 modules/vertexnav_accel/src/types.hpp create mode 100644 modules/vertexnav_accel/src/vertex_graph.cpp create mode 100644 modules/vertexnav_accel/src/vertex_graph.hpp create mode 100644 modules/vertexnav_accel/tests/test_gapnav_accel.py create mode 100644 resources/images/RAIL-group-logo-flat.jpg create mode 100755 resources/notebooks/RAIL-onboarding-01-known-space-navigation.ipynb create mode 100644 resources/notebooks/RAIL-onboarding-02-visual-simulator.ipynb create mode 100644 resources/notebooks/environments-playground.ipynb create mode 100644 resources/testing/lsp_xai_maze_0SG.ExpNavVisLSP.pt create mode 100644 resources/testing/lsp_xai_maze_4SG.ExpNavVisLSP.pt diff --git a/.dockerignore b/.dockerignore new file mode 100644 index 0000000..7da0269 --- /dev/null +++ b/.dockerignore @@ -0,0 +1,2 @@ +./data +./resources \ No newline at end of file diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..a7e306e --- /dev/null +++ b/.gitignore @@ -0,0 +1,137 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +pip-wheel-metadata/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +.python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# Other auto-generated files +*.~undo-tree~ + + + +/data/ +/resources/unity/ diff --git a/Dockerfile b/Dockerfile new file mode 100644 index 0000000..0a750a4 --- /dev/null +++ b/Dockerfile @@ -0,0 +1,89 @@ +FROM nvidia/cudagl:11.3.1-devel-ubuntu20.04 + +ENV VIRTUALGL_VERSION 2.5.2 +ARG NUM_BUILD_CORES + +# Install all apt dependencies +RUN apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y tzdata +RUN apt-get update && apt-get install -y software-properties-common +# Add ppa for python3.8 install +RUN apt-add-repository -y ppa:deadsnakes/ppa +RUN apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y --no-install-recommends \ + curl ca-certificates cmake git python3.8 python3.8-dev \ + xvfb libxv1 libxrender1 libxrender-dev gcc-10 g++-10 libgeos-dev \ + libboost-all-dev libcgal-dev ffmpeg python3.8-tk \ + texlive texlive-latex-extra dvipng cm-super \ + libeigen3-dev ninja-build wget + + +# Install VirtualGL +RUN curl -sSL https://downloads.sourceforge.net/project/virtualgl/"${VIRTUALGL_VERSION}"/virtualgl_"${VIRTUALGL_VERSION}"_amd64.deb -o virtualgl_"${VIRTUALGL_VERSION}"_amd64.deb && \ + dpkg -i virtualgl_*_amd64.deb && \ + /opt/VirtualGL/bin/vglserver_config -config +s +f -t && \ + rm virtualgl_*_amd64.deb + + +# Install python dependencies +RUN curl https://bootstrap.pypa.io/get-pip.py -o get-pip.py && python3 get-pip.py && rm get-pip.py +COPY modules/requirements.txt requirements.txt +RUN pip3 install -r requirements.txt +RUN pip3 install torch==2.0.0+cu118 torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118 +RUN pip install torch_geometric -f https://data.pyg.org/whl/torch-2.0.0+cu118.html +RUN pip3 install captum + +# Needed for using matplotlib without a screen +RUN echo "backend: TkAgg" > matplotlibrc + +# Use gcc-10 and g++-10 +RUN update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-10 10 && \ + update-alternatives --install /usr/bin/g++ g++ /usr/bin/g++-10 10 + +# Build GTSAM && Build vertexnav_accel +RUN git clone https://github.com/borglab/gtsam.git && \ + cd gtsam && git checkout tags/4.1.1 && \ + mkdir build && cd build && \ + cmake .. && make -j${NUM_BUILD_CORES} install +COPY modules/vertexnav_accel modules/vertexnav_accel +RUN pip3 install modules/vertexnav_accel + + +# Copy and install the remaining code +COPY modules/conftest.py modules/conftest.py +COPY modules/setup.cfg modules/setup.cfg + +COPY modules/lsp_accel modules/lsp_accel +RUN pip3 install modules/lsp_accel + +COPY modules/common modules/common +RUN pip3 install modules/common +COPY modules/example modules/example +RUN pip3 install modules/example +COPY modules/learning modules/learning +RUN pip3 install modules/learning +COPY modules/gridmap modules/gridmap +RUN pip3 install modules/gridmap +COPY modules/unitybridge modules/unitybridge +RUN pip3 install modules/unitybridge +COPY modules/environments modules/environments +RUN pip3 install modules/environments +COPY modules/vertexnav modules/vertexnav +RUN pip3 install modules/vertexnav +COPY modules/lsp modules/lsp +RUN pip3 install modules/lsp +COPY modules/lsp_xai modules/lsp_xai +RUN pip3 install modules/lsp_xai +COPY modules/lsp_gnn modules/lsp_gnn +RUN pip3 install modules/lsp_gnn +COPY modules/vertexnav_lsp modules/vertexnav_lsp +RUN pip3 install modules/vertexnav_lsp +COPY modules/mrlsp modules/mrlsp +RUN pip3 install modules/mrlsp +COPY modules/mrlsp_accel modules/mrlsp_accel +RUN pip3 install modules/mrlsp_accel +COPY modules/lsp_select modules/lsp_select +RUN pip3 install modules/lsp_select + +# Set up the starting point for running the code +COPY entrypoint.sh /entrypoint.sh +RUN chmod 755 /entrypoint.sh +ENTRYPOINT ["/entrypoint.sh"] diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..4c5a501 --- /dev/null +++ b/LICENSE @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2021 Gregory J. Stein + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..9331446 --- /dev/null +++ b/Makefile @@ -0,0 +1,177 @@ +MAKEFLAGS += --no-print-directory +## ==== Core Arguments and Parameters ==== +MAJOR ?= 0 +MINOR ?= 1 +VERSION = $(MAJOR).$(MINOR) +APP_NAME ?= rail-core +NUM_BUILD_CORES ?= $(shell grep -c ^processor /proc/cpuinfo) + + +# Handle Optional GPU +USE_GPU ?= true +ifeq ($(USE_GPU),true) + DOCKER_GPU_ARG = --gpus all +endif + +# Paths and Key File Names +EXPERIMENT_NAME ?= dbg +RAIL_SIM_VERSION ?= 1.0.0 +RAIL_SIM_DIR ?= $(shell pwd)/resources/unity/ +RAIL_SIM_BASENAME ?= rail_sim + +# Docker args +DISPLAY ?= :0.0 +DATA_BASE_DIR ?= $(shell pwd)/data +RESOURCES_BASE_DIR ?= $(shell pwd)/resources +XPASSTHROUGH ?= false +DOCKER_FILE_DIR = "." +DOCKERFILE = ${DOCKER_FILE_DIR}/Dockerfile +IMAGE_NAME = ${APP_NAME} +DOCKER_CORE_VOLUMES = \ + --env XPASSTHROUGH=$(XPASSTHROUGH) \ + --env DISPLAY=$(DISPLAY) \ + $(DOCKER_GPU_ARG) \ + --volume="$(RAIL_SIM_DIR)/v$(RAIL_SIM_VERSION):/unity/:ro" \ + --volume="$(DATA_BASE_DIR):/data/:rw" \ + --volume="$(RESOURCES_BASE_DIR):/resources/:ro" \ + --volume="$(RESOURCES_BASE_DIR)/notebooks:/notebooks/:rw" \ + --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" +DOCKER_BASE = docker run --init --ipc=host --rm \ + $(DOCKER_ARGS) $(DOCKER_CORE_VOLUMES) \ + ${IMAGE_NAME}:${VERSION} +DOCKER_PYTHON = $(DOCKER_BASE) python3 + + + + +.PHONY: help +help:: + @echo '' + @echo 'Usage: make [TARGET] [EXTRA_ARGUMENTS]' + @echo 'Targets:' + @echo ' help display this help message' + @echo ' build build docker image (incremental)' + @echo ' rebuild build docker image from scratch' + @echo ' kill close all project-related docker containers' + @echo ' test run pytest in docker container' + @echo 'Extra Arguments:' + @echo ' DATA_BASE_DIR [./data] local path to directory for storing data' + @echo ' USE_GPU [true] enable or disable using the GPU' + @echo ' XPASSTHROUGH [false] use the local X server for visualization' + @echo ' PYTEST_FILTER [.py] filter unit tests' + @echo ' DOCKER_ARGS [] extra arguments passed to Docker; -it will enable "interactive mode"' + @echo '' + + +## ==== Helpers for setting up the environment ==== +define arg_check_unity + @echo "DEPRICATION: arg_check_unity no longer required" +endef + +define xhost_activate + @echo "Enabling local xhost sharing:" + @echo " Display: $(DISPLAY)" + @-DISPLAY=$(DISPLAY) xhost + + @-xhost + +endef + +arg-check-unity: + $(call arg_check_unity) +arg-check-data: + @[ "${DATA_BASE_DIR}" ] && true || \ + ( echo "ERROR: Environment variable 'DATA_BASE_DIR' must be set." 1>&2; exit 1 ) +xhost-activate: + $(call xhost_activate) + +unity-simulator-full-name = $(RAIL_SIM_DIR)/v$(RAIL_SIM_VERSION)/$(RAIL_SIM_BASENAME).x86_64 +.PHONY: unity-simulator +unity-simulator: $(unity-simulator-full-name) +UNITY_BASENAME ?= $(RAIL_SIM_BASENAME) +$(unity-simulator-full-name): + @echo "Downloading the Unity simulator" + @mkdir -p $(RAIL_SIM_DIR) + cd $(RAIL_SIM_DIR) \ + && curl -OL https://github.com/RAIL-group/RAIL-group-simulator/releases/download/v$(RAIL_SIM_VERSION)/rail_sim.zip \ + && unzip rail_sim.zip \ + && rm rail_sim.zip + @echo "Unity simulator downloaded and unpacked." + + +## ==== Build targets ==== + +.PHONY: build +build: $(unity-simulator-full-name) + @echo "Building the Docker container" + @docker build -t ${IMAGE_NAME}:${VERSION} \ + --build-arg NUM_BUILD_CORES=$(NUM_BUILD_CORES) \ + -f ./${DOCKERFILE} . + +.PHONY: rebuild +rebuild: + @docker build -t ${IMAGE_NAME}:${VERSION} --no-cache \ + --build-arg NUM_BUILD_CORES=$(NUM_BUILD_CORES) \ + -f ./${DOCKERFILE} . + +.PHONY: kill +kill: + @echo "Closing all running docker containers:" + @docker kill $(shell docker ps -q --filter ancestor=${IMAGE_NAME}:${VERSION}) + +.PHONY: shell +shell: DOCKER_ARGS ?= -it +shell: + @$(DOCKER_BASE) bash + + +## ==== Running tests & cleanup ==== +.PHONY: test +test: DOCKER_ARGS ?= -it +test: PYTEST_FILTER ?= "py" +test: build + @$(call xhost_activate) + @mkdir -p $(DATA_BASE_DIR)/test_logs + @$(DOCKER_PYTHON) \ + -m py.test -vk $(PYTEST_FILTER) \ + -rsx \ + --full-trace \ + --ignore-glob=**/pybind11/* \ + --ignore-glob=**/scratch/* \ + --html=/data/test_logs/report.html \ + --xpassthrough=$(XPASSTHROUGH) \ + --unity-path=/unity/$(UNITY_BASENAME).x86_64 \ + $(TEST_ADDITIONAL_ARGS) \ + /modules/ + +flake8: DOCKER_ARGS = -it --workdir /modules +flake8: build + @echo "Running flake8 format checker..." + @$(DOCKER_BASE) flake8 + @echo "... no formatting issues discovered." + +## ==== Other Targets ==== + +tensorboard: + @docker run -it \ + -p 0.0.0.0:6006:6006 \ + $(DOCKER_CORE_VOLUMES) \ + $(IMAGE_NAME):$(VERSION) tensorboard \ + --logdir /data --host 0.0.0.0 + +notebook: DOCKER_ARGS=-it -p 8888:8888 +notebook: build + @$(DOCKER_BASE) jupyter notebook \ + --notebook-dir=/notebooks \ + --no-browser --allow-root \ + --ip 0.0.0.0 \ + --NotebookApp.token='' --NotebookApp.password='' + + +## ==== Includes ==== +include modules/example/Makefile.mk +include modules/lsp/Makefile.mk +include modules/lsp_xai/Makefile.mk +include modules/vertexnav/Makefile.mk +include modules/lsp_gnn/Makefile.mk +include modules/mrlsp/Makefile.mk +include modules/lsp_select/Makefile.mk + diff --git a/README.md b/README.md new file mode 100644 index 0000000..72681e2 --- /dev/null +++ b/README.md @@ -0,0 +1,52 @@ + +

+ +

+ +Open source software provided by the [Robotic Anticipatory Intelligence & Learning (RAIL) Group](https://cs.gmu.edu/~gjstein/) at George Mason University (PI: Prof. Gregory J. Stein), emphasizing capabilities for long-horizon robot planning under uncertainty. In addition to our algorithmic and theoretical contributions, we provide tools for headless visual simulation and procedural environment generation and additionally tutorials in the form of [Jupyter notebooks](./resources/notebooks) that run inside Docker, providing easy and reproducible access to our tools. + +This repository can reproduce many of the capabilities and results from the following publications from our lab: +1. Gregory J. Stein, Christopher Bradley, and Nicholas Roy. "Learning over Subgoals for Efficient Navigation of Structured, Unknown Environments." In: Conference on Robot Learning (CoRL). 2018. [paper](http://proceedings.mlr.press/v87/stein18a.html), [talk (14 min)](https://youtu.be/4eHdGUoLlpg). Code Module: [`lsp`](./modules/lsp). +2. Gregory J. Stein. "Generating High-Quality Explanations for Navigation in Partially-Revealed Environments." In: Neural Information Processing Systems (NeurIPS). 2021. [paper](https://proceedings.neurips.cc/paper/2021/hash/926ec030f29f83ce5318754fdb631a33-Abstract.html), [video (13 min)](https://youtu.be/rWxHJJMEPFI), [blog post](https://cs.gmu.edu/~gjstein/2021/11/explainable-navigation-under-uncertainty/). Code Module: [`lsp-xai`](./modules/lsp_xai). +3. Gregory J. Stein, Christopher Bradley, Victoria Preston, and Nicholas Roy. "Enabling Topological Planning with Monocular Vision." In: International Conference on Robotics and Automation (ICRA). 2020. [paper](https://arxiv.org/abs/2003.14368), [talk (10 min)](https://youtu.be/UVZ3UcK6MhI). Code Module: [`vertexnav`](./modules/vertexnav). +4. Raihan Islam Arnob and Gregory J. Stein. "Improving Reliable Navigation under Uncertainty via Predictions Informed by Non-Local Information." International Conference on Intelligent Robots and Systems (IROS). 2023. *paper forthcoming*. Code Module: [`lsp_gnn`](./modules/lsp_gnn). +5. Abhish Khanal and Gregory J. Stein. "Learning Augmented, Multi-Robot Long-Horizon Navigation in Partially Mapped Environments". In: International Conference of Robotics and Automation (ICRA). 2023. [paper](https://arxiv.org/abs/2303.16654). Code Module: [`mrlsp`](./modules/mrlsp). +6. Abhishek Paudel and Gregory J. Stein. "Data-Efficient Policy Selection for Navigation in Partial Maps via Subgoal-Based Abstraction." International Conference on Intelligent Robots and Systems (IROS). 2023. [paper](https://arxiv.org/abs/2304.01094). Code Module: [`lsp_select`](./modules/lsp_select). + +See the respective modules for details on each. + +## Getting Started Guide + +Prerequisities: +- Ubuntu 20.04 or greater. +- Docker with the NVIDIA container runtime. Install Docker via [their website](https://docs.docker.com/get-docker/) and the NVIDIA Docker Runtime via [their official GitHub repository](https://github.com/NVIDIA/nvidia-docker#quickstart). +- GNU Make. Provided as part of the `build-essential` package through apt: `sudo apt-get install build-essential` + +Build Steps: +- Clone the repository and `cd` into it. +- Build the Docker container via `make build`. +- [once per system restart] Run `make xhost-activate` to provide the container low-level access to the GPU. + +The following top-level commands are then available: +```bash +# Spin up Jupyter, interactive python notebooks, to run our +# onboarding tutorials and interactive examples. Will build +# the container if necessary. A good starting point. +make notebook + +# Run test code for all modules; will build if necessary. +make test +``` + +Each module---see the list below---provides make targets of their own, often geared towards reproducing results from their respective research publications and contributions. See below and in the module-specific README files for + +### Running Jupyter Notebooks: Tutorials and Demos + +We also provide a handful of [Jupyter notebooks](./resources/notebooks) for interactively running code within the Docker container. The `make notebook` command will spin up a Jupyter environment and provide access to both interactive demos and also a few onboarding tutorials used within our lab. Notebooks allow running algorithmic code and procedural environment generation as well as access to the RAIL Sim visual simulator. On GitHub, the notebooks can also be [viewed in the browser](./resources/notebooks) without downloading or building the code. + +`make notebook` will spin up a Docker container running Jupyter, which can be accessed from the browser at `http://localhost:8888`. + + +### Running Tests + +Each module comes with tests to verify that the provided code is running correctly. The top-level Make target `test` runs all the tests for each module in the repository within the Docker container. Running `make test` will run all tests via `pytest`. To run only a subset of the tests use the `PYTEST_FILTER` argument: e.g., `make test PYTEST_FILTER=lsp` will run only tests containing the string `lsp`. diff --git a/entrypoint.sh b/entrypoint.sh new file mode 100644 index 0000000..ac7e651 --- /dev/null +++ b/entrypoint.sh @@ -0,0 +1,23 @@ +#!/bin/bash +set -e + +# Needed to point the system towards pytorch CUDA +export LD_LIBRARY_PATH=/usr/local/lib/python3.8/dist-packages/torch/lib:$LD_LIBRARY_PATH +export LD_LIBRARY_PATH=/usr/local/lib:$LD_LIBRARY_PATH + + +# Main command +if [ "$XPASSTHROUGH" = true ] +then + echo "Passing through local X server." + $@ +elif nvidia-smi > /dev/null 2>&1 ; then + echo "Using Docker virtual X server (with GPU)." + export VGL_DISPLAY=$DISPLAY + xvfb-run -a --server-num=$((99 + $RANDOM % 10000)) \ + --server-args='-screen 0 640x480x24 +extension GLX +render -noreset' vglrun $@ +else + echo "Using Docker virtual X server (no GPU)." + xvfb-run -a --server-num=$((99 + $RANDOM % 10000)) \ + --server-args='-screen 0 640x480x24' $@ +fi diff --git a/modules/common/common/__init__.py b/modules/common/common/__init__.py new file mode 100644 index 0000000..dabb8c8 --- /dev/null +++ b/modules/common/common/__init__.py @@ -0,0 +1,61 @@ +"""Some shared classes and functions.""" +import math +import numpy as np + + +class Pose(object): + counter = 0 + + def __init__(self, x, y, yaw=0.0): + self.x = x + self.y = y + self.yaw = yaw + self.index = Pose.counter + Pose.counter += 1 + + def __repr__(self): + return "" % (self.x, self.y, self.yaw) + + @staticmethod + def cartesian_distance(pose_a, pose_b): + return math.sqrt( + math.pow(pose_a.x - pose_b.x, 2) + + math.pow(pose_a.y - pose_b.y, 2)) + + def __mul__(self, oth): + return oth.__rmul__(self) + + def __rmul__(self, oth): + """Define transform out = oth*self. This should be the equivalent + of adding an additional pose 'oth' to the current pose 'self'. + This means that, for example, if we have a robot in pose 'self' and + a motion primitive that ends at 'oth' the position of the end of the + motion primitive in the world frame is oth*self. + """ + + try: + x = self.x + math.cos(self.yaw) * oth.x - math.sin( + self.yaw) * oth.y + y = self.y + math.cos(self.yaw) * oth.y + math.sin( + self.yaw) * oth.x + yaw = (self.yaw + oth.yaw) % (2 * math.pi) + return Pose(x, y, yaw) + except AttributeError: + return Pose(oth * self.x, oth * self.y, self.yaw) + else: + raise TypeError(('Type {0} cannot rmul a Pose object.').format( + type(oth).__name__)) + + +def compute_path_length(path): + """Compute the length of a path comprised of poses.""" + + # Convert a list of poses to a numpy array + if type(path) is list: + path = np.array([[p.x, p.y] for p in path]).T + + if path.shape[1] < 2: + return 0 + + # Compute the path length + return np.linalg.norm(path[:, 1:] - path[:, :-1], axis=0).sum() diff --git a/modules/common/setup.py b/modules/common/setup.py new file mode 100644 index 0000000..5b8a0fb --- /dev/null +++ b/modules/common/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='common', + version='1.0.0', + description='Some shared resources for RAIL-core', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=[]) diff --git a/modules/common/tests/test_common_pose.py b/modules/common/tests/test_common_pose.py new file mode 100644 index 0000000..1bf5c73 --- /dev/null +++ b/modules/common/tests/test_common_pose.py @@ -0,0 +1,107 @@ +"""Some simple tests for the shared Pose class""" + +import math +import pytest + +from common import Pose, compute_path_length + + +def test_pose_core(): + pose_a = Pose(x=1, y=2) + assert pose_a.x == pytest.approx(1) + assert pose_a.y == pytest.approx(2) + assert pose_a.yaw == pytest.approx(0) + + pose_b = Pose(3, 5.5) + assert pose_b.x == pytest.approx(3) + assert pose_b.y == pytest.approx(5.5) + assert pose_b.yaw == pytest.approx(0) + + pose_c = Pose(8.75, 5, yaw=2.2) + assert pose_c.x == pytest.approx(8.75) + assert pose_c.y == pytest.approx(5) + assert pose_c.yaw == pytest.approx(2.2) + + assert Pose.cartesian_distance(pose_a, Pose(1, 5)) == pytest.approx(3) + assert Pose.cartesian_distance(pose_a, Pose(1, 5, 0.1)) == pytest.approx(3) + assert Pose.cartesian_distance(pose_a, Pose(5, 2, 0.1)) == pytest.approx(4) + assert Pose.cartesian_distance(pose_a, + Pose(2, 1, + 0.1)) == pytest.approx(math.sqrt(2)) + + +def test_pose_composition_no_yaw(): + """Test that we can combine pose objects (no yaw).""" + + pose_a = Pose(x=1, y=2) + pose_b = Pose(x=3, y=5.5) + + pose_aa = pose_a * pose_a + pose_ab = pose_a * pose_b + pose_ba = pose_b * pose_a + + assert pose_aa.x == pytest.approx(2) + assert pose_aa.y == pytest.approx(4) + assert pose_aa.yaw == pytest.approx(0) + assert Pose.cartesian_distance(pose_aa, Pose(2, 4)) == pytest.approx(0) + + assert pose_ab.x == pytest.approx(4) + assert pose_ab.y == pytest.approx(7.5) + assert pose_ab.yaw == pytest.approx(0) + assert Pose.cartesian_distance(pose_ab, Pose(4, 7.5)) == pytest.approx(0) + + assert pose_ba.x == pytest.approx(4) + assert pose_ba.y == pytest.approx(7.5) + assert pose_ba.yaw == pytest.approx(0) + assert Pose.cartesian_distance(pose_ba, Pose(4, 7.5)) == pytest.approx(0) + + +def test_pose_composition_with_yaw(): + """Test that we can combine pose objects (no yaw).""" + + pose_a = Pose(x=1, y=2, yaw=math.pi) + pose_b = Pose(x=3, y=5.5, yaw=math.pi / 2) + + # Applying a twice gets us back to the origin + pose_aa = pose_a * pose_a + assert pose_aa.x == pytest.approx(0) + assert pose_aa.y == pytest.approx(0) + assert (pose_aa.yaw == pytest.approx(0) or pose_aa.yaw == pytest.approx(2 * math.pi)) + + # First b, then a (we left-multiply transforms) + pose_ab = pose_a * pose_b + assert pose_ab.x == pytest.approx(pose_b.x - pose_a.y) + assert pose_ab.y == pytest.approx(pose_b.y + pose_a.x) + assert (pose_ab.yaw == pytest.approx(3 * math.pi / 2) + or pose_ab.yaw == pytest.approx(- math.pi / 2)) + + # First a, then b (we left-multiply transforms) + pose_ba = pose_b * pose_a + assert pose_ba.x == pytest.approx(pose_a.x - pose_b.x) + assert pose_ba.y == pytest.approx(pose_a.y - pose_b.y) + assert (pose_ba.yaw == pytest.approx(3 * math.pi / 2) + or pose_ba.yaw == pytest.approx(- math.pi / 2)) + + +def test_compute_pose_path_length(): + pose_a = Pose(0, 0) + pose_b = Pose(3, 4) + pose_c = Pose(7, 7) + + path_len_a = compute_path_length([pose_a]) + assert path_len_a == pytest.approx(0) + + path_len_aa = compute_path_length([pose_a, pose_a]) + assert path_len_aa == pytest.approx(0) + + path_len_bb = compute_path_length([pose_b, pose_b]) + assert path_len_bb == pytest.approx(0) + + path_len_ab = compute_path_length([pose_a, pose_b]) + assert path_len_ab == pytest.approx(5) + + path_len_aba = compute_path_length([pose_a, pose_b, pose_a]) + assert path_len_aba == pytest.approx(10) + + path_len_abc = compute_path_length([pose_a, pose_b, pose_c]) + assert path_len_abc == pytest.approx(10) diff --git a/modules/conftest.py b/modules/conftest.py new file mode 100644 index 0000000..b1b320b --- /dev/null +++ b/modules/conftest.py @@ -0,0 +1,31 @@ +import os.path +import pytest + + +def pytest_addoption(parser): + """Shared command line options for pytest.""" + parser.addoption("--xpassthrough", default="false", action="store") + parser.addoption("--unity-path", default=None, action="store") + parser.addoption("--lsp-xai-maze-net-0SG-path", default=None, action="store") + parser.addoption("--lsp-select-network-file", default=None, action="store") + parser.addoption("--lsp-select-generator-network-file", default=None, action="store") + + +@pytest.fixture() +def do_debug_plot(pytestconfig): + if pytestconfig.getoption("xpassthrough") == 'true': + return True + + return False + + +@pytest.fixture() +def unity_path(pytestconfig): + unity_path_str = pytestconfig.getoption("unity_path") + if unity_path_str is None: + pytest.skip("Unity path not provided") + + if not os.path.exists(unity_path_str): + raise ValueError(f"Unity path '{unity_path_str}' does not exist.") + + return unity_path_str diff --git a/modules/environments/README.md b/modules/environments/README.md new file mode 100644 index 0000000..efa2fa2 --- /dev/null +++ b/modules/environments/README.md @@ -0,0 +1,3 @@ +# Environments: Tools for Procedural Environment Generation and Loading + +This module manages many of the common environments we use in our simulated experiments, focusing on navigation through building-like spaces. The module is best explained by example, for which we refer to the Jupyter notebook [showcasing some generated environments from this module](../../resources/notebooks/environments-playground.ipynb). diff --git a/modules/environments/environments/__init__.py b/modules/environments/environments/__init__.py new file mode 100644 index 0000000..2fc9416 --- /dev/null +++ b/modules/environments/environments/__init__.py @@ -0,0 +1,5 @@ +from . import generate # noqa +from . import world # noqa +from . import simulated # noqa +from . import utils # noqa +from . import office2 # noqa diff --git a/modules/environments/environments/base_generator.py b/modules/environments/environments/base_generator.py new file mode 100644 index 0000000..37de7ab --- /dev/null +++ b/modules/environments/environments/base_generator.py @@ -0,0 +1,67 @@ +import math +import numpy as np +import random + +from common import Pose +from gridmap.utils import inflate_grid +from gridmap.constants import COLLISION_VAL + + +class MapGenBase(object): + def __init__(self, args): + self.grid = None + self.hr_grid = None + self._inflated_mask = None + self.resolution_m = 1.0 + self.pose_gen_counter = 0 + self.args = args + self.map_counter = 0 + self.descriptor = '' + + def gen_map(self, random_seed=None): + pass + + def get_start_goal_poses(self, min_separation=1, max_separation=1e10): + """Loop through the points in the grid and get a pair of poses, subject to a certain condition. + Returns: + did_succeed (Bool) + robot_pose (Pose) + goal_pose (Pose)""" + # If the inflated grid has not been generated, generate it + if self._inflated_mask is None: + planning_resolution = self.args.base_resolution * self.args.planning_downsample_factor + inflation_radius = self.args.inflation_radius_m / planning_resolution + self._inflated_mask = inflate_grid( + self.grid, + inflation_radius=inflation_radius, + collision_val=COLLISION_VAL) < 1 + + # Now sample a random point + allowed_indices = np.where(self._inflated_mask) + + counter = 0 + while True and counter < 2000: + idx_start = random.randint(0, allowed_indices[0].size - 1) + idx_goal = random.randint(0, allowed_indices[0].size - 1) + start = Pose(x=allowed_indices[0][idx_start], + y=allowed_indices[1][idx_start], + yaw=0) + + goal = Pose(x=allowed_indices[0][idx_goal], + y=allowed_indices[1][idx_goal], + yaw=0) + + # Confirm that the poses are in 'allowed' cells + if not self._inflated_mask[ + start.x, start.y] or not self._inflated_mask[goal.x, + goal.y]: + continue + + dist = math.sqrt( + math.pow(start.x - goal.x, 2) + math.pow(start.y - goal.y, 2)) + if dist >= min_separation and dist <= max_separation: + return (True, start, goal) + + counter += 1 + + return (False, None, None) diff --git a/modules/environments/environments/clutter_generator.py b/modules/environments/environments/clutter_generator.py new file mode 100644 index 0000000..f187771 --- /dev/null +++ b/modules/environments/environments/clutter_generator.py @@ -0,0 +1,240 @@ +# from .env_generation_base import * +import cv2 +import math +import numpy as np +import random +import scipy.ndimage +from gridmap.utils import inflate_grid + +L_TMP = 100 +L_UNSET = -1 +L_BKD = 0 +L_CLUTTER = 1 +L_DOOR = 2 +L_HALL = 3 +L_ROOM = 4 +L_UNK = 5 + + +def get_room_orientation(labels, room_label): + is_room = labels == room_label + nonzero_x = np.where(np.amax(is_room, axis=1)) + nonzero_y = np.where(np.amax(is_room, axis=0)) + + xm = max(nonzero_x[0][0] - 1, 0) + xM = min(nonzero_x[0][-1] + 2, labels.shape[0]) + ym = max(nonzero_y[0][0] - 1, 0) + yM = min(nonzero_y[0][-1] + 2, labels.shape[1]) + sub_is_room = is_room[xm:xM, ym:yM] + + try: + from MinimumBoundingBox import MinimumBoundingBox + + coords = np.where(sub_is_room) + coords = tuple(zip(*coords)) + bounding_rect = MinimumBoundingBox(coords) + angle = (bounding_rect.unit_vector_angle + math.pi / 8) % ( + math.pi / 4 + ) - math.pi / 8 + return (angle, 1) + except: # noqa: E722 + return (0.0, 0) + + +def add_clutter_to_room( + labels, + grid, + room_label, + inflation_radius_m, + resolution_m, + do_insert_central_clutter, + num_wall_clutter, + rmat, +): + is_room = labels == room_label + nonzero_x = np.where(np.amax(is_room, axis=1)) + nonzero_y = np.where(np.amax(is_room, axis=0)) + + xm = max(nonzero_x[0][0] - 1, 0) + xM = min(nonzero_x[0][-1] + 2, labels.shape[0]) + ym = max(nonzero_y[0][0] - 1, 0) + yM = min(nonzero_y[0][-1] + 2, labels.shape[1]) + + sub_grid_labels = labels[xm:xM, ym:yM] + sub_grid = grid[xm:xM, ym:yM] + + inflation_radius = inflation_radius_m / resolution_m + inflated_door_sub_grid = inflate_grid(sub_grid, inflation_radius, L_DOOR) + + # Inflate doors + sub_grid_not_near_door = np.logical_not(inflated_door_sub_grid) + + # Try to add a bit of furnature + fw = int(round(1.5 / resolution_m)) + fh = int(round(1.0 / resolution_m)) + counter = 0 + + # Add furnature anywhere in the room + while counter < 300 and do_insert_central_clutter: + counter += 1 + trial = np.zeros([xM - xm, yM - ym]) + xr = random.randint(0, xM - xm) + yr = random.randint(0, yM - ym) + + pts = np.array([[0, 0], [fw, 0], [fw, fh], [0, fh]]) + pts = np.matmul(rmat, pts.T).T + np.array([[xr, yr]]) + pts = np.round(pts).astype(int) + cv2.fillPoly(trial, [pts], 1) + + try: + is_touching_room = np.logical_and( + trial == 1, sub_grid_labels == room_label + ).any() + is_outside_room = np.logical_and( + trial == 1, sub_grid_labels != room_label + ).any() + is_near_door = np.logical_and(trial == 1, sub_grid_not_near_door == 0).any() + if is_touching_room and not is_outside_room and not is_near_door: + # Success! Add the furnature + labels[xm:xM, ym:yM][trial == 1] = 0 + grid[xm:xM, ym:yM][trial == 1] = L_CLUTTER + break + except: # noqa: E722 + pass + + # Now add some clutter near the walls + clutter_counter = 0 + while counter < 25 * num_wall_clutter: + counter += 1 + trial = np.zeros([xM - xm, yM - ym]) + + fw = int(round(0.35 / resolution_m)) + fh = int(round(0.35 / resolution_m)) + + xr = random.randint(0, xM - xm) + yr = random.randint(0, yM - ym) + + pts = np.array([[0, 0], [fw, 0], [fw, fh], [0, fh]]) + pts = np.matmul(rmat, pts.T).T + np.array([[xr, yr]]) + pts = np.round(pts).astype(int) + cv2.fillPoly(trial, [pts], 1) + + # If all of the points are not near a door and at least one of the points is in a wall + is_near_door = np.logical_and(trial == 1, sub_grid_not_near_door == 0).any() + is_touching_room = np.logical_and( + trial == 1, sub_grid_labels == room_label + ).any() + is_touching_wall = np.logical_and(trial == 1, sub_grid_labels == 0).any() + is_in_another_room = np.logical_and( + trial == 1, + np.logical_not( + np.logical_or(sub_grid == L_BKD, sub_grid_labels == room_label) + ), + ).any() + if ( + not is_near_door + and is_touching_wall + and not is_in_another_room + and is_touching_room + ): + # Success! Add the furnature + grid[xm:xM, ym:yM][trial == 1] = L_CLUTTER + clutter_counter += 1 + if clutter_counter >= num_wall_clutter: + break + + +def add_forest( + grid, mask, label=L_CLUTTER, resolution_m=0.04, radius_m=1.4, num_pillars=250 +): + + inflation_radius_m = 1.5 + nonzero_x = np.where(np.amax(mask, axis=1)) + nonzero_y = np.where(np.amax(mask, axis=0)) + + xm = max(nonzero_x[0][0] - 1, 0) + xM = min(nonzero_x[0][-1] + 2, grid.shape[0]) + ym = max(nonzero_y[0][0] - 1, 0) + yM = min(nonzero_y[0][-1] + 2, grid.shape[1]) + + sub_mask = mask[xm:xM, ym:yM] + + inflation_radius = inflation_radius_m / resolution_m + + # Generate pillar circle + rad = radius_m / resolution_m + kernel_size = int(1 + 2 * math.ceil(rad)) + cind = int(math.ceil(rad)) + y, x = np.ogrid[-cind : kernel_size - cind, -cind : kernel_size - cind] + kernel = np.zeros((kernel_size, kernel_size)) + kernel[y * y + x * x <= rad * rad] = 1 + + counter = 0 + trial = np.zeros([xM - xm, yM - ym]) + while counter < num_pillars: + counter += 1 + mid_trial = np.zeros(trial.shape).astype(bool) + xr = random.randint(0, xM - xm - kernel_size) + yr = random.randint(0, yM - ym - kernel_size) + mid_trial[xr : xr + kernel_size, yr : yr + kernel_size] = kernel + + is_inside_room = not np.logical_and(mid_trial, np.logical_not(sub_mask)).any() + inflated_trial = inflate_grid(trial, inflation_radius, 1) + is_overlapping = np.logical_and(mid_trial, inflated_trial).any() + if is_inside_room and not is_overlapping: + trial = np.logical_or(mid_trial, trial) + + grid[xm:xM, ym:yM][trial == 1] = L_CLUTTER + return grid + + +def add_clutter( + grid, + label=L_ROOM, + resolution_m=0.04, + do_insert_central_clutter=True, + num_wall_clutter=6, + rot_deg=None, +): + # Parameter definitions + inflation_radius_m = 1.0 + + # Get rooms after masking by doors + room_grid = grid == label + # Group the rooms into connected components + labels, nb = scipy.ndimage.label(room_grid) + + if rot_deg is None: + angle = 0.0 + angle_count = 0.00001 + # Get the average angle + for ii in range(1, nb + 1): + a, c = get_room_orientation(labels, room_label=ii) + angle += a + angle_count += c + + avg_angle = angle / angle_count + sr = math.sin(avg_angle) + cr = math.cos(avg_angle) + rmat = np.array([[cr, sr], [-sr, cr]]) + else: + avg_angle = (rot_deg - 24.5) * math.pi / 180.0 + sr = math.sin(avg_angle) + cr = math.cos(avg_angle) + rmat = np.array([[cr, sr], [-sr, cr]]) + rmat = np.array([[cr, sr], [-sr, cr]]) + + # Loop through the rooms and add a bit of clutter to each + for ii in range(1, nb + 1): + add_clutter_to_room( + labels, + grid, + room_label=ii, + inflation_radius_m=inflation_radius_m, + resolution_m=resolution_m, + do_insert_central_clutter=do_insert_central_clutter, + num_wall_clutter=num_wall_clutter, + rmat=rmat, + ) + + return grid diff --git a/modules/environments/environments/constants.py b/modules/environments/environments/constants.py new file mode 100644 index 0000000..d08707c --- /dev/null +++ b/modules/environments/environments/constants.py @@ -0,0 +1,9 @@ + +L_TMP = 100 +L_UNSET = -1 +L_BKD = 0 +L_CLUTTER = 1 +L_DOOR = 2 +L_HALL = 3 +L_ROOM = 4 +L_UNK = 5 diff --git a/modules/environments/environments/generate.py b/modules/environments/environments/generate.py new file mode 100644 index 0000000..6b92fb7 --- /dev/null +++ b/modules/environments/environments/generate.py @@ -0,0 +1,85 @@ +"""Primary functions for dispatching map generation.""" +from gridmap.utils import inflate_grid +from gridmap.planning import compute_cost_grid_from_position +import common + + +def _set_default_arguments(args, defaults): + """Helper function to set default auguments for each map. + + Any argument not specified (or None) in the command line will be set as + the default values in their respective environment. + """ + for k, v in defaults.items(): + if not hasattr(args, k) or getattr(args, k) is None: + setattr(args, k, v) + + +def MapGenerator(args): + + if args.map_type.lower() == 'ploader': + from . import pickle_loader + _set_default_arguments(args, pickle_loader.DEFAULT_PARAMETERS) + return pickle_loader.MapGenPLoader(args) + elif args.map_type.lower() == 'maze': + from . import guided_maze + _set_default_arguments(args, guided_maze.DEFAULT_PARAMETERS) + return guided_maze.MapGenMaze(args) + elif args.map_type.lower() == 'office': + from . import office + _set_default_arguments(args, office.DEFAULT_PARAMETERS) + return office.MapGenOffice(args) + elif args.map_type.lower() == 'office2': + from . import office2 + _set_default_arguments(args, office2.DEFAULT_PARAMETERS) + return office2.MapGenOffice2(args) + else: + raise ValueError('Map type "%s" not recognized' % args.map_type) + + +def map_and_poses(args, num_attempts=1000, Pose=common.Pose): + """Helper function that generates a map and feasible start end poses""" + + # Add some extra argumetns + args.map_maze_path_width = 10 + args.map_maze_cell_dims = [8, 6] + args.map_maze_wide_path_width = 14 + args.map_maze_all_wide = True + + # Generate a new map + map_generator = MapGenerator(args) + _, grid, map_data = map_generator.gen_map(random_seed=args.current_seed) + + # Initialize the sensor/robot variables + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_known_grid = inflate_grid(grid, inflation_radius=inflation_radius) + + # Get the poses (ensure they are connected) + for _ in range(num_attempts): + did_succeed, start, goal = map_generator.get_start_goal_poses() + if not did_succeed: + continue + + cost_grid, get_path = compute_cost_grid_from_position( + inflated_known_grid, [goal.x, goal.y]) + did_plan, _ = get_path([start.x, start.y], + do_sparsify=False, + do_flip=False) + if did_plan: + break + else: + raise RuntimeError("Could not find a pair of poses that " + "connect during start/goal pose generation.") + + # A few other post-load-processing operations and arg-setting + if map_data is None: + map_data = dict() + map_data['resolution'] = args.base_resolution + map_data['x_offset'] = 0.0 + map_data['y_offset'] = 0.0 + + if not hasattr(args, 'num_breadcrumb_elements'): + args.num_breadcrumb_elements = 0 + args.breadcrumb_type = None + + return grid, map_data, start, goal diff --git a/modules/environments/environments/guided_maze.py b/modules/environments/environments/guided_maze.py new file mode 100644 index 0000000..773e1fc --- /dev/null +++ b/modules/environments/environments/guided_maze.py @@ -0,0 +1,190 @@ +import math +import numpy as np +import random +import skimage.graph + +from common import Pose +from . import base_generator + +DEFAULT_PARAMETERS = { + 'base_resolution': 0.3, + 'inflation_radius_m': 0.75, + 'laser_max_range_m': 18.0, + 'num_breadcrumb_elements': 2000, +} + + +def gen_map_maze_base(width_cells=7, + height_cells=10, + path_width=10, + wide_path_width=18, + all_wide=False, + random_seed=None): + + # Some parameters + pw = path_width + ww = path_width + 2 + PW = wide_path_width + dPW = (PW - pw) // 2 # Wide path width difference + + assert (PW < ww + pw) + + # Initialize the random generator + random.seed(random_seed) + np.random.seed(random_seed) + + # store parameters + w, h = width_cells, height_cells + + # Initialize the wall and cell objects + v_walls = [(x, y, x + 1, y) for x in range(w - 1) for y in range(h)] + h_walls = [(x, y, x, y + 1) for x in range(w) for y in range(h - 1)] + walls = v_walls + h_walls + cells = [set([(x, y)]) for x in range(w) for y in range(h)] + + # Init the grid + grid = np.zeros([w * 2 - 1, h * 2 - 1]) + grid[::2, ::2] = 1 + + def get_grid_cell(cx, cy): + return np.array([cx * 2, cy * 2]) + + def get_wall_cell(w): + return (get_grid_cell(w[0], w[1]) + get_grid_cell(w[2], w[3])) // 2 + + random.shuffle(walls) + + # Build the maze + for wall in walls: + set_a = None + set_b = None + + for s in cells: + if (wall[0], wall[1]) in s: + set_a = s + if (wall[2], wall[3]) in s: + set_b = s + + if set_a is not set_b: + cells.remove(set_a) + cells.remove(set_b) + cells.append(set_a.union(set_b)) + c = get_wall_cell(wall) + grid[c[0], c[1]] = 1 + + # Turn this into a numpy array + path_grid = grid + path_grid[path_grid == 0] = -1 + start = (2 * random.randint(0, w - 1), 2 * random.randint(0, h - 1)) + end = start + while end == start: + end = (2 * random.randint(0, w - 1), 2 * random.randint(0, h - 1)) + + path, _ = skimage.graph.route_through_array(path_grid, + start, + end, + fully_connected=False) + path = np.array(path).T + + grid[path[0], path[1]] = 2 + + xd = np.ones([2 * w]) * pw + xd[::2] = ww + xd = xd.astype(int) + xp = (np.cumsum(xd) + 0 * ww).astype(int) + + yd = np.ones([2 * h]) * pw + yd[::2] = ww + yd = yd.astype(int) + yp = (np.cumsum(yd) + 0 * ww).astype(int) + + hr_grid = np.zeros([xp[-1] + ww, yp[-1] + ww]) + semantic_grid = np.zeros([xp[-1] + ww, yp[-1] + ww]) + semantic_labels = { + 'wall': 1, + 'hallway': 2, + 'goal_path': 3, + } + + for xx in range(2 * w - 1): + for yy in range(2 * h - 1): + if grid[xx, yy] == 1: + # The path is clear + if all_wide: + hr_grid[xp[xx]:xp[xx] + xd[xx + 1] + dPW, + yp[yy]:yp[yy] + yd[yy + 1] + dPW] = 1 + semantic_grid[xp[xx] - dPW:xp[xx] + xd[xx + 1] + dPW, + yp[yy] - dPW:yp[yy] + yd[yy + 1] + + dPW] = semantic_labels['hallway'] + else: + hr_grid[xp[xx]:xp[xx] + xd[xx + 1], + yp[yy]:yp[yy] + yd[yy + 1]] = 1 + semantic_grid[xp[xx] - dPW:xp[xx] + xd[xx + 1], + yp[yy] - dPW:yp[yy] + + yd[yy + 1]] = semantic_labels['hallway'] + + for xx in range(2 * w - 1): + for yy in range(2 * h - 1): + if grid[xx, yy] == 2: + # The path connects the start and goal + hr_grid[xp[xx] - dPW:xp[xx] + xd[xx + 1] + dPW, + yp[yy] - dPW:yp[yy] + yd[yy + 1] + dPW] = 1 + semantic_grid[xp[xx] - dPW:xp[xx] + xd[xx + 1] + dPW, + yp[yy] - dPW:yp[yy] + yd[yy + 1] + + dPW] = semantic_labels['goal_path'] + + out_grid = np.ones(semantic_grid.shape) + out_grid[semantic_grid == semantic_labels['goal_path']] = 0 + out_grid[semantic_grid == semantic_labels['hallway']] = 0 + + start = [xp[start[0]] + pw // 2, yp[start[1]] + pw // 2] + end = [xp[end[0]] + pw // 2, yp[end[1]] + pw // 2] + + return { + 'occ_grid': out_grid, + 'semantic_grid': semantic_grid, + 'semantic_labels': semantic_labels, + 'start': start, + 'end': end, + 'x_offset': 0.0, + 'y_offset': 0.0, + } + + +class MapGenMaze(base_generator.MapGenBase): + def gen_map(self, random_seed=None): + map_data = gen_map_maze_base( + random_seed=random_seed, + path_width=self.args.map_maze_path_width, + wide_path_width=self.args.map_maze_wide_path_width, + height_cells=self.args.map_maze_cell_dims[0], + width_cells=self.args.map_maze_cell_dims[1], + all_wide=self.args.map_maze_all_wide) + map_data['resolution'] = self.args.base_resolution + + self.hr_grid = map_data['occ_grid'].copy() + self.grid = map_data['occ_grid'].copy() + self.tmp_start = map_data['start'] + self.tmp_goal = map_data['end'] + + return self.hr_grid, self.grid, map_data + + def get_start_goal_poses(self, min_separation=1, max_separation=1e10): + """Loop through the points in the grid and get a pair of poses, subject to a +certain condition. This is a more specific pose generation procedure because we +want to demonstrate the more specific features of this particular map. + + Returns: + did_succeed (Bool) + robot_pose (NamedTuple('PoseT', 'x y yaw')) + goal_pose (NamedTuple('PoseT', 'x y yaw')) + + """ + start = Pose(x=self.tmp_start[0], + y=self.tmp_start[1], + yaw=2 * math.pi * random.random()) + goal = Pose(x=self.tmp_goal[0], + y=self.tmp_goal[1], + yaw=2 * math.pi * random.random()) + + return (True, start, goal) diff --git a/modules/environments/environments/office.py b/modules/environments/environments/office.py new file mode 100644 index 0000000..2d92c2f --- /dev/null +++ b/modules/environments/environments/office.py @@ -0,0 +1,482 @@ +import numpy as np +import random +import scipy.ndimage + +from . import base_generator +from .clutter_generator import add_clutter, add_forest +from .utils import calc + + +GRID_SIZE = 2000 +NUM_HALLWAYS = 10 + +L_TMP = 100 +L_UNSET = -1 +L_BKD = 0 +L_CLUTTER = 1 +L_DOOR = 2 +L_HALL = 3 +L_ROOM = 4 +L_UNK = 5 + +DEFAULT_PARAMETERS = { + 'base_resolution': 0.1, + 'inflation_radius_m': 0.25, + 'planning_downsample_factor': 1, +} + + +class Direction: + def __init__(self, init=None): + if init is not None: + if init + 4 < 0: + raise ValueError("Direction index should not be so far negative.") + self.index = (init + 4) % 4 + else: + self.index = random.randint(0, 3) + + def update_direction(self): + if random.random() >= 0.2: + return + else: + if random.random() >= 0.5: + self.index = (4 + self.index - 1) % 4 + else: + self.index = (4 + self.index + 1) % 4 + + def get_vec(self, offset=0): + val = (self.index + offset + 4) % 4 + if val == 0: + return np.array([1, 0]) + elif val == 1: + return np.array([0, 1]) + elif val == 2: + return np.array([-1, 0]) + elif val == 3: + return np.array([0, -1]) + else: + raise ValueError("Direction.index should never have this value") + + +def downsample_grid(hr_grid, downsample_factor): + grid = scipy.ndimage.maximum_filter(hr_grid, size=downsample_factor) + grid = grid[::downsample_factor, ::downsample_factor] + return grid + + +def initialize_grid(): + return L_UNSET * np.ones([GRID_SIZE, GRID_SIZE]) + + +def fill_region(grid, fill_vec, start_cell, dir_vec, fill_val=L_HALL): + fmx = int(min(start_cell[0], start_cell[0] + fill_vec[0])) + fmy = int(min(start_cell[1], start_cell[1] + fill_vec[1])) + fMx = int(max(start_cell[0], start_cell[0] + fill_vec[0])) + fMy = int(max(start_cell[1], start_cell[1] + fill_vec[1])) + + # Bounds check + if fmx < 0 or fmy < 0 or fMx > grid.shape[0] or fmy > grid.shape[1]: + return False, None + + # Collision check + if fill_val != L_BKD and grid[fmx:fMx, fmy:fMy].max().max() > L_UNSET: + return False, None + + # Fill the region + grid[fmx:fMx, fmy:fMy] = fill_val + + return True, grid + + +def add_hall(grid, start_cell, direction, length, width): + fill_vec = length * direction.get_vec(0) + width * direction.get_vec(1) + did_succeed, grid = fill_region( + grid, fill_vec, start_cell, direction.get_vec(0), fill_val=L_HALL + ) + return did_succeed, grid + + +def create_empty_hallways(grid, resolution, num_hallways=NUM_HALLWAYS): + # Some initializations + current_direction = Direction() + current_cell = np.array([grid.shape[0] / 2, grid.shape[1] / 2]) + + # Add a hallway and get a new cell point + for _ in range(num_hallways): + hall_length = random.randint(int(8 / resolution), int(16 / resolution)) + hall_width = int(round(3.0 / resolution)) + did_succeed, grid = add_hall( + grid, current_cell, current_direction, hall_length, hall_width + ) + + # If adding fails, return failure + if not did_succeed: + return False, None + + # Update the current cell + current_cell += hall_length * current_direction.get_vec(0) + + new_direction = Direction(current_direction.index) + new_direction.update_direction() + + # Update current cell to account for new direction + if new_direction.index != current_direction.index: + current_cell += hall_width * current_direction.get_vec(1) + + current_direction = new_direction + + return True, grid + + +def add_walls(grid, wall_fill_val=L_BKD, space_val=L_HALL): + """This is done with a simple convolution filter""" + kernel = np.ones([3, 3]) + + free_grid_mask = grid == space_val + inflated_mask = scipy.ndimage.filters.convolve( + free_grid_mask, kernel, mode="constant", cval=0 + ) + + grid[np.logical_and(inflated_mask > 0, grid == L_UNSET)] = wall_fill_val + + return grid + + +def create_offices(grid, resolution, num_offices): + for _ in range(num_offices): + # Find a random wall point + idx = np.where(grid == L_BKD) + idx_idx = random.randint(0, idx[0].size - 1) + start_x = idx[0][idx_idx] + start_y = idx[1][idx_idx] + + # Find the direction of the hallway + if grid[start_x + 1, start_y + 0] == L_HALL: + hall_direction = Direction(0) + elif grid[start_x + 0, start_y + 1] == L_HALL: + hall_direction = Direction(1) + elif grid[start_x - 1, start_y + 0] == L_HALL: + hall_direction = Direction(2) + elif grid[start_x + 0, start_y - 1] == L_HALL: + hall_direction = Direction(3) + else: + # Likely a corner point for the wall + continue + + # Some parameters + door_width = int(1.5 / resolution) + office_width = int(random.uniform(7.0, 9.0) / resolution) + office_depth = int(random.uniform(5.0, 7.0) / resolution) + + # Check that the door fits + door_vector = hall_direction.get_vec(1) + door_fits = True + for ii in range(-1, door_width + 1): + if ( + grid[start_x + ii * door_vector[0], start_y + ii * door_vector[1]] + != L_BKD + ): + door_fits = False + if not door_fits: + continue + + # Try to fill the office + office_offset = random.randint(1, office_width - door_width - 1) + fill_vec = office_width * hall_direction.get_vec( + 1 + ) + office_depth * hall_direction.get_vec(2) + start_cell = np.array([start_x, start_y]) + start_cell -= office_offset * hall_direction.get_vec(1) + # Correction for 'lopsided' function + if hall_direction.get_vec(2).max() > 0: + start_cell += hall_direction.get_vec(2) + + did_succeed, new_grid = fill_region( + grid, fill_vec, start_cell, hall_direction, fill_val=L_ROOM + ) + + if not did_succeed: + continue + else: + grid = new_grid + + # Create the door + for ii in range(door_width): + grid[start_x + ii * door_vector[0], start_y + ii * door_vector[1]] = L_DOOR + + # Put walls around the office (temporary label value) + grid = add_walls(grid, wall_fill_val=L_TMP, space_val=L_ROOM) + + # Replace the temporary value with background/wall + grid[grid == L_TMP] = L_BKD + + return grid + + +def gen_map_office(resolution, random_seed=None): + # Initialize the random generator + random.seed(random_seed) + np.random.seed(random_seed) + + # Create the empty hallways + while True: + grid = initialize_grid() + did_succeed, grid = create_empty_hallways(grid, resolution, NUM_HALLWAYS) + if did_succeed: + break + + grid = add_walls(grid, wall_fill_val=L_BKD) + grid = create_offices(grid, resolution, num_offices=400) + + # Trim the edges of the grid + col_max = np.amax(grid, axis=0) + row_max = np.amax(grid, axis=1) + + # Create clutter + grid = add_clutter(grid, resolution_m=resolution) + grid = add_clutter( + grid, + label=L_HALL, + resolution_m=resolution, + do_insert_central_clutter=False, + num_wall_clutter=30, + ) + + grid = grid[row_max > 0, :] + grid = grid[:, col_max > 0] + + # Pad the edges + grid = np.pad(grid, pad_width=2, mode="constant", constant_values=L_UNSET) + + semantic_labels = { + 'background': L_BKD, + 'clutter': L_CLUTTER, + 'door': L_DOOR, + 'hallway': L_HALL, + 'room': L_ROOM, + 'other': L_UNK, + } + + wall_class_index = { + 'hallway': L_HALL, + 'room': L_ROOM, + } + + occupancy_grid = (grid <= L_CLUTTER).astype(float) + + polys, walls = calc.split_semantic_grid_to_polys(occupancy_grid, + grid, + wall_class_index, + resolution, + do_compute_walls=True) + + return { + "occ_grid": (grid <= L_CLUTTER).astype(float), + "semantic_grid": grid.copy(), + "semantic_labels": semantic_labels, + "polygons": polys, + "walls": walls, + "x_offset": 0.0, + "y_offset": 0.0, + } + + +def gen_map_ring(args, ring_height_m=50.0, ring_width_m=50.0, random_seed=None): + # Initialize the random generator + random.seed(random_seed) + np.random.seed(random_seed) + + # Create the empty ring + grid = initialize_grid() + sx = grid.shape[0] // 2 + sy = grid.shape[1] // 2 + resolution = args.base_resolution + hall_width = int(round(3.0 / resolution)) + ring_width = int(round(ring_width_m / resolution)) + ring_height = int(round(ring_height_m / resolution)) + grid[ + sx - hall_width : sx + ring_width + hall_width, + sx - hall_width : sx + ring_height + hall_width, + ] = L_HALL + grid[sx : sx + ring_width, sx : sx + ring_height] = L_UNSET + + # Add walls + grid = add_walls(grid, wall_fill_val=L_BKD) + + # Now, add the center portion and put a temporary wall around it + vest_width = int(round(8 / resolution)) + vest_height = int(round(5 / resolution)) + connect_width = int(round(2.0 / resolution)) + cx = sx + ring_width // 2 + grid[cx - vest_width // 2 : cx + vest_width // 2, sy : sy + vest_height] = L_HALL + grid[ + cx - vest_width // 2 : cx + vest_width // 2, + sy + ring_height - vest_height : sy + ring_height, + ] = L_HALL + grid[ + cx - connect_width // 2 : cx + connect_width // 2, sy : sy + ring_height + ] = L_HALL + + # With a random prob, block the center of the path + do_block = random.random() >= args.map_ring_connection_prob + if do_block is True: + grid[ + cx - connect_width / 2 : cx + connect_width / 2, + sy + ring_height / 2 - 2 : sy + ring_height / 2 + 2, + ] = L_UNSET + + grid = add_walls(grid, wall_fill_val=L_TMP) + + grid = create_offices(grid, args.base_resolution, num_offices=400) + grid[grid == L_TMP] = L_BKD + + # Create clutter + grid = add_clutter( + grid, resolution_m=args.base_resolution / args.planning_downsample_factor + ) + grid = add_clutter( + grid, + label=L_HALL, + resolution_m=args.base_resolution / args.planning_downsample_factor, + do_insert_central_clutter=False, + num_wall_clutter=30, + ) + + # Trim the edges of the grid + col_max = np.amax(grid, axis=0) + row_max = np.amax(grid, axis=1) + grid = grid[row_max > 0, :] + grid = grid[:, col_max > 0] + + # Pad the edges + grid = np.pad(grid, pad_width=2, mode="constant", constant_values=L_UNSET) + + # Create the start goal pose generators (each should generate a PoseT + # NamedTuple that places the pose in a room near one end of the connection + # or the other). + label_grid = grid.copy() + + grid = (grid <= L_CLUTTER).astype(float) + return grid, downsample_grid(grid, args.planning_downsample_factor), label_grid + + +def gen_map_lattice(args, ring_height_m=50.0, ring_width_m=50.0, random_seed=None): + # Initialize the random generator + random.seed(random_seed) + np.random.seed(random_seed) + + # Create the empty ring + grid = initialize_grid() + sx = grid.shape[0] / 2 + sy = grid.shape[1] / 2 + resolution = args.base_resolution + hall_width = int(round(3.0 / resolution)) + wider_hall_width = int(round(5.0 / resolution)) + ring_width = int(round(ring_width_m / resolution)) + ring_height = int(round(ring_height_m / resolution)) + + # Add the 2 main hallways + grid[ + sx - hall_width : sx + ring_width + hall_width, + sx - hall_width : sx + ring_height + hall_width, + ] = L_HALL + grid[ + sx - hall_width : sx + ring_width + hall_width, sx : sx + ring_height + ] = L_UNSET + + # Add walls + grid = add_walls(grid, wall_fill_val=L_BKD) + + # Add a few connecting hallways + nh = 5 + + ri = int(random.random() * nh) + dm = ring_width * 1.0 / (nh - 1) + for ii in range(nh): + cx = int(sx + dm * ii + 0.0 * dm) + if ii == ri: + grid[ + cx - wider_hall_width / 2 : cx + wider_hall_width / 2, + sy : sy + ring_height, + ] = L_HALL + else: + grid[ + cx - hall_width / 2 : cx + hall_width / 2, sy : sy + ring_height + ] = L_HALL + grid[ + cx - hall_width / 2 : cx + hall_width / 2, + sy + ring_height / 2 - 2 : sy + ring_height / 2 + 2, + ] = L_UNSET + + grid = add_walls(grid, wall_fill_val=L_TMP) + + # Trim the edges of the grid + col_max = np.amax(grid, axis=0) + row_max = np.amax(grid, axis=1) + grid = grid[row_max > 0, :] + grid = grid[:, col_max > 0] + + # Pad the edges + grid = np.pad(grid, pad_width=2, mode="constant", constant_values=L_UNSET) + + # Create the start goal pose generators (each should generate a PoseT + # NamedTuple that places the pose in a room near one end of the connection + # or the other). + label_grid = grid.copy() + + grid = (grid <= L_CLUTTER).astype(float) + return grid, downsample_grid(grid, args.planning_downsample_factor), label_grid + + +def gen_map_forest(args, ring_height_m=50.0, ring_width_m=50.0, random_seed=None): + # Initialize the random generator + random.seed(random_seed) + np.random.seed(random_seed) + + # Create the empty ring + grid = initialize_grid() + sx = grid.shape[0] / 2 + resolution = args.base_resolution + ring_width = int(round(ring_width_m / resolution)) + ring_height = int(round(ring_height_m / resolution)) + + # Add some pillars + mask = np.zeros(grid.shape) + mask[sx : sx + ring_width, sx : sx + ring_height] = 2 + grid[mask > 1] = L_ROOM + grid = add_forest( + grid, + mask > 1, + label=L_HALL, + resolution_m=args.base_resolution / args.planning_downsample_factor, + ) + + # Trim the edges of the grid + col_max = np.amax(grid, axis=0) + row_max = np.amax(grid, axis=1) + grid = grid[row_max > 0, :] + grid = grid[:, col_max > 0] + + # Pad the edges + grid = np.pad(grid, pad_width=20, mode="constant", constant_values=L_UNSET) + + # Create the start goal pose generators (each should generate a PoseT + # NamedTuple that places the pose in a room near one end of the connection + # or the other). + label_grid = grid.copy() + + grid = (grid <= L_CLUTTER).astype(float) + return grid, downsample_grid(grid, args.planning_downsample_factor), label_grid + + +class MapGenOffice(base_generator.MapGenBase): + def gen_map(self, random_seed=None): + map_data = gen_map_office( + resolution=self.args.base_resolution, random_seed=random_seed + ) + map_data["resolution"] = self.args.base_resolution + + self.hr_grid = map_data["occ_grid"].copy() + self.grid = map_data["occ_grid"].copy() + + return self.hr_grid, self.grid, map_data diff --git a/modules/environments/environments/office2.py b/modules/environments/environments/office2.py new file mode 100644 index 0000000..68fee57 --- /dev/null +++ b/modules/environments/environments/office2.py @@ -0,0 +1,826 @@ +import numpy as np +from scipy.ndimage import label +import scipy +from skimage.morphology import skeletonize +import sknw + +from . import base_generator +from .utils import calc +from common import Pose +import gridmap +from environments.constants import ( + L_TMP, + L_BKD, + L_CLUTTER, + L_DOOR, + L_HALL, + L_ROOM, + L_UNK +) + + +# default parameters +RESOLUTION = 0.5 # this value yields a reasonable scale of office environment in sim +INFLATION_RADIUS_M = RESOLUTION * 1.5 +LASER_MAX_RANGE_M = 36 * RESOLUTION + +# the default parameters below have units in terms of grid cells +GRID_SIZE = (500, 300) +NUM_OF_HALLWAYS = 5 +BOUNDARY_THRESHOLD = 30 +MIN_SPACING_HALLWAYS = 30 +HALLWAY_WIDTH = 5 +ROOM_WIDTH = 20 +ROOM_LENGTH_RANGE = (25, 35) +ROOM_DOOR_SPACE = 1 +HALLWAY_ROOM_SPACE = 1 +DOOR_SIZE = 8 +MAX_TABLES_PER_ROOM = 2 +TABLE_SIZE_RANGE = (4, 8) +TABLE_WALL_BUFFER = 3 + +DEFAULT_PARAMETERS = { + 'base_resolution': RESOLUTION, + 'inflation_radius_m': INFLATION_RADIUS_M, + 'laser_max_range_m': LASER_MAX_RANGE_M, +} + +semantic_labels = { + 'background': L_BKD, + 'clutter': L_CLUTTER, + 'door': L_DOOR, + 'hallway': L_HALL, + 'room': L_ROOM, + 'other': L_UNK, +} + +wall_class_index = { + 'hallway': L_HALL, + 'room': L_ROOM, +} + + +def generate_random_lines(seed, + num_of_lines=NUM_OF_HALLWAYS, + grid_size=GRID_SIZE, + spacing_between_lines=MIN_SPACING_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + max_iter=10000): + """Generate random horizontal and vertical lines in a grid. + Args: + seed (int): Random seed + num_of_lines (integer): Number of lines + grid_size (tuple): Size of the grid + spacing_between_lines (int): Spacing between two parallel lines + boundary_threshold (int): Minimum spacing between lines and boundary of grid + max_iter (int): Maximum number of iterations to run + Returns: + final_semantic_grid (2D array): Grid with horizontal and vertical lines + line_segments: list of line segments, each segment as ((start_x, start_y), (end_x, end_y)) + """ + np.random.seed(seed) + + def _check_if_connected(semantic_grid, grid): + # 8-neighbor structure/kernel for connected components + s = [[1, 1, 1], + [1, 1, 1], + [1, 1, 1]] + grid[semantic_grid == L_UNK] = 0 + new_grid = 1 - grid.copy() + _, num_features = label(new_grid, structure=s) + if num_features > 1: + return False + else: + return True + + # keep track of the boundaries within which parallel line can't be drawn in row and col + row = set() + col = set() + # space between parallel hallways + space_between_parallel = spacing_between_lines + # lower bound of both x and y + xy_lower_bound = 0 + boundary_threshold + 1 + x_upper_bound = grid_size[0] - boundary_threshold - 1 + y_upper_bound = grid_size[1] - boundary_threshold - 1 + + grid = np.ones(grid_size, dtype=int) + final_semantic_grid = grid.copy() * L_TMP + intermediate_semantic_grid = grid.copy() * L_TMP + line_segments = [] + + for _ in range(max_iter): + # Randomly pick a point that is at a safe distance from the + # boundaries before the inflation + random_point = np.random.randint( + xy_lower_bound, [x_upper_bound, y_upper_bound] + ) + + # finds the distance from every boundaries + distance_to_bounds = [x_upper_bound - random_point[0], + random_point[0] - xy_lower_bound + 1, + random_point[1] - xy_lower_bound + 1, + y_upper_bound - random_point[1]] + + # direction specifies where the line should proceed + direction = np.argmax(distance_to_bounds) + sorted_direction = np.argsort(distance_to_bounds)[::-1] + + for direction in sorted_direction: + + if direction == 0: # Draws from top to bottom (top left is (0,0)) + if random_point[1] in col: + continue + intermediate_semantic_grid[random_point[0]:x_upper_bound + 1, + random_point[1]] = L_UNK + + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[1] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[1] + space_between_parallel + 1, y_upper_bound) + lb_buffer = max( + random_point[0] - space_between_parallel, xy_lower_bound) + + line_segments.append(((random_point[0], random_point[1]), + (x_upper_bound, random_point[1]))) + + col.update(range(lb, ub)) + row.update(range(lb_buffer, random_point[0])) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + elif direction == 1: # Draws from bottom to top + if random_point[1] in col: + continue + intermediate_semantic_grid[xy_lower_bound:random_point[0] + 1, random_point[1]] = L_UNK + + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[1] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[1] + space_between_parallel + 1, y_upper_bound) + ub_buffer = min( + random_point[0] + space_between_parallel, x_upper_bound) + + line_segments.append(((random_point[0], random_point[1]), + (xy_lower_bound, random_point[1]))) + + col.update(range(lb, ub)) + row.update(range(random_point[0], ub_buffer)) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + elif direction == 2: # Draws from right to left + if random_point[0] in row: + continue + intermediate_semantic_grid[random_point[0], xy_lower_bound:random_point[1] + 1] = L_UNK + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[0] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[0] + space_between_parallel + 1, x_upper_bound) + ub_buffer = min( + random_point[1] + space_between_parallel, y_upper_bound) + + line_segments.append(((random_point[0], random_point[1]), + (random_point[0], xy_lower_bound))) + row.update(range(lb, ub)) + col.update(range(random_point[1], ub_buffer)) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + elif direction == 3: # Draws from left to right + if random_point[0] in row: + continue + intermediate_semantic_grid[random_point[0], random_point[1]:y_upper_bound + 1] = L_UNK + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[0] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[0] + space_between_parallel + 1, x_upper_bound) + lb_buffer = max( + random_point[1] - space_between_parallel, xy_lower_bound) + + line_segments.append(((random_point[0], random_point[1]), + (random_point[0], y_upper_bound))) + + row.update(range(lb, ub)) + col.update(range(lb_buffer, random_point[1])) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + if len(line_segments) >= num_of_lines: + break + else: + print(f"Needed to generate {num_of_lines} lines but only generated {len(line_segments)} lines.") + + return final_semantic_grid, line_segments + + +def inflate_lines_to_create_hallways(grid, hallway_inflation_scale=HALLWAY_WIDTH): + """Inflate the lines by a kernel. + Args: + grid (2D array): Grid with lines + hallway_inflation_scale (int): Number pixel to grow in 8-neighbor direction + Returns: + grid_with_hallway (2D array): grid with inflated lines as hallways + """ + original_grid = np.zeros_like(grid) + original_grid[grid == L_UNK] = 1 + kernel_dim = 2 * hallway_inflation_scale + 1 + hallway_inflation_kernel = np.ones((kernel_dim, kernel_dim), dtype=int) + + grid_with_hallway = scipy.ndimage.convolve( + original_grid, hallway_inflation_kernel) + grid_with_hallway[grid_with_hallway > 0] = semantic_labels['hallway'] + grid_with_hallway[grid_with_hallway == 0] = semantic_labels['background'] + + return grid_with_hallway + + +def add_rooms(grid_with_hallway, + line_segments, + hallway_inflation_scale=HALLWAY_WIDTH, + room_b=ROOM_WIDTH, + room_l_range=ROOM_LENGTH_RANGE): + """Add rooms to the hallway grid (along the hallways). + Args: + grid_with_hallway (2D array): Grid with hallways (can contain special rooms too) + line_segments (list): List of line segments corresponding to hallways, + each segment as ((start_x, start_y), (end_x, end_y)) + hallway_inflation_scale (int): Hallway width (same as kernel size used to create hallways from lines) + room_b (int): Width/breadth of room + room_l_range (tuple): Tuple of two integers representing (minimum, maximum) lengths of rooms + Returns: + grid_with_room (2D array): Grid with rooms + rooms_coords (list): List of room coordinates, each coordinate as ((start_x, start_y), (end_x, end_y)) + """ + grid_with_room = grid_with_hallway.copy() + rooms_coords = [] + for line in line_segments: + start, end = line + is_horizontal = start[0] == end[0] + axis = int(is_horizontal) + if start[axis] > end[axis]: + start, end = end, start + + if is_horizontal: + # add rooms on horizontal hallway end points + # end 1 + room_l = np.random.randint(*room_l_range) + room_p1 = (start[0] - int(room_l / 2), start[1] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE) + room_p2 = (room_p1[0] + room_l, room_p1[1] + room_b) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (start[0] - int(DOOR_SIZE / 2), start[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE) + door_p2 = (door_p1[0] + DOOR_SIZE, door_p1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + # end 2 + room_l = np.random.randint(*room_l_range) + room_q1 = (end[0] - int(room_l / 2), end[1] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1) + room_q2 = (room_q1[0] + room_l, room_q1[1] + room_b) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (end[0] - int(DOOR_SIZE / 2), end[1] + hallway_inflation_scale + 1) + door_q2 = (door_q1[0] + DOOR_SIZE, door_q1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + # add rooms along horizontal hallway + for y in range(start[1], end[1] - hallway_inflation_scale, 1): + room_l = np.random.randint(*room_l_range) + room_p1 = (start[0] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE, y) + room_p2 = (room_p1[0] + room_b, room_p1[1] + room_l) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (room_p2[0], room_p2[1] - ROOM_DOOR_SPACE - DOOR_SIZE) + door_p2 = (room_p2[0] + HALLWAY_ROOM_SPACE, room_p2[1] - ROOM_DOOR_SPACE) + # correction for door extending beyond hallway end 2 + door_check_slice = grid_with_room[door_p2[0]:door_p2[0] + 1, door_p1[1]:door_p2[1]] + overflow_len = len(np.where(door_check_slice == semantic_labels['background'])[1]) + if overflow_len > 0: + door_p1 = (room_p1[0] + room_b, room_p1[1] + ROOM_DOOR_SPACE) + door_p2 = (door_p1[0] + HALLWAY_ROOM_SPACE, door_p1[1] + DOOR_SIZE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + room_l = np.random.randint(*room_l_range) + room_q1 = (start[0] + hallway_inflation_scale + 1 + HALLWAY_ROOM_SPACE, y) + room_q2 = (room_q1[0] + room_b, room_q1[1] + room_l) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (room_q1[0] - HALLWAY_ROOM_SPACE, room_q1[1] + ROOM_DOOR_SPACE) + door_q2 = (room_q1[0], room_q1[1] + ROOM_DOOR_SPACE + DOOR_SIZE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + else: + # add rooms on vertical hallway end points + # end 1 + room_l = np.random.randint(*room_l_range) + room_p1 = (start[0] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE, start[1] - int(room_l / 2)) + room_p2 = (room_p1[0] + room_b, room_p1[1] + room_l) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (start[0] - hallway_inflation_scale - HALLWAY_ROOM_SPACE, start[1] - int(DOOR_SIZE / 2)) + door_p2 = (door_p1[0] + HALLWAY_ROOM_SPACE, door_p1[1] + DOOR_SIZE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + # end 2 + room_l = np.random.randint(*room_l_range) + room_q1 = (end[0] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1, end[1] - int(room_l / 2)) + room_q2 = (room_q1[0] + room_b, room_q1[1] + room_l) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (end[0] + hallway_inflation_scale + 1, end[1] - int(DOOR_SIZE / 2)) + door_q2 = (door_q1[0] + HALLWAY_ROOM_SPACE, door_q1[1] + DOOR_SIZE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + # add rooms along vertical hallway + for x in range(start[0], end[0] - hallway_inflation_scale, 1): + room_l = np.random.randint(*room_l_range) + room_p1 = (x, start[1] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE) + room_p2 = (room_p1[0] + room_l, room_p1[1] + room_b) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (room_p2[0] - ROOM_DOOR_SPACE - DOOR_SIZE, room_p2[1]) + door_p2 = (room_p2[0] - ROOM_DOOR_SPACE, room_p2[1] + HALLWAY_ROOM_SPACE) + # correction for door extending beyond hallway end 2 + door_check_slice = grid_with_room[door_p1[0]:door_p2[0], door_p2[1]:door_p2[1] + 1] + overflow_len = len(np.where(door_check_slice == semantic_labels['background'])[0]) + if overflow_len > 0: + door_p1 = (room_p1[0] + ROOM_DOOR_SPACE, room_p1[1] + room_b) + door_p2 = (door_p1[0] + DOOR_SIZE, door_p1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + room_l = np.random.randint(*room_l_range) + room_q1 = (x, start[1] + hallway_inflation_scale + 1 + HALLWAY_ROOM_SPACE) + room_q2 = (room_q1[0] + room_l, room_q1[1] + room_b) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (room_q1[0] + ROOM_DOOR_SPACE, room_q1[1] - HALLWAY_ROOM_SPACE) + door_q2 = (room_q1[0] + ROOM_DOOR_SPACE + DOOR_SIZE, room_q1[1]) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + return grid_with_room, rooms_coords + + +def add_special_rooms(grid_with_hallway, + intersections, + hallway_inflation_scale=HALLWAY_WIDTH, + room_length_range=ROOM_LENGTH_RANGE): + """Add special rooms to the hallway grid wherever possible to connect two hallways. + Args: + grid_with_hallway (2D array): Grid with hallways + intersections (list): List of intersection points + hallway_inflation_scale (int): Hallway width (same as kernel size used to create hallways from lines) + room_l_range (tuple): Tuple of two integers representing (minimum, maximum) lengths of rooms + Returns: + grid_with_sp_room (2D array): Grid with special rooms + rooms_coords (list): List of special room coordinates, each coordinate as ((start_x, start_y), (end_x, end_y)) + """ + def _check_intersection_or_hallway_end(side_point, extended_point): + check_point_start = side_point[0] + check_point_end = side_point[1] + hallway_end_check_start = extended_point[0] + hallway_end_check_end = extended_point[1] + + another_intersection_met, hallway_end = False, False + + if grid_with_sp_room[check_point_start[0], check_point_start[1]] == semantic_labels['hallway']: + another_intersection_met = True + + if grid_with_sp_room[check_point_end[0], check_point_end[1]] == semantic_labels['hallway']: + another_intersection_met = True + + if grid_with_sp_room[hallway_end_check_start[0], hallway_end_check_start[1]] == semantic_labels['background']: + hallway_end = True + if grid_with_sp_room[hallway_end_check_end[0], hallway_end_check_end[1]] == semantic_labels['background']: + hallway_end = True + + return another_intersection_met, hallway_end + + grid_with_sp_room = grid_with_hallway.copy() + intersections = np.round(intersections).astype(int) + intersection_with_distance = [] + for i, inter in enumerate(intersections): + x, y = inter[0], inter[1] + for next_point in intersections[i + 1:]: + if next_point[0] == x or next_point[1] == y: + intersection_with_distance.append( + [[inter, next_point], np.linalg.norm(inter - next_point)]) + intersection_with_distance.sort(key=lambda x: x[1]) + + # if intersection distance less than a certain room size; remove the intersection + min_room_length, max_room_length = room_length_range[0], room_length_range[1] + min_intersection_distance = min_room_length + 3 * hallway_inflation_scale + max_intersection_distance = max_room_length + 5 * hallway_inflation_scale + + intersection_with_distance = [intersection for intersection in intersection_with_distance if ( + intersection[1] >= min_intersection_distance and intersection[1] < max_intersection_distance)] + + rooms_coords = [] + for intersection in intersection_with_distance: + # find whether the line is horizontal or vertical. + start, end = intersection[0] + is_horizontal = start[0] == end[0] + axis = int(is_horizontal) + if start[axis] > end[axis]: + start, end = end, start + distance = {} + if (is_horizontal): + ''' + find the minimum distance along the hallway in which the room can be expanded + in the ascending direction + ''' + another_intersection_met = False + hallway_end = False + distance_ascending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_ascending += 1 + poi_ascending = start[0] + distance_ascending + + check_point_start = [poi_ascending, + start[1] + hallway_inflation_scale + 1] + check_point_end = [poi_ascending, + end[1] - hallway_inflation_scale - 1] + + hallway_end_check_start = [poi_ascending + 1, start[1]] + hallway_end_check_end = [poi_ascending + 1, end[1]] + + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + + distance['ascending'] = distance_ascending + ''' + find the minimum distance along the hallway in which the room can be expanded + in the descending direction + ''' + another_intersection_met = False + hallway_end = False + distance_descending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_descending += 1 + poi_descending = start[0] - distance_descending + + check_point_start = [poi_descending, + start[1] + hallway_inflation_scale + 1] + check_point_end = [poi_descending, + end[1] - hallway_inflation_scale - 1] + + hallway_end_check_start = [poi_descending - 1, start[1]] + hallway_end_check_end = [poi_descending - 1, end[1]] + + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + distance['descending'] = distance_descending + + # Add "special room" in the ascending direction + if distance['ascending'] > max_room_length: + room_p1 = [start[0] + distance['ascending'] - max_room_length, + start[1] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1] + room_p2 = [end[0] + distance['ascending'], end[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE] + room_slice = grid_with_sp_room[room_p1[0] - + 1:room_p2[0] + 1, room_p1[1]:room_p2[1]] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_p1[0]:room_p2[0], + room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add doors + grid_with_sp_room[room_p1[0] + ROOM_DOOR_SPACE:room_p1[0] + ROOM_DOOR_SPACE + DOOR_SIZE, + room_p1[1] - HALLWAY_ROOM_SPACE:room_p1[1]] = semantic_labels['door'] + grid_with_sp_room[room_p2[0] - ROOM_DOOR_SPACE - DOOR_SIZE:room_p2[0] - ROOM_DOOR_SPACE, + room_p2[1]:room_p2[1] + HALLWAY_ROOM_SPACE] = semantic_labels['door'] + + # Add "special room" in the descending direction + if distance['descending'] > max_room_length: + room_q1 = [start[0] - distance['descending'] + 1, start[1] + + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1] + room_q2 = [end[0] - distance['descending'] + max_room_length, + end[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE] + room_slice = grid_with_sp_room[room_q1[0] - + 1:room_q2[0] + 1, room_q1[1]:room_q2[1]] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_q1[0]:room_q2[0], + room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add doors + grid_with_sp_room[room_q1[0] + ROOM_DOOR_SPACE:room_q1[0] + ROOM_DOOR_SPACE + DOOR_SIZE, + room_q1[1] - HALLWAY_ROOM_SPACE:room_q1[1]] = semantic_labels['door'] + grid_with_sp_room[room_q2[0] - ROOM_DOOR_SPACE - DOOR_SIZE:room_q2[0] - ROOM_DOOR_SPACE, + room_q2[1]:room_q2[1] + HALLWAY_ROOM_SPACE] = semantic_labels['door'] + + else: + ''' + find the minimum distance along the hallway in which the room can be expanded + in the ascending direction + ''' + another_intersection_met = False + hallway_end = False + distance_ascending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_ascending += 1 + poi_ascending = start[1] + distance_ascending + check_point_start = [ + start[0] + hallway_inflation_scale + 1, poi_ascending] + check_point_end = [ + end[0] - hallway_inflation_scale - 1, poi_ascending] + + hallway_end_check_start = [start[0], poi_ascending + 1] + hallway_end_check_end = [end[0], poi_ascending + 1] + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + + distance['ascending'] = distance_ascending + ''' + find the minimum distance along the hallway in which the room can be expanded + in the descending direction + ''' + another_intersection_met = False + hallway_end = False + distance_descending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_descending += 1 + poi_descending = start[1] - distance_descending + check_point_start = [ + start[0] + hallway_inflation_scale + 1, poi_descending] + check_point_end = [ + end[0] - hallway_inflation_scale - 1, poi_descending] + + hallway_end_check_start = [start[0], poi_descending - 1] + hallway_end_check_end = [end[0], poi_descending - 1] + + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + distance['descending'] = distance_descending + + # Add "special room" in the ascending direction + if distance['ascending'] > max_room_length: + room_p1 = [start[0] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1, + start[1] + distance['ascending'] - max_room_length] + room_p2 = [end[0] - hallway_inflation_scale - + HALLWAY_ROOM_SPACE, end[1] + distance['ascending'] - 1] + room_slice = grid_with_sp_room[room_p1[0]:room_p2[0], room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_p1[0]:room_p2[0], + room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add doors + grid_with_sp_room[room_p1[0] - HALLWAY_ROOM_SPACE:room_p1[0], + room_p1[1] + ROOM_DOOR_SPACE:room_p1[1] + ROOM_DOOR_SPACE + DOOR_SIZE] = ( + semantic_labels['door']) + grid_with_sp_room[room_p2[0]:room_p2[0] + HALLWAY_ROOM_SPACE, + room_p2[1] - ROOM_DOOR_SPACE - DOOR_SIZE:room_p2[1] - ROOM_DOOR_SPACE] = ( + semantic_labels['door']) + # Add "special room" in the descending direction + if distance['descending'] > max_room_length: + room_q1 = [start[0] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1, + start[1] - distance['descending']] + room_q2 = [end[0] - hallway_inflation_scale - HALLWAY_ROOM_SPACE, + end[1] - distance['descending'] + max_room_length] + room_slice = grid_with_sp_room[room_q1[0] + + 1:room_q2[0] - 1, room_q1[1]:room_q2[1]] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_q1[0]:room_q2[0], + room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add doors + grid_with_sp_room[room_q1[0] - HALLWAY_ROOM_SPACE:room_q1[0], + room_q1[1] + ROOM_DOOR_SPACE:room_q1[1] + ROOM_DOOR_SPACE + DOOR_SIZE] = ( + semantic_labels['door']) + grid_with_sp_room[room_q2[0]:room_q2[0] + HALLWAY_ROOM_SPACE, + room_q2[1] - ROOM_DOOR_SPACE - DOOR_SIZE:room_q2[1] - ROOM_DOOR_SPACE] = ( + semantic_labels['door']) + + return grid_with_sp_room, rooms_coords + + +def add_tables(grid_with_rooms, + rooms_coords, + max_tables_per_room=MAX_TABLES_PER_ROOM, + table_size_range=TABLE_SIZE_RANGE, + table_wall_buffer=TABLE_WALL_BUFFER): + """Add tables to grid with rooms. + Args: + grid_with_rooms (2D array): Grid with rooms + rooms_coords (list): List of all room coordinates, each coordinate as ((start_x, start_y), (end_x, end_y)) + max_tables_per_room (int): Maximum number of tables to per room + table_size_range (tuple): Tuple of two integers representing (minimum, maximum) lengths of tables + table_wall_buffer (int): Minimum spacing between table and room walls + Returns: + grid_with_tables (2D array): Grid with tables + table_poses_sizes (list): List of tuples containing table center coordinates and lengths, + each tuple as (center_x, center_y, length_x, length_y) + """ + grid_with_tables = grid_with_rooms.copy() + table_poses_sizes = [] + for room_p1, room_p2 in rooms_coords: + for _ in range(max_tables_per_room): + size_x, size_y = np.random.choice(np.arange(table_size_range[0], table_size_range[1] + 1, 2), + size=2) + table_x = np.random.randint(room_p1[0] + int(size_x / 2) + table_wall_buffer, + room_p2[0] - int(size_x / 2) - table_wall_buffer) + table_y = np.random.randint(room_p1[1] + int(size_y / 2) + table_wall_buffer, + room_p2[1] - int(size_y / 2) - table_wall_buffer) + table_p1 = (table_x - int(size_x / 2), table_y - int(size_y / 2)) + table_p2 = (table_x + int(size_x / 2), table_y + int(size_y / 2)) + table_slice = grid_with_tables[table_p1[0]:table_p2[0], + table_p1[1]:table_p2[1]] + if not np.any(table_slice == semantic_labels['clutter']): + grid_with_tables[table_p1[0]:table_p2[0], + table_p1[1]:table_p2[1]] = semantic_labels['clutter'] + table_poses_sizes.append((table_x, table_y, size_x, size_y)) + + return grid_with_tables, table_poses_sizes + + +def determine_intersections(hallway_mask): + """Returns a dictionary containing intersection points and deadend points of hallways.""" + sk = skeletonize(hallway_mask) + graph = sknw.build_sknw(sk) + vertex_data = graph.nodes() + counter = {id: 0 + for id in vertex_data} + edges = graph.edges() + for s, e in edges: + counter[s] += 1 + counter[e] += 1 + pendant_vertices = [key + for key in counter + if counter[key] == 1] + intersection_vertices = list(set(vertex_data) - set(pendant_vertices)) + intersections = np.array([vertex_data[i]['o'] + for i in intersection_vertices]) + pendants = np.array([vertex_data[i]['o'] + for i in pendant_vertices]) + return { + 'intersections': intersections, + 'deadends': pendants + } + + +def count_loops_in_hallways(hallway_mask): + # 8-neighbor structure/kernel for connected components + s = [[1, 1, 1], + [1, 1, 1], + [1, 1, 1]] + grid = 1 - hallway_mask + _, num_features = label(grid, s) + return num_features - 1 + + +def gen_map_office2(random_seed, + resolution=RESOLUTION, + grid_size=GRID_SIZE, + num_of_hallways=NUM_OF_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + min_spacing_hallways=MIN_SPACING_HALLWAYS, + hallway_width=HALLWAY_WIDTH, + room_width=ROOM_WIDTH, + room_length_range=ROOM_LENGTH_RANGE): + + grid_with_lines, line_segments = generate_random_lines(seed=random_seed, + grid_size=grid_size, + num_of_lines=num_of_hallways, + spacing_between_lines=min_spacing_hallways, + boundary_threshold=boundary_threshold) + grid_with_hallway = inflate_lines_to_create_hallways(grid_with_lines, + hallway_inflation_scale=hallway_width) + features = determine_intersections(grid_with_hallway == semantic_labels['hallway']) + grid_with_special_rooms, special_rooms_coords = add_special_rooms(grid_with_hallway, + intersections=features['intersections'], + hallway_inflation_scale=hallway_width, + room_length_range=room_length_range) + grid_with_rooms, rooms_coords = add_rooms(grid_with_special_rooms, + line_segments, + hallway_inflation_scale=hallway_width, + room_b=room_width, + room_l_range=room_length_range) + rooms_coords += special_rooms_coords + + occupancy_grid = (grid_with_rooms <= L_CLUTTER).astype(float) + polys, walls = calc.split_semantic_grid_to_polys(occupancy_grid, + grid_with_rooms, + wall_class_index, + resolution=resolution, + do_compute_walls=True) + + grid, table_poses_sizes = add_tables(grid_with_rooms, rooms_coords) + occupancy_grid = (grid <= L_CLUTTER).astype(float) + + return { + "occ_grid": occupancy_grid.copy(), + "semantic_grid": grid.copy(), + "semantic_labels": semantic_labels, + "polygons": polys, + "walls": walls, + "x_offset": 0.0, + "y_offset": 0.0, + "resolution": resolution, + "features": features, + "tables": table_poses_sizes + } + + +class MapGenOffice2(base_generator.MapGenBase): + def gen_map(self, random_seed=None): + self.map_data = gen_map_office2(random_seed, + resolution=self.args.base_resolution, + grid_size=GRID_SIZE, + num_of_hallways=NUM_OF_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + min_spacing_hallways=MIN_SPACING_HALLWAYS, + hallway_width=HALLWAY_WIDTH, + room_width=ROOM_WIDTH, + room_length_range=ROOM_LENGTH_RANGE) + + self.hr_grid = self.map_data["occ_grid"].copy() + self.grid = self.map_data["occ_grid"].copy() + + return self.hr_grid, self.grid, self.map_data + + def get_start_goal_poses(self, min_separation=150, max_separation=1e10, num_attemps=1000): + inflation_radius = self.args.inflation_radius_m / self.args.base_resolution + inflated_grid = gridmap.utils.inflate_grid(self.grid, inflation_radius) + free_cells = np.column_stack(np.where(inflated_grid == gridmap.constants.FREE_VAL)) + for _ in range(num_attemps): + rand_indices = np.random.choice(np.arange(len(free_cells)), size=2, replace=False) + start, goal = free_cells[rand_indices] + cost_grid, _ = gridmap.planning.compute_cost_grid_from_position(inflated_grid, goal) + path_cost = cost_grid[start[0], start[1]] + if path_cost >= min_separation and path_cost <= max_separation: + start = Pose(x=start[0], y=start[1]) + goal = Pose(x=goal[0], y=goal[1]) + return (True, start, goal) + else: + raise RuntimeError("Could not find a pair of poses that " + "connect during start/goal pose generation.") diff --git a/modules/environments/environments/pickle_loader.py b/modules/environments/environments/pickle_loader.py new file mode 100644 index 0000000..72fac1a --- /dev/null +++ b/modules/environments/environments/pickle_loader.py @@ -0,0 +1,127 @@ +import math +import numpy as np +import pickle +import random +import scipy + +from . import base_generator +from common import Pose +from gridmap.constants import COLLISION_VAL + + +def _downsample_grid(hr_grid, downsample_factor): + grid = scipy.ndimage.maximum_filter(hr_grid, size=downsample_factor) + grid = grid[::downsample_factor, ::downsample_factor] + return grid + + +def _inflate_grid_label(grid, inflation_radius, label_val): + """This removes any information about uncertainty; it thresholds the grid + before occupancy_grid + """ + flattened_grid = np.zeros(grid.shape) + flattened_grid[grid == label_val] = 1 + + kernel_size = int(1 + 2 * math.ceil(inflation_radius)) + cind = int(math.ceil(inflation_radius)) + y, x = np.ogrid[-cind:kernel_size - cind, -cind:kernel_size - cind] + kernel = np.zeros((kernel_size, kernel_size)) + kernel[y * y + x * x <= inflation_radius * inflation_radius] = 1 + + inflated_mask = scipy.ndimage.filters.convolve(flattened_grid, + kernel, + mode='constant', + cval=0) + return inflated_mask + + +class MapGenPLoader(base_generator.MapGenBase): + _map_data = None + + def gen_map(self, random_seed=None): + self.args.planning_downsample_factor = 1 + cirriculum_fraction = self.args.cirriculum_fraction + + # Initialize the random generators + random.seed(random_seed) + np.random.seed(random_seed) + + # Simple processing of the loaded grid + if isinstance(self.args.map_file, str): + map_file = self.args.map_file + elif isinstance(self.args.map_file, list): + if cirriculum_fraction is None: + map_file = random.choice(self.args.map_file) + else: + assert cirriculum_fraction > 0.0 + assert cirriculum_fraction <= 1.0 + + map_areas = [] + for mf in self.args.map_file: + with open(mf, 'rb') as pfile: + map_data = pickle.load(pfile) + map_areas.append((mf, map_data['occ_grid'].size)) + + sorted_map_files = [ + md[0] for md in sorted(map_areas, key=lambda x: x[1]) + ] + num_maps = math.ceil(cirriculum_fraction * + (len(sorted_map_files) - 1)) + map_file = random.choice(sorted_map_files[:num_maps]) + else: + raise TypeError("arg 'map_file' must be string or list.") + + with open(map_file, 'rb') as pfile: + self._map_data = pickle.load(pfile) + + self.hr_grid = self._map_data['occ_grid'].copy() + self.grid = _downsample_grid(self.hr_grid, + self.args.planning_downsample_factor) + return self.hr_grid, self.grid, self._map_data + + def get_start_goal_poses(self, min_separation=1, max_separation=1e10): + """Loop through the points in the grid and get a pair of poses, subject to a certain condition. + Returns: + did_succeed (Bool) + robot_pose (NamedTuple('PoseT', 'x y yaw')) + goal_pose (NamedTuple('PoseT', 'x y yaw')) +""" + # If the inflated grid has not been generated, generate it + if self._inflated_mask is None: + planning_resolution = self.args.base_resolution * self.args.planning_downsample_factor + inflation_radius = self.args.inflation_radius_m / planning_resolution + self._inflated_mask = _inflate_grid_label( + self.grid, + inflation_radius=inflation_radius, + label_val=COLLISION_VAL) < 1 + + allowed_indices = np.where(self._inflated_mask) + allowed_indices_start = allowed_indices + allowed_indices_goal = allowed_indices + + counter = 0 + while True and counter < 2000: + idx_start = random.randint(0, allowed_indices_start[0].size - 1) + start = Pose(x=allowed_indices_start[0][idx_start], + y=allowed_indices_start[1][idx_start], + yaw=random.uniform(0, 2 * math.pi)) + + idx_goal = random.randint(0, allowed_indices_goal[0].size - 1) + goal = Pose(x=allowed_indices_goal[0][idx_goal], + y=allowed_indices_goal[1][idx_goal], + yaw=random.uniform(0, 2 * math.pi)) + + # Confirm that the poses are in 'allowed' cells + if not self._inflated_mask[ + start.x, start.y] or not self._inflated_mask[goal.x, + goal.y]: + continue + + dist = math.sqrt( + math.pow(start.x - goal.x, 2) + math.pow(start.y - goal.y, 2)) + if dist >= min_separation and dist <= max_separation: + return (True, start, goal) + + counter += 1 + + return (False, None, None) diff --git a/modules/environments/environments/simulated.py b/modules/environments/environments/simulated.py new file mode 100644 index 0000000..f299743 --- /dev/null +++ b/modules/environments/environments/simulated.py @@ -0,0 +1,266 @@ +import math +import numpy as np +import random +import shapely +import shapely.prepared +import tempfile + +from .utils.calc import obstacles_and_boundary_from_occupancy_grid +from .world import World +from unitybridge import UnityBridge + + +def eucl_dist(p1, p2): + return math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + + +class WorldBuildingUnityBridge(UnityBridge): + """Connection between World object and unity""" + def make_world(self, world, scale=10.0): + self.do_buffer = True + + self.send_message("main_builder floor") + + if hasattr(world, 'map_data') and 'walls' in world.map_data.keys(): + for wall_class in world.map_data['walls'].keys(): + for wall in world.map_data['walls'][wall_class]: + self._make_wall(wall, wall_class) + else: + self._make_obstacles(world, scale) + + if hasattr(world, 'clutter_element_poses'): + for pose in world.clutter_element_poses: + self.create_object(command_name='clutter', + pose=pose, + height=random.random() * 0.5) + + if hasattr(world, 'table_poses_sizes'): + table_pose_sizes = np.array(world.table_poses_sizes) * world.resolution + for x, y, size_x, size_y in table_pose_sizes: + self.send_message(f'main_builder table {x} {y} {size_x} {size_y}', pause=0.001) + + if hasattr(world, 'breadcrumb_element_poses'): + if not hasattr(world, 'breadcrumb_type'): + world.breadcrumb_type = None + if world.breadcrumb_type is None: + breadcrumb_command = 'breadcrumb' + elif isinstance(world.breadcrumb_type, str): + breadcrumb_command = f'breadcrumb_{world.breadcrumb_type}' + else: + raise ValueError('world.breadcrumb_type expected to be str or None. ' + f'Value is: {world.breadcrumb_type}') + for pose in world.breadcrumb_element_poses: + self.create_object(command_name=breadcrumb_command, + pose=pose, + height=random.random() * 0.001) + + if hasattr(world, 'light_poses'): + for x, y in world.light_poses: + self.send_message(f'main_builder light {x * self.sim_scale} {y * self.sim_scale}', pause=0.001) + + if hasattr(world, 'ceiling_poses'): + for x, y, s in world.ceiling_poses: + self.send_message(f'main_builder ceiling {x * self.sim_scale} {y * self.sim_scale} ' + f'{s * self.sim_scale}', pause=0.001) + + self.do_buffer = False + with tempfile.NamedTemporaryFile("w", delete=False) as temp_file: + for message in self.messages: + temp_file.write(message + "\n") + + self.send_message(f"main_builder file {temp_file.name}", 0.0) + self.unity_listener.parse_string() + + def move_object_to_pose(self, object_name, pose, pause=-1): + if pause <= 0: + self.send_message("{} move_respond {} {} {} {}".format( + object_name, pose.x * self.sim_scale, pose.y * self.sim_scale, + 1.5, pose.yaw), pause=pause) + self.unity_listener.parse_string() + else: + self.send_message("{} move {} {} {} {}".format( + object_name, pose.x * self.sim_scale, pose.y * self.sim_scale, + 1.5, pose.yaw), pause=pause) + + def _make_obstacles(self, world, scale): + for obstacle in world.obstacles: + points = obstacle.exterior.coords + spoints = points[1:] + points[-1:] + for pa, pb in zip(points, spoints): + coords = "" + nsegs = int(eucl_dist(pa, pb) / scale + 0.5) + nsegs = max(nsegs, 1) + xs = np.linspace(pa[0], pb[0], nsegs + 1, endpoint=True) + ys = np.linspace(pa[1], pb[1], nsegs + 1, endpoint=True) + + for x, y in zip(xs, ys): + coords += f" {x * self.sim_scale} {y * self.sim_scale}" + + message = "main_builder dungeon_poly" + coords + self.send_message(message) + + def _make_wall(self, wall, wall_class): + points = wall.coords + spoints = points[1:] + points[-1:] + for pa, pb in zip(points, spoints): + coords = "" + nsegs = int(eucl_dist(pa, pb) / 10 + 0.5) + nsegs = max(nsegs, 1) + xs = np.linspace(pa[0], pb[0], nsegs + 1, endpoint=True) + ys = np.linspace(pa[1], pb[1], nsegs + 1, endpoint=True) + + for y, x in zip(xs, ys): + coords += f" {x * self.sim_scale} {y * self.sim_scale}" + + message = f"main_builder poly_{wall_class}" + coords + self.send_message(message) + + +class OccupancyGridWorld(World): + """Use occupancy grid to improve planning efficiency""" + def __init__(self, + grid, + map_data, + num_breadcrumb_elements=500, + min_breadcrumb_signed_distance=4.0, + breadcrumb_type=None, + min_interlight_distance=3, + min_light_to_wall_distance=2, + max_attempts_lights=10000): + self.grid = (1.0 - grid.T) # Differences in occupancy value + self.map_data = map_data + self.resolution = map_data['resolution'] + + obstacles, boundary = obstacles_and_boundary_from_occupancy_grid( + self.grid, self.resolution) + + self.x = (np.arange(0, self.grid.shape[0]) + 0.0) * self.resolution + self.y = (np.arange(0, self.grid.shape[1]) + 0.0) * self.resolution + + super(OccupancyGridWorld, self).__init__(obstacles=obstacles, + boundary=boundary) + + self.breadcrumb_type = breadcrumb_type + self.breadcrumb_element_poses = [] + while len(self.breadcrumb_element_poses) < num_breadcrumb_elements: + pose = self.get_random_pose( + min_signed_dist=min_breadcrumb_signed_distance, + semantic_label='goal_path') + signed_dist = self.get_signed_dist(pose) + if signed_dist >= min_breadcrumb_signed_distance: + self.breadcrumb_element_poses.append(pose) + + # If there are tables, light poses aren't generated above them since tables are obstacles. + # To fix this, we need to create a world without tables and generate light poses in this world. + # Sometimes, this also affects ceiling poses, and hence ceiling poses are generated accordingly. + if 'tables' in self.map_data.keys(): + self.table_poses_sizes = self.map_data['tables'] + semantic_grid = self.map_data['semantic_grid'] + grid_no_tables = (semantic_grid < self.map_data['semantic_labels']['clutter']).astype(float) + grid_no_tables = (1.0 - grid_no_tables.T) + obstacles, boundary = obstacles_and_boundary_from_occupancy_grid( + grid_no_tables, self.resolution) + world = World(obstacles, boundary) + self.light_poses = _generate_light_poses(world=world, + min_interlight_distance=min_interlight_distance, + min_light_to_wall_distance=min_light_to_wall_distance, + max_attempts=max_attempts_lights) + self.ceiling_poses = _generate_ceiling_poses(world.known_space_poly) + else: + self.light_poses = _generate_light_poses(world=self, + min_interlight_distance=min_interlight_distance, + min_light_to_wall_distance=min_light_to_wall_distance, + max_attempts=max_attempts_lights) + self.ceiling_poses = _generate_ceiling_poses(self.known_space_poly) + + def get_random_pose(self, + xbounds=None, + ybounds=None, + min_signed_dist=0, + num_attempts=10000, + semantic_label=None): + """Get a random pose in the world, respecting the signed distance + to all the obstacles. + Each "bound" is a N-element list structured such that: + > xmin = min(xbounds) + > xmax = max(xbounds) + "num_attempts" is the number of trials before an error is raised. + """ + + for _ in range(num_attempts): + pose = super(OccupancyGridWorld, + self).get_random_pose(xbounds, ybounds, + min_signed_dist, num_attempts) + if semantic_label is None: + return pose + + pose_cell_x = np.argmin(np.abs(self.y - pose.x)) + pose_cell_y = np.argmin(np.abs(self.x - pose.y)) + + grid_label_ind = self.map_data['semantic_grid'][pose_cell_x, + pose_cell_y] + if grid_label_ind == self.map_data['semantic_labels'][ + semantic_label]: + return pose + else: + raise ValueError("Could not find random point within bounds") + + def get_grid_from_poly(self, known_space_poly, proposed_world=None): + known_space_poly = known_space_poly.buffer(self.resolution / 2) + mask = -1 * np.ones(self.grid.shape) + + for ii in range(mask.shape[0]): + for jj in range(mask.shape[1]): + p = shapely.geometry.Point(self.y[jj], self.x[ii]) + if known_space_poly.contains(p): + mask[ii, jj] = 1 + + out_grid = -1.0 * np.ones(mask.shape) + out_grid[mask == 1] = 0.0 + + if proposed_world is not None: + for v in proposed_world.vertices: + cell_y = np.argmin(np.abs(self.y - v[0])) + cell_x = np.argmin(np.abs(self.x - v[1])) + out_grid[cell_x, cell_y] = 1.0 + + for w in proposed_world.walls: + ys = np.linspace(w[0][0], w[1][0], 100) + xs = np.linspace(w[0][1], w[1][1], 100) + + for x, y in zip(xs, ys): + cell_x = np.argmin(np.abs(self.x - x)) + cell_y = np.argmin(np.abs(self.y - y)) + out_grid[cell_x, cell_y] = 1.0 + + return out_grid.T + + +def _generate_ceiling_poses(known_space_poly, tile_size=2.5): + x, y = known_space_poly.exterior.xy + x_min, y_min = min(x), min(y) + x_max, y_max = max(x), max(y) + ceiling_poses = [] + for xx in np.arange(x_min, x_max + tile_size, tile_size): + for yy in np.arange(y_min, y_max + tile_size, tile_size): + tile_poly = shapely.geometry.Polygon([[xx - tile_size / 2, yy - tile_size / 2], + [xx + tile_size / 2, yy - tile_size / 2], + [xx + tile_size / 2, yy + tile_size / 2], + [xx - tile_size / 2, yy + tile_size / 2]]) + if known_space_poly.intersects(tile_poly): + ceiling_poses.append([xx, yy, tile_size]) + + return ceiling_poses + + +def _generate_light_poses(world, min_interlight_distance, min_light_to_wall_distance, + max_attempts=10000): + new_pose = world.get_random_pose(min_signed_dist=min_light_to_wall_distance) + light_poses = [[new_pose.x, new_pose.y]] + for _ in range(max_attempts): + new_pose = world.get_random_pose(min_signed_dist=min_light_to_wall_distance) + interlight_distance_squared = (np.subtract(light_poses, [new_pose.x, new_pose.y])**2).sum(1) + if np.all(interlight_distance_squared >= min_interlight_distance**2): + light_poses.append([new_pose.x, new_pose.y]) + + return light_poses diff --git a/modules/environments/environments/utils/__init__.py b/modules/environments/environments/utils/__init__.py new file mode 100644 index 0000000..d7b359b --- /dev/null +++ b/modules/environments/environments/utils/__init__.py @@ -0,0 +1,2 @@ +from . import convert # noqa +from . import calc # noqa diff --git a/modules/environments/environments/utils/calc.py b/modules/environments/environments/utils/calc.py new file mode 100644 index 0000000..45a39b5 --- /dev/null +++ b/modules/environments/environments/utils/calc.py @@ -0,0 +1,131 @@ +import itertools +import numpy as np +import shapely.geometry +import shapely.ops + + +def full_simplify_shapely_polygon(poly): + """This function simplifies a polygon, removing any colinear points. + Though Shapely has this functionality built-in, it won't remove the + "start point" of the polygon, even if it's colinear.""" + + if isinstance(poly, shapely.geometry.MultiPolygon) or isinstance( + poly, shapely.geometry.GeometryCollection): + return shapely.geometry.MultiPolygon( + [full_simplify_shapely_polygon(p) for p in poly]) + + poly = poly.simplify(0.001, preserve_topology=True) + # The final point is removed, since shapely will auto-close polygon + points = np.array(poly.exterior.coords) + if (points[-1] == points[0]).all(): + points = points[:-1] + + def is_colinear(p1, p2, p3, tol=1e-6): + """Checks if the area formed by a triangle made of the three points + is less than a tolerance value.""" + return abs(p1[0] * (p2[1] - p3[1]) + p2[0] * (p3[1] - p1[1]) + p3[0] * + (p1[1] - p2[1])) < tol + + if is_colinear(points[0], points[1], points[-1]): + poly = shapely.geometry.Polygon(points[1:]) + + return poly + + +def _convert_grid_to_poly(grid, resolution, do_full_simplify=True): + """Takes an occupancy grid and builds a polygon out of all cells that have a value >= 0.5. + The resolution parameter controls how large each grid cell is in metric space. By + default, the polygon is 'full simplified', but can be disabled to save computation.""" + + polys = [] + for index, val in np.ndenumerate(grid): + if val < 0.5: + continue + + y, x = index + y *= resolution + x *= resolution + y -= 0.5 * resolution + x -= 0.5 * resolution + r = resolution + polys.append( + shapely.geometry.Polygon([(x, y), (x + r, y), (x + r, y + r), + (x, y + r) + ]).buffer(0.001 * resolution, 0)) + + joined_poly = shapely.ops.cascaded_union(polys) + + if do_full_simplify: + return full_simplify_shapely_polygon(joined_poly) + else: + return joined_poly + + +def split_semantic_grid_to_polys(occupancy_grid, semantic_grid, semantic_class_index, + resolution, do_compute_walls=True, verbose=False): + # Compute the shapely polygons for the different classes + polys = { + label: _convert_grid_to_poly(semantic_grid == val, resolution) + for label, val in semantic_class_index.items() + } + polys['all_free_space'] = _convert_grid_to_poly(occupancy_grid < 0.5, resolution) + + if verbose: + for label, poly in polys.items(): + print(f"polys['{label}'].area: {poly.area}") + + if not do_compute_walls: + return polys + + # Compute the walls + wall_class_labels = set(semantic_class_index.keys()) + all_walls = polys['all_free_space'].boundary + + # Split the walls by the various semantic classes + for label in wall_class_labels: + inf_poly_boundary = polys[label].buffer(0.1 * resolution, 0).boundary + if isinstance(all_walls, shapely.geometry.GeometryCollection): + all_walls = shapely.geometry.MultiLineString([ls for ls in all_walls]) + all_walls = shapely.ops.split( + all_walls, inf_poly_boundary) + + # Split the walls by class + inflated_polys = {label: poly.buffer(0.2 * resolution, 0) + for label, poly in polys.items()} + walls = {label: [] for label in wall_class_labels} + walls['base'] = [] + for w in all_walls: + for label in wall_class_labels: + if inflated_polys[label].contains(w): + walls[label].append(w) + break + else: + walls['base'].append(w) + + return polys, walls + + +def obstacles_and_boundary_from_occupancy_grid(grid, resolution): + known_space_poly = _convert_grid_to_poly(grid, resolution, do_full_simplify=False) + + def get_obstacles(poly): + if isinstance(poly, shapely.geometry.MultiPolygon): + return list( + itertools.chain.from_iterable([get_obstacles(p) + for p in poly])) + + obstacles = [ + full_simplify_shapely_polygon(shapely.geometry.Polygon(interior)) + for interior in list(poly.interiors) + ] + + # Simplify the polygon + boundary = full_simplify_shapely_polygon(poly) + + obstacles.append(boundary) + + return obstacles + + obs = get_obstacles(known_space_poly) + obs.sort(key=lambda x: x.area, reverse=True) + return obs[1:], obs[0] diff --git a/modules/environments/environments/utils/convert.py b/modules/environments/environments/utils/convert.py new file mode 100644 index 0000000..1012ec4 --- /dev/null +++ b/modules/environments/environments/utils/convert.py @@ -0,0 +1,40 @@ +"""Functions devoted to converting between various data types.""" +import common +import math +import numpy as np + + +def ranges_from_depth_image(depth, max_range=200.0): + """Convert depth image into ranges.""" + dshape = depth.shape + dslice = depth[dshape[0] // 2, :, :] + ranges = (1.0 * dslice[:, 0] + dslice[:, 1] / 256.0 + + dslice[:, 2] / 256.0 / 256.0) / 256.0 * max_range + return ranges.astype(np.float32) + + +def depths_from_depth_image(depth_image): + return (1.0 * depth_image[:, :, 0] + depth_image[:, :, 1] / 256.0 + + depth_image[:, :, 2] / 256.0 / 256.0) / 256.0 * 200.0 + + +def image_aligned_to_robot(image, r_pose): + """Permutes an image from axis-aligned to robot frame.""" + cols = image.shape[1] + roll_amount = int(round(-cols * r_pose.yaw / (2 * math.pi))) + return np.roll(image, shift=roll_amount, axis=1) + + +def image_aligned_from_robot_to_global(image, r_pose): + inv_pose = common.Pose(r_pose.x, r_pose.y, -r_pose.yaw) + return image_aligned_to_robot(image, inv_pose) + + +def image_aligned_to_subgoal(image, r_pose, subgoal): + """Permutes an image from axis-aligned to subgoal-pointing frame. + The subgoal should appear at the center of the image.""" + cols = image.shape[1] + sp = subgoal.get_centroid() + yaw = np.arctan2(sp[1] - r_pose.y, sp[0] - r_pose.x) - r_pose.yaw + roll_amount = int(round(-cols * yaw / (2 * math.pi))) + return np.roll(image, shift=roll_amount, axis=1) diff --git a/modules/environments/environments/world.py b/modules/environments/environments/world.py new file mode 100644 index 0000000..275112c --- /dev/null +++ b/modules/environments/environments/world.py @@ -0,0 +1,136 @@ +import random +from common import Pose +import shapely +import shapely.prepared +from shapely import geometry + + +class World(object): + """Stores the shapely polygons that define the world (base structure for + many environments). + + Attributes: + obstacles: list of shapely polygons + boudary: shapely polygon which defines the outer obstacle of world + clutter_element_poses: positions of clutter + known_space_poly: shapely polygon representing known, free space + area: area of known space polygon + """ + def __init__(self, obstacles, boundary=None): + self.obstacles = obstacles + self.boundary = boundary + self._internal_obstacles = list(obstacles) + self.clutter_element_poses = [] + if self.boundary is not None: + self.obstacles.append(boundary) + self.known_space_poly = boundary + for obs in self._internal_obstacles: + self.known_space_poly = self.known_space_poly.difference(obs) + self.area = self.known_space_poly.area + else: + self.obs_poly = shapely.geometry.Polygon() + for obs in self._internal_obstacles: + self.obs_poly = self.obs_poly.union(obs) + self.known_space_poly = shapely.geometry.Polygon() + self.area = 1 + + def compute_iou(self, known_space_poly): + """Return intersection over union of kown space between + estimate and ground truth""" + try: + intersection = self.known_space_poly.intersection( + known_space_poly).area + union = self.known_space_poly.union(known_space_poly).area + return intersection / union + except: # noqa + print("IoU failed!") + return 0.0 + + @property + def map_bounds(self): + """Get the x and y limits of the underlying map. + + Returns: + xbounds: 2-element tuple [min(x), max(x)] + ybounds: 2-element tuple [min(y), max(y)] + """ + + if self.boundary is not None: + xs, ys = self.boundary.exterior.xy + xmin = min(xs) + xmax = max(xs) + ymin = min(ys) + ymax = max(ys) + else: + # FIXME: should not be hard coded + return (-100, 200), (-100, 200) + + return (xmin, xmax), (ymin, ymax) + + def get_signed_dist(self, pose): + """Get the signed distance to obstacles from a point.""" + # Loop through objects, get closest point and return distance + point = geometry.Point([pose.x, pose.y]) + distance = 1e10 + for obstacle in self._internal_obstacles: + if obstacle.contains(point): + obs_dist = -obstacle.exterior.distance(point) + else: + obs_dist = obstacle.distance(point) + + distance = min(distance, obs_dist) + + if self.boundary is not None: + # Ensure that the point is also inside the boundary + if self.boundary.contains(point): + boundary_dist = self.boundary.exterior.distance(point) + else: + boundary_dist = -self.boundary.distance(point) + distance = min(distance, boundary_dist) + + return distance + + def get_random_pose(self, + xbounds=None, + ybounds=None, + min_signed_dist=0, + max_signed_dist=10000, + num_attempts=10000): + """Get a random pose in the world, respecting the signed distance + to all the obstacles. + + Each "bound" is a N-element list structured such that: + + > xmin = min(xbounds) + > xmax = max(xbounds) + + "num_attempts" is the number of trials before an error is raised. + """ + + try: + xbounds, ybounds = self._map_bounds + except AttributeError: + pass + + if xbounds is None or ybounds is None: + if self.boundary is None: + raise ValueError("If world.boundary is None, bounds " + + "must be provided.") + else: + xbounds, ybounds = self.boundary.exterior.xy + + xmin = min(xbounds) + xmax = max(xbounds) + ymin = min(ybounds) + ymax = max(ybounds) + + counter = 0 + while counter < num_attempts: + pose = Pose(random.uniform(xmin, xmax), random.uniform(ymin, ymax)) + obs_signed_distance = self.get_signed_dist(pose) + if obs_signed_distance >= min_signed_dist and obs_signed_distance <= max_signed_dist: + return pose + else: + counter += 1 + else: + raise ValueError("Could not find random point within bounds") diff --git a/modules/environments/setup.py b/modules/environments/setup.py new file mode 100644 index 0000000..8557a2c --- /dev/null +++ b/modules/environments/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='environments', + version='1.0.0', + description='Devoted to instantiating simulated environments', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'unitybridge']) diff --git a/modules/environments/tests/test_office2_environment_gen.py b/modules/environments/tests/test_office2_environment_gen.py new file mode 100644 index 0000000..7fe3ce0 --- /dev/null +++ b/modules/environments/tests/test_office2_environment_gen.py @@ -0,0 +1,133 @@ +from environments import office2 +import environments +import matplotlib.pyplot as plt +import scipy +import numpy as np + + +def test_office2_mapgen_intermediate(do_debug_plot, unity_path): + + def make_plotting_grid(known_map): + kernel = np.ones((3, 3)) / 9 + grid = scipy.ndimage.convolve(known_map, kernel) + walls = (known_map == 1) & (grid < 1) + grid_map = known_map.copy() + grid_map += 1 + grid_map[known_map == 0] = 0 + grid_map[known_map == 1] = 1 + grid_map[walls] = 2 + + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + grid[:, :, 0][grid_map == 0] = 1 + grid[:, :, 0][grid_map == 2] = 0 + grid[:, :, 1][grid_map == 0] = 1 + grid[:, :, 1][grid_map == 2] = 0 + grid[:, :, 2][grid_map == 0] = 1 + grid[:, :, 2][grid_map == 2] = 0 + + grid[:, :, 0][grid_map == 1] = 0.65 + grid[:, :, 1][grid_map == 1] = 0.65 + grid[:, :, 2][grid_map == 1] = 0.75 + + return grid + + seed = 2005 + grid_with_lines, line_segments = office2.generate_random_lines(seed=seed) + grid_with_hallway = office2.inflate_lines_to_create_hallways(grid_with_lines) + features = office2.determine_intersections(grid_with_hallway == office2.semantic_labels['hallway']) + grid_with_special_rooms, special_rooms_coords = office2.add_special_rooms(grid_with_hallway, + intersections=features['intersections']) + grid_with_rooms, rooms_coords = office2.add_rooms(grid_with_special_rooms, line_segments) + rooms_coords += special_rooms_coords + grid_with_tables, _ = office2.add_tables(grid_with_rooms, rooms_coords) + + known_map = (grid_with_tables <= office2.L_CLUTTER).astype(float) + + if do_debug_plot: + plt.figure(figsize=(16, 8)) + plt.subplot(231) + plt.imshow(grid_with_lines.T, cmap='viridis') + plt.title('Randomly generated lines') + plt.subplot(232) + plt.imshow(grid_with_hallway.T, cmap='viridis') + plt.title('Lines inflated to create hallways') + plt.subplot(233) + plt.imshow(grid_with_special_rooms.T, cmap='viridis') + plt.title('Grid with special rooms') + plt.subplot(234) + plt.imshow(grid_with_rooms.T, cmap='viridis') + plt.title('Grid with rooms') + plt.subplot(235) + plt.imshow(grid_with_tables.T, cmap='viridis') + plt.title('Grid with tables') + plt.subplot(236) + plt.imshow(make_plotting_grid(known_map.T)) + plt.title('Final occupancy grid') + plt.show() + + assert np.std(grid_with_lines) > 0 + assert np.std(grid_with_lines - grid_with_hallway) > 0 + assert np.std(grid_with_hallway - grid_with_rooms) > 0 + assert np.std(grid_with_special_rooms - grid_with_rooms) > 0 + assert np.std(grid_with_rooms - grid_with_tables) > 0 + + +def test_office2_mapgen_final(do_debug_plot, unity_path): + args = lambda: None # noqa: E731 + args.current_seed = 2005 + args.map_type = 'office2' + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + if do_debug_plot: + plt.figure(figsize=(8, 6)) + plt.subplot(211) + plt.imshow(known_map.T, cmap='binary') + plt.scatter(pose.x, pose.y, color='blue') + plt.scatter(goal.x, goal.y, color='green') + plt.title('Occupancy grid') + plt.subplot(212) + plt.imshow(map_data['semantic_grid'].T, cmap='viridis') + plt.title('Semantic grid') + plt.show() + + assert np.std(known_map) > 0 + assert known_map.size > 0 + assert np.std(map_data['semantic_grid']) > 0 + assert map_data['semantic_grid'].size > 0 + + +def test_office2_simulator(do_debug_plot, unity_path): + args = lambda: None # noqa: E731 + args.current_seed = 2005 + args.map_type = 'office2' + args.base_resolution = office2.RESOLUTION + args.inflation_radius_m = office2.INFLATION_RADIUS_M + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + world = environments.simulated.OccupancyGridWorld( + known_map, map_data, num_breadcrumb_elements=0) + builder = environments.simulated.WorldBuildingUnityBridge + + with builder(unity_path) as unity_bridge: + unity_bridge.move_object_to_pose('robot', args.base_resolution * pose) + pano_image_init = unity_bridge.get_image('robot/pano_camera') + unity_bridge.make_world(world) + pano_image_start = unity_bridge.get_image('robot/pano_camera') + unity_bridge.move_object_to_pose('robot', args.base_resolution * goal) + pano_image_goal = unity_bridge.get_image('robot/pano_camera') + + if do_debug_plot: + plt.figure(figsize=(8, 6)) + plt.subplot(211) + plt.imshow(pano_image_start) + plt.subplot(212) + plt.imshow(pano_image_goal) + plt.show() + + assert np.std(pano_image_start.mean(2)) > 0 + assert np.std(pano_image_goal.mean(2)) > 0 + assert np.std(pano_image_init - pano_image_start) > 0 + assert np.std(pano_image_start - pano_image_goal) > 0 + assert np.mean(pano_image_start) > 60 + assert np.mean(pano_image_goal) > 60 diff --git a/modules/environments/tests/test_office_environment_gen.py b/modules/environments/tests/test_office_environment_gen.py new file mode 100644 index 0000000..618797c --- /dev/null +++ b/modules/environments/tests/test_office_environment_gen.py @@ -0,0 +1,49 @@ +"""This test is mostly for *visual* inspection of the office environment.""" +import environments.generate +import matplotlib.pyplot as plt + + +def test_office_env_occupancy_gen(do_debug_plot, unity_path): + args = lambda: None # noqa: E731 + args.current_seed = 8616 + args.map_type = 'office' + known_map, map_data, start_pose, goal_pose = environments.generate.map_and_poses(args) + + if do_debug_plot: + import shapely.geometry + + def plot_shapely_linestring(ax, ls, color=[0.25, 0.25, 1.0], alpha=1.0): + if isinstance(ls, shapely.geometry.MultiLineString): + [plot_shapely_linestring(ax, line, color, alpha) for line in ls] + return + + x, y = ls.xy + ax.plot(x, y, color=color, alpha=alpha, linewidth=0.2) + + plt.subplot(131) + plt.imshow(known_map) + plt.subplot(132) + plt.imshow(map_data['semantic_grid']) + plt.subplot(133) + for wall in map_data['walls']['room']: + plot_shapely_linestring(plt.gca(), wall, color=[1.0, 0, 0]) + for wall in map_data['walls']['hallway']: + plot_shapely_linestring(plt.gca(), wall, color=[0.0, 0, 1.0]) + for wall in map_data['walls']['base']: + plot_shapely_linestring(plt.gca(), wall, color=[0.5, 0.5, 0.5]) + plt.show() + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, map_data, num_breadcrumb_elements=0, + min_interlight_distance=3.0, + min_light_to_wall_distance=1.5) + builder = environments.simulated.WorldBuildingUnityBridge + + with builder(unity_path) as unity_bridge: + unity_bridge.make_world(world) + unity_bridge.move_object_to_pose("robot", args.base_resolution * start_pose) + pano_image = unity_bridge.get_image("robot/pano_camera") + if do_debug_plot: + plt.imshow(pano_image) + plt.show() diff --git a/modules/environments/tests/test_simulator_speed.py b/modules/environments/tests/test_simulator_speed.py new file mode 100644 index 0000000..5c5d0dc --- /dev/null +++ b/modules/environments/tests/test_simulator_speed.py @@ -0,0 +1,95 @@ +import environments +import lsp +import numpy as np +import matplotlib.pyplot as plt +import time + + +def test_simulator_speed(unity_path, do_debug_plot): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 100 + args.step_size = 1.8 + args.field_of_view_deg = 360 + args.map_type = 'maze' + args.base_resolution = 0.3 + args.inflation_radius_m = 0.75 + args.laser_max_range_m = 18 + args.unity_path = unity_path + num_frames = 100 + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + time_taken_list = [] + for i in range(num_frames): + pose = world.get_random_pose() + t = time.time() + unity_bridge.move_object_to_pose("robot", simulator.pose_grid_to_world(pose)) + pano_image = unity_bridge.get_image("robot/pano_camera") + frame_time = time.time() - t + time_taken_list.append(frame_time) + print(f'Frame {i + 1} Time: {frame_time}') + + if do_debug_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(111) + plt.imshow(pano_image) + plt.title(f'Frame {i + 1} Time: {frame_time}') + plt.show() + plt.pause(0.01) + + print('With ceiling and floor') + print(f'Average time per frame (with {num_frames} frames): {np.mean(time_taken_list)}') + print(f'Standard deviation: {np.std(time_taken_list)}') + + # Remove all ceiling/floor poses + world.ceiling_poses = [] + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + time_taken_list = [] + for i in range(num_frames): + pose = world.get_random_pose() + t = time.time() + unity_bridge.move_object_to_pose("robot", simulator.pose_grid_to_world(pose)) + pano_image = unity_bridge.get_image("robot/pano_camera") + frame_time = time.time() - t + time_taken_list.append(frame_time) + print(f'Frame {i + 1} Time: {frame_time}') + + if do_debug_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(111) + plt.imshow(pano_image) + plt.title(f'Frame {i + 1} Time: {frame_time}') + plt.show() + plt.pause(0.01) + + print('Without ceiling and floor') + print(f'Average time per frame (with {num_frames} frames): {np.mean(time_taken_list)}') + print(f'Standard deviation: {np.std(time_taken_list)}') + + if do_debug_plot: + plt.ioff() diff --git a/modules/example/Makefile.mk b/modules/example/Makefile.mk new file mode 100644 index 0000000..067d1f8 --- /dev/null +++ b/modules/example/Makefile.mk @@ -0,0 +1,24 @@ + +help:: + @echo "Example Targets (from the example module)" + @echo " example-core Create a simple example image" + @echo " example-clean Deletes the simple example image" + @echo "" + +# This target is to make an image by calling a script within 'example' +example-image = $(DATA_BASE_DIR)/example_module/demo_image.png +$(example-image): + @mkdir -p $(DATA_BASE_DIR)/example_module + @$(DOCKER_PYTHON) -m example.scripts.gen_random_mat \ + --image-name /data/example_module/demo_image.png + +# A high-level target that calls other targets with a more convenient name +.PHONY: example-core +example-core: $(example-image) + +example-clean: + @echo "Cleaning products from 'example' repo." + @echo -n "Are you sure? [y/N] " && read ans && [ $${ans:-N} = y ] + @-$(DOCKER_BASE) rm -r /data/example_module + @echo "...done cleaning." + diff --git a/modules/example/README.org b/modules/example/README.org new file mode 100644 index 0000000..01cefaa --- /dev/null +++ b/modules/example/README.org @@ -0,0 +1,106 @@ + +* RAIL-core Example Module + +This is a bare-bones module to illustrate how modules in the RAIL group should be structured. + +** Basic Usage + +This module provides a couple of simple make targets and tests to illustrate some basic functionality. In the top level directory, build the repository using =make build=. We provide two targets: + +- =make example-core= Create a simple image of a randomly generated matrix saved to =RAIL-core/data/example_module/demo_image.png=. Running with =XPASSTHROUGH=true= (e.g., =make example-core XPASSTHROUGH=true=) will instead visualize the plot, rather than writing it to file. Note that once the image exists, running =example-core= again will do nothing, so as to save on computation. In more complex environments, this can result in a significant computational savings. By default, this repository runs assuming that a GPU is available; use the argument =USE_GPU=false= to disable the GPU: i.e., =make example-core USE_GPU=false=) +- =make example-clean= Remove the =RAIL-core/data/example_module= directory (after asking for confirmation). +- =README.org= This file! README files can be written in either =.org= or GitHub Markdown syntax. + +** Overall Structure + +This module has the following structure: + +- =example= The main folder in which the code of this module is defined. This example module provides only a single function =gen_random_matrix= in Once the module is installed, this function can be accessed via =example.core.gen_random_matrix= (once =example= is imported). +- =example.scripts= We also provide a scripts folder for running scripts specific to this module. We have included a single script that performs a simple function. The syntax for running the script can be found [[file:./Makefile.mk::7][in the makefile]]. +- =Makefile.mk= A =Makefile= for Make targets specific to this module or project. More details on this below. +- =setup.py= A setup script that specifies how =pip= will build or install the module. +- =tests= A folder for tests specific to this function. Running =make test= will run all tests in the repository, including these. More details below. + +*** Adding new modules + +By default, modules are not added to the build process nor are the make targets added to the central Makefile. For Docker, you must both copy and then build the repository. For the example module, this looks as follows: + +#+begin_src dockerfile +COPY modules/example modules/example +RUN pip3 install modules/example +#+end_src + +For the Makefile, the =include= keyword appends the contents of another file at the location of the include. For the example module: + +#+begin_src makefile +include modules/example/Makefile.mk +#+end_src + +Since all the make targets are all effectively concatenated into a single Makefile, it is important to ensure that variable names and the names of targets will not conflict with one another. It is for this reason that all the names for the example module (and presumably others) all share a prefix =example-= with the other targets in their module. The only exception is the =make help= target, which is designed to be "extended" by other sub-Makefiles. This is done using the double-colon syntax that indicates that multiple definitions of the same target are to be combined, rather than overridden: + +#+begin_src makefile +help:: + @echo "Example Targets (from the example module)" + @echo " example-core Create a simple example image" + @echo " example-clean Deletes the simple example image" + @echo "" +#+end_src + +Even though this definition of =help::= is only for the =example= module, running =make help= will display the help for all modules. + +** The Makefile: running code within Docker + +Though the "top level" Makefile exists in the main directory of the repository, each module can provide its own =Makefile.mk=, which is appended to the top-level Makefile via the GNU Make [[https://www.gnu.org/software/make/manual/html_node/Include.html][=include= syntax]]. This means that each of the "local" Makefiles effectively inherit the variables defined at the top level. Chief among these is the =$(DOCKER_PYTHON)= variable, which is used to run Python within the primary Docker container. Our Makefile uses this to provide two make targets that run python code within Docker. + +The first Make target, =example-core= creates a single image via a simple script included in =example.scripts=: + +#+begin_src makefile +# This target is to make an image by calling a script within 'example' +example-image = $(DATA_BASE_DIR)/example_module/demo_image.png +$(example-image): + @mkdir -p $(DATA_BASE_DIR)/example_module + @$(DOCKER_PYTHON) -m example.scripts.gen_random_mat \ + --image-name /data/example_module/demo_image.png + +# A high-level target that calls other targets with a more convenient name +.PHONY: example-core +example-core: $(example-image) +#+end_src + +There are a few things to note about the construction of this target. First, we have created a separate target called =$(example-image)=. Make is, at its core, a build system: it's primary responsibility is to create files by running code. When those files exist, it decides the code to "create them" needs not be rerun. In this case, we have defined a variable =example-image= with a single filename in it, which is where our script will save the image. The target for =$(example-image)= runs a python script inside Docker and ultimately write that image to file. The =example-core= target specifies =$(example-image)= (our image) as its only dependency, via the following syntax: + +#+begin_src makefile +.PHONY: example-core +example-core: $(example-image) +#+end_src + +This code specifies that (1) =example-core= is "phony" (i.e., Make is not expecting that running this code will produce a file), (2) that running =example-core= does not execute any code of its own, and (3) that =example-core= requires =$(example-image)= to be completed before it is considered complete. If the file specified by =$(example-image)= already exists, Make will respond "nothing to be done" for =example-core=. Otherwise, Make will run the target defined by =$(example-image)=, presumably creating that file. + +We finally provide another "clean" target as =example-clean=, which removes the image file we created (and its parent directory). + +** The Tests: debugging and testing code + +We include a couple of very simple tests in =tests/test_example.py=. Tests are run via [[https://docs.pytest.org/][pytest]]. Pytest looks for tests in files that begin with =test_= and proceeds to run functions beginning with =test_= inside those functions. Tests are a fantastic way to ensure your code runs as expected and also to develop new ideas. Run =make test= in the top-level directory to run all tests across modules; set the =PYTEST_FILTER= to filter which tests are run: =make test PYTEST_FILTER=test_example= will run only the tests that include the string =test_example=, which should limit the scope to this module. Pytest will run through all the tests, reporting which succeed or fail. Once complete, pytest will produce an log (as an HTML file) in =data/test_logs= for more convenient browsing. + +Our first test runs the =get_random_matrix= function for a few different arguments and confirms that the random matrices have the correct shape and that their values are within expected bounds. We reproduce it here in its entirety: + +#+begin_src python +import example +import pytest + +@pytest.mark.parametrize("mat_shape", [(1, 4), (2, 2), (2,), (1, 2, 3, 4)]) +def test_get_random_matrix_is_correct_size(mat_shape): + mat = example.core.get_random_matrix(mat_shape) + assert mat.shape == mat_shape + assert mat.min() >= 0.0 + assert mat.max() <= 1.0 +#+end_src + +The =parametrize= decorator provided by the =pytest= package has been used to run the test for multiple sets of arguments, reusing the existing code rather than making duplicate tests for each. The four tests are run separately, allowing us to confirm that each runs as expected in isolation. + +Our second test relies on a "test fixture", a reusable block of code defined in =modules/conftest.py=. This "fixture" defines the =do_debug_plot= variable derived from the =XPASSTHROUGH= command line argument. Fixtures are designed to run some code before the test is run and provide their output as input arguments to the test. This can be incredibly handy for defining code that sets up an object or environment and is reused across multiple tests. For this test, the =do_debug_plot= argument specifies whether or not we should plot something in the middle of the test, incredibly useful if you use tests as part of your development and debugging process (as you probably should)! In this case, I have some plotting code that I normally don't want to run, so that the tests run from start-to-finish without interruption, but that I also don't want to remove, so that I can visualize the function output when I so choose. When running all the tests via =make test=, the =test_optional_demo_plot= will automatically pass, yet setting =XPASSTHROUGH=true= will run the plotting code inside the test. Try it with the following: + +#+begin_src bash +# Run plotting demo (without GPU [optional]) +make test USE_GPU=false XPASSTHROUGH=true PYTEST_FILTER=test_optional_demo_plot +#+end_src diff --git a/modules/example/example/__init__.py b/modules/example/example/__init__.py new file mode 100644 index 0000000..a9ba477 --- /dev/null +++ b/modules/example/example/__init__.py @@ -0,0 +1,2 @@ +from . import core # noqa +from . import scripts # noqa diff --git a/modules/example/example/core.py b/modules/example/example/core.py new file mode 100644 index 0000000..1b0fd10 --- /dev/null +++ b/modules/example/example/core.py @@ -0,0 +1,6 @@ +import numpy as np + + +def get_random_matrix(mat_shape): + """Return a matrix of random numbers of specified shape.""" + return np.random.rand(*mat_shape) diff --git a/modules/example/example/scripts/__init__.py b/modules/example/example/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/example/example/scripts/gen_random_mat.py b/modules/example/example/scripts/gen_random_mat.py new file mode 100644 index 0000000..ed39767 --- /dev/null +++ b/modules/example/example/scripts/gen_random_mat.py @@ -0,0 +1,20 @@ +"""Generate matrix of random numbers and optionally write image to file.""" +import argparse +import example +import matplotlib.pyplot as plt + + +def main(args): + mat = example.core.get_random_matrix((5, 5)) + plt.imshow(mat) + if args.image_name is not None: + plt.savefig(args.image_name, dpi=150) + else: + print(mat) + + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument("--image-name", required=False) + args = parser.parse_args() + main(args) diff --git a/modules/example/setup.py b/modules/example/setup.py new file mode 100644 index 0000000..ef5156c --- /dev/null +++ b/modules/example/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='example', + version='1.0.0', + description='A simple example module', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/example/tests/test_example.py b/modules/example/tests/test_example.py new file mode 100644 index 0000000..ee3a070 --- /dev/null +++ b/modules/example/tests/test_example.py @@ -0,0 +1,23 @@ +import example +import pytest + + +@pytest.mark.parametrize("mat_shape", [(1, 4), (2, 2), (2,), (1, 2, 3, 4)]) +def test_get_random_matrix_is_correct_size(mat_shape): + mat = example.core.get_random_matrix(mat_shape) + assert mat.shape == mat_shape + assert mat.min() >= 0.0 + assert mat.max() <= 1.0 + + +def test_optional_demo_plot(do_debug_plot): + """Show that if plotting is enabled, the plot will show during testing. Note +that the optional argument inherits from 'XPASSTHROUGH' and is set in the +'fixtures' defined in the top-level testing directory.""" + if do_debug_plot: + import matplotlib.pyplot as plt + mat = example.core.get_random_matrix((25, 25)) + plt.figure(figsize=(8, 8)) + plt.imshow(mat) + plt.title("Debug: we can plot from inside a test") + plt.show() diff --git a/modules/gridmap/README.md b/modules/gridmap/README.md new file mode 100644 index 0000000..b5023fc --- /dev/null +++ b/modules/gridmap/README.md @@ -0,0 +1,10 @@ +# `gridmap`: Mapping and Planning with Occupancy Grids + +`gridmap` is a Python module designed to provide utilities for robot mapping and planning in occupancy grids. Functionality is split across four files: + +- `laser.py` For representing laser scanns and ray casting into an occupancy grid. It allows users to get directions from a laser scanner, simulate sensor measurements, generate a line between two points using Bresenham's line algorithm, and perform ray casting in the occupancy grid. +- `mapping.py` For constructing an occupancy grid from planer laser scans. It offers two main functionalities: insertion of a scan into the occupancy grid, and getting a fully-connected observed grid from a given pose. The latter function returns a grid where any components not connected to the robot's region are marked as 'unobserved', which can be crucial for avoiding invalid planning to unreachable frontiers. +- `planning.py` For planning in the occupancy grid. It provides functionality to use Dijkstra's algorithm to generate paths in the grid and optionally *sparsify* them: shortening them while still respecting occupancy. +- `utils.py` Provides a utility function for inflating obstacles in the occupancy grid, useful to create a safe distance between robot and obstacles during planning. + +Our [Jupyter Notebook onboarding tutorials](../../resources/notebooks/) make extensive use of the `gridmap` package for simulated robot navigation through previously-unmapped simulated environments. Look there for worked examples of the use of `gridmap`. diff --git a/modules/gridmap/gridmap/__init__.py b/modules/gridmap/gridmap/__init__.py new file mode 100644 index 0000000..7f6c237 --- /dev/null +++ b/modules/gridmap/gridmap/__init__.py @@ -0,0 +1,5 @@ +from . import constants # noqa +from . import laser # noqa +from . import mapping # noqa +from . import planning # noqa +from . import utils # noqa diff --git a/modules/gridmap/gridmap/constants.py b/modules/gridmap/gridmap/constants.py new file mode 100644 index 0000000..700875a --- /dev/null +++ b/modules/gridmap/gridmap/constants.py @@ -0,0 +1,10 @@ +""" +Define some constants shared across the lsp module +""" + +COLLISION_VAL = 1 +FREE_VAL = 0 +UNOBSERVED_VAL = -1 +assert (COLLISION_VAL > FREE_VAL) +assert (FREE_VAL > UNOBSERVED_VAL) +OBSTACLE_THRESHOLD = 0.5 * (FREE_VAL + COLLISION_VAL) diff --git a/modules/gridmap/gridmap/laser.py b/modules/gridmap/gridmap/laser.py new file mode 100644 index 0000000..916daf5 --- /dev/null +++ b/modules/gridmap/gridmap/laser.py @@ -0,0 +1,286 @@ +""" +Functions for simulating a laser sensor and ray casting in a grid. +""" +import numpy as np +import math + + +def get_laser_scanner_directions(num_points, field_of_view_rad): + """Creates an array of direction vectors in the sensor frame.""" + angles_rad = np.linspace(-field_of_view_rad / 2, field_of_view_rad / 2, + num_points) + directions = np.vstack((np.cos(angles_rad), np.sin(angles_rad))) + return directions + + +def simulate_sensor_measurement(occupancy_grid, + laser_scanner_directions, + max_range, + sensor_pose, + subsample=1): + """Ray cast to get a simulated laser measurement from a grid. + + Args: + occupancy_grid (np.Array): the ground-truth map. + laser_scanner_directions (np.Array): list of direction unit vectors + that define the laser (see 'get_laser_scanner_directions'). + max_range (float): maximum range of ray casting. + sensor_pose (Pose): pose (x, y, yaw) of the sensor. + subsample (int) [DEPRECATED]: scale factor for subsampling grid during + ray casting; should give higher-precision. + """ + + # Apply the pose transformation to the laser scanner rays + origin = [ + sensor_pose.x - 0.5 * (subsample - 1), + sensor_pose.y - 0.5 * (subsample - 1) + ] + rotation_mat = np.array( + [[math.cos(sensor_pose.yaw), -math.sin(sensor_pose.yaw)], + [math.sin(sensor_pose.yaw), + math.cos(sensor_pose.yaw)]]) + rotated_directions = np.matmul(rotation_mat, laser_scanner_directions) + transformed_rays = max_range * rotated_directions + transformed_rays[0, :] += origin[0] + transformed_rays[1, :] += origin[1] + + # Loop through the rays and cast them into the grid + num_scans = laser_scanner_directions.shape[1] + outputs = np.zeros((2, num_scans)) + for [target, out] in np.nditer([transformed_rays, outputs], + order='F', + flags=['external_loop'], + op_flags=[['readonly'], ['readwrite']], + op_dtypes=['float64', 'float64']): + _, end = cast_ray(occupancy_grid, origin, target, scale=4) + out[0] = end[0] - origin[0] + out[1] = end[1] - origin[1] + + # Project the points onto rotated_directions (and add minor correction + # factor) + val = np.zeros(num_scans) + for ii in range(num_scans): + val[ii] = (outputs[0, ii] * rotated_directions[0, ii] + + outputs[1, ii] * rotated_directions[1, ii]) + outputs[0, + ii] = (val[ii] + 0.5 * subsample) * rotated_directions[0, ii] + outputs[1, + ii] = (val[ii] + 0.5 * subsample) * rotated_directions[1, ii] + + return np.linalg.norm(outputs, axis=0) + + +def bresenham_points(start, target, scale=4, do_floor=True): + """Get the points along a line using Bresenham's Algorithm. + + Using Bresenham's algorithm, this function returns a list of points foom the + starting location to the target location. An optional scale argument can be + passed to compute points at a fractional grid resolution. For example, if + requesting the points between start=[0.0, 0.9] and target=[5.0, 1.9], we + might want the line to "jump" earlier. Using scale=2 allows us to accomplish + this: + + >>> bresenham_points(start=[0.0, 0.9], target=[5.0, 1.9], \ + scale=1, do_floor=True) + array([[0, 1, 2, 3, 4, 5], + [0, 0, 0, 1, 1, 1]]) + >>> bresenham_points(start=[0.0, 0.9], target=[5.0, 1.9], \ + scale=2, do_floor=True) + array([[0, 1, 2, 3, 4, 5], + [0, 1, 1, 1, 1, 1]]) + + If the values are not "floored", all the sub-pixel point are returned: + >>> bresenham_points(start=[0.0, 0.9], target=[5.0, 1.9], \ + scale=2, do_floor=False) + array([[ 0. , 0.5, 1. , 1.5, 2. , 2.5, 3. , 3.5, 4. , 4.5, 5. ], + [ 0.5, 0.5, 0.5, 1. , 1. , 1. , 1. , 1. , 1.5, 1.5, 1.5]]) + + Args: + start (2x float): 2D starting point + target (2x float): 2D ending point + scale (int): Optional sub-pixel scale argument + do_floor (Bool): Optional argument to return integer coordinates + or fractional coordinages (for scale != 1) + + Returns: 2xN numpy array of N coordinates corresponding to points given by + Bresenham's algorithm. (This includes the endpoints start and target.) + """ + + # Convert to integers + upscaled_start_int = [int(scale * start[0]), int(scale * start[1])] + upscaled_target_int = [int(scale * target[0]), int(scale * target[1])] + + upscaled_point = upscaled_start_int + + dx = upscaled_target_int[0] - upscaled_start_int[0] + xstep = 1 + if dx < 0: + dx = -dx + xstep = -1 + + dy = upscaled_target_int[1] - upscaled_start_int[1] + ystep = 1 + if dy < 0: + dy = -dy + ystep = -1 + + if dx == 0: + # Vertical + upsampled_points = np.zeros([2, dy + 1]) + for ii in range(dy + 1): + upsampled_points[0, ii] = upscaled_point[0] + upsampled_points[1, ii] = upscaled_point[1] + upscaled_point[1] += ystep + elif dy == 0: + # Horizontal + upsampled_points = np.zeros([2, dx + 1]) + for ii in range(dx + 1): + upsampled_points[0, ii] = upscaled_point[0] + upsampled_points[1, ii] = upscaled_point[1] + upscaled_point[0] += xstep + elif dx > dy: + n = dx + dy += dy + e = dy - dx + dx += dx + + upsampled_points = np.zeros([2, n + 1]) + for ii in range(n + 1): + upsampled_points[0, ii] = upscaled_point[0] + upsampled_points[1, ii] = upscaled_point[1] + if e >= 0: + upscaled_point[1] += ystep + e -= dx + e += dy + upscaled_point[0] += xstep + else: + n = dy + dx += dx + e = dx - dy + dy += dy + + upsampled_points = np.zeros([2, n + 1]) + for ii in range(n + 1): + upsampled_points[0, ii] = upscaled_point[0] + upsampled_points[1, ii] = upscaled_point[1] + if e >= 0: + upscaled_point[0] += xstep + e -= dy + e += dx + upscaled_point[1] += ystep + + # Now return the collision state and the current pose + points = 1.0 * upsampled_points / scale + + if do_floor is True: + points = points.astype(int) + indices = np.unique(points, axis=1, return_index=True)[1] + points = np.array([points[:, ind] for ind in sorted(indices)]).T + + return points + + +def cast_ray(occupancy_grid, start, target, scale=4, obstacle_threshold=1): + """Cast a ray through an occupancy grid, returning at collision. This + function uses Bresenham's line algorithm to determine if a ray passing + through a grid collides with obstacles in the grid. + """ + + # Convert to integers + upscaled_start_int = [int(scale * start[0]), int(scale * start[1])] + upscaled_target_int = [int(scale * target[0]), int(scale * target[1])] + upscaled_point = upscaled_start_int + did_collide = False + + dx = upscaled_target_int[0] - upscaled_start_int[0] + xstep = 1 + if dx < 0: + dx = -dx + xstep = -1 + + dy = upscaled_target_int[1] - upscaled_start_int[1] + ystep = 1 + if dy < 0: + dy = -dy + ystep = -1 + + if dx == 0: + # Vertical + for ii in range(dy): + # Check for collision + # If outside the grid, the ray will not collide + point = [upscaled_point[0] // scale, upscaled_point[1] // scale] + if not (0 <= point[0] < occupancy_grid.shape[0] + and 0 <= point[1] < occupancy_grid.shape[1]): + return (False, upscaled_target_int) + elif occupancy_grid[point[0], point[1]] >= obstacle_threshold: + did_collide = True + break + + # Update current position + upscaled_point[1] += ystep + elif dy == 0: + # Horizontal + for ii in range(dx): + # Check for collision + # If outside the grid, the ray will not collide + point = [upscaled_point[0] // scale, upscaled_point[1] // scale] + if not (0 <= point[0] < occupancy_grid.shape[0] + and 0 <= point[1] < occupancy_grid.shape[1]): + return (False, upscaled_target_int) + elif occupancy_grid[point[0], point[1]] >= obstacle_threshold: + did_collide = True + break + + # Update current position + upscaled_point[0] += xstep + elif dx > dy: + n = dx + dy += dy + e = dy - dx + dx += dx + + for ii in range(n): + # Check for collision + # If outside the grid, the ray will not collide + point = [upscaled_point[0] // scale, upscaled_point[1] // scale] + if not (0 <= point[0] < occupancy_grid.shape[0] + and 0 <= point[1] < occupancy_grid.shape[1]): + return (False, upscaled_target_int) + elif occupancy_grid[point[0], point[1]] >= obstacle_threshold: + did_collide = True + break + + # Update current position + if e >= 0: + upscaled_point[1] += ystep + e -= dx + e += dy + upscaled_point[0] += xstep + else: + n = dy + dx += dx + e = dx - dy + dy += dy + + for ii in range(n): + # Check for collision + # If outside the grid, the ray will not collide + point = [upscaled_point[0] // scale, upscaled_point[1] // scale] + if not (0 <= point[0] < occupancy_grid.shape[0] + and 0 <= point[1] < occupancy_grid.shape[1]): + return (False, upscaled_target_int) + elif occupancy_grid[point[0], point[1]] >= obstacle_threshold: + did_collide = True + break + + # Update current position + if e >= 0: + upscaled_point[0] += xstep + e -= dy + e += dx + upscaled_point[1] += ystep + + # Now return the collision state and the current pose + point = [1.0 * upscaled_point[0] / scale, 1.0 * upscaled_point[1] / scale] + return (did_collide, [point[0] + 0.0 / scale, point[1] + 0.0 / scale]) diff --git a/modules/gridmap/gridmap/mapping.py b/modules/gridmap/gridmap/mapping.py new file mode 100644 index 0000000..6bd91d9 --- /dev/null +++ b/modules/gridmap/gridmap/mapping.py @@ -0,0 +1,234 @@ +"""A set of functions useful for manipulating occupancy grids.""" + +import math +import matplotlib +import numpy as np +import scipy + +from . import laser + +from .constants import (COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL, + OBSTACLE_THRESHOLD) + + +def _transform_rays(rays, sensor_pose): + """Transform (rotate and offset) a laser scan according to pose.""" + origin = np.array([[sensor_pose.x], [sensor_pose.y]]) + rotation_mat = np.array( + [[math.cos(sensor_pose.yaw), -math.sin(sensor_pose.yaw)], + [math.sin(sensor_pose.yaw), + math.cos(sensor_pose.yaw)]]) + + return np.matmul(rotation_mat, rays) + origin + + +def _get_poly_for_scan(transformed_rays, sensor_pose): + """Returns a polygon obj for a transformed scan. + + For the polygon to completely contain the region defined by the scan, + this function requires that the sensor_pose be used to close the path. + """ + origin_np = np.array([[sensor_pose.x], [sensor_pose.y]]) + path_points = np.concatenate((origin_np, transformed_rays, origin_np), + axis=1) + return matplotlib.path.Path(path_points.T, closed=True) + + +def _set_points_inside_poly(grid, + poly, + value, + max_range=None, + sensor_pose=None): + """Sets the value of any grid points defined by a polygon. + + This function is suitable for setting all free points defined by a + laser scan converted into a matplotlib.path.Path via the + _get_poly_for_scan function. + """ + + # Compute the bounds + bounds_min = poly.vertices.min(axis=0) + bounds_max = poly.vertices.max(axis=0) + bounds_min = np.floor(bounds_min) + bounds_max = np.ceil(bounds_max) + bounds_min[0] = max(bounds_min[0], 0) + bounds_min[1] = max(bounds_min[1], 0) + bounds_max[0] = min(bounds_max[0], grid.shape[0] - 1) + bounds_max[1] = min(bounds_max[1], grid.shape[1] - 1) + + # Get list of points + x = np.arange(bounds_min[0], bounds_max[0] + 1) + 0.5 + y = np.arange(bounds_min[1], bounds_max[1] + 1) + 0.5 + xv, yv = np.meshgrid(x, y) + xr = np.reshape(xv, (xv.size, 1)) + yr = np.reshape(yv, (yv.size, 1)) + grid_points = np.concatenate((xr, yr), axis=1) + + # Prune points outside the max range if necessary + if max_range is not None: + origin_np = np.array([[sensor_pose.x], [sensor_pose.y]]) + is_within_range = np.sum( + (grid_points - origin_np.T)**2, axis=1) < (max_range**2) + grid_points = grid_points[is_within_range, :] + + # Compute inside points and set grid value + inside_points = poly.contains_points(grid_points) + + grid = grid.copy() + grid[grid_points[inside_points, 0].astype(int), + grid_points[inside_points, 1].astype(int)] = value + + return grid + + +def _set_collision_boundary(grid, + transformed_rays, + is_within_max_range, + connect_neighbor_distance=None): + """Adds obstacles defined by the transformed_rays. + + Obstacles are inserted at the endpoints of each of the transformed rays + for which is_within_max_range is True. If connect_neighbor_distance is not + None, lines of 'occupied' are drawn between neighboring points of a fixed + distance (in units of grid cells). Rays must already be transformed. + """ + + # Filter out points that are above max range or outside the grid + coll_points = transformed_rays.astype(int) + coll_points = coll_points[:, is_within_max_range] + coll_points = coll_points[:, coll_points[0, :] >= 0] + coll_points = coll_points[:, coll_points[1, :] >= 0] + coll_points = coll_points[:, coll_points[0, :] < grid.shape[0]] + coll_points = coll_points[:, coll_points[1, :] < grid.shape[1]] + + if connect_neighbor_distance is None: + grid[coll_points[0], coll_points[1]] = COLLISION_VAL + else: + for ii in range(coll_points.shape[1] - 1): + start = coll_points[:, ii] + end = coll_points[:, ii + 1] + if np.linalg.norm(start - end) < connect_neighbor_distance: + bpoints = laser.bresenham_points(start, end) + grid[bpoints[0, :], bpoints[1, :]] = COLLISION_VAL + else: + grid[start[0], start[1]] = COLLISION_VAL + + return grid + + +def _update_grid_with_projected_measurement(grid, measurement_grid, + occupied_prob, unoccupied_prob): + """Fuses an old grid and a new 'measurement_grid'. + + The measurement_grid should correspond to a new laser scan projected + into 2D space. The new measurement is fused into the old according to the + likelihood of observing occupied or unoccupied space. + """ + free_spaces = (measurement_grid == FREE_VAL) + coll_spaces = (measurement_grid == COLLISION_VAL) + unobserved_spaces = (grid == UNOBSERVED_VAL) + + grid = grid.copy() + # If the occupancy grid was unobserved, add the new value (no + # "probablity") + grid[unobserved_spaces] = measurement_grid[unobserved_spaces] + + # Otherwise, a probabilistic approach is used to join them + grid[free_spaces] = (unoccupied_prob * FREE_VAL + + (1 - unoccupied_prob) * grid[free_spaces]) + grid[coll_spaces] = (occupied_prob * COLLISION_VAL + + (1 - occupied_prob) * grid[coll_spaces]) + + return grid + + +def insert_scan(occupancy_grid, + laser_scanner_directions, + laser_ranges, + max_range, + sensor_pose, + connect_neighbor_distance=None, + occupied_prob=0.9, + unoccupied_prob=0.1, + do_only_compute_visibility=False): + """Add a new scan to an occupancy grid. + + We follow the Octomap Server convention for inserting scans: if the + grid is unoccupied, the value from the laser scan is trusted as the + ground truth. However, if another sensor observation has already + been revealed in that region, the new points are weighted by their + respective probabilities and averaged into the new grid. See + "_update_grid_with_projected_measurement" for implementation. + + Args: + occupancy_grid (np.Array): 2D grid of currently observed map. + laser_scanner_directions (np.Array): list of unit vectors + indicating direction of each element of 'range'. + laser_ranges (np.Array): 1D list of laser ranges/distances. + max_range (float): maximum range of sensor. Ranges above this distance + will not be inserted as obstacles and the insertion of free space + is limited to this value. + sensor_pose (Pose): pose at which the measurement will be inserted. + connect_neighbor_distance (int): Distance (in grid cells) that + neighboring obstacles should be connected. Important when the + max_range is large compared to the number of ranges. + occupied_prob (float): likelihood an observed obstacle is an obstacle. + unoccupied_prob (float): likelihood a free cell is actually free. + + Returns: + occupancy_grid (np.Array): grid with new scan inserted. + """ + + # Truncate the points by the max range (for efficiency purposes) + truncated_ranges = laser_ranges.copy() + truncated_ranges[truncated_ranges > max_range] = max_range + + # Compute the rays + rays = truncated_ranges * laser_scanner_directions + transformed_rays = _transform_rays(rays, sensor_pose) + + # Populate the new grid with the free/collision points + new_measurement_grid = UNOBSERVED_VAL * np.ones(occupancy_grid.shape) + poly = _get_poly_for_scan(transformed_rays, sensor_pose) + new_measurement_grid = _set_points_inside_poly(new_measurement_grid, + poly, + value=FREE_VAL, + max_range=max_range, + sensor_pose=sensor_pose) + new_measurement_grid = _set_collision_boundary( + grid=new_measurement_grid, + transformed_rays=transformed_rays, + is_within_max_range=(laser_ranges < max_range), + connect_neighbor_distance=connect_neighbor_distance) + + if do_only_compute_visibility: + return new_measurement_grid + + # Update grid with new measurement + occupancy_grid = _update_grid_with_projected_measurement( + grid=occupancy_grid.copy(), + measurement_grid=new_measurement_grid, + occupied_prob=occupied_prob, + unoccupied_prob=unoccupied_prob) + + return occupancy_grid + + +def get_fully_connected_observed_grid(occupancy_grid, pose): + """Returns a version of the observed grid in which components + unconnected to the region containing the robot are set to 'unobserved'. + This useful for preventing the system from generating any frontiers + that cannot be planned to. Also, certain geometrys may cause frontiers + to be erroneously ruled out if "stray" observed space exists. + """ + # Group the frontier points into connected components + labels, _ = scipy.ndimage.label( + np.logical_and(occupancy_grid < OBSTACLE_THRESHOLD, + occupancy_grid >= FREE_VAL)) + + occupancy_grid = occupancy_grid.copy() + robot_label = labels[int(pose.x), int(pose.y)] + mask = np.logical_and(labels > 0, labels != robot_label) + occupancy_grid[mask] = UNOBSERVED_VAL + + return occupancy_grid diff --git a/modules/gridmap/gridmap/planning.py b/modules/gridmap/gridmap/planning.py new file mode 100644 index 0000000..737290f --- /dev/null +++ b/modules/gridmap/gridmap/planning.py @@ -0,0 +1,125 @@ +import numpy as np +import skimage.graph + +from . import laser +from .constants import OBSTACLE_THRESHOLD +from .utils import inflate_grid + + +def compute_cost_grid_from_position(occupancy_grid, + start, + use_soft_cost=False, + obstacle_cost=-1, + ends=None, + only_return_cost_grid=False): + """Get the cost grid and planning function for a grid/start position. + + The primary purpose of this function is to plan using Dijkstra's algorithm. + If use_soft_cost == True, a soft inflation cost is added to the grid before + planning; This is useful for planning in practice, but increases planning + time, so defaults to False. The cost grid is computed by thresholding the + input occupancy_grid using OBSTACLE_THRESHOLD: anything below this value, + including free space, is treated as unoccupied. In addition to returning + the cost grid from the start position, this function also provides a + helper utility for generating a plan to a 'target' position in the grid. + + Args: + occupancy_grid (np.Array): input grid over which cost is computed + start (Pose): location of the start position for cost computation + use_soft_cost (Bool): do use soft costs. + + Returns: + cost_grid (np.Array): the Dijkstra's algorithm cost of traveling from + the 'start' position to other positions in the grid. If the point + is unreachable, the cost_grid is infinite for that grid cell. + get_plan (function): Returns the plan from 'start' to a provided + 'target' argument (also a Pose). Optional argumnent 'do_sparsify' + will return a sparse version of the plan, computed via the cost + grid; the sparsification will only happen a fixed number of points + into the future, specified by 'bound'. Optional argument 'do_flip' + will reverse the order of the computed plan and the order of the + sparsification. + """ + if len(np.array(start).shape) > 1: + starts = start.T + else: + starts = [start] + + if use_soft_cost is not None and use_soft_cost: + scale_factor = 50 + input_cost_grid = np.ones(occupancy_grid.shape) * scale_factor + g1 = inflate_grid(occupancy_grid, 1.5) + g2 = inflate_grid(g1, 1.0) + g3 = inflate_grid(g2, 1.5) + soft_cost_grid = 8 * g1 + 5 * g2 + g3 + input_cost_grid += soft_cost_grid + else: + scale_factor = 1 + soft_cost_grid = None + input_cost_grid = np.ones(occupancy_grid.shape) + + input_cost_grid[occupancy_grid >= OBSTACLE_THRESHOLD] = obstacle_cost + + mcp = skimage.graph.MCP_Geometric(input_cost_grid) + if ends is None: + cost_grid = mcp.find_costs(starts=starts)[0] / (1.0 * scale_factor) + else: + cost_grid = mcp.find_costs(starts=starts, + ends=ends)[0] / (1.0 * scale_factor) + + if only_return_cost_grid: + return cost_grid + + def get_path(target, do_sparsify=False, do_flip=False, bound=25): + try: + path_list = mcp.traceback(target) + except ValueError: + # Planning failed + return False, np.array([[]]) + path = np.zeros((2, len(path_list))) + if not do_flip: + for ii in range(len(path_list)): + path[:, ii] = path_list[ii] + else: + for ii in range(len(path_list)): + path[:, -1 - ii] = path_list[ii] + + if not do_sparsify: + return True, path.astype(int) + + # Sparsify the path + pstart = path[:, 0] + keep = [0] + inf_grid = np.isinf(cost_grid) + + if soft_cost_grid is not None: + tmp_grid = np.logical_or( + soft_cost_grid >= 0.05 * scale_factor * OBSTACLE_THRESHOLD, + inf_grid) + else: + tmp_grid = inf_grid + + if bound is not None: + bound = min(path.shape[1] - 1, bound) + else: + bound = path.shape[1] - 1 + + for ii in range(2, bound): + # Cast ray to the current terminal point + did_collide, _ = laser.cast_ray(tmp_grid, pstart, path[:, ii]) + + # If the ray tracing collides, add this point to the 'keep' list + # and update pstart + if did_collide: + keep.append(ii) + pstart = path[:, ii] + + for ii in range(bound, path.shape[1] - 1): + keep.append(ii) + + keep.append(path.shape[1] - 1) + path = path[:, keep] + + return True, path.astype(int) + + return cost_grid, get_path diff --git a/modules/gridmap/gridmap/utils.py b/modules/gridmap/gridmap/utils.py new file mode 100644 index 0000000..e5f6f11 --- /dev/null +++ b/modules/gridmap/gridmap/utils.py @@ -0,0 +1,49 @@ +import math +import numpy as np +import scipy.ndimage + +from .constants import COLLISION_VAL, OBSTACLE_THRESHOLD + + +def inflate_grid(grid, + inflation_radius, + obstacle_threshold=OBSTACLE_THRESHOLD, + collision_val=COLLISION_VAL): + """Inflates obstacles in an occupancy grid + + Creates a mask for all grid cells exceeding the obstacle threshold and + uses a convolution to compute how much the obstacles should inflate. The + inflated mask is used to set the cells of a copy of the initial grid to + occupied. All other cells are unchanged: free space and unnoccupied cells + outside of the inflation radius are preserved (therefore, frontiers can + still be computed from an inflated grid). + + Args: + grid (np.Array): occupancy grid + inflation_radius (float): radius (in grid units) to inflate obstacles. + Note that this is a float; a fractional inflation radius can be + used to determine whether or not corners of a box are included. + obstacle_threshold (float): value above which a cell is an obstacle. + collision_val (float): value obstacles are given after inflation. + + Returns: + inflated_grid (np.Array): grid with inflated obstacles. + """ + + obstacle_grid = np.zeros(grid.shape) + obstacle_grid[grid >= obstacle_threshold] = 1 + + kernel_size = int(1 + 2 * math.ceil(inflation_radius)) + cind = int(math.ceil(inflation_radius)) + y, x = np.ogrid[-cind:kernel_size - cind, -cind:kernel_size - cind] + kernel = np.zeros((kernel_size, kernel_size)) + kernel[y * y + x * x <= inflation_radius * inflation_radius] = 1 + inflated_mask = scipy.ndimage.filters.convolve(obstacle_grid, + kernel, + mode='constant', + cval=0) + inflated_mask = inflated_mask >= 1.0 + inflated_grid = grid.copy() + inflated_grid[inflated_mask] = collision_val + + return inflated_grid diff --git a/modules/gridmap/setup.py b/modules/gridmap/setup.py new file mode 100644 index 0000000..f60b42a --- /dev/null +++ b/modules/gridmap/setup.py @@ -0,0 +1,10 @@ +from setuptools import setup, find_packages + +setup(name='gridmap', + version='1.0.0', + description='Methods for mapping and planning in grids.', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy']) diff --git a/modules/gridmap/tests/test_gridmap.py b/modules/gridmap/tests/test_gridmap.py new file mode 100644 index 0000000..f4fa6bd --- /dev/null +++ b/modules/gridmap/tests/test_gridmap.py @@ -0,0 +1,141 @@ +import numpy as np +import random + +import common +import gridmap + + +def _make_sample_two_frontier_grid(add_blocking_wall=False, + add_nonblocking_wall=False): + """Generates a simple grid with two frontiers. Known space is on the left side +of the map and both frontiers lead to the same open portion of the map. The +returned dictionary object contains a goal pose that both frontiers can reach. + +Two walls can be added to the map. The first, the 'blocking wall', separates the +unknown space so that only one of the two frontiers can be reached. The second, +the 'nonblocking wall' does not separate the unknown space but introduces an +obstacle so that the delta_success_cost should be non-zero for both frontiers. + +Finally, one of the frontiers is considerably smaller than the other, so +intermediate levels of inflating the grid should block off one before the other. + """ + + # Generate a simple grid + boundary_ind = 75 + grid = gridmap.constants.UNOBSERVED_VAL * np.ones([150, 150]) + grid[1:-2, 1:boundary_ind] = gridmap.constants.FREE_VAL + grid[1, :] = gridmap.constants.COLLISION_VAL + grid[-2, :] = gridmap.constants.COLLISION_VAL + grid[:, 1] = gridmap.constants.COLLISION_VAL + grid[:, -2] = gridmap.constants.COLLISION_VAL + grid[:, boundary_ind] = gridmap.constants.COLLISION_VAL + grid[130:140, boundary_ind] = gridmap.constants.FREE_VAL + grid[20:21, boundary_ind] = gridmap.constants.FREE_VAL + + known_grid = grid.copy() + known_grid[known_grid == + gridmap.constants.UNOBSERVED_VAL] = gridmap.constants.FREE_VAL + + if add_blocking_wall: + # The known_grid should now have a "wall" that prevents us from reaching the + # goal from one of the frontiers. + known_grid[boundary_ind, + boundary_ind:] = gridmap.constants.COLLISION_VAL + + if add_nonblocking_wall: + # Add a wall so that the delta_success_cost will be nonzero + known_grid[10:-10, boundary_ind + 25] = gridmap.constants.COLLISION_VAL + + # Define the robot pose and the goal + pose = common.Pose(x=20.0, y=30.0, yaw=np.pi / 3) + goal = common.Pose(x=20.0, y=120.0, yaw=0) + + return {'grid': grid, 'known_grid': known_grid, 'pose': pose, 'goal': goal} + + +# Testing the sensor functionality +def test_basic_sensor_insertion(): + random.seed(8616) + np.random.seed(8616) + + # Generate a simple grid + boundary_ind = 75 + grid = np.zeros([150, 150]) + grid[1, :] = gridmap.constants.COLLISION_VAL + grid[-2, :] = gridmap.constants.COLLISION_VAL + grid[:, 1] = gridmap.constants.COLLISION_VAL + grid[:, -2] = gridmap.constants.COLLISION_VAL + grid[:, boundary_ind] = gridmap.constants.COLLISION_VAL + grid[40:50, 40:50] = gridmap.constants.COLLISION_VAL + + directions = gridmap.laser.get_laser_scanner_directions( + num_points=512, field_of_view_rad=2 * np.pi / 3) + + for _ in range(10): + pose = common.Pose(x=random.uniform(3.0, 60.0), + y=random.uniform(3.0, 60.0), + yaw=random.uniform(0, 2 * np.pi)) + ranges = gridmap.laser.simulate_sensor_measurement(grid, + directions, + max_range=102, + sensor_pose=pose) + + empty_grid = gridmap.constants.UNOBSERVED_VAL * np.ones(grid.shape) + scan_inserted_grid = gridmap.mapping.insert_scan( + empty_grid, + directions, + ranges, + max_range=100, + sensor_pose=pose, + connect_neighbor_distance=3) + + # Assert that few "occupied" points are out of place + assert np.sum( + np.logical_and( + scan_inserted_grid == gridmap.constants.COLLISION_VAL, grid + == gridmap.constants.FREE_VAL)) < 20 + # Assert that few "unoccupied" points exist where they should not + assert np.sum( + np.logical_and(scan_inserted_grid == gridmap.constants.FREE_VAL, + grid == gridmap.constants.COLLISION_VAL)) < 5 + assert np.sum(scan_inserted_grid[:, boundary_ind:] == + gridmap.constants.FREE_VAL) == 0 + + +def test_grid_inflation(): + """Confirm that inflating the grid generates plans incapable of going through small gaps""" + + # Get the basic grid + data = _make_sample_two_frontier_grid(add_blocking_wall=False, + add_nonblocking_wall=False) + grid = data['grid'] + pose = data['pose'] + goal = data['goal'] + + # Initialize the grids + uninflated_grid = grid.copy() + inflated_grid = gridmap.utils.inflate_grid(grid, inflation_radius=2.5) + very_inflated_grid = gridmap.utils.inflate_grid(grid, inflation_radius=8.0) + + # The plan should succeed and find the path through the small gap + _, uninflated_get_costs = gridmap.planning.compute_cost_grid_from_position( + uninflated_grid, [pose.x, pose.y]) + did_plan, path_sparse = uninflated_get_costs([goal.x, goal.y], + do_sparsify=True) + assert did_plan + assert common.compute_path_length(path_sparse) < 100.0 + + # The plan should succeed but have to go through the larger far gap + _, inflated_get_costs = gridmap.planning.compute_cost_grid_from_position( + inflated_grid, [pose.x, pose.y]) + did_plan, path_sparse = inflated_get_costs([goal.x, goal.y], + do_sparsify=True) + assert did_plan + assert common.compute_path_length(path_sparse) > 100.0 + + # The plan should not succeed + _, very_inflated_get_costs = gridmap.planning.compute_cost_grid_from_position( + very_inflated_grid, [pose.x, pose.y]) + did_plan, path_sparse = very_inflated_get_costs([goal.x, goal.y], + do_sparsify=True) + assert not did_plan diff --git a/modules/learning/README.md b/modules/learning/README.md new file mode 100644 index 0000000..f663ef7 --- /dev/null +++ b/modules/learning/README.md @@ -0,0 +1,52 @@ +# Learning: Data Handling and Visualization + +## Introduction + +This Python module consists of two main components: a data processing component (`data.py`) and a logging component (`logging.py`). The data processing component is responsible for handling pickled files, loading and saving them with compression, and loading them into a PyTorch `Dataset` for use in machine learning applications. The logging component is designed to log data using Matplotlib for visualization via TensorBoard. + +## File Overview + +### data.py + +- `write_compressed_pickle(pickle_filepath, datum, compresslevel=COMPRESS_LEVEL)`: This function writes a datum to a file as a compressed pickle. It compresses the pickle file using the gzip compression method with a specified compression level. + +- `load_compressed_pickle(pickle_filepath)`: This function loads a datum from a compressed pickle file. The function uses gzip to decompress the pickle file and then loads the datum. + +- `CSVPickleDataset`: This is a custom PyTorch `Dataset` class designed for data that is saved as compressed pickle files. It also optionally preprocesses the data on-the-fly during data loading. + +### logging.py + +- `tensorboard_plot_decorator(plot_func)`: This function is a decorator for creating Matplotlib plots to be saved and viewed in TensorBoard. The decorated function should take a `Figure` object as a keyword argument and perform its plot using that figure. The decorator takes care of creating the figure, transforming the plot into an image format suitable for TensorBoard, and writing the image to TensorBoard. + +## Usage + +The `tensorboard_plot_decorator` is meant to wrap a matplotlib-based plotting function so that its outputs may be stored in TensorBoard for easy visualization. It wraps a function whose signature includes the `fig` keyword, which specifies the matplotlib figure on which the plotting will be done. Here is a minimal example using this functino. + +```python +import torch +from torch.utils.tensorboard import SummaryWriter +from logging import tensorboard_plot_decorator + +# Instantiate a TensorBoard writer +writer = SummaryWriter() + +# Decorator applied to a plotting function +@tensorboard_plot_decorator +def plot_line(fig, x, y): + ax = fig.add_subplot(1, 1, 1) + ax.plot(x, y) + ax.set_title('Line Plot') + ax.set_xlabel('x') + ax.set_ylabel('y') + +# Generate some data for plotting +x = [1, 2, 3, 4, 5] +y = [2, 3, 5, 7, 11] + +# Call the decorated function +plot_line(writer, 'Line Plot', 0, x, y) # 0 is the index (step number) + +# Close the writer +writer.close() +``` + diff --git a/modules/learning/learning/__init__.py b/modules/learning/learning/__init__.py new file mode 100644 index 0000000..40b8e60 --- /dev/null +++ b/modules/learning/learning/__init__.py @@ -0,0 +1,2 @@ +from . import data # noqa: F401 +from . import logging # noqa: F401 diff --git a/modules/learning/learning/data.py b/modules/learning/learning/data.py new file mode 100644 index 0000000..4726365 --- /dev/null +++ b/modules/learning/learning/data.py @@ -0,0 +1,54 @@ +import glob +import gzip +import os +import _pickle as cPickle +import torch.utils.data as torch_data + +COMPRESS_LEVEL = 2 + + +def write_compressed_pickle(pickle_filepath, datum, compresslevel=COMPRESS_LEVEL): + """Write a datum to file as a compressed pickle.""" + with gzip.GzipFile(pickle_filepath, 'wb', compresslevel) as f: + cPickle.dump(datum, f, protocol=-1) + + +def load_compressed_pickle(pickle_filepath): + """Load a datum to file as a compressed pickle.""" + with gzip.GzipFile(pickle_filepath, 'rb') as pfile: + return cPickle.load(pfile) + + +class CSVPickleDataset(torch_data.Dataset): + def __init__(self, csv_filename, preprocess_function=None): + if not isinstance(csv_filename, list): + csv_filename = [csv_filename] + + self.preprocess_function = preprocess_function + self._pickle_paths = [] + + csvs = [] + for csvf in csv_filename: + if '*' in csvf: + csvs += glob.glob(csvf) + else: + csvs.append(csvf) + + for csvf in csvs: + csv_file_directory = os.path.split(csvf)[0] + with open(csvf, 'r') as fdata: + self._pickle_paths += [ + os.path.join(csv_file_directory, line.rstrip('\n')) + for line in fdata] + + def __getitem__(self, index): + datum = load_compressed_pickle(self._pickle_paths[index]) + + # Preprocess the data + if self.preprocess_function: + datum = self.preprocess_function(datum) + + return datum + + def __len__(self): + return len(self._pickle_paths) diff --git a/modules/learning/learning/logging.py b/modules/learning/learning/logging.py new file mode 100644 index 0000000..d653f4d --- /dev/null +++ b/modules/learning/learning/logging.py @@ -0,0 +1,17 @@ +from matplotlib.figure import Figure +from matplotlib.backends.backend_agg import FigureCanvas +import numpy as np + + +def tensorboard_plot_decorator(plot_func): + def wrapper(self, writer, name, index, *args, **kwds): + fig = Figure(dpi=200) + canvas = FigureCanvas(fig) + kwds['fig'] = fig + plot_func(self, *args, **kwds) + canvas.draw() + plot_image = np.array(canvas.renderer.buffer_rgba())[:, :, 0:3] + plot_image = np.transpose(plot_image, (2, 0, 1)) + writer.add_image(name, plot_image, index) + + return wrapper diff --git a/modules/learning/setup.py b/modules/learning/setup.py new file mode 100644 index 0000000..44f10f6 --- /dev/null +++ b/modules/learning/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='learning', + version='1.0.0', + description='Some shared resources for machine learning.', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'torch']) diff --git a/modules/learning/tests/test_learning_data.py b/modules/learning/tests/test_learning_data.py new file mode 100644 index 0000000..279b2a6 --- /dev/null +++ b/modules/learning/tests/test_learning_data.py @@ -0,0 +1,28 @@ +import learning +import tempfile +import numpy as np +import os + + +def test_learning_data_compressed_save_load(): + """Show that we can save and load a dictionary.""" + + with tempfile.TemporaryDirectory() as pickle_dir: + pickle_filename = os.path.join(pickle_dir, 'a_pickle.pickle.gz') + + datum = {'something': 'a string', + 'another': 104.3, + 'numpy': np.random.rand(5, 5)} + print("Writing data:") + print(datum) + + learning.data.write_compressed_pickle(pickle_filename, datum) + datum_loaded = learning.data.load_compressed_pickle(pickle_filename) + + # Some print statements + print("Loaded data:") + print(datum_loaded) + + assert datum['something'] == datum_loaded['something'] + assert datum['another'] == datum_loaded['another'] + assert (datum['numpy'] == datum_loaded['numpy']).all() diff --git a/modules/lsp/Makefile.mk b/modules/lsp/Makefile.mk new file mode 100644 index 0000000..3759494 --- /dev/null +++ b/modules/lsp/Makefile.mk @@ -0,0 +1,152 @@ + +help:: + @echo "Learned Subgoal Planning (lsp):" + @echo " lsp-maze Runs the 'guided maze' experiments." + @echo "" + +LSP_MAZE_BASENAME ?= lsp/maze +LSP_MAZE_NUM_TRAINING_SEEDS ?= 500 +LSP_MAZE_NUM_TESTING_SEEDS ?= 100 +LSP_MAZE_NUM_EVAL_SEEDS ?= 1000 +LSP_MAZE_CORE_ARGS ?= --unity_path /unity/$(UNITY_BASENAME).x86_64 \ + --map_type maze \ + --save_dir /data/$(LSP_MAZE_BASENAME)/ + +lsp-maze-data-gen-seeds = \ + $(shell for ii in $$(seq 1000 $$((1000 + $(LSP_MAZE_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_data/data_collect_plots/data_training_$${ii}.png"; done) \ + $(shell for ii in $$(seq 2000 $$((2000 + $(LSP_MAZE_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_data/data_collect_plots/data_testing_$${ii}.png"; done) + +$(lsp-maze-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-maze-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-maze-data-gen-seeds): + @echo "Generating Data [$(LSP_MAZE_BASENAME) | seed: $(seed) | $(traintest)"] + @$(call xhost_activate) + @-rm -f $(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_data/data_$(traintest)_$(seed).csv + @mkdir -p $(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_data/data + @mkdir -p $(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_data/data_collect_plots + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_generate_data \ + $(LSP_MAZE_CORE_ARGS) \ + --save_dir /data/$(LSP_MAZE_BASENAME)/training_data/ \ + --current_seed $(seed) --data_file_base_name data_$(traintest) + +.SECONDARY: $(lsp-maze-data-gen-seeds) + +lsp-maze-train-file = $(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt +$(lsp-maze-train-file): $(lsp-maze-data-gen-seeds) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/training_logs/$(EXPERIMENT_NAME) + $(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_train_net \ + --save_dir /data/$(LSP_MAZE_BASENAME)/training_logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_MAZE_BASENAME)/training_data/ + +lsp-maze-eval-seeds = \ + $(shell for ii in $$(seq 10000 $$((10000 + $(LSP_MAZE_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/results/$(EXPERIMENT_NAME)/maze_learned_$${ii}.png"; done) +$(lsp-maze-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-maze-eval-seeds): $(lsp-maze-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_MAZE_BASENAME)/results/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_eval \ + $(LSP_MAZE_CORE_ARGS) \ + --save_dir /data/$(LSP_MAZE_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/$(LSP_MAZE_BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt \ + --current_seed $(seed) --image_filename maze_learned_$(seed).png + +lsp-maze-results: + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_plotting \ + --data_file /data/$(LSP_MAZE_BASENAME)/results/$(EXPERIMENT_NAME)/logfile.txt \ + --output_image_file /data/$(LSP_MAZE_BASENAME)/results/results_$(EXPERIMENT_NAME).png + +# ==== Office (office2) Experiments === + +LSP_OFFICE_BASENAME ?= lsp/office +LSP_OFFICE_NUM_TRAINING_SEEDS ?= 500 +LSP_OFFICE_NUM_TESTING_SEEDS ?= 100 +LSP_OFFICE_NUM_EVAL_SEEDS ?= 1000 +LSP_OFFICE_CORE_ARGS ?= --unity_path /unity/$(UNITY_BASENAME).x86_64 \ + --map_type office2 \ + --save_dir /data/$(LSP_OFFICE_BASENAME)/ + +lsp-office-data-gen-seeds = \ + $(shell for ii in $$(seq 1000 $$((1000 + $(LSP_OFFICE_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_data/data_collect_plots/data_training_$${ii}.png"; done) \ + $(shell for ii in $$(seq 2000 $$((2000 + $(LSP_OFFICE_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_data/data_collect_plots/data_testing_$${ii}.png"; done) + +$(lsp-office-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-office-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-office-data-gen-seeds): + @echo "Generating Data [$(LSP_OFFICE_BASENAME) | seed: $(seed) | $(traintest)"] + @$(call xhost_activate) + @-rm -f $(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_data/data_$(traintest)_$(seed).csv + @mkdir -p $(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_data/data + @mkdir -p $(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_data/data_collect_plots + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_generate_data \ + $(LSP_OFFICE_CORE_ARGS) \ + --save_dir /data/$(LSP_OFFICE_BASENAME)/training_data/ \ + --current_seed $(seed) --data_file_base_name data_$(traintest) + +.SECONDARY: $(lsp-office-data-gen-seeds) + +lsp-office-train-file = $(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt +$(lsp-office-train-file): $(lsp-office-data-gen-seeds) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/training_logs/$(EXPERIMENT_NAME) + $(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_train_net \ + --save_dir /data/$(LSP_OFFICE_BASENAME)/training_logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_OFFICE_BASENAME)/training_data/ + +lsp-office-eval-seeds = \ + $(shell for ii in $$(seq 10000 $$((10000 + $(LSP_OFFICE_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/results/$(EXPERIMENT_NAME)/office_learned_$${ii}.png"; done) +$(lsp-office-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-office-eval-seeds): $(lsp-office-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_OFFICE_BASENAME)/results/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_eval \ + $(LSP_OFFICE_CORE_ARGS) \ + --save_dir /data/$(LSP_OFFICE_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/$(LSP_OFFICE_BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt \ + --current_seed $(seed) --image_filename office_learned_$(seed).png + +lsp-office-results: + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_plotting \ + --data_file /data/$(LSP_OFFICE_BASENAME)/results/$(EXPERIMENT_NAME)/logfile.txt \ + --output_image_file /data/$(LSP_OFFICE_BASENAME)/results/results_$(EXPERIMENT_NAME).png + +# ==== Helper Targets ==== + +.PHONY: lsp-maze-data-gen lsp-maze-train lsp-maze-eval lsp-maze-results lsp-maze +lsp-maze-data-gen: $(lsp-maze-data-gen-seeds) +lsp-maze-train: $(lsp-maze-train-file) +lsp-maze-eval: $(lsp-maze-eval-seeds) +lsp-maze: lsp-maze-eval + $(MAKE) lsp-maze-results + +.PHONY: lsp-office-data-gen lsp-office-train lsp-office-eval lsp-office-results lsp-office +lsp-office-data-gen: $(lsp-office-data-gen-seeds) +lsp-office-train: $(lsp-office-train-file) +lsp-office-eval: $(lsp-office-eval-seeds) +lsp-office: lsp-office-eval + $(MAKE) lsp-office-results + + +# ==== Check that the code is functioning ==== + +lsp-maze-check: DATA_BASE_DIR = $(shell pwd)/data/check +lsp-maze-check: LSP_MAZE_NUM_TRAINING_SEEDS = 12 +lsp-maze-check: LSP_MAZE_NUM_TESTING_SEEDS = 4 +lsp-maze-check: LSP_MAZE_NUM_EVAL_SEEDS = 12 +lsp-maze-check: build + $(MAKE) lsp-maze DATA_BASE_DIR=$(DATA_BASE_DIR) \ + LSP_MAZE_NUM_TRAINING_SEEDS=$(LSP_MAZE_NUM_TRAINING_SEEDS) \ + LSP_MAZE_NUM_TESTING_SEEDS=$(LSP_MAZE_NUM_TESTING_SEEDS) \ + LSP_MAZE_NUM_EVAL_SEEDS=$(LSP_MAZE_NUM_EVAL_SEEDS) + +lsp-office-check: DATA_BASE_DIR = $(shell pwd)/data/check +lsp-office-check: LSP_OFFICE_NUM_TRAINING_SEEDS = 12 +lsp-office-check: LSP_OFFICE_NUM_TESTING_SEEDS = 4 +lsp-office-check: LSP_OFFICE_NUM_EVAL_SEEDS = 12 +lsp-office-check: build + $(MAKE) lsp-office DATA_BASE_DIR=$(DATA_BASE_DIR) \ + LSP_OFFICE_NUM_TRAINING_SEEDS=$(LSP_OFFICE_NUM_TRAINING_SEEDS) \ + LSP_OFFICE_NUM_TESTING_SEEDS=$(LSP_OFFICE_NUM_TESTING_SEEDS) \ + LSP_OFFICE_NUM_EVAL_SEEDS=$(LSP_OFFICE_NUM_EVAL_SEEDS) diff --git a/modules/lsp/README.org b/modules/lsp/README.org new file mode 100644 index 0000000..a5e3147 --- /dev/null +++ b/modules/lsp/README.org @@ -0,0 +1,86 @@ +* LSP: Learning over Subgoals Planning + +Algorithmic code pertaining to the Learning over Subgoals Planning algorithm for learning-augmented, model-based planning in partially-mapped environments. This module reproduces core algorithm and results first presented in the following paper: + +Stein, Christopher Bradley, and Nicholas Roy. "Learning over Subgoals for Efficient Navigation of Structured, Unknown Environments". In: Conference on Robot Learning (CoRL). 2018. [[http://proceedings.mlr.press/v87/stein18a.html][paper]], [[https://youtu.be/4eHdGUoLlpg][talk, 14 min]]. [Best Paper Finalist] + +#+begin_src bibtex +@inproceedings{stein2018learning, + title={Learning over subgoals for efficient navigation of structured, unknown environments}, + author={Stein, Gregory J and Bradley, Christopher and Roy, Nicholas}, + booktitle={Conference on Robot Learning (CoRL)}, + pages={213--222}, + year={2018}, +} +#+end_src + +Readers are referred to the paper for algorithmic details. + +See also the Jupyter notebook-based onboarding tutorials discussed in the top-level README, as they make heavy use of the tools provided by this module. + +** Usage +*** Reproducing Results + +Note: =make build= (see top-level README) must be successfully run before running the following commands. + +The =Makefile.mk= provides multiple targets for reproducing results. +- =make lsp-maze= will generate results from our Guided Maze environment, in which a green path on the ground indicates the correct route to the unseen goal. The target first generates training data (via optimistic planning through similar environments), then trains a neural network to predict subgoal properties (predictions about the goodness of actions that enter unseen space), then evaluates performance using the trained neural network. Upon completing evaluation, it generates statistics and a scatterplot comparing the results with and without the learned model. +- =make lsp-office= will generate results in the =office2= environment: procedurally generated hallway-like maps. The process is similar to the above. + +Both targets are run in single-threaded mode by default, however both data generation and evaluation can be run on multiple seeds in parallel. As such, running =make lsp-maze -j3= will run three concurrent instances. As data generation has a smaller VRAM footprint than does evaluation, it is often possible to run more concurrent instances specifically for data generation: + +#+begin_src bash +make build +make lsp-maze-data-gen -j6 +make lsp-maze -j3 +#+end_src + +GNU Make keeps track of progress, so if (for whatever reason) the code is stopped during a run. Rerunning the above commands will resume where it left off, without the need to redo any of the completed data generation, training, or evaluation instances. + +For the =maze= environment, running this code produces the following results plot, which demonstrates (expectedly) significant improvement over the non-learned baseline: + +[[./resources/images/results_maze_dbg.png]] + +*** The Planner and PlanningLoop Classes + +The =Planner= class provides a relatively simple API for updating an internal "state of the world" and computing which subgoal the planner recommends. The planner classes are most easily used in tandem with the =PlanningLoop= class also provided alongside the =lsp.planning= module. They are most often used in scripts to emulate a robot iteratively receiving data, updating its map and plan, and then taking action. + +For example, the following code shows how to generate data using the =KnownSubgoalPlanner= class: + +#+begin_src python + known_planner = lsp.planners.KnownSubgoalPlanner( + goal=goal, known_map=known_map, args=args, + do_compute_weightings=True) + + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge, + robot, + args, + verbose=True) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + known_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + + # Get and write the data + subgoal_training_data = known_planner.get_subgoal_training_data() + lsp.utils.data.write_training_data_to_pickle( + subgoal_training_data, + step_counter=known_planner.update_counter, + args=known_planner.args) + + if not do_plan_with_naive: + planning_loop.set_chosen_subgoal( + known_planner.compute_selected_subgoal()) +#+end_src + +At every iteration, the =planning_loop= class yields the =step_data= dictionary, which contains the information needed to update the =known_planner=. The =known_planner= contains functionality to generate training data, with labels generated from the known map. At the end, the known planner can be optionally used to set the "chosen subgoal" of the =planning_loop=, which the =planning_loop= object will use to plan for the next step and will therefore follow the plan chosen by the known planner. If the chosen subgoal is not set, the =planning_loop= will simply plan using Dijkstra's algorithm (as if all unseen space were unoccupied). + +More examples of how to use the =Planner= classes can be found in the =lsp.scripts= for data generation and evaluation and in =tests.test_lsp_evaluate=. diff --git a/modules/lsp/lsp/__init__.py b/modules/lsp/lsp/__init__.py new file mode 100644 index 0000000..aad0d20 --- /dev/null +++ b/modules/lsp/lsp/__init__.py @@ -0,0 +1,8 @@ +from .pose import Pose # noqa: F401 +from . import constants # noqa: F401 +from . import robot # noqa: F401 +from . import simulators # noqa: F401 +from . import planners # noqa: F401 +from . import learning # noqa: F401 +from . import scripts # noqa: F401 +from . import utils # noqa: F401 diff --git a/modules/lsp/lsp/constants.py b/modules/lsp/lsp/constants.py new file mode 100644 index 0000000..700875a --- /dev/null +++ b/modules/lsp/lsp/constants.py @@ -0,0 +1,10 @@ +""" +Define some constants shared across the lsp module +""" + +COLLISION_VAL = 1 +FREE_VAL = 0 +UNOBSERVED_VAL = -1 +assert (COLLISION_VAL > FREE_VAL) +assert (FREE_VAL > UNOBSERVED_VAL) +OBSTACLE_THRESHOLD = 0.5 * (FREE_VAL + COLLISION_VAL) diff --git a/modules/lsp/lsp/core.py b/modules/lsp/lsp/core.py new file mode 100644 index 0000000..8ebe2bf --- /dev/null +++ b/modules/lsp/lsp/core.py @@ -0,0 +1,939 @@ +""" +This function stores everything pertaining to learned subgoal planning and frontiers. +""" + +from collections import namedtuple +import logging +import math +import numpy as np +import scipy.ndimage +import skimage.measure +import itertools +import time + +from gridmap.constants import (COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL, + OBSTACLE_THRESHOLD) + +import lsp +from gridmap import planning +import gridmap.utils +import lsp_accel + +IS_FROM_LAST_CHOSEN_REWARD = 0 * 10.0 + + +class Frontier(object): + def __init__(self, points): + """Initialized with a 2xN numpy array of points (the grid cell + coordinates of all points on frontier boundary).""" + inds = np.lexsort((points[0, :], points[1, :])) + sorted_points = points[:, inds] + self.props_set = False + self.is_from_last_chosen = False + self.is_obstructed = False + self.prob_feasible = 1.0 + self.delta_success_cost = 0.0 + self.exploration_cost = 0.0 + self.negative_weighting = 0.0 + self.positive_weighting = 0.0 + + self.counter = 0 + self.last_observed_pose = None + + # Any duplicate points should be eliminated (would interfere with + # equality checking). + dupes = [] + for ii in range(1, sorted_points.shape[1]): + if (sorted_points[:, ii - 1] == sorted_points[:, ii]).all(): + dupes += [ii] + self.points = np.delete(sorted_points, dupes, axis=1) + + # Compute and cache the hash + self.hash = hash(self.points.tobytes()) + + def set_props(self, + prob_feasible, + is_obstructed=False, + delta_success_cost=0, + exploration_cost=0, + positive_weighting=0, + negative_weighting=0, + counter=0, + last_observed_pose=None, + did_set=True): + self.props_set = did_set + self.just_set = did_set + self.prob_feasible = prob_feasible + self.is_obstructed = is_obstructed + self.delta_success_cost = delta_success_cost + self.exploration_cost = exploration_cost + self.positive_weighting = positive_weighting + self.negative_weighting = negative_weighting + self.counter = counter + self.last_observed_pose = last_observed_pose + + @property + def centroid(self): + return self.get_centroid() + + def get_centroid(self): + """Returns the point that is the centroid of the frontier""" + centroid = np.mean(self.points, axis=1) + return centroid + + def get_frontier_point(self): + """Returns the point that is on the frontier that is closest to the + actual centroid""" + center_point = np.mean(self.points, axis=1) + norm = np.linalg.norm(self.points - center_point[:, None], axis=0) + ind = np.argmin(norm) + return self.points[:, ind] + + def get_distance_to_point(self, point): + norm = np.linalg.norm(self.points - point[:, None], axis=0) + return norm.min() + + def __hash__(self): + return self.hash + + def __eq__(self, other): + return hash(self) == hash(other) + + +def get_frontiers(occupancy_grid, group_inflation_radius=0): + """Get froniers from the map. + + Frontiers exist at the boundary between free and unknown space. The + points that make up the frontiers exist in the *unknown* portion of + the space. This helps avoid some planning issues later on; if frontiers + are generated in the *known* portion of the map, they may obstruct + the robot's path and erroneously rule out regions of the map. + + We compute the frontiers using connected components. Masked by all the + frontiers, a map should confine an agent to the observed region. + """ + filtered_grid = scipy.ndimage.maximum_filter(np.logical_and( + occupancy_grid < OBSTACLE_THRESHOLD, occupancy_grid == FREE_VAL), size=3) + frontier_point_mask = np.logical_and(filtered_grid, + occupancy_grid == UNOBSERVED_VAL) + + if group_inflation_radius < 1: + inflated_frontier_mask = frontier_point_mask + else: + inflated_frontier_mask = gridmap.utils.inflate_grid( + frontier_point_mask, + inflation_radius=group_inflation_radius, + obstacle_threshold=0.5, + collision_val=1.0) > 0.5 + + # Group the frontier points into connected components + labels, nb = scipy.ndimage.label(inflated_frontier_mask) + + # Extract the frontiers + frontiers = set() + for ii in range(nb): + raw_frontier_indices = np.where( + np.logical_and(labels == (ii + 1), frontier_point_mask)) + frontiers.add( + Frontier( + np.concatenate((raw_frontier_indices[0][None, :], + raw_frontier_indices[1][None, :]), + axis=0))) + + return frontiers + + +def mask_grid_with_frontiers(occupancy_grid, frontiers, do_not_mask=None): + """Mask grid cells in the provided occupancy_grid with the frontier points + contained with the set of 'frontiers'. If 'do_not_mask' is provided, and + set to either a single frontier or a set of frontiers, those frontiers are + not masked.""" + + if do_not_mask is not None: + # Ensure that 'do_not_mask' is a set + if isinstance(do_not_mask, Frontier): + do_not_mask = set([do_not_mask]) + elif not isinstance(do_not_mask, set): + raise TypeError("do_not_mask must be either a set or a Frontier") + masking_frontiers = frontiers - do_not_mask + else: + masking_frontiers = frontiers + + masked_grid = occupancy_grid.copy() + for frontier in masking_frontiers: + masked_grid[frontier.points[0, :], + frontier.points[1, :]] = COLLISION_VAL + + return masked_grid + + +def _eucl_dist(p1, p2): + """Helper to compute Euclidean distance.""" + return math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + + +def _get_nearest_feasible_frontier(frontier, reference_frontier_set): + """Returns the nearest 'feasible' frontier from a reference set.""" + f_gen = [(of, _eucl_dist(of.get_centroid(), frontier.get_centroid())) + for of in reference_frontier_set if of.prob_feasible > 0.0] + if len(f_gen) == 0: + return None, 1e10 + else: + return min(f_gen, key=lambda fd: fd[1]) + + +def update_frontier_set(old_set, new_set, max_dist=None, chosen_frontier=None): + """Updates an old set of frontiers with a new set of frontiers. + + If a frontier persists, it is kept. If a new frontier appears, it is added. + Everything is done with python set operations. Finally, if a + "chosen_frontier" is passed, any frontier that derives its properties (i.e. + is closest to) that frontier from the old set has its 'is_from_last_chosen' + property set to true. + """ + + # Update the 'just_set' and 'is_from_last_chosen' properties + for frontier in old_set: + frontier.just_set = False + frontier.is_from_last_chosen = False + + # Shallow copy of the set + old_set = old_set.copy() + + # These are the frontiers that will not appear in the new set + outgoing_frontier_set = old_set - new_set + added_frontier_set = new_set - old_set + if max_dist is not None: + # Loop through the newly added_frontier_set and set properties based + # upon the outgoing_frontier_set + for af in added_frontier_set: + nearest_frontier, nearest_frontier_dist = ( + _get_nearest_feasible_frontier( + frontier=af, + reference_frontier_set=outgoing_frontier_set, + )) + if nearest_frontier_dist < max_dist: + af.set_props( + prob_feasible=nearest_frontier.prob_feasible, + delta_success_cost=nearest_frontier.delta_success_cost, + exploration_cost=nearest_frontier.exploration_cost, + did_set=False) + try: + af.image = nearest_frontier.image + af.mask = nearest_frontier.mask + af.goal_loc_x_mat = nearest_frontier.goal_loc_x_mat + af.goal_loc_y_mat = nearest_frontier.goal_loc_y_mat + except AttributeError: + pass + + if nearest_frontier == chosen_frontier: + af.is_from_last_chosen = True + else: + af.set_props(prob_feasible=1.0, + delta_success_cost=0.0, + exploration_cost=0.0, + did_set=False) + + # Remove frontier_set that don't appear in the new set + old_set.difference_update(outgoing_frontier_set) + + # Add the new frontier_set + old_set.update(added_frontier_set) + + return old_set + + +def update_frontiers_properties_known(inflated_known_grid, + inflated_observed_grid, + all_frontiers, + new_frontiers, + start_pose, + end_pose, + downsample_factor=1): + if not new_frontiers: + return + + # If the goal is in known space, all frontiers are successful + # and the success cost is identically zero. + goal_visible = goal_in_range(inflated_observed_grid, start_pose, end_pose, + all_frontiers) + if goal_visible: + for f in new_frontiers: + f.set_props(prob_feasible=1.0, + delta_success_cost=0.0, + positive_weighting=1.0) + return + + # Determine if any success frontiers + inflated_mixed_grid = np.ones_like(inflated_known_grid) + inflated_mixed_grid[np.logical_and( + inflated_known_grid == FREE_VAL, + inflated_observed_grid == UNOBSERVED_VAL)] = UNOBSERVED_VAL + + known_goal_distances = get_goal_distances(inflated_mixed_grid, end_pose, + new_frontiers, downsample_factor) + success_frontiers = [ + f for (f, kgd) in known_goal_distances.items() if kgd < 1e8 + ] + failure_frontiers = [ + f for (f, kgd) in known_goal_distances.items() if kgd >= 1e8 + ] + + # Compute and set the success costs + if success_frontiers: + observed_goal_distances = get_goal_distances(inflated_observed_grid, + end_pose, + success_frontiers, + downsample_factor) + for f, ogd in observed_goal_distances.items(): + if ogd > 1e8: + f.set_props(prob_feasible=0.0) + else: + kgd = known_goal_distances[f] + f.set_props(prob_feasible=1.0, delta_success_cost=kgd - ogd) + + if failure_frontiers: + # Get the cost grid from the robot in the inflated_known_grid + if downsample_factor > 1: + inflated_known_grid = skimage.measure.block_reduce( + inflated_known_grid, (downsample_factor, downsample_factor), + np.min) + inflated_mixed_grid = skimage.measure.block_reduce( + inflated_mixed_grid, (downsample_factor, downsample_factor), + np.min) + known_cost_grid = planning.compute_cost_grid_from_position( + inflated_known_grid, + start=[ + start_pose.x // downsample_factor, + start_pose.y // downsample_factor + ], + only_return_cost_grid=True) + + unk_regions = (inflated_mixed_grid == UNOBSERVED_VAL) + labels, nb = scipy.ndimage.label(unk_regions) + + # Loop through frontiers and for each + for f in failure_frontiers: + # Figure out which label that frontier matches + fp = f.points // downsample_factor + flabel = labels[fp[0, :], fp[1, :]].max() + cost_region = known_cost_grid[labels == flabel] + min_cost = cost_region.min() + max_cost = cost_region.max() + if min_cost > 1e8: + f.set_props(prob_feasible=0.0) + f.is_obstructed = True + else: + if max_cost > 1e8: + cost_region[cost_region > 1e8] = 0 + max_cost = cost_region.max() + + exploration_cost = 2 * downsample_factor * (max_cost - + min_cost) + f.set_props(prob_feasible=0.0, + exploration_cost=exploration_cost) + + +def update_frontiers_weights_known(inflated_known_grid, + inflated_observed_grid, + all_frontiers, + new_frontiers, + start_pose, + end_pose, + downsample_factor=1): + for frontier in new_frontiers: + if frontier.prob_feasible > 0.5: + # Compute the positive weighting + frontier.positive_weighting = lsp.utils.calc.compute_frontier_positive_weighting( + inflated_observed_grid, inflated_known_grid, all_frontiers, + frontier, start_pose, end_pose) + else: + # Compute the negative weighting + frontier.negative_weighting = lsp.utils.calc.compute_frontier_negative_weighting( + inflated_observed_grid, inflated_known_grid, all_frontiers, frontier, + start_pose, end_pose, frontier.exploration_cost) + + +def goal_in_range(grid, robot_pose, goal_pose, frontiers): + goal_visible = any( + f.get_distance_to_point(np.array([int(goal_pose.x), + int(goal_pose.y)])) < 1.5 + for f in frontiers) + goal_visible = (goal_visible or + grid[int(goal_pose.x), int(goal_pose.y)] != UNOBSERVED_VAL) + return goal_visible + + +def update_frontiers_goal_in_frontier(all_frontiers, end_pose): + """This function checks to see if the goal point is inside a frontier. If + it is, all frontiers are set as leading to the goal (and + props_set <- True).""" + + is_goal_in_frontier = False + for f in all_frontiers: + if [int(end_pose.x), int(end_pose.y)] in f.points.T.tolist(): + is_goal_in_frontier = True + + if is_goal_in_frontier: + for f in all_frontiers: + if f.props_set is False: + f.set_props(prob_feasible=1.0) + + +FrontWithPoint = namedtuple('FrontWithPoint', ['frontier', 'point']) + + +def get_frontier_distances(grid, frontiers, downsample_factor=1): + """get_frontier_distances takes an occupancy_grid and returns a dictionary. The + number of elemnts in it is the number of non repeating combinations of + frontiers so that every frontier pair is a key to the dictionary. Each key + is a frozenset of two frontiers. The value in the dictionary is a touple + that contatains two elements. The first element is the distance between the + two frontiers that make up the key, and the second element is the shortest + path between the frontiers stored as a numpy array. + """ + if len(frontiers) <= 1: + return None + + occupancy_grid = np.copy(grid) + frontier_distances = dict() + + frontier_with_point_list = [ + FrontWithPoint(frontier=f, + point=f.get_frontier_point() // downsample_factor) + for f in frontiers + ] + + all_frontier_points = np.concatenate([f.points for f in frontiers], axis=1) + + occupancy_grid[occupancy_grid == UNOBSERVED_VAL] = COLLISION_VAL + occupancy_grid[all_frontier_points[0, :], + all_frontier_points[1, :]] = FREE_VAL + + if downsample_factor > 1: + occupancy_grid = skimage.measure.block_reduce( + occupancy_grid, (downsample_factor, downsample_factor), np.min) + + # I only need the upper triangular block of the pairs. This means that I + # don't need the final fwp_1 (since it would only be comparing against + # itself) and I use the enumerate function to select only a subset of the + # fwp_2 entries. + for ind, fwp_1 in enumerate(frontier_with_point_list[:-1]): + # Compute the cost grid for the first frontier + start = fwp_1.frontier.points // downsample_factor + cost_grid = planning.compute_cost_grid_from_position( + occupancy_grid, + start=start, + use_soft_cost=False, + only_return_cost_grid=True) + for fwp_2 in frontier_with_point_list[ind + 1:]: + ff_set = frozenset([fwp_1.frontier, fwp_2.frontier]) + fpoints = fwp_2.frontier.points // downsample_factor + cost = downsample_factor * (cost_grid[fpoints[0, :], + fpoints[1, :]].min()) + frontier_distances[ff_set] = cost + + return frontier_distances + + +def get_robot_distances(grid, robot_pose, frontiers, downsample_factor=1): + """take in occupancy grid and robot position and returns a dictionary relating a frontier to it's distance + from the robot, and the path corresponding to that distance""" + occupancy_grid = np.copy(grid) + robot_distances = dict() + if len(frontiers) <= 0: + return [0, np.array([[]])] + + # Properly mask the occupancy grid + for frontier in frontiers: + occupancy_grid[frontier.points[0, :], frontier.points[1, :]] = FREE_VAL + occupancy_grid[occupancy_grid == UNOBSERVED_VAL] = COLLISION_VAL + if downsample_factor > 1: + occupancy_grid = skimage.measure.block_reduce( + occupancy_grid, (downsample_factor, downsample_factor), np.min) + + cost_grid = planning.compute_cost_grid_from_position( + occupancy_grid, + start=[ + robot_pose.x // downsample_factor, + robot_pose.y // downsample_factor + ], + use_soft_cost=False, + only_return_cost_grid=True) + + # Compute the cost for each frontier + for frontier in frontiers: + f_pt = frontier.get_frontier_point() // downsample_factor + cost = cost_grid[f_pt[0], f_pt[1]] + + if math.isinf(cost): + cost = 100000000000 + frontier.set_props(prob_feasible=0.0, is_obstructed=True) + frontier.just_set = False + + robot_distances[frontier] = downsample_factor * cost + + return robot_distances + + +def get_goal_distances(grid, goal_pose, frontiers, downsample_factor=1): + """take in occupancy grid and goal position and returns a dictionary relating a frontier to it's distance + from the goal, and the path corresponding to that distance""" + goal_distances = dict() + if len(frontiers) <= 0: + return [0, np.array([[]])] + + occupancy_grid = np.copy(grid) + occupancy_grid[occupancy_grid == FREE_VAL] = COLLISION_VAL + occupancy_grid[occupancy_grid == UNOBSERVED_VAL] = FREE_VAL + + if downsample_factor > 1: + occupancy_grid = skimage.measure.block_reduce( + occupancy_grid, (downsample_factor, downsample_factor), np.min) + + # Compute the cost grid + cost_grid = planning.compute_cost_grid_from_position( + occupancy_grid, + start=[ + goal_pose.x // downsample_factor, goal_pose.y // downsample_factor + ], + use_soft_cost=False, + only_return_cost_grid=True) + + # Compute the cost for each frontier + for frontier in frontiers: + fpts = frontier.points // downsample_factor + cost = downsample_factor * (cost_grid[fpts[0, :], fpts[1, :]].min()) + + if math.isinf(cost): + cost = 100000000000 + frontier.set_props(prob_feasible=0.0, is_obstructed=True) + frontier.just_set = False + + goal_distances[frontier] = cost + + return goal_distances + + +class FState(object): + """Used to conviently store the 'state' during recursive cost search. + """ + def __init__(self, new_frontier, distances, old_state=None): + nf = new_frontier + p = nf.prob_feasible + # Success cost + try: + sc = nf.delta_success_cost + distances['goal'][nf] + except KeyError: + sc = nf.delta_success_cost + distances['goal'][nf.id] + # Exploration cost + ec = nf.exploration_cost + + if old_state is not None: + self.frontier_list = old_state.frontier_list + [nf] + # Store the old frontier + of = old_state.frontier_list[-1] + # Known cost (travel between frontiers) + try: + kc = distances['frontier'][frozenset([nf, of])] + except KeyError: + kc = distances['frontier'][frozenset([nf.id, of.id])] + self.cost = old_state.cost + old_state.prob * (kc + p * sc + + (1 - p) * ec) + self.prob = old_state.prob * (1 - p) + else: + # This is the first frontier, so the robot must accumulate a cost of getting to the frontier + self.frontier_list = [nf] + # Known cost (travel to frontier) + try: + kc = distances['robot'][nf] + except KeyError: + kc = distances['robot'][nf.id] + + if nf.is_from_last_chosen: + kc -= IS_FROM_LAST_CHOSEN_REWARD + self.cost = kc + p * sc + (1 - p) * ec + self.prob = (1 - p) + + def __lt__(self, other): + return self.cost < other.cost + + +def get_ordering_cost(subgoals, distances): + """A helper function to compute the expected cost of a particular ordering. + The function takes an ordered list of subgoals (the order in which the robot + aims to explore beyond them). Consistent with the subgoal planning API, + 'distances' is a dictionary with three keys: 'robot' (a dict of the + robot-subgoal distances), 'goal' (a dict of the goal-subgoal distances), and + 'frontier' (a dict of the frontier-frontier distances).""" + fstate = None + for s in subgoals: + fstate = FState(s, distances, fstate) + + return fstate.cost + + +def get_lowest_cost_ordering(subgoals, distances, do_sort=True): + """This computes the lowest cost ordering (the policy) the robot will follow + for navigation under uncertainty. It wraps a branch-and-bound search + function implemented in C++ in 'lsp_accel'. As is typical of + branch-and-bound functions, function evaluation is fastest if the high-cost + plans can be ruled out quickly: i.e., if the first expansion is already of + relatively low cost, many of the other branches can be pruned. When + 'do_sort' is True, a handful of common-sense heuristics are run to find an + initial ordering that is of low cost to take advantage of this property. The + subgoals are sorted by the various heuristics and the ordering that + minimizes the expected cost is chosen. That ordering is used as an input to + the search function, which searches it first.""" + + if len(subgoals) == 0: + return None, None + + if do_sort: + order_heuristics = [] + order_heuristics.append({ + s: ii for ii, s in enumerate(subgoals) + }) + order_heuristics.append({ + s: 1 - s.prob_feasible for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + + s.delta_success_cost + for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + + s.exploration_cost + for s in subgoals + }) + + heuristic_ordering_dat = [] + for heuristic in order_heuristics: + ordered_subgoals = sorted(subgoals, reverse=False, key=lambda s: heuristic[s]) + ordering_cost = lsp.core.get_ordering_cost(ordered_subgoals, distances) + heuristic_ordering_dat.append((ordering_cost, ordered_subgoals)) + + subgoals = min(heuristic_ordering_dat, key=lambda hod: hod[0])[1] + + s_dict = {hash(s): s for s in subgoals} + rd_cpp = {hash(s): distances['robot'][s] for s in subgoals} + gd_cpp = {hash(s): distances['goal'][s] for s in subgoals} + fd_cpp = {(hash(sp[0]), hash(sp[1])): distances['frontier'][frozenset(sp)] + for sp in itertools.permutations(subgoals, 2)} + s_cpp = [ + lsp_accel.FrontierData(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in subgoals + ] + + cost, ordering = lsp_accel.get_lowest_cost_ordering( + s_cpp, rd_cpp, gd_cpp, fd_cpp) + ordering = [s_dict[sid] for sid in ordering] + + return cost, ordering + + +def get_lowest_cost_ordering_beginning_with(frontier_of_interest, + subgoals, + distances, + do_sort=False): + subgoals = [s for s in subgoals if not s == frontier_of_interest] + + if len(subgoals) == 0: + state = FState(frontier_of_interest, distances) + return state.cost, state.frontier_list + if len(subgoals) == 1: + state = FState(frontier_of_interest, distances) + state = FState(subgoals[0], distances, state) + return state.cost, state.frontier_list + + if frontier_of_interest not in subgoals: + subgoals.append(frontier_of_interest) + + if do_sort: + try: + h = { + s: distances['goal'][s] + distances['robot'][s] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in subgoals + } + except KeyError: + h = { + s: distances['goal'][s.id] + distances['robot'][s.id] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in subgoals + } + subgoals.sort(reverse=False, key=lambda s: h[s]) + + s_dict = {hash(s): s for s in subgoals} + try: + rd_cpp = {hash(s): distances['robot'][s] for s in subgoals} + gd_cpp = {hash(s): distances['goal'][s] for s in subgoals} + fd_cpp = {(hash(sp[0]), hash(sp[1])): + distances['frontier'][frozenset(sp)] + for sp in itertools.permutations(subgoals, 2)} + except KeyError: + rd_cpp = {hash(s): distances['robot'][s.id] for s in subgoals} + gd_cpp = {hash(s): distances['goal'][s.id] for s in subgoals} + fd_cpp = {(hash(sp[0]), hash(sp[1])): + distances['frontier'][frozenset([sp[0].id, sp[1].id])] + for sp in itertools.permutations(subgoals, 2)} + + s_cpp = [ + lsp_accel.FrontierData(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in subgoals + if s != frontier_of_interest + ] + + foi = lsp_accel.FrontierData(frontier_of_interest.prob_feasible, + frontier_of_interest.delta_success_cost, + frontier_of_interest.exploration_cost, + hash(frontier_of_interest), + frontier_of_interest.is_from_last_chosen) + + cost, ordering = lsp_accel.get_lowest_cost_ordering_beginning_with( + foi, s_cpp, rd_cpp, gd_cpp, fd_cpp) + ordering = [s_dict[sid] for sid in ordering] + + return cost, ordering + + +def get_lowest_cost_ordering_not_beginning_with(frontier_of_interest, + subgoals, + distances, + do_sort=False): + subgoals = [s for s in subgoals if not s == frontier_of_interest] + + if len(subgoals) == 0: + state = FState(frontier_of_interest, distances) + return state.cost, state.frontier_list + if len(subgoals) == 1: + state = FState(frontier_of_interest, distances) + state = FState(subgoals[0], distances, state) + return state.cost, state.frontier_list + + if frontier_of_interest not in subgoals: + subgoals.append(frontier_of_interest) + + if do_sort: + try: + h = { + s: distances['goal'][s] + distances['robot'][s] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in subgoals + } + except KeyError: + h = { + s: distances['goal'][s.id] + distances['robot'][s.id] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in subgoals + } + subgoals.sort(reverse=False, key=lambda s: h[s]) + + s_dict = {hash(s): s for s in subgoals} + try: + rd_cpp = {hash(s): distances['robot'][s] for s in subgoals} + gd_cpp = {hash(s): distances['goal'][s] for s in subgoals} + fd_cpp = {(hash(sp[0]), hash(sp[1])): + distances['frontier'][frozenset(sp)] + for sp in itertools.permutations(subgoals, 2)} + except KeyError: + rd_cpp = {hash(s): distances['robot'][s.id] for s in subgoals} + gd_cpp = {hash(s): distances['goal'][s.id] for s in subgoals} + fd_cpp = {(hash(sp[0]), hash(sp[1])): + distances['frontier'][frozenset([sp[0].id, sp[1].id])] + for sp in itertools.permutations(subgoals, 2)} + + s_cpp = [ + lsp_accel.FrontierData(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in subgoals + ] + + foi = lsp_accel.FrontierData(frontier_of_interest.prob_feasible, + frontier_of_interest.delta_success_cost, + frontier_of_interest.exploration_cost, + hash(frontier_of_interest), + frontier_of_interest.is_from_last_chosen) + + cost, ordering = lsp_accel.get_lowest_cost_ordering_not_beginning_with( + foi, s_cpp, rd_cpp, gd_cpp, fd_cpp) + ordering = [s_dict[sid] for sid in ordering] + + return cost, ordering + + +def get_lowest_cost_ordering_old(frontiers, distances): + """Recursively compute the lowest cost ordering of provided frontiers. + """ + def get_ordering_sub(frontiers, state=None): + """Sub-function defined for recursion. Property 'bound' is set for + branch-and-bound, which vastly speeds up computation in practice.""" + if len(frontiers) == 1: + s = FState(frontiers[0], distances, state) + get_ordering_sub.bound = min(s.cost, get_ordering_sub.bound) + return s + + if state is not None and state.cost > get_ordering_sub.bound: + return state + + try: + return min([ + get_ordering_sub([fn for fn in frontiers if fn != f], + FState(f, distances, state)) + for f in frontiers + ]) + except ValueError: + return None + + get_ordering_sub.bound = 1e10 + h = { + s: distances['goal'][s] + distances['robot'][s] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in frontiers + } + frontiers.sort(reverse=False, key=lambda s: h[s]) + + best_state = get_ordering_sub(frontiers) + if best_state is None: + return None, None + else: + return best_state.cost, best_state.frontier_list + + +def get_top_n_frontiers(frontiers, goal_dist, robot_dist, n): + """This heuristic is for retrieving the 'best' N frontiers""" + + # This sorts the frontiers by (1) any frontiers that "derive their + # properties" from the last chosen frontier and (2) the probablity that the + # frontiers lead to the goal. + frontiers = [f for f in frontiers if f.prob_feasible > 0] + + h_prob = {s: s.prob_feasible for s in frontiers} + try: + h_dist = {s: goal_dist[s] + robot_dist[s] for s in frontiers} + except KeyError: + h_dist = {s: goal_dist[s.id] + robot_dist[s.id] for s in frontiers} + + fs_prob = sorted(list(frontiers), key=lambda s: h_prob[s], reverse=True) + fs_dist = sorted(list(frontiers), key=lambda s: h_dist[s], reverse=False) + + seen = set() + fs_collated = [] + + for front_d in fs_dist[:2]: + if front_d not in seen: + seen.add(front_d) + fs_collated.append(front_d) + + for front_p in fs_prob: + if front_p not in seen: + seen.add(front_p) + fs_collated.append(front_p) + + assert len(fs_collated) == len(seen) + assert len(fs_collated) == len(fs_prob) + assert len(fs_collated) == len(fs_dist) + + return fs_collated[0:n] + + +def get_top_n_frontiers_distance(frontiers, goal_dist, robot_dist, n): + """This heuristic is for retrieving the 'best' N frontiers""" + + frontiers = [f for f in frontiers if f.prob_feasible > 0] + + try: + h_dist = {s: goal_dist[s] + robot_dist[s] for s in frontiers} + except KeyError: + h_dist = {s: goal_dist[s.id] + robot_dist[s.id] for s in frontiers} + + fs_dist = sorted(list(frontiers), key=lambda s: h_dist[s], reverse=False) + + return fs_dist[0:n] + + +def get_best_expected_cost_and_frontier_list(grid, + robot_pose, + goal_pose, + frontiers, + num_frontiers_max=0, + downsample_factor=1, + do_correct_low_prob=False): + """Compute the best frontier using the LSP algorithm.""" + logger = logging.getLogger("frontier") + + # Remove frontiers that are infeasible + frontiers = [f for f in frontiers if f.prob_feasible != 0] + + # Calculate the distance to the goal, if infeasible, remove frontier + stime = time.time() + goal_distances = get_goal_distances(grid, + goal_pose, + frontiers=frontiers, + downsample_factor=downsample_factor) + frontiers = [f for f in frontiers if f.prob_feasible != 0] + logger.debug(f"time to get goal_distances: {time.time() - stime}") + + stime = time.time() + robot_distances = get_robot_distances(grid, + robot_pose, + frontiers=frontiers, + downsample_factor=downsample_factor) + logger.debug(f"time to get robot_distances: {time.time() - stime}") + + # Get the most n probable frontiers to limit computational load + if num_frontiers_max > 0 and num_frontiers_max < len(frontiers): + frontiers = get_top_n_frontiers(frontiers, goal_distances, + robot_distances, num_frontiers_max) + + # Calculate robot and frontier distances + stime = time.time() + frontier_distances = get_frontier_distances( + grid, frontiers=frontiers, downsample_factor=downsample_factor) + logger.debug(f"time to get frontier_distances: {time.time() - stime}") + + # Make one last pass to eliminate infeasible frontiers + frontiers = [f for f in frontiers if f.prob_feasible != 0] + + distances = { + 'frontier': frontier_distances, + 'robot': robot_distances, + 'goal': goal_distances, + } + + stime = time.time() + + if do_correct_low_prob: + old_probs = [f.prob_feasible for f in frontiers] + sum_old_probs = sum(old_probs) + if sum_old_probs < 1.0: + # print("[WARN] Fixing low probability frontiers.") + for f in frontiers: + f.prob_feasible /= sum_old_probs + + out = get_lowest_cost_ordering(frontiers, distances) + logger.debug(f"time to get ordering: {time.time() - stime}") + + if do_correct_low_prob and sum_old_probs < 1.0: + for f in frontiers: + f.prob_feasible *= sum_old_probs + + return out diff --git a/modules/lsp/lsp/learning/__init__.py b/modules/lsp/lsp/learning/__init__.py new file mode 100644 index 0000000..fe15518 --- /dev/null +++ b/modules/lsp/lsp/learning/__init__.py @@ -0,0 +1 @@ +from . import models # noqa diff --git a/modules/lsp/lsp/learning/models/__init__.py b/modules/lsp/lsp/learning/models/__init__.py new file mode 100644 index 0000000..118429c --- /dev/null +++ b/modules/lsp/lsp/learning/models/__init__.py @@ -0,0 +1,2 @@ +from .vis_lsp_oriented import VisLSPOriented # noqa: F401 +from . import shared # noqa: F401 diff --git a/modules/lsp/lsp/learning/models/shared.py b/modules/lsp/lsp/learning/models/shared.py new file mode 100644 index 0000000..91eea1f --- /dev/null +++ b/modules/lsp/lsp/learning/models/shared.py @@ -0,0 +1,39 @@ +import torch.nn as nn + + +class EncoderNBlocks(nn.Module): + def __init__(self, in_channels, out_channels, num_layers): + super(EncoderNBlocks, self).__init__() + nin = in_channels + nout = out_channels + modules = [] + + # First layer + modules.append( + nn.Conv2d(nin, + nout, + kernel_size=3, + stride=1, + padding=1, + bias=False)) + modules.append(nn.BatchNorm2d(nout, momentum=0.01)) + modules.append(nn.LeakyReLU(0.1, inplace=True)) + + # Add remaining layers + for ii in range(1, num_layers): + modules.append( + nn.Conv2d(nout, + nout, + kernel_size=3, + stride=1, + padding=1, + bias=False)) + modules.append(nn.BatchNorm2d(nout, momentum=0.01)) + modules.append(nn.LeakyReLU(0.1, inplace=True)) + + modules.append(nn.MaxPool2d(kernel_size=2, stride=2)) + + self.cnn_layers = nn.Sequential(*modules) + + def forward(self, x): + return self.cnn_layers(x) diff --git a/modules/lsp/lsp/learning/models/vis_lsp_oriented.py b/modules/lsp/lsp/learning/models/vis_lsp_oriented.py new file mode 100644 index 0000000..9f64443 --- /dev/null +++ b/modules/lsp/lsp/learning/models/vis_lsp_oriented.py @@ -0,0 +1,158 @@ +import numpy as np +import torch +import torch.nn as nn +import torch.nn.functional as F +import learning + +from .shared import EncoderNBlocks + + +class VisLSPOriented(nn.Module): + name = "VisLSPOriented" + + def __init__(self, args=None, num_outputs=3): + super(VisLSPOriented, self).__init__() + self._args = args + + # Initialize the blocks + self.enc_1 = EncoderNBlocks(3, 64, num_layers=2) + self.enc_2 = EncoderNBlocks(64, 64, num_layers=2) + self.enc_3 = EncoderNBlocks(64 + 4, 128, num_layers=2) + self.enc_4 = EncoderNBlocks(128, 128, num_layers=2) + self.enc_5 = EncoderNBlocks(128, 256, num_layers=2) + self.enc_6 = EncoderNBlocks(256, 128, num_layers=2) + self.conv_1x1 = nn.Conv2d(128, 16, kernel_size=1) + + self.fc_outs = nn.Sequential( + nn.Flatten(), + nn.Linear(256, 128), + nn.LeakyReLU(0.1, inplace=True), + nn.Linear(128, 64), + nn.LeakyReLU(0.1, inplace=True), + nn.Linear(64, 32), + nn.LeakyReLU(0.1, inplace=True), + nn.Linear(32, 16), + nn.LeakyReLU(0.1, inplace=True), + nn.Linear(16, num_outputs), + ) + + self.goal_bn = nn.BatchNorm2d(2) + self.subgoal_bn = nn.BatchNorm2d(2) + + def forward(self, data, device): + image = data['image'].to(device) + + # Compute goal info tensor + if 'goal_loc_x' in data.keys(): + g = self.goal_bn( + torch.stack((data['goal_loc_x'], data['goal_loc_y']), + 1).expand([-1, -1, 32, -1]).float().to(device)) + else: + raise ValueError("Missing goal location data.") + + if 'subgoal_loc_x' in data.keys(): + s = self.subgoal_bn( + torch.stack((data['subgoal_loc_x'], data['subgoal_loc_y']), + 1).expand([-1, -1, 32, -1]).float().to(device)) + else: + raise ValueError("Missing subgoal location data.") + + x = image + + # Encoding layers + x = self.enc_1(x) + x = self.enc_2(x) + x = torch.cat((x, s, g), 1) # Add the goal info tensor + x = self.enc_3(x) + x = self.enc_4(x) + x = self.enc_5(x) + x = self.enc_6(x) + x = self.conv_1x1(x) + x = self.fc_outs(x) + + return x + + def loss(self, nn_out, data, device='cpu', writer=None, index=None): + # Separate outputs. + is_feasible_logits = nn_out[:, 0] + delta_cost_pred = nn_out[:, 1] + exploration_cost_pred = nn_out[:, 2] + + # Convert the data + is_feasible_label = data['is_feasible'].to(device) + delta_cost_label = data['delta_success_cost'].to(device) + exploration_cost_label = data['exploration_cost'].to(device) + pweight = data['positive_weighting'].to(device) + nweight = data['negative_weighting'].to(device) + rpw = self._args.relative_positive_weight + + # Compute the contribution from the is_feasible_label + is_feasible_xentropy = torch.mean(rpw * is_feasible_label * -F.logsigmoid(is_feasible_logits) * pweight / 10 + + (1 - is_feasible_label) * -F.logsigmoid(-is_feasible_logits) * nweight / 10) + + # Delta Success Cost + delta_cost_pred_error = torch.mean(torch.square( + delta_cost_pred - delta_cost_label) / (100 ** 2) * is_feasible_label) + + # Exploration Cost + exploration_cost_pred_error = torch.mean(torch.square( + exploration_cost_pred - exploration_cost_label) / (200 ** 2) * (1 - is_feasible_label)) + + # Sum the contributions + loss = is_feasible_xentropy + delta_cost_pred_error + exploration_cost_pred_error + + # Logging + if writer is not None: + writer.add_scalar("Loss/is_feasible_xentropy", + is_feasible_xentropy.item(), + index) + writer.add_scalar("Loss/delta_success_cost_loss", + delta_cost_pred_error.item(), + index) + writer.add_scalar("Loss/exploration_cost_loss", + exploration_cost_pred_error.item(), + index) + writer.add_scalar("Loss/total_loss", + loss.item(), + index) + + return loss + + @learning.logging.tensorboard_plot_decorator + def plot_images(self, fig, image, out, data): + image = np.transpose(image, (1, 2, 0)) + pred_feasible = torch.sigmoid(out[0]).cpu().numpy() + is_feasible = data['is_feasible'][0] + + axs = fig.subplots(1, 1) + axs.imshow(image, interpolation='none') + axs.set_title(f"{is_feasible}: {pred_feasible}") + + @classmethod + def preprocess_data(_, datum, is_training=True): + datum['image'] = np.transpose(datum['image'], (2, 0, 1)).astype(np.float32) / 255 + return datum + + @classmethod + def get_net_eval_fn(_, network_file, device): + model = VisLSPOriented() + model.load_state_dict(torch.load(network_file)) + model.eval() + model.to(device) + + def frontier_net(nn_input_data): + with torch.no_grad(): + nn_input_data = VisLSPOriented.preprocess_data(nn_input_data, is_training=False) + out = model({ + 'image': torch.tensor(np.expand_dims(nn_input_data['image'], axis=0)).float(), + 'goal_loc_x': torch.tensor(np.expand_dims(nn_input_data['goal_loc_x'], axis=0)).float(), + 'goal_loc_y': torch.tensor(np.expand_dims(nn_input_data['goal_loc_y'], axis=0)).float(), + 'subgoal_loc_x': torch.tensor(np.expand_dims(nn_input_data['subgoal_loc_x'], axis=0)).float(), + 'subgoal_loc_y': torch.tensor(np.expand_dims(nn_input_data['subgoal_loc_y'], axis=0)).float(), + }, device=device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + return out[0, 0], out[0, 1], out[0, 2] + + return frontier_net diff --git a/modules/lsp/lsp/planners/__init__.py b/modules/lsp/lsp/planners/__init__.py new file mode 100644 index 0000000..463689f --- /dev/null +++ b/modules/lsp/lsp/planners/__init__.py @@ -0,0 +1,6 @@ +from . import utils # noqa: F401 +from .planner import Planner # noqa: F401 +from .known_planner import KnownPlanner # noqa: F401 +from .dijkstra_planner import DijkstraPlanner # noqa: F401 +from .subgoal_planner import KnownSubgoalPlanner, LearnedSubgoalPlanner # noqa: F401 +from .planning_loop import PlanningLoop # noqa: F401 diff --git a/modules/lsp/lsp/planners/dijkstra_planner.py b/modules/lsp/lsp/planners/dijkstra_planner.py new file mode 100644 index 0000000..b5cfc0d --- /dev/null +++ b/modules/lsp/lsp/planners/dijkstra_planner.py @@ -0,0 +1,41 @@ +import numpy as np +from .planner import Planner +import gridmap + + +class DijkstraPlanner(Planner): + def __init__(self, goal, args): + super(DijkstraPlanner, self).__init__(goal) + + self.subgoals = None + self.selected_subgoal = None + self.observed_map = None + self.args = args + + self.inflation_radius = args.inflation_radius_m / args.base_resolution + + def compute_selected_subgoal(self): + if not self.subgoals: + return None + + # Compute cost grid + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + self.inflated_grid, [self.goal.x, self.goal.y], use_soft_cost=True) + + # Compute the plan + did_plan, path = get_path([self.robot_pose.x, self.robot_pose.y], + do_sparsify=False, + do_flip=True) + if not did_plan: + import matplotlib.pyplot as plt + plt.figure() + plt.imshow(self.inflated_grid) + plt.show() + plt.pause(100) + if np.argmax(self.observed_map[path[0, -1], path[1, -1]] >= 0): + return None + + # Determine the chosen subgoal + ind = np.argmax(self.observed_map[path[0, :], path[1, :]] < 0) + return min(self.subgoals, + key=lambda s: s.get_distance_to_point((path.T)[ind])) diff --git a/modules/lsp/lsp/planners/known_planner.py b/modules/lsp/lsp/planners/known_planner.py new file mode 100644 index 0000000..249de02 --- /dev/null +++ b/modules/lsp/lsp/planners/known_planner.py @@ -0,0 +1,57 @@ +import numpy as np +from .planner import Planner +import gridmap +from ..pose import compute_path_length + + +class KnownPlanner(Planner): + def __init__(self, goal, known_map, args): + super(KnownPlanner, self).__init__(goal) + + self.known_map = known_map + self.subgoals = set() + self.selected_subgoal = None + self.observed_map = None + self.args = args + self.inflation_radius = args.inflation_radius_m / args.base_resolution + if self.inflation_radius >= np.sqrt(5): + self.downsample_factor = 2 + else: + self.downsample_factor = 1 + + self.inflated_known_grid = gridmap.utils.inflate_grid( + known_map, inflation_radius=self.inflation_radius) + + # Compute cost grid + _, self.get_path = gridmap.planning.compute_cost_grid_from_position( + self.inflated_known_grid, [goal.x, goal.y], use_soft_cost=True) + + def compute_path_to_goal(self): + """Returns the path and distance to the goal.""" + did_plan, path = self.get_path([self.robot_pose.x, self.robot_pose.y], + do_sparsify=True, + do_flip=True, + bound=None) + + distance = compute_path_length(path) + return did_plan, path, distance + + def compute_selected_subgoal(self): + if not self.subgoals: + return None + + # Compute the plan + did_plan, path = self.get_path([self.robot_pose.x, self.robot_pose.y], + do_sparsify=False, + do_flip=True, + bound=None) + if did_plan is False: + print("Plan did not succeed...") + raise NotImplementedError("Not sure what to do here yet") + if np.argmax(self.observed_map[path[0, -1], path[1, -1]] >= 0): + return None + + # Determine the chosen subgoal + ind = np.argmax(self.observed_map[path[0, :], path[1, :]] < 0) + return min(self.subgoals, + key=lambda s: s.get_distance_to_point((path.T)[ind])) diff --git a/modules/lsp/lsp/planners/planner.py b/modules/lsp/lsp/planners/planner.py new file mode 100644 index 0000000..8873208 --- /dev/null +++ b/modules/lsp/lsp/planners/planner.py @@ -0,0 +1,38 @@ +import copy +import gridmap + + +class Planner(object): + """Abstract class for planning with frontiers.""" + def __init__(self, goal): + self.name = 'Planner' + self.observed_map = None + self.goal = goal + + def update(self, observation, observed_map, subgoals, robot_pose, *args, + **kwargs): + self.observation = observation + self.observed_map = observed_map + self.subgoals = [copy.copy(s) for s in subgoals] + self.robot_pose = robot_pose + self.inflated_grid = self._get_inflated_occupancy_grid() + + def compute_selected_subgoal(self): + """Returns the selected subgoal (frontier).""" + raise NotImplementedError() + + def _get_inflated_occupancy_grid(self): + """Compute the inflated grid.""" + # Inflate the grid and generate a plan + inflated_grid = gridmap.utils.inflate_grid( + self.observed_map, inflation_radius=self.inflation_radius) + + inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, self.robot_pose) + # Prevents robot from getting stuck occasionally: sometimes (very + # rarely) the robot would reveal an obstacle and then find itself + # within the inflation radius of that obstacle. This should have + # no side-effects, since the robot is expected to be in free space. + inflated_grid[int(self.robot_pose.x), int(self.robot_pose.y)] = 0 + + return inflated_grid diff --git a/modules/lsp/lsp/planners/planning_loop.py b/modules/lsp/lsp/planners/planning_loop.py new file mode 100644 index 0000000..be09158 --- /dev/null +++ b/modules/lsp/lsp/planners/planning_loop.py @@ -0,0 +1,135 @@ +import gridmap +import lsp +import numpy as np +import time + + +class PlanningLoop(): + def __init__(self, goal, known_map, simulator, unity_bridge, robot, args, + verbose=False): + self.goal = goal + self.known_map = known_map + self.simulator = simulator + self.unity_bridge = unity_bridge + self.robot = robot + self.args = args + self.did_succeed = True + self.verbose = verbose + self.chosen_subgoal = None + self.current_path = None + + def __iter__(self): + counter = 0 + count_since_last_turnaround = 100 + fn_start_time = time.time() + robot_grid = lsp.constants.UNOBSERVED_VAL * np.ones_like(self.known_map) + + # Main planning loop + while (np.abs(self.robot.pose.x - self.goal.x) >= 3 * self.args.step_size + or np.abs(self.robot.pose.y - self.goal.y) >= 3 * self.args.step_size): + + if self.verbose: + print(f"Goal: {self.goal.x}, {self.goal.y}") + print(f"Robot: {self.robot.pose.x}, {self.robot.pose.y} [motion: {self.robot.net_motion}]") + print(f"Counter: {counter} | Count since last turnaround: " + f"{count_since_last_turnaround}") + + # Compute observations and update map + pano_image, pano_segmentation_image = self.simulator.get_image( + self.robot, do_get_segmentation=True) + _, robot_grid, visible_region = ( + self.simulator.get_laser_scan_and_update_map(self.robot, robot_grid, True)) + + # Compute intermediate map grids for planning + visibility_mask = gridmap.utils.inflate_grid(visible_region, 1.8, -0.1, 1.0) + inflated_grid = self.simulator.get_inflated_grid(robot_grid, self.robot) + inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, self.robot.pose) + + # Compute the subgoal + subgoals = self.simulator.get_updated_frontier_set(inflated_grid, self.robot, set()) + + yield { + 'subgoals': subgoals, + 'image': pano_image, + 'seg_image': pano_segmentation_image, + 'robot_grid': robot_grid, + 'robot_pose': self.robot.pose, + 'visibility_mask': visibility_mask, + } + + if self.chosen_subgoal is None: + if self.verbose: + print("Planning with naive/Dijkstra planner.") + planning_grid = lsp.core.mask_grid_with_frontiers( + inflated_grid, + [], + ) + else: + if self.verbose: + print("Planning via subgoal masking.") + planning_grid = lsp.core.mask_grid_with_frontiers( + inflated_grid, subgoals, do_not_mask=self.chosen_subgoal) + + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [self.goal.x, self.goal.y], use_soft_cost=True) + did_plan, path = get_path([self.robot.pose.x, self.robot.pose.y], + do_sparsify=True, do_flip=True) + self.current_path = path + + # Move the robot + motion_primitives = self.robot.get_motion_primitives() + do_use_path = (count_since_last_turnaround > 10) + costs, _ = lsp.primitive.get_motion_primitive_costs( + planning_grid, + cost_grid, + self.robot.pose, + path, + motion_primitives, + do_use_path=do_use_path) + if abs(min(costs)) < 1e10: + primitive_ind = np.argmin(costs) + self.robot.move(motion_primitives, primitive_ind) + if primitive_ind == len(motion_primitives) - 1: + count_since_last_turnaround = -1 + else: + # Force the robot to return to known space + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [self.goal.x, self.goal.y], + use_soft_cost=True, + obstacle_cost=1e5) + did_plan, path = get_path([self.robot.pose.x, self.robot.pose.y], + do_sparsify=True, + do_flip=True) + costs, _ = lsp.primitive.get_motion_primitive_costs( + planning_grid, + cost_grid, + self.robot.pose, + path, + motion_primitives, + do_use_path=False) + self.robot.move(motion_primitives, np.argmin(costs)) + + # Check that the robot is not 'stuck'. + if self.robot.max_travel_distance( + num_recent_poses=100) < 5 * self.args.step_size: + print("Planner stuck") + self.did_succeed = False + break + + if self.robot.net_motion > 4000: + print("Reached maximum distance.") + self.did_succeed = False + break + + counter += 1 + count_since_last_turnaround += 1 + if self.verbose: + print("") + + if self.verbose: + print("TOTAL TIME:", time.time() - fn_start_time) + + def set_chosen_subgoal(self, new_chosen_subgoal): + self.chosen_subgoal = new_chosen_subgoal diff --git a/modules/lsp/lsp/planners/subgoal_planner.py b/modules/lsp/lsp/planners/subgoal_planner.py new file mode 100644 index 0000000..b72c102 --- /dev/null +++ b/modules/lsp/lsp/planners/subgoal_planner.py @@ -0,0 +1,218 @@ +import copy +import gridmap +import lsp +import numpy as np +import torch + +from .planner import Planner + +NUM_MAX_FRONTIERS = 12 + + +class BaseSubgoalPlanner(Planner): + def __init__(self, goal, args, verbose=False): + super(BaseSubgoalPlanner, self).__init__(goal) + self.subgoals = set() + self.selected_subgoal = None + self.observed_map = None + self.args = args + self.verbose = verbose + + self.inflation_radius = args.inflation_radius_m / args.base_resolution + if self.inflation_radius >= np.sqrt(5): + self.downsample_factor = 2 + else: + self.downsample_factor = 1 + + self.update_counter = 0 + + def update(self, observation, observed_map, subgoals, robot_pose, + visibility_mask): + """Updates the internal state with the new grid/pose/laser scan. + + This function also computes a few necessary items, like which + frontiers have recently been updated and computes their properties + from the known grid. + """ + self.update_counter += 1 + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=2.0 / self.args.base_resolution, + chosen_frontier=self.selected_subgoal) + + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, self.goal) + + # Update the subgoal inputs + self._update_subgoal_inputs(observation['image'], robot_pose, self.goal) + + # Once the subgoal inputs are set, compute their properties + self._update_subgoal_properties(robot_pose, self.goal) + + def _update_subgoal_inputs(self, image, robot_pose, goal_pose): + # Loop through subgoals and get the 'input data' + for subgoal in self.subgoals: + if subgoal.props_set: + continue + + # Compute the data that will be passed to the neural net + input_data = lsp.utils.learning_vision.get_oriented_input_data( + image, robot_pose, goal_pose, subgoal) + + # Store the input data alongside each subgoal + subgoal.nn_input_data = input_data + + def _update_subgoal_properties(self, robot_pose, goal_pose): + raise NotImplementedError("Method for abstract class") + + +class KnownSubgoalPlanner(BaseSubgoalPlanner): + + def __init__(self, goal, known_map, args, verbose=False, do_compute_weightings=False): + super(KnownSubgoalPlanner, self).__init__(goal, args, verbose) + + self.known_map = known_map + self.inflated_known_grid = gridmap.utils.inflate_grid( + known_map, inflation_radius=self.inflation_radius) + self.do_compute_weightings = do_compute_weightings + + # Compute cost grid + _, self.get_path = gridmap.planning.compute_cost_grid_from_position( + self.inflated_known_grid, [goal.x, goal.y], use_soft_cost=True) + + def _update_subgoal_properties(self, robot_pose, goal_pose): + new_subgoals = [s for s in self.subgoals if not s.props_set] + lsp.core.update_frontiers_properties_known(self.inflated_known_grid, + self.inflated_grid, + self.subgoals, new_subgoals, + robot_pose, goal_pose, + self.downsample_factor) + + if self.do_compute_weightings: + lsp.core.update_frontiers_weights_known(self.inflated_known_grid, + self.inflated_grid, + self.subgoals, new_subgoals, + robot_pose, goal_pose, + self.downsample_factor) + + self.updated_subgoals = [subgoal for subgoal in new_subgoals + if not subgoal.is_obstructed] + + if self.verbose: + for subgoal in self.updated_subgoals: + lsp.utils.command_line.print_frontier_data( + subgoal, num_leading_spaces=16, print_weights=True) + + def get_subgoal_training_data(self): + data = [] + for subgoal in self.updated_subgoals: + datum = subgoal.nn_input_data + datum['is_feasible'] = subgoal.prob_feasible + datum['delta_success_cost'] = subgoal.delta_success_cost + datum['exploration_cost'] = subgoal.exploration_cost + datum['positive_weighting'] = subgoal.positive_weighting + datum['negative_weighting'] = subgoal.negative_weighting + data.append(datum) + + return data + + def compute_selected_subgoal(self): + """Use the known map to compute the selected subgoal.""" + + if not self.subgoals: + return None + + # Compute the plan + did_plan, path = self.get_path([self.robot_pose.x, self.robot_pose.y], + do_sparsify=False, + do_flip=True, + bound=None) + if did_plan is False: + print("Plan did not succeed...") + raise NotImplementedError("Not sure what to do here yet") + if np.argmax(self.observed_map[path[0, -1], path[1, -1]] >= 0): + return None + + # Determine the chosen subgoal + ind = np.argmax(self.observed_map[path[0, :], path[1, :]] < 0) + return min(self.subgoals, + key=lambda s: s.get_distance_to_point((path.T)[ind])) + + +class LearnedSubgoalPlanner(BaseSubgoalPlanner): + + def __init__(self, goal, args, device=None, verbose=False): + super(LearnedSubgoalPlanner, self).__init__(goal, args) + + if device is not None: + self.device = device + else: + use_cuda = torch.cuda.is_available() + self.device = torch.device("cuda" if use_cuda else "cpu") + + self.subgoal_property_net = lsp.learning.models.VisLSPOriented.get_net_eval_fn( + args.network_file, device=self.device) + + def _update_subgoal_properties(self, robot_pose, goal_pose): + + for subgoal in self.subgoals: + if subgoal.props_set: + continue + + [prob_feasible, delta_success_cost, exploration_cost] = \ + self.subgoal_property_net(subgoal.nn_input_data) + + subgoal.set_props(prob_feasible=prob_feasible, + delta_success_cost=delta_success_cost, + exploration_cost=exploration_cost, + last_observed_pose=robot_pose) + + for subgoal in self.subgoals: + if not self.args.silence and subgoal.prob_feasible > 0.0: + print(" " * 20 + "PLAN (%.2f %.2f) | %.6f | %7.2f | %7.2f" % + (subgoal.get_centroid()[0], subgoal.get_centroid()[1], + subgoal.prob_feasible, subgoal.delta_success_cost, + subgoal.exploration_cost)) + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + + if is_goal_in_range: + print("Goal in Range") + return None + + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor, + do_correct_low_prob=True)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + print("Problem with planning.") + self.latest_ordering = None + self.selected_subgoal = None + return None + + self.latest_ordering = frontier_ordering + self.selected_subgoal = frontier_ordering[0] + return self.selected_subgoal diff --git a/modules/lsp/lsp/planners/utils.py b/modules/lsp/lsp/planners/utils.py new file mode 100644 index 0000000..c36d857 --- /dev/null +++ b/modules/lsp/lsp/planners/utils.py @@ -0,0 +1,87 @@ +import os +import gzip +import _pickle as cPickle +# for Palatino and other serif fonts use: + +COMPRESS_LEVEL = 2 + + +def write_supervised_training_datum_oriented(planner): + # Get the data from the planner + try: + data = planner.subgoal_data_list + if not planner.updated_subgoals: + return False, '' + except AttributeError: + raise AttributeError( + f"Planner {type(planner).__name__} does not have 'subgoal_data_list'. " + f"Consider using an lsp.planner.KnownSubgoalPlanner." + ) + + if not data: + return False, [] + + # Write the datum to file + args = planner.args + pickle_names = [] + csv_full_path = get_csv_file_supervised(args) + for ii, datum in enumerate(data): + data_filename = os.path.join( + 'data', + f'dat_{args.current_seed}_{planner.update_counter}_{ii}.supervised.pgz' + ) + + pickle_name = os.path.join(args.save_dir, data_filename) + with gzip.GzipFile(pickle_name, 'wb', + compresslevel=COMPRESS_LEVEL) as f: + cPickle.dump(datum, f, protocol=-1) + + with open(csv_full_path, 'a') as f: + f.write(f'{data_filename}\n') + + pickle_names.append(pickle_name) + + return True, pickle_names + + +def write_comparison_training_datum(planner, target_subgoal): + subgoal_training_datum = None + if target_subgoal is None: + return False, '' + + # Get the 'target subgoal' from the chosen planner + for s in planner.subgoals: + if s == target_subgoal: + target_subgoal = s + break + + subgoal_training_datum = planner.compute_subgoal_data(target_subgoal, 24) + + if subgoal_training_datum is None: + return False, '' + + # Write the datum to file + args = planner.args + csv_full_path = get_csv_file_combined(args) + data_filename = os.path.join( + 'data', + f'dat_{args.current_seed}_{planner.update_counter}.combined.pgz') + + pickle_name = os.path.join(args.save_dir, data_filename) + with gzip.GzipFile(pickle_name, 'wb', compresslevel=COMPRESS_LEVEL) as f: + cPickle.dump(subgoal_training_datum, f, protocol=-1) + + with open(csv_full_path, 'a') as f: + f.write(f'{data_filename}\n') + + return True, pickle_name + + +def get_csv_file_supervised(args): + csv_filename = f'{args.data_file_base_name}_{args.current_seed}.supervised.csv' + return os.path.join(args.save_dir, csv_filename) + + +def get_csv_file_combined(args): + csv_filename = f'{args.data_file_base_name}_{args.current_seed}.combined.csv' + return os.path.join(args.save_dir, csv_filename) diff --git a/modules/lsp/lsp/pose.py b/modules/lsp/lsp/pose.py new file mode 100644 index 0000000..9de947b --- /dev/null +++ b/modules/lsp/lsp/pose.py @@ -0,0 +1,26 @@ +"""Defines the Pose class used throughout lsp.""" +import math +import numpy as np +from common import Pose # noqa + + +# A utility function +def compute_path_length(path): + """Compute the length of a path.""" + length = 0 + + # Optionally convert a list of poses to a numpy array + if type(path) is list: + poses = path + path = np.zeros([2, len(poses)]) + for ii, pose in enumerate(poses): + path[0, ii] = pose.x + path[1, ii] = pose.y + + # Compute the path length + for ii in range(1, path.shape[1]): + length += math.sqrt( + math.pow(path[0, ii - 1] - path[0, ii], 2) + + math.pow(path[1, ii - 1] - path[1, ii], 2)) + + return length diff --git a/modules/lsp/lsp/primitive.py b/modules/lsp/lsp/primitive.py new file mode 100644 index 0000000..c9d147c --- /dev/null +++ b/modules/lsp/lsp/primitive.py @@ -0,0 +1,117 @@ +""" +Functions and Classes useful for determining useful properties of motion +primitives. + +A Motion_Primitive is, at its core, a set of poses and a cost. Other functions, +including 'is_primitive_in_collision' and 'get_motion_primitive_costs' are used +to determine properties of the primitives as they relate to the cost grid. +""" + +import math +import numpy as np + +from .pose import Pose +from .constants import OBSTACLE_THRESHOLD + + +class Motion_Primitive(): + def __init__(self, poses, cost, map_data=None): + self.poses = poses + self.cost = cost + self.map_data = map_data + + def transform(self, pose): + """Transform the motion primitive by a given pose. + + This is equivalent to 'right multiplying' the pose/transform. + The resulting primitive should be such that the output poses + are the input poses applied to the pose. + """ + new_poses = [p * pose for p in self.poses] + return Motion_Primitive(poses=new_poses, cost=self.cost) + + +def is_primitive_in_collision(occupancy_grid, motion_primitive): + """Loop through points in the motion primitive and determines if any are + in collision. (Note, motion primitive points must be in the world frame, + as is obtained from the 'get_motion_primitives' method.)""" + + for pose in motion_primitive.poses: + if occupancy_grid[int(pose.x), int(pose.y)] > OBSTACLE_THRESHOLD: + return True + + return False + + +def get_motion_primitive_costs(occupancy_grid, + cost_grid, + robot_pose, + path, + motion_primitive_list, + do_use_path=True): + # Initialize the costs + costs = np.zeros(len(motion_primitive_list)) + + def get_cost_via_grid(primitive_pose): + """Get the cost via the grid""" + # Subsample the grid to compute the cost + # Compute the cost of each motion primitive + # Interpolate over the cost grid + x = primitive_pose.x - 0.5 + y = primitive_pose.y - 0.5 + ix = int(x) + iy = int(y) + dx = x - ix + dy = y - iy + cost_x0y0 = min(cost_grid[ix, iy], + cost_grid[ix + 1, iy + 1] + 1 + math.sqrt(2)) + cost_x1y0 = min(cost_grid[ix + 1, iy + 0], cost_x0y0 + 1 + 1) + cost_x0y1 = min(cost_grid[ix + 0, iy + 1], cost_x0y0 + 1 + 1) + cost_x1y1 = min(cost_grid[ix + 1, iy + 1], + cost_x0y0 + 1 + math.sqrt(2)) + + cost = ((1 - dx) * (1 - dy) * cost_x0y0 + (dx) * (1 - dy) * cost_x1y0 + + (1 - dx) * (dy) * cost_x0y1 + (dx) * (dy) * cost_x1y1) + return cost + + # Determine the 'target pose' for the path method + try: + target_pose = Pose(x=path[0, 1], y=path[1, 1]) + except: # noqa + do_use_path = False + + def get_cost_via_path(primitive_pose): + """Get cost for pose via the path method. A correcton factor is added + via the cost grid method to compensate for the fact that the path + does not give the exact cost. Using this correction factor allows us + to more directly switch between the different methods (mostly for + the purposes of computing training data). + """ + grid_cost = get_cost_via_grid(robot_pose) + target_robot_dist = Pose.cartesian_distance(target_pose, robot_pose) + target_primitive_dist = Pose.cartesian_distance( + target_pose, primitive_pose) + + return grid_cost - target_robot_dist + target_primitive_dist + + # This check ensures that the sparse plan won't encourage the robot to + # travel backwards. + for primitive in motion_primitive_list: + do_use_path = ( + do_use_path and Pose.cartesian_distance(target_pose, robot_pose) > + 10 * Pose.cartesian_distance(robot_pose, primitive.poses[-1])) + + for c, primitive in enumerate(motion_primitive_list): + if is_primitive_in_collision(occupancy_grid, + primitive) or get_cost_via_grid( + primitive.poses[-1]) == float('inf'): + # Determine if any are in collision with the grid. + costs[c] = 1e10 + elif do_use_path: + costs[c] = get_cost_via_path(primitive.poses[-1]) + primitive.cost + else: + costs[c] = get_cost_via_grid(primitive.poses[-1]) + primitive.cost + + robot_cost = get_cost_via_grid(robot_pose) + + return (costs - robot_cost, robot_cost) diff --git a/modules/lsp/lsp/robot.py b/modules/lsp/lsp/robot.py new file mode 100644 index 0000000..7d656d0 --- /dev/null +++ b/modules/lsp/lsp/robot.py @@ -0,0 +1,163 @@ +""" +Includes definitions for various 'Robot' classes which are useful for +storing the agent's state and getting the agent's available actions during +navigation. The primary robot class is the "Turtlebot_Robot", which defines +a basic set of motion primitives relevant to differential drive robots. +""" + +import copy +import math + +from common import Pose +from . import Pose as localPose +from . import primitive + + +class Robot: + """Base robot class. + + All robots must define the 'move' function, which defines how they can + move through space. The Robot class is also useful for defining how an + embodied agent travels through space and for storing a history of poses. + """ + def __init__(self, pose, map_data=None): + self.pose = copy.copy(pose) + self.all_poses = [copy.copy(self.pose)] + self.does_use_motion_primitives = 0 + self.net_motion = 0 + self.map_data = map_data + + def move(self, plan, distance=1.0, stationary=False): + # Start at 1 so that the "rounded current robot pose" is not used + if stationary: + self.all_poses.append(copy.copy(self.all_poses[-1])) + return + + ii = 1 + remaining_dist = distance + while remaining_dist > 0 and ii < plan.shape[1]: + subgoal = plan[:, ii] + dx = subgoal[0] - self.pose.x + dy = subgoal[1] - self.pose.y + step_dist = math.sqrt(dx * dx + dy * dy) + if step_dist < remaining_dist: + remaining_dist -= step_dist + self.pose.x = subgoal[0] + self.pose.y = subgoal[1] + self.net_motion += step_dist + ii += 1 + else: + self.pose.x += remaining_dist * dx / step_dist + self.pose.y += remaining_dist * dy / step_dist + self.net_motion += remaining_dist + self.all_poses += [copy.copy(self.pose)] + return + + def max_travel_distance(self, num_recent_poses): + """Returns the farthest distance between two poses out of the last N poses""" + max_dist = 0.0 + if len(self.all_poses) < num_recent_poses: + return 1e10 + for pose_a in self.all_poses[-num_recent_poses:]: + for pose_b in self.all_poses[-num_recent_poses:]: + max_dist = max(max_dist, + localPose.cartesian_distance(pose_a, pose_b)) + return max_dist + + @property + def pose_m(self): + if self.map_data is None: + return self.pose + + return Pose(x=self.pose.x * self.map_data['resolution'] + + self.map_data['x_offset'], + y=self.pose.y * self.map_data['resolution'] + + self.map_data['y_offset'], + yaw=self.pose.yaw) + + +class Motion_Primitive_Robot(Robot): + """A simple robot that moves using motion primitives. + + This is the base class for robots that use motion primitives to move. + As such, the 'get_motion_primitives' function must be defined and the + move class has been updated to include the selected primitive for motion. + """ + def __init__(self, + pose, + num_primitives=32, + primitive_length=2.8, + map_data=None): + self.pose = copy.copy(pose) + self.all_poses = [copy.copy(self.pose)] + self.net_motion = 0 + self.does_use_motion_primitives = 1 + self.num_primitives = num_primitives + self.primitive_length = primitive_length + self.map_data = map_data + + def get_motion_primitives(self): + """Returns the motion primitives available to the robot at the current + time (can be a function of robot state).""" + # Create motion primitives + return [ + primitive.Motion_Primitive(poses=[ + Pose(x=self.primitive_length * + math.cos(2 * math.pi * i / self.num_primitives), + y=self.primitive_length * + math.sin(2 * math.pi * i / self.num_primitives), + yaw=0) * self.pose + ], cost=self.primitive_length) + for i in range(self.num_primitives) + ] + + def move(self, motion_primitives, ind, stationary=False): + if stationary: + self.all_poses.append(self.all_poses[-1]) + return + + primitive = motion_primitives[ind] + self.net_motion += primitive.cost + p = primitive.poses[-1] + self.pose = Pose(p.x, p.y, p.yaw) + for pose in primitive.poses: + self.all_poses.append(Pose(p.x, p.y, p.yaw)) + + +class Turtlebot_Robot(Motion_Primitive_Robot): + """A simple 'turtlebot' robot class.""" + def __init__(self, + pose, + num_primitives=10, + max_yaw=math.pi / 2, + primitive_length=1.0, + map_data=None): + self.pose = copy.copy(pose) + self.all_poses = [copy.copy(self.pose)] + self.net_motion = 0 + self.does_use_motion_primitives = 1 + self.num_primitives = num_primitives + self.max_yaw = max_yaw + self.primitive_length = primitive_length + self.map_data = map_data + + def get_motion_primitives(self): + """Returns the motion primitives available to the robot at the current + time (can be a function of robot state).""" + self.pose = Pose(self.pose.x, self.pose.y, self.pose.yaw) + r0 = self.primitive_length + N = self.num_primitives + angles = [(i * 1.0 / N - 1) * self.max_yaw / 2 + for i in range(2 * N + 1)] + primitive_list = [ + primitive.Motion_Primitive(poses=[ + Pose(x=r0 * math.cos(angle) * (math.cos(angle)), + y=r0 * math.sin(angle) * (math.cos(angle)), + yaw=2 * angle) * self.pose + ], cost=r0) for angle in angles + ] + primitive_list += [ + primitive.Motion_Primitive( + poses=[Pose(x=0, y=0, yaw=math.pi) * self.pose], cost=2 * r0) + ] + return primitive_list diff --git a/modules/lsp/lsp/scripts/__init__.py b/modules/lsp/lsp/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/lsp/lsp/scripts/shared.py b/modules/lsp/lsp/scripts/shared.py new file mode 100644 index 0000000..534b1b0 --- /dev/null +++ b/modules/lsp/lsp/scripts/shared.py @@ -0,0 +1,70 @@ +import argparse +import math + + +def get_command_line_parser(): + parser = argparse.ArgumentParser( + description='Learning over Subgoals Planning (core)', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument('--silence', action='store_true') + parser.add_argument('--current_seed', required=True, type=int) + parser.add_argument('--logfile_name', type=str, default='logfile.txt') + + parser.add_argument('--save_dir', + type=str, + required=True, + help='Directory in which to save the data') + + parser.add_argument('--unity_path', + type=str, + required=True, + help='Path to the Unity simulator.') + + group = parser.add_argument_group('Robot and Sensor Arguments') + group.add_argument('--step_size', + type=float, + required=False, + default=1.8, + help='The step size for the robot motion') + group.add_argument('--max_primitive_yaw', + type=float, + required=False, + default=math.pi / 3, + help='Maximum yaw robot can turn per step.') + group.add_argument('--num_primitives', + type=int, + required=False, + default=32, + help='Base number used to generate motion primitives.') + group.add_argument('--laser_max_range_m', + type=float, + required=False, + help='Max laser range (in meters)') + group.add_argument('--laser_scanner_num_points', + type=int, + default=1024, + help='Number of points in simulated laser scan.') + group.add_argument('--field_of_view_deg', + type=float, + required=False, + default=360.0, + help='Robot field of view (in degrees).') + + # Map Arguments + group = parser.add_argument_group('Map Generation Arguments') + group.add_argument('--map_type', type=str) + group.add_argument( + '--map_file', + type=str, + nargs='+', + default=None, + help='Image file(s) imported via the "loader" map type.') + + group = parser.add_argument_group('Mapping and Planning Arguments') + group.add_argument( + '--disable_known_grid_correction', + action='store_true', + help='Do not use the known grid to correct the observed map.') + + return parser diff --git a/modules/lsp/lsp/scripts/vis_lsp_eval.py b/modules/lsp/lsp/scripts/vis_lsp_eval.py new file mode 100644 index 0000000..69e776b --- /dev/null +++ b/modules/lsp/lsp/scripts/vis_lsp_eval.py @@ -0,0 +1,128 @@ +import common +import os +import matplotlib.pyplot as plt +import lsp +import environments + + +def evaluate_main(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + # Write starting seed to the log file + logfile = os.path.join(args.save_dir, args.logfile_name) + with open(logfile, "a+") as f: + f.write(f"LOG: {args.current_seed}\n") + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + learned_planner = lsp.planners.LearnedSubgoalPlanner(goal=goal, + args=args) + learned_robot = get_robot() + learned_planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge, + learned_robot, + args, + verbose=True) + + for counter, step_data in enumerate(learned_planning_loop): + # Update the planner objects + learned_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + + # Compute the subgoal and set + learned_planning_loop.set_chosen_subgoal( + learned_planner.compute_selected_subgoal()) + + naive_robot = get_robot() + naive_planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge, + naive_robot, + args, + verbose=True) + + for counter, step_data in enumerate(naive_planning_loop): + non_learned_grid = step_data['robot_grid'] + + learned_dist = common.compute_path_length(learned_robot.all_poses) + naive_dist = common.compute_path_length(naive_robot.all_poses) + did_succeed = learned_planning_loop.did_succeed and naive_planning_loop.did_succeed + + with open(logfile, "a+") as f: + err_str = '' if did_succeed else '[ERR]' + f.write(f"[Learn] {err_str} s: {args.current_seed:4d}" + f" | learned: {learned_dist:0.3f}" + f" | baseline: {naive_dist:0.3f}\n") + + # Write final plot to file + image_file = os.path.join(args.save_dir, args.image_filename) + + plt.figure(figsize=(12, 8)) + plt.subplot(121) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(learned_planner.observed_map, known_map)) + path = learned_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.savefig(image_file, dpi=150) + plt.title(f"Learned Cost: {common.compute_path_length(path):.2f}") + + plt.subplot(122) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(non_learned_grid, known_map)) + path = naive_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Naive Cost: {common.compute_path_length(path):.2f}") + + plt.savefig(image_file, dpi=150) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + from . import shared + parser = shared.get_command_line_parser() + parser.add_argument('--network_file', type=str) + parser.add_argument('--image_filename', type=str) + args = parser.parse_args() + + evaluate_main(args) diff --git a/modules/lsp/lsp/scripts/vis_lsp_generate_data.py b/modules/lsp/lsp/scripts/vis_lsp_generate_data.py new file mode 100644 index 0000000..8a6adfb --- /dev/null +++ b/modules/lsp/lsp/scripts/vis_lsp_generate_data.py @@ -0,0 +1,95 @@ +import os +import matplotlib.pyplot as plt +import lsp +import environments + + +def data_gen_main(args, do_plan_with_naive=True): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + known_planner = lsp.planners.KnownSubgoalPlanner( + goal=goal, known_map=known_map, args=args, + do_compute_weightings=True) + + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge, + robot, + args, + verbose=True) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + known_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + + # Get and write the data + subgoal_training_data = known_planner.get_subgoal_training_data() + lsp.utils.data.write_training_data_to_pickle( + subgoal_training_data, + step_counter=known_planner.update_counter, + args=known_planner.args) + + if not do_plan_with_naive: + planning_loop.set_chosen_subgoal( + known_planner.compute_selected_subgoal()) + + # Write final plot to file + image_file = os.path.join( + args.save_dir, 'data_collect_plots', + os.path.splitext(args.data_file_base_name)[0] + f'_{args.current_seed}.png') + print(image_file) + + plt.figure(figsize=(8, 8)) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(known_planner.observed_map, known_map)) + path = robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + p = path[-1] + plt.plot(ys, xs, 'r') + plt.plot(p.y, p.x, 'go') + plt.savefig(image_file, dpi=150) + + +if __name__ == "__main__": + from . import shared + parser = shared.get_command_line_parser() + parser.add_argument('--data_file_base_name', type=str) + args = parser.parse_args() + + data_gen_main(args) diff --git a/modules/lsp/lsp/scripts/vis_lsp_plotting.py b/modules/lsp/lsp/scripts/vis_lsp_plotting.py new file mode 100644 index 0000000..180329b --- /dev/null +++ b/modules/lsp/lsp/scripts/vis_lsp_plotting.py @@ -0,0 +1,134 @@ +import argparse +import matplotlib.pyplot as plt +import matplotlib +import numpy as np +import pandas as pd +import re +import scipy.stats +import os + + +def process_results_data(args): + # Load data and loop through rows + data = [] + for line in open(args.data_file).readlines(): + d = re.match(r'.*?s: (.*?) . learned: (.*?) . baseline: (.*?)\n', line) + if d is None: + continue + d = d.groups() + data.append([int(d[0]), float(d[1]), float(d[2])]) + + return pd.DataFrame(data, columns=['seed', 'learned_cost', 'baseline_cost']) + + +def build_plot(ax, data, args, cmap='Blues'): + xy = np.vstack([data['baseline_cost'], data['learned_cost']]) + z = scipy.stats.gaussian_kde(xy)(xy) + + data['zs'] = z + data = data.sort_values(by=['zs']) + z = data['zs'] + colors = matplotlib.colormaps[cmap]((z - z.min()) / (z.max() - z.min()) * 0.75 + 0.25) + + ax.scatter(data['baseline_cost'], data['learned_cost'], c=colors) + ax.set_aspect('equal', adjustable='box') + cb = 1.05 * max(max(data['baseline_cost']), max(data['learned_cost'])) + ax.plot([0, cb], [0, cb], 'k', alpha=0.3) + ax.set_xlim([0, cb]) + ax.set_ylim([0, cb]) + ax.set_xlabel('Optimistic Baseline Cost') + ax.set_ylabel('Learned Planner Cost') + + +def add_tensorboard_data(ax, folder_path): + import matplotlib.pyplot as plt + import os + import pandas as pd + from tensorboard.backend.event_processing.event_accumulator import EventAccumulator + + def get_smoothed_event_data(folder_path, smooth_factor=500, scalar_name='Loss/total_loss'): + # Get the event file + fname = sorted(os.listdir(folder_path))[-1] + epath = os.path.join(folder_path, fname) + + # Load the event file data + event_acc = EventAccumulator(epath) + event_acc.Reload() + + # Smooth the data + data = pd.DataFrame([(e.step, e.value) for e in event_acc.Scalars('Loss/total_loss')]) + data = data.fillna(0) + smoothed_data = data[1].ewm(halflife=str(smooth_factor), + times=pd.DatetimeIndex(data[0])).mean() + smoothed_data.fillna(0) + + return {'steps': data[0], + 'unsmoothed': data[1], + 'smoothed': smoothed_data} + + data_train = get_smoothed_event_data(os.path.join(folder_path, 'train')) + data_test = get_smoothed_event_data(os.path.join(folder_path, 'test')) + plt.plot(data_train['steps'], data_train['unsmoothed'], color='magenta', alpha=0.1) + plt.plot(data_test['steps'], data_test['unsmoothed'], 'b', alpha=0.1) + plt.plot(data_train['steps'], data_train['smoothed'], color='magenta', alpha=0.8) + plt.plot(data_test['steps'], data_test['smoothed'], 'b', alpha=0.8) + plt.xlim([data_test['steps'].min(), data_test['steps'].max()]) + plt.ylim(0, data_test['smoothed'][10:].max()) + + plt.legend(['Training (unsmoothed)', + 'Testing (unsmoothed)', + 'Training (smoothed)', + 'Testing (smoothed)']) + plt.title('Neural Net Training Loss') + plt.xlabel('Steps') + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description='Generate a figure (and write to file) for results from the interpretability project.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--data_file', + type=str, + required=False, + default=None) + parser.add_argument('--output_image_file', + type=str, + required=False, + default=None) + parser.add_argument('--xpassthrough', + type=str, + required=False, + default='false') + args = parser.parse_args() + + data = process_results_data(args) + + print(data.describe()) + fig = plt.figure(dpi=200, figsize=(9, 6)) + + from matplotlib import gridspec + spec = gridspec.GridSpec(nrows=1, ncols=2, + width_ratios=[3, 1.8]) + + ax = fig.add_subplot(spec[0]) + build_plot(ax, data, args) + cost_mean_base = data['baseline_cost'].mean() + cost_mean_learn = data['learned_cost'].mean() + improvement = (cost_mean_base - cost_mean_learn) / (cost_mean_base) + title_string = (f"Results: {args.output_image_file}\n" + f"Optimistic Baseline Cost: {cost_mean_base:.2f}\n" + f"Learned Cost: {cost_mean_learn:.2f}\n" + f"Improvement %: {100*improvement:0.2f} | {data['baseline_cost'].size} seeds") + ax.set_title(title_string) + print(title_string) + + try: + ax = fig.add_subplot(spec[1]) + bpath = args.data_file.replace('/results/', '/training_logs/') + bpath = os.path.dirname(bpath) + add_tensorboard_data(ax, bpath) + except: # noqa:E722 + print("TensorBoard data could not be loaded.") + print(args) + + plt.savefig(args.output_image_file, dpi=300) diff --git a/modules/lsp/lsp/scripts/vis_lsp_train_net.py b/modules/lsp/lsp/scripts/vis_lsp_train_net.py new file mode 100644 index 0000000..0f69962 --- /dev/null +++ b/modules/lsp/lsp/scripts/vis_lsp_train_net.py @@ -0,0 +1,140 @@ +import argparse +import glob +import learning +import lsp +import os +import torch +from torch.utils.tensorboard import SummaryWriter + + +def train_main(args): + + # Get the data files for training + + # Set up the learning + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + model = lsp.learning.models.VisLSPOriented(args).to(device) + print(f"Training Device: {device}") + + # Create the datasets and loaders + training_data_files = glob.glob(os.path.join(args.data_csv_dir, "*training*.csv")) + testing_data_files = glob.glob(os.path.join(args.data_csv_dir, "*testing*.csv")) + preprocess_function = lsp.learning.models.VisLSPOriented.preprocess_data + train_dataset = learning.data.CSVPickleDataset(training_data_files, preprocess_function) + test_dataset = learning.data.CSVPickleDataset(testing_data_files, preprocess_function) + train_loader = torch.utils.data.DataLoader(train_dataset, + batch_size=args.batch_size, + shuffle=True, + num_workers=8) + test_loader = torch.utils.data.DataLoader(test_dataset, + batch_size=args.batch_size, + shuffle=True, + num_workers=4) + test_loader_iter = iter(test_loader) + + # Set up logging + train_writer = SummaryWriter(log_dir=os.path.join(args.save_dir, "train")) + test_writer = SummaryWriter(log_dir=os.path.join(args.save_dir, "test")) + + # Define the optimizer + learning_rate = args.learning_rate + optimizer = torch.optim.Adam(model.parameters(), lr=learning_rate) + scheduler = torch.optim.lr_scheduler.StepLR(optimizer, step_size=1, + gamma=args.learning_rate_decay_factor) + + tot_index = 0 + for epoch in range(args.num_epochs): + for index, batch in enumerate(train_loader): + out = model(batch, device) + loss = model.loss(out, + batch, + device=device, + writer=train_writer, + index=tot_index) + + if index % 100 == 0: + with torch.no_grad(): + try: + tbatch = next(test_loader_iter) + except StopIteration: + test_loader_iter = iter(test_loader) + tbatch = next(test_loader_iter) + + tim = tbatch['image'] + tout = model(tbatch, device) + tloss = model.loss(tout, + tbatch, + device=device, + writer=test_writer, + index=tot_index) + + print(f"Test Loss({epoch}.{index}, {tot_index}): {tloss.item()}") + model.plot_images(test_writer, + 'image', + tot_index, + image=tim[0].detach(), + out=tout[0].detach().cpu(), + data=tbatch) + + # Perform update + optimizer.zero_grad() + loss.backward() + optimizer.step() + tot_index += 1 + + # Step the learning rate scheduler + scheduler.step() + + # Now save the trained model to file + torch.save(model.state_dict(), os.path.join(args.save_dir, f"{model.name}.pt")) + + +def get_parser(): + # Add new arguments + parser = argparse.ArgumentParser( + description="Train LSP net with PyTorch.", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + # Logging + parser.add_argument('--save_dir', type=str) + parser.add_argument('--data_csv_dir', type=str) + parser.add_argument( + '--mini_summary_frequency', + default=100, + help='Frequency (in steps) mini summary printed to the terminal', + type=int) + parser.add_argument('--summary_frequency', + default=100, + help='Frequency (in steps) summary is logged to file', + type=int) + + # Training + parser.add_argument('--num_epochs', + default=8, + help='Number of epochs to run training', + type=int) + parser.add_argument('--learning_rate', + default=0.002, + help='Initial learning rate', + type=float) + parser.add_argument('--learning_rate_decay_factor', + default=0.5, + help='How much learning rate decreases between epochs.', + type=float) + parser.add_argument('--batch_size', + default=32, + help='Number of data per training iteration batch', + type=int) + parser.add_argument('--relative_positive_weight', + default=1.0, + help='Initial learning rate', + type=float) + + return parser + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + args = get_parser().parse_args() + train_main(args) diff --git a/modules/lsp/lsp/simulators.py b/modules/lsp/lsp/simulators.py new file mode 100644 index 0000000..6653e6d --- /dev/null +++ b/modules/lsp/lsp/simulators.py @@ -0,0 +1,237 @@ +"""We define the Simulator class which stores parameters so that certain common +operations, like inflating the occupancy grid, computing simulated sensor +measurements, and plotting are easily computed. +""" +import logging +import math +import time + +import common +import environments + +from gridmap import laser, mapping, utils +from gridmap.constants import UNOBSERVED_VAL +import lsp.core + + +class Simulator(object): + def __init__(self, + known_map, + goal, + args, + unity_bridge=None, + world=None, + verbose=True): + """args requires a number of values: + + - base_resolution (float) resolution of a single grid cell + - inflation_radius_m (float) inflation radius of grid (in meters) + - laser_max_range_m (float) max range of laser scanner (in meters) + - field_of_view_deg (float) laser scanner field of view + - laser_scanner_num_points (int) number of points in the sim scan + - current_seed (int) seed for map generation (only used to name logs) + """ + # Store some necesasry data and arguments + self.args = args + self.goal = goal + self.resolution = args.base_resolution + self.inflation_radius = args.inflation_radius_m / self.resolution + self.frontier_grouping_inflation_radius = 0 + + self.laser_max_range_m = args.laser_max_range_m + self.disable_known_grid_correction = args.disable_known_grid_correction + + # Store the known grid + self.known_map = known_map.copy() + self.inflated_known_grid = utils.inflate_grid( + known_map, inflation_radius=self.inflation_radius) + + # Create the directions object + self.laser_scanner_num_points = args.laser_scanner_num_points + self.directions = laser.get_laser_scanner_directions( + num_points=self.laser_scanner_num_points, + field_of_view_rad=math.radians(args.field_of_view_deg)) + + self.unity_bridge = unity_bridge + self.world = world + # self.grid_data_dict = None + + self.verbose = verbose + + def get_laser_scan(self, robot): + """Get a simulated laser scan.""" + # Get the laser scan + ranges = laser.simulate_sensor_measurement( + self.known_map, + self.directions, + max_range=self.laser_max_range_m / self.resolution + 2, + sensor_pose=robot.pose) + + return ranges + + def pose_grid_to_world(self, grid_pose): + if self.world is None: + raise ValueError("Cannot convert to world coords if world is None") + x = grid_pose.x * self.resolution + min(self.world.x) + y = grid_pose.y * self.resolution + min(self.world.y) + return common.Pose(x, y, grid_pose.yaw) + + def get_image(self, robot, do_crop=True, do_get_depth=False, do_get_segmentation=False): + """Get image from unity simulation environment.""" + if self.unity_bridge is None: + if not do_get_depth and not do_get_segmentation: + return None + elif do_get_depth and do_get_segmentation: + return None, None, None, + else: + return None, None + + if self.verbose: + print("Computing Image") + t = time.time() + + # Move the vehicle to the pose and get an image + self.unity_bridge.move_object_to_pose( + "robot", self.pose_grid_to_world(robot.pose)) + + # Get, crop, and orient the image + pano_image = self.unity_bridge.get_image("robot/pano_camera") + if do_crop: + s = pano_image.shape + pano_image = pano_image[s[0] // 4:3 * s[0] // 4] + pano_image = environments.utils.convert.image_aligned_to_robot( + image=pano_image, r_pose=robot.pose) + + if do_get_depth: + # Get, crop, and orient the image + pano_depth_image = self.unity_bridge.get_image("robot/pano_depth_camera") + if do_crop: + s = pano_depth_image.shape + pano_depth_image = pano_depth_image[s[0] // 4:3 * s[0] // 4] + pano_depth_image = environments.utils.convert.image_aligned_to_robot( + image=pano_depth_image, r_pose=robot.pose) + pano_depth_image = environments.utils.convert.depths_from_depth_image( + pano_depth_image) + + if do_get_segmentation: + pano_segmentation_image = self.unity_bridge.get_image("robot/pano_segmentation_camera") + if do_crop: + s = pano_segmentation_image.shape + pano_segmentation_image = pano_segmentation_image[s[0] // 4:3 * s[0] // 4] + pano_segmentation_image = environments.utils.convert. \ + image_aligned_to_robot( + image=pano_segmentation_image, r_pose=robot.pose) + + if self.verbose: + print(f" image time: {time.time() - t}") + + if do_get_depth and do_get_segmentation: + return pano_image, pano_depth_image, pano_segmentation_image + elif do_get_depth: + return pano_image, pano_depth_image + elif do_get_segmentation: + return pano_image, pano_segmentation_image + else: + return pano_image + + def get_laser_scan_and_update_map(self, + robot, + observed_map, + get_newly_observed=False): + """Get the simulate laser scan and insert it into the grid.""" + logger = logging.getLogger("simulators") + stime = time.time() + ranges = self.get_laser_scan(robot) + logger.debug(f"time to get laser scan: {time.time() - stime}") + + if not self.disable_known_grid_correction: + return self._update_map_with_correction(robot, ranges, + observed_map, + get_newly_observed) + + # Insert the scan + stime = time.time() + observed_map = mapping.insert_scan(observed_map, + self.directions, + laser_ranges=ranges, + max_range=self.laser_max_range_m / + self.resolution, + sensor_pose=robot.pose, + connect_neighbor_distance=2) + logger.debug(f"time to insert laser scan: {time.time() - stime}") + + # Optionally get and return the visibility mask + if get_newly_observed: + newly_observed_grid = mapping.insert_scan( + 0 * observed_map - 1, + self.directions, + laser_ranges=ranges, + max_range=self.laser_max_range_m / self.resolution, + sensor_pose=robot.pose, + connect_neighbor_distance=2) + + # Optionally "correct" the grid using the known map. This compensates + # for errors in the reprojection of the laser scan introduces by the + # Bresenham line algorithm used for ray tracing. + if not self.disable_known_grid_correction: + known = self.known_map.copy() + mask = (observed_map == UNOBSERVED_VAL) + known[mask] = UNOBSERVED_VAL + observed_map = known + + if get_newly_observed: + known = self.known_map.copy() + mask = (newly_observed_grid == UNOBSERVED_VAL) + known[mask] = UNOBSERVED_VAL + newly_observed_grid = known + + if get_newly_observed: + return ranges, observed_map, newly_observed_grid + else: + return ranges, observed_map + + def _update_map_with_correction(self, robot, ranges, observed_map, + get_newly_observed): + newly_observed_grid = mapping.insert_scan( + observed_map, + self.directions, + laser_ranges=ranges, + max_range=self.laser_max_range_m / self.resolution, + sensor_pose=robot.pose, + do_only_compute_visibility=True) + + new_visibility_mask = (newly_observed_grid != UNOBSERVED_VAL) + observed_map[new_visibility_mask] = self.known_map[new_visibility_mask] + + if get_newly_observed: + newly_observed_grid[new_visibility_mask] = self.known_map[ + new_visibility_mask] + return ranges, observed_map, newly_observed_grid + else: + return ranges, observed_map + + def get_updated_frontier_set(self, inflated_grid, robot, saved_frontiers): + """Compute the frontiers, store the new ones and compute properties.""" + new_frontiers = lsp.core.get_frontiers( + inflated_grid, + group_inflation_radius=self.frontier_grouping_inflation_radius) + saved_frontiers = lsp.core.update_frontier_set(saved_frontiers, + new_frontiers) + + lsp.core.update_frontiers_goal_in_frontier(saved_frontiers, self.goal) + + return saved_frontiers + + def get_inflated_grid(self, observed_map, robot): + """Compute the inflated grid.""" + # Inflate the grid and generate a plan + inflated_grid = utils.inflate_grid( + observed_map, inflation_radius=self.inflation_radius) + + # Prevents robot from getting stuck occasionally: sometimes (very + # rarely) the robot would reveal an obstacle and then find itself + # within the inflation radius of that obstacle. This should have + # no side-effects, since the robot is expected to be in free space. + inflated_grid[int(robot.pose.x), int(robot.pose.y)] = 0 + + return inflated_grid diff --git a/modules/lsp/lsp/utils/__init__.py b/modules/lsp/lsp/utils/__init__.py new file mode 100644 index 0000000..95abb99 --- /dev/null +++ b/modules/lsp/lsp/utils/__init__.py @@ -0,0 +1,5 @@ +from . import plotting # noqa +from . import command_line # noqa +from . import learning_vision # noqa +from . import data # noqa +from . import calc # noqa diff --git a/modules/lsp/lsp/utils/calc.py b/modules/lsp/lsp/utils/calc.py new file mode 100644 index 0000000..78e4f3d --- /dev/null +++ b/modules/lsp/lsp/utils/calc.py @@ -0,0 +1,45 @@ +import gridmap +import lsp +import numpy as np + + +def compute_frontier_negative_weighting( + occupancy_grid, known_grid, all_frontiers, chosen_frontier, start_pose, + end_pose, exploration_cost): + """How expensive it is to misclassify a negative frontier. + This is simply the exploration cost. (Decided after much deliberation). + """ + return exploration_cost + + +def compute_frontier_positive_weighting(occupancy_grid, known_grid, + all_frontiers, chosen_frontier, + start_pose, end_pose): + """How expensive it is to misclassify a positive frontier. + The positive weighting is computed by determining how expensive it would be + to navigate to the goal if the fronteir were classified as negative. We + first compute the cost function to plan if the chosen frontier is masked. + We compute the distance to the farthest point in unknown space, double it + and return that. This is more or less an upper bound on first-order-cost, + but it works well in practice. + """ + + # Copy the occupancy grid + known_grid = known_grid.copy() + occupancy_grid = occupancy_grid.copy() + + # Mask the grid with chosen frontier (after inflation) + pos_frontiers = [f for f in all_frontiers if f.prob_feasible > 0.5] + masked_grid = lsp.core.mask_grid_with_frontiers(known_grid, pos_frontiers) + + cost_grid = gridmap.planning.compute_cost_grid_from_position( + masked_grid, [start_pose.x, start_pose.y], only_return_cost_grid=True) + + # Compute the cost to the farthest unknown point + cost_grid[occupancy_grid == lsp.constants.FREE_VAL] = 0 + cost_grid[occupancy_grid == lsp.constants.COLLISION_VAL] = 0 + cost_grid[cost_grid == float("inf")] = 0 + exploration_cost = 2 * np.amax(cost_grid) + + # Now compute the cost from the robot to the goal through the frontier + return exploration_cost diff --git a/modules/lsp/lsp/utils/command_line.py b/modules/lsp/lsp/utils/command_line.py new file mode 100644 index 0000000..d5726fa --- /dev/null +++ b/modules/lsp/lsp/utils/command_line.py @@ -0,0 +1,121 @@ +"""Helper functions for interpreting and displaying to the command line. + +Any of the provided scripts will provide full documentation of the args and +what they do if "--help" is passed to the command line. Inspection of this file also yields this information. +""" + +import argparse +import math + + +def yes_or_no(question): + reply = str(input(question + " (y/n): ")).lower().strip() + if reply[0] == 'y': + return True + if reply[0] == 'n': + return False + else: + return yes_or_no("Invalid input: please enter") + + +def print_frontier_data(frontier, num_leading_spaces=4, print_weights=False): + if print_weights: + s = "TRAIN (%6.2f %6.2f) | P %.6f | DS %8.2f (%8.2f) | EX %8.2f (%8.2f)" % ( + frontier.get_centroid()[0], frontier.get_centroid()[1], + frontier.prob_feasible, frontier.delta_success_cost, + frontier.positive_weighting, + frontier.exploration_cost, + frontier.negative_weighting) + else: + s = "TRAIN (%6.2f %6.2f) | P %.6f | DS %8.2f | EX %8.2f" % ( + frontier.get_centroid()[0], frontier.get_centroid()[1], + frontier.prob_feasible, frontier.delta_success_cost, + frontier.exploration_cost) + print(num_leading_spaces * " " + s) + + +def get_parser(): + parser = argparse.ArgumentParser( + description='Compare the different approaches for navigation.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument('--save_dir', + type=str, + required=True, + help='Directory in which to save the data') + parser.add_argument( + '--silence', + action='store_true', + help='[Depricated] If set, all non-error print statements are squashed.' + ) + parser.add_argument('--unity_path', + default=None, + help='Path to Unity environment.') + + group = parser.add_argument_group('General Simulation Arguments') + group.add_argument('--seed', + type=int, + nargs='+', + required=False, + default=None, + help='The seed for the random number generation') + + group = parser.add_argument_group('Robot and Sensor Arguments') + group.add_argument('--step_size', + type=float, + required=False, + default=1.8, + help='The step size for the robot motion') + group.add_argument('--max_primitive_yaw', + type=float, + required=False, + default=math.pi / 3, + help='Maximum yaw robot can turn per step.') + group.add_argument('--num_primitives', + type=int, + required=False, + default=10, + help='Base number used to generate motion primitives.') + group.add_argument('--laser_max_range_m', + type=float, + required=False, + default=12.0, + help='Max laser range (in meters)') + group.add_argument('--laser_scanner_num_points', + type=int, + default=1024, + help='Number of points in simulated laser scan.') + group.add_argument('--field_of_view_deg', + type=float, + required=False, + default=360.0, + help='Robot field of view (in degrees).') + + group = parser.add_argument_group('Mapping and Planning Arguments') + group.add_argument('--base_resolution', + type=float, + required=False, + default=None, + help='The size of one sim grid cell') + group.add_argument( + '--inflation_radius_m', + type=float, + required=False, + default=0.4, + help='How much to inflate the grid (in units of meters).') + group.add_argument( + '--disable_known_grid_correction', + action='store_true', + help='Do not use the known grid to correct the observed map.') + + # Map Arguments + group = parser.add_argument_group('Map Generation Arguments') + group.add_argument('--map_type', type=str) + group.add_argument( + '--map_file', + type=str, + nargs='+', + default=None, + help='Image file(s) imported via the "loader" map type.') + + return parser diff --git a/modules/lsp/lsp/utils/data.py b/modules/lsp/lsp/utils/data.py new file mode 100644 index 0000000..a59b5b8 --- /dev/null +++ b/modules/lsp/lsp/utils/data.py @@ -0,0 +1,40 @@ +import gzip +import _pickle as cPickle +import os + +COMPRESS_LEVEL = 2 + + +def write_training_data_to_pickle(data, step_counter, args): + # Get the data from the planner + # Ensure data is a list + try: + iter(data) + except TypeError: + data = [data] + + csv_full_path = get_csv_filename(args) + + pickle_names = [] + for ii, datum in enumerate(data): + data_filename = os.path.join( + 'data', + f'dat_{args.current_seed}_{step_counter}_{ii}.pgz' + ) + + pickle_name = os.path.join(args.save_dir, data_filename) + with gzip.GzipFile(pickle_name, 'wb', + compresslevel=COMPRESS_LEVEL) as f: + cPickle.dump(datum, f, protocol=-1) + + with open(csv_full_path, 'a') as f: + f.write(f'{data_filename}\n') + + pickle_names.append(pickle_name) + + return pickle_names + + +def get_csv_filename(args): + csv_filename = f'{args.data_file_base_name}_{args.current_seed}.csv' + return os.path.join(args.save_dir, csv_filename) diff --git a/modules/lsp/lsp/utils/learning_vision.py b/modules/lsp/lsp/utils/learning_vision.py new file mode 100644 index 0000000..ff9d9e5 --- /dev/null +++ b/modules/lsp/lsp/utils/learning_vision.py @@ -0,0 +1,117 @@ +import math +import common +import environments +import numpy as np + + +def get_angle_rad(position, obs_pose): + return (math.atan2(position[1] - obs_pose.y, position[0] - obs_pose.x) - + obs_pose.yaw) % (2 * math.pi) + + +def dist(a, b): + d = b - a + return math.sqrt(d[0]**2 + d[1]**2) + + +def get_directions(num_im_cols): + """Returns an array of 'direction vectors' for a panoramic image + from Unity""" + + angles_rad = np.linspace(-math.pi, math.pi, num_im_cols + 1)[:-1] + directions = np.vstack((np.cos(angles_rad), np.sin(angles_rad))) + return (directions, angles_rad) + + +def get_range_bearing_vecs(max_range, num_range, num_bearing): + vec_range = np.linspace(start=0.0, stop=max_range, num=num_range + 1) + vec_range = vec_range[1:] + _, vec_bearing = get_directions(num_bearing) + return vec_range, vec_bearing + + +def get_rel_goal_loc_vecs(pose, goal_pose, num_bearing, subgoal=None): + # Lookup vectors + _, vec_bearing = get_directions(num_bearing) + if subgoal is None: + vec_bearing = vec_bearing + pose.yaw + else: + sp = subgoal.get_centroid() + subgoal_yaw = np.arctan2(sp[1] - pose.y, sp[0] - pose.x) + vec_bearing = vec_bearing + subgoal_yaw + + robot_point = np.array([pose.x, pose.y]) + goal_point = np.array([goal_pose.x, goal_pose.y]) + rel_goal_point = goal_point - robot_point + + goal_loc_x_vec = rel_goal_point[0] * np.cos( + vec_bearing) + rel_goal_point[1] * np.sin(vec_bearing) + goal_loc_y_vec = -rel_goal_point[0] * np.sin( + vec_bearing) + rel_goal_point[1] * np.cos(vec_bearing) + + return (goal_loc_x_vec[:, np.newaxis].T, goal_loc_y_vec[:, np.newaxis].T) + + +def get_range_bearing_indices(obs_pose, lookup_point, vec_range, vec_bearing): + """Helper function for computing lookup indices for setting/getting values + in a range-bearing grid. Also returns a bool 'is_inside' that is True if + the lookup point is inside the grid and False if the lookup point is + outside the grid (and projected inside).""" + p_angle_rad = get_angle_rad(lookup_point, obs_pose) + p_range = dist(lookup_point, np.array([obs_pose.x, obs_pose.y])) + ind_bearing = np.argmax(np.cos(vec_bearing - p_angle_rad)) + ind_range = np.argmin(abs(vec_range - p_range)) + is_inside = p_range <= (vec_range[-1] + vec_range[1] - vec_range[0]) + + return is_inside, ind_range, ind_bearing + + +def get_oriented_input_data(pano_image, robot_pose, goal_pose, subgoal): + """Helper function that returns a dictionary of the input data provided to the +neural network in the 'oriented' data configuration. The 'pano_image' is assumed +to be in the robot coordinate frame, and will be 'rotated' such that the subgoal +of interest is at the center of the image. Similarly, the goal information will +be stored as two vectors with each element corresponding to the sin and cos of +the relative position of the goal in the 'oriented' image frame.""" + + # Re-orient the image based on the subgoal centroid + oriented_pano_image = environments.utils.convert.image_aligned_to_subgoal( + pano_image, robot_pose, subgoal) + + # Compute the goal information + num_bearing = pano_image.shape[1] // 4 + goal_loc_x_vec, goal_loc_y_vec = get_rel_goal_loc_vecs( + robot_pose, goal_pose, num_bearing, subgoal) + + sc = subgoal.get_centroid() + subgoal_pose = common.Pose(sc[0], sc[1], 0) + subgoal_loc_x_vec, subgoal_loc_y_vec = get_rel_goal_loc_vecs( + robot_pose, subgoal_pose, num_bearing, subgoal) + + return { + 'image': oriented_pano_image, + 'goal_loc_x': goal_loc_x_vec, + 'goal_loc_y': goal_loc_y_vec, + 'subgoal_loc_x': subgoal_loc_x_vec, + 'subgoal_loc_y': subgoal_loc_y_vec, + } + + +def get_oriented_data_from_obs(updated_frontiers, pose, goal, image): + """Get a list of dict objects, each containing the data needed to train a +learning algorithm to estimate subgoal propperties. The data should be saved +such that the images associated with each frontier are oriented towards that +particular frontier.""" + + # Initialize some vectors + data = [] + for s in updated_frontiers: + datum = get_oriented_input_data(image, pose, goal, s) + datum['is_feasible'] = s.prob_feasible + datum['delta_success_cost'] = s.delta_success_cost + datum['exploration_cost'] = s.exploration_cost + datum['positive_weighting'] = s.positive_weighting + datum['negative_weighting'] = s.negative_weighting + data.append(datum) + + return data diff --git a/modules/lsp/lsp/utils/plotting.py b/modules/lsp/lsp/utils/plotting.py new file mode 100644 index 0000000..a845b31 --- /dev/null +++ b/modules/lsp/lsp/utils/plotting.py @@ -0,0 +1,294 @@ +""" +This file contains various plotting functions. +""" + +import argparse +import matplotlib +import matplotlib.pyplot as plt +from matplotlib import cm +import numpy as np +import os +import scipy.stats +from skimage.measure import LineModelND, ransac +from ..constants import (COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL, + OBSTACLE_THRESHOLD) + + +def plot_grid(ax, grid, cost, path, robot_pose, goal_pose): + ax.clear() + # ax.get_xaxis().set_ticks([]) + # ax.get_yaxis().set_ticks([]) + ax.scatter(goal_pose[1] - 0.5, + goal_pose[0] - 0.5, + color='green', + s=10, + label='point') + ax.scatter(robot_pose[1] - 0.5, + robot_pose[0] - 0.5, + color='blue', + s=10, + label='point') + if path is not None: + ax.set_title("Net Cost: %f" % cost) + ax.imshow(grid, origin='lower') + + if path is not None: + ax.plot(path[1, :] - 0.5, path[0, :] - 0.5) + + +def _convert_path_to_map_frame(path, map_data): + return np.stack(( + map_data['resolution'] * path[0, :] + map_data['x_offset'], + map_data['resolution'] * path[1, :] + map_data['y_offset'], + )) + + +def _colored_map_grid(grid_map, known_map=None): + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + collision = grid_map >= OBSTACLE_THRESHOLD + free = np.logical_and(grid_map < OBSTACLE_THRESHOLD, grid_map >= FREE_VAL) + grid[:, :, 0][free] = 1 + grid[:, :, 0][collision] = 0 + grid[:, :, 1][free] = 1 + grid[:, :, 1][collision] = 0 + grid[:, :, 2][free] = 1 + grid[:, :, 2][collision] = 0 + + if known_map is not None: + known_collision = known_map == COLLISION_VAL + unobserved = grid_map == UNOBSERVED_VAL + unknown_obstacle = np.logical_and(known_collision, unobserved) + grid[:, :, 0][unknown_obstacle] = 0.65 + grid[:, :, 1][unknown_obstacle] = 0.65 + grid[:, :, 2][unknown_obstacle] = 0.75 + + return grid + + +def plot_grid_to_scale( + ax, + grid, + map_data=None, + cmap=None): + + grid_shape = grid.shape + if map_data is not None: + xlimits = [ + map_data['x_offset'], + map_data['x_offset'] + map_data['resolution'] * grid_shape[0]] + ylimits = [ + map_data['y_offset'], + map_data['y_offset'] + map_data['resolution'] * grid_shape[1]] + extent = ylimits + xlimits + else: + extent = [0, grid_shape[1], 0, grid_shape[0]] + + ax.imshow(grid, extent=extent, origin='lower', cmap=cmap) + + +def plot_navigation_data( + ax, + observed_map_grid=None, + known_map_grid=None, + robot_pose=None, + goal_pose=None, + map_data=None, + robot_poses=None, + robot_poses_m=None, + planned_path=None, + planned_path_m=None): + + # Plot the base grid + color_map = _colored_map_grid(observed_map_grid, known_map_grid) + plot_grid_to_scale(ax, color_map, map_data) + + # Plot the points + if robot_pose is not None: + ax.scatter(robot_pose.y, robot_pose.x, + color='blue', s=10, label='point') + if goal_pose is not None: + ax.scatter(goal_pose.y, goal_pose.x, + color='green', s=10, label='point') + + # Plot the paths + if robot_poses is not None and map_data is not None: + rxs = [map_data['x_offset'] + map_data['resolution'] * p.x for p in robot_poses] + rys = [map_data['y_offset'] + map_data['resolution'] * p.y for p in robot_poses] + ax.plot(rys, rxs, 'b') + elif robot_poses is not None: + rxs = [p.x for p in robot_poses] + rys = [p.y for p in robot_poses] + ax.plot(rys, rxs, 'b') + elif robot_poses_m is not None: + rxs = [p.x for p in robot_poses_m] + rys = [p.y for p in robot_poses_m] + ax.plot(rys, rxs, 'b') + + if planned_path is not None: + planned_path = np.array(planned_path) + if map_data is not None: + planned_path_m = _convert_path_to_map_frame(planned_path, map_data) + else: + ax.plot(planned_path[1, :], planned_path[0, :], 'b:') + if planned_path_m is not None: + planned_path_m = np.array(planned_path_m) + ax.plot(planned_path_m[1, :], planned_path_m[0, :], 'b:') + + +def plot_results_data(data_file, ax=None): + data = np.loadtxt(data_file) + + ele = [v for v in range(1000, 1424) if v not in data[:, 0]] + print(f"Missing elements: {ele}") + + # Use only the success cases + data = data[data[:, 1] == 1] + + # Compute some helper plot bounds + limit_f = max(data[:, 8]) + limit_n = max(data[:, 7]) + limit = max(limit_f, limit_n) + 100 + + # Compute the RANSAC fit + to_fit_data = np.column_stack([data[:, 7], data[:, 8]]) + model_robust, inliers = ransac(to_fit_data, + LineModelND, + min_samples=min(800, data.shape[0] - 1), + residual_threshold=200, + max_trials=1000) + line_y = model_robust.predict_y([0, limit + 1000]) + slope = (line_y[1] - line_y[0]) / (limit + 1000 - 0) + + if ax is None: + fig = plt.figure(figsize=(2, 4), dpi=300) + ax = fig.add_subplot(1, 1, 1) + + p_bad = matplotlib.collections.PatchCollection([ + matplotlib.patches.Rectangle([0, 0], 9000, 9000, alpha=0.2, angle=45) + ]) + p_bad.set_color([1.0, 0.9, 0.9]) + ax.add_collection(p_bad) + p_good = matplotlib.collections.PatchCollection([ + matplotlib.patches.Rectangle([0, 0], 9000, -9000, alpha=0.2, angle=45) + ]) + p_good.set_color([0.9, 1.0, 0.9]) + ax.add_collection(p_good) + + xy = np.vstack([data[:, 7], data[:, 8]]) + z = scipy.stats.gaussian_kde(xy)(xy) + colors = cm.get_cmap('viridis')((z - z.min()) / (z.max() - z.min())) + outliers = np.logical_not(inliers) + good_outliers = np.logical_and(outliers, slope * data[:, 7] > data[:, 8]) + bad_outliers = np.logical_and(outliers, slope * data[:, 7] < data[:, 8]) + plt.scatter(data[outliers, 7], + data[outliers, 8], + s=10, + facecolors='none', + edgecolors=colors[outliers]) + plt.scatter(data[inliers, 7], data[inliers, 8], c=z[inliers], s=10) + # Print out some stats + num_outliers = np.sum(outliers.astype(float)) / outliers.shape[0] + num_good_outliers = np.sum( + good_outliers.astype(float)) / good_outliers.shape[0] + num_bad_outliers = np.sum( + bad_outliers.astype(float)) / bad_outliers.shape[0] + f_dist = sum(data[:, 8]) + n_dist = sum(data[:, 7]) + + # Center line (boundary between good/bad) + plt.plot([0, 1.1 * limit], [0, 1.1 * limit], 'k--') + + # # RANSAC fit line + # plt.plot([0, limit + 1000], line_y) + + # Format the plot + ax.set_xlabel("Dijkstra Heuristic Net Distance (Baseline)") + ax.set_ylabel("Frontier Planning Net Distance (Ours)") + ax.axis([0, limit, 0, limit]) + plt.colorbar(ticks=[], + label="Low Data Density High Data Density") + plt.savefig(os.path.join(args.data_base_dir, args.results_base_name) + + '_fig.png', + dpi=300) + + # Write to data file + fname = os.path.join(args.data_base_dir, + args.results_base_name) + '_summary.txt' + with open(fname, 'w') as f: + f.write(f"Num Points: {outliers.shape[0]}\n") + f.write(f"% Outliers: {num_outliers}\n") + f.write(f"% Bad Outliers: {num_bad_outliers}\n") + f.write(f"% Good Outliers: {num_good_outliers}\n") + f.write( + f"Net Dist: (Frontier {f_dist:.1f})/(Naive {n_dist:.1f}) = {f_dist/n_dist}\n" + ) + f.write(f"Slope of fit line: {slope}\n") + + +np.seterr(divide='ignore') + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Plot a grid file') + parser.add_argument('--zip_file', + type=str, + help='File with grid and path data.', + required=False, + default=None) + parser.add_argument('--data_file', + type=str, + help='File with grid and path data.', + required=False, + default=None) + parser.add_argument('--frontier_pred_files', + type=str, + help='File with grid and path data.', + nargs='+', + required=False, + default=None) + parser.add_argument('--data_base_dir', + type=str, + help='Data directory (results in /data/results)', + default='/data/') + parser.add_argument('--results_base_name', + type=str, + help='Filename where figure will be written.', + required=True) + args = parser.parse_args() + + if args.data_file is not None: + plot_results_data(args.data_file) + else: + data = np.load(args.zip_file) + grid = data['grid'] + path = data['path'] + cost = data['cost'] + robot_pose = data['robot_pose'] + goal_pose = data['goal_pose'] + + fig = plt.figure() + ax = fig.add_subplot(1, 1, 1) + plot_grid(ax, grid, cost, path, robot_pose, goal_pose) + plt.show() + + +def make_plotting_grid(grid_map, known_map=None): + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + collision = grid_map >= OBSTACLE_THRESHOLD + free = np.logical_and(grid_map < OBSTACLE_THRESHOLD, grid_map >= FREE_VAL) + grid[:, :, 0][free] = 1 + grid[:, :, 0][collision] = 0 + grid[:, :, 1][free] = 1 + grid[:, :, 1][collision] = 0 + grid[:, :, 2][free] = 1 + grid[:, :, 2][collision] = 0 + + if known_map is not None: + known_collision = known_map == COLLISION_VAL + unobserved = grid_map == UNOBSERVED_VAL + unknown_obstacle = np.logical_and(known_collision, unobserved) + grid[:, :, 0][unknown_obstacle] = 0.65 + grid[:, :, 1][unknown_obstacle] = 0.65 + grid[:, :, 2][unknown_obstacle] = 0.75 + + return grid diff --git a/modules/lsp/resources/images/results_maze_dbg.png b/modules/lsp/resources/images/results_maze_dbg.png new file mode 100644 index 0000000000000000000000000000000000000000..1761ea9af1132db74bb6868f224ed5b27ee2dfeb GIT binary patch literal 431694 zcmeFZcRbho|36GaMuQ>^BBP8@Mj{azQOe9p2%$2vvXxRqL`G@YdqqZ>At{uRvPrTN z$tbJe{n@$B=bY>Mey{(o+x6GS?e;mJa~kjQd_A9!$9+AX{%R+b*3oXGrJ$f#r+idi zgMxxKkb+_jH8mA}W$nnNdHkP*qk^uZrtLY$%O>{b6sjhUb{B0OFIt^tcQ&_ou(Gug z5fm5Pw};)*(b3L9Qb@@9KYu{b*4{#>la~4>UWCT(sGb7_g&-&SAEis8j57r#1%I%NBxmelwP<*(prN5r zk$d;sJO(b3VC_ZRN9+-}`hIxsfIKO&+aFK=0- z$Ng%7r*x)ly5S#ml;UCXf`>s}Vly-I&2WC5IQ4kNXCA+DlO7z=vSC`kceJxG`-Z+; zROo{T0aZ6Q1T?$sNNJrJYyJMU{i%=n_U+qUTwSf6C?r_Bu-+}`_YC{zh5bZTjoz+i&AC{9_@wva>yzKY%h^FI2539wyhkYsj^1^$K!`?kQc=P4U zmp%hgVi)3Ee++KB7&6;l?p<#A9N)OHb*P3$gY8UB!ng|?H^)Ces{P`daJ5~l6tLF@$q|NY|+eecYa z%m-8k@*RGy`>aHIl>Gl$u@oueKaaxf+_@W%4qmQ&`&MGPKDmD+}9s@nSiq1|0hjqbDhFm*$QWn~DSN7KghlGauOiw#**|x2+rG;_*`t^3s&WfdO zGsfoTi3O6qI(R{s>0t(&-m=?x!Gweab|Ik+Nl8gho;*2xdz;v&&!2rd@-H0GDg6A~ zCc$n}p(cpc#KtDeQ9|fU$ze4$`ZHx7{@1Us!v3qMu3r7^+c!H$M=c$PfQ*IZr3I|} zVS9VwGv!|EKq1=N+G5VVjk3FZ`DRYerPKmh*5>AByWh*6QXW6)zkmOJR8`eCB!nR& zGqdm0rz@v2^lYH#r;^P^x6UaJpbFa=eD!-AFv+ua7s(PYIxR3h-zM%xE z)YMe!wQFC-D+S*P3tOeBsd+$BGR~yxhGpB6Sp6}Tqeox((lOIUI5|2t7GIv&7`c7x zR{xk7b}7$!#*vYc6s^>aqb;e|3amRTJ393H?6H$?ZWp)tgnjt>-8)j5&bMZ*6A}{2 zr(!uj#UgaUy!#}D%8=x{*RNmT&wL+l;^gAuViy-@j);gDZj8NF+3L?u{mgS={|*_i zKrHRcnwqNm`n7mgcmg+yi;MLep0>1Tb(MK;-@qm|6!=7O%CUhJ7tx5>%L6uZ{?ySq=)v#UM0TFt?@P9f#!X?Dn21ak-k2v8S!0qq3=q;mnycDl;!0{yy}1 zR}Ra|pJ(2&Ly&^Lw4}6Do3F02QcfcR1zg4ak(8?j3fCPR2X5XU-I1A@nUimJM^mG_ zXr}IvrN7>qZA2&Yd-3U~Z{N;bG_*C6l$7*IPfy=_>9c&_OaD!BCr+Hm84x=COikkk zpBZa5Kl!y?WZ?2?iKf^iYnq&`+n&g#F1pWsW5T)HjgHLddIr1l)B(FsS9qfD-o0yC zivGcS+T!BHjLC(Ga=L44Hf-k8$=WlgyLH<(+VRdp=H;b1qn$!RC;QxJ3)RD0N8Tp~ z?2*~MTj_w;;7G3s_r&bY##q^FRJ7wq4jnoaYxO>$nLL;jXj&E(hi*lE|FI}Fj{X!2QK)_dHa`&ePrh1bD`POg1+Q%~Yo zr#;yl>_(coW4(Vb`-Fsq)X$QKVDli$uy|J>i-g8E&mxUPmC7rWE3fnGWTliWJ%9e( zCp$a45sNIVqoWgRI`;W92lw^F#nk)ENd zloTG5`RS2rX?|7~mg{&rH2e1L(;F_Y~G7Gb_=uCzJ>95 zuZz8{+jA8xyPjPN={##}%CP=sK`c zq}@ra5>utWVb#QjztEc#RUi(9N^M7u=}isut|F&n!)-b7%|?o&BO^3-cd2d^77+^tc@(I?R!onJ<)`DXWr{7b?qcQLtZy$S>B7GR>b+6N?*7J(e>eY;j^72RDxhfcu zm)^K(Q+UVhojdfg%6E5hOTH^#nl;FA+G{+0n{1}##b4D_U3Ko-S*P_9my)s;EVZ=4 z8u9fv8ZKa?ZPL%PjGZn(1EcBn_;Fi9<_yF2Tvumd{B3k%av-?*7W#u_PFeMaN0gLE z5iG4TbeMlyTz=DsVNIO$Bzd#W*HvzEhNuli@43hJ0T&lT1&olt_#OqmKUFsnw*$*GrN3Q ze_%_V#ux`);q_OP9Y44P7XbF#k5$R|PI0po>2xhHkYYqmoH}1-@3Pp+xF}^TI~8`7pnJ7{6*h7 z8aldb!ND6s@7`s4r}_BZ_vTX{msaVuTw*0(9&J~*(1vxDtXeAT)vH%6@vUaRb*F1A zm%7hYzJI^T#KeR)lZ}OCt*xysIa-NWm3YP5m8c6waYN7eTAbK!0}yl;SYP_qB@x~^ zg{>TKS`!42Sk&zLG&lE&%lEU>6TNIGq_hJ~(@%eRhTgkJ&Bn&|wX^W#dsX!Z*l>Z{ z#AxxjHPe1Opged?R;)qqRJ-85eutDFb{#N)Y@ZYW+Lrwnw=Dnc-;g+V&~cdFZF>0X z>(@tpe|-7!#TZ-co`^+I^GtZs%a`(bw!J%s8lrU$1hZ4OmAHzaJY7R0jZ9evhL{?Lv#=QQxzZXI#t1a@3Eh|=>uin=KL5GN({4Bp)1XWvcB#u!TU-?b=FW@cstRpFsguUl6=P#4LxoLgSf zLHLzk$ftmZ4_O??JG9T)oj?)aYxn8!v**t%UcI6Ma(Z^DpK5lZHyDdY@dAx+uj#9` z`FTbsPi_#<&pTXoV_o0qC@qMTuCDH3`c;7GpPJ&82;Qv@U{+|g)7Rg2W9?QS0M;1A z+uIZ(dShf)0!&d-aByr$y z>ywu!TH^6*BX;o1@BKC0l+wY6HT0@o zCqGeQX?D@biR{}a3vST&?c4g@yLaDv@PHFg7|79OW|Rq=w2(C1$+U5lR*~r1QCUO+EdTK;qc!+#GW^Kj`Kf z^zOvEUtjK?l&4e?Fes1*QtSKtnE+vV1%;jL>=fXojE^R;bI2plGAa*x_Uyp)=m$D% zV2YlHHLQ}3hsg&W9;Wv6^h7fQY+3ote&E)h%}F-0Zn;-!v-KL4-z?&2E5mwf4-a1c z#>0B&%%5}X#44owgaSQ&b>05``-gi<4|a8T6T*TG-v8^z&;hq;9!Ez7GH9TBfRu8zg8d&E}WTeiMWx$L^FhZc^ipt8k*R$u$ z%}rkVF@&;FjSLURpfXKPP05XS;#Tc6t&oJJUqjJtWuC=c-90@!42zu=@MOs%Y}&M`#A|6A zp-&q&)PNJ){hBgw64BBdeHJ`8G-NvYslsLIi?XbKrhb0oQ;U<&ii#@Vy<3mfB!B+# zA$PNg9FJf2^^XqfgxY{r3mO)^=)4B2+}wSARX52=f@s1O-CKJN z2O71FHPjJL8+c+3(6(YYpEm8gR+P)lr#aQt)wk?5z9P4v$pN@^<+x9OtSFSy8?>ONS1zk1N1#3hI8WTc?sb?|7uyizPtC1jxMMNVVqKZH#u zHhm*xXK-*Z&K}g-7l(_-(F;Ne?d}r~>2CmRp{$>Ym8^RoHhus8{m}7phoPV@kKEaE z!0#v60y|M#&OOGH>-*6l!>k%?X=cX7cch7TWb9)m|Jp5k54ROx&IUP8P$M#-30h~U z^W4{V&Dcesn6gy;Uj1iwv5n6znf4_|du;?jNl|+YxutI?+IutT64%0SoG!k6vH{|9 zapndF)y<3AFZI7to(kNuPwrdkbSBOzb+6Y#rWzEz@T3HBEGp|9mX-1TZ^A)9D!9xY zzqYBrZfMX+DV^9R<5iOK5E9~>x0)_|&6l%5O_|A7RTx}HOS_SfDy!c{-b>tQ?8U~Y z%I~TlyBic-WSE|wmNy?pMQ(U}NYk>ou1+E=1;koq_CEL{{no8|W;;};H<_sqNJcmb zdApa)0Djn({Zc%7>=?iB@3Gcwg*uS-P}iQ@TSXLY*mmvNb9}fXKb>m=B>dLfLeB+f z<;R-^^r`V!?F)ZfKfr_J5w-0(ot~5+ls;OjOmT~&I#_Rg}um^y@I?wF-dF+>O$?Bd$Jo4GUMeey{< zeD(;I0DRN@HV^Y(Uo(zsHb*KJb8>R7W@Tkn*Mnx^1GX&p>wR`l+@Viv>%MRa(+xs(xXiT)NcpF&$Dcj(@+ElU`i{FV>|e_g6Zb{ zN1S6!;WVDc+46y?lJM}P%#xN(5Abm;_;j4dxpU{_fJrN7EX>Vm42v8Y!c9o=e4>iC zmLDrFD&m_~@Gt@4l~Yty%o!`0po|9r(fD;Nud@05dnWyCsnvf_^%VC*DO716pgEps ze8?xZz0$s;r=Om?T`wd=S-nz`Y2C(f^QJh3I7w(x*B9m{_``I%DdV}@gTM!r4|hX7 z)aDzD50>5-{uD&>xvLfpRnF6=n=-S{Pnw@N5p)OL|k=FDR*zi*$b1MGh=t!H#ufKs#xq6)Y8Z(s#(Sq^A`tGzd{N@~4+^CraL z9gw7u)isVGKlZR_htmvz(Ao8epB#%6WV)}U381R=Jjndev8&>;738-xX6Ss_p(z_` z1wDTJ_=&^N3Ev+>Lql|?uL48zhS1p+2Dd^^u{4C>v{O*<#7F_1&*IR}g&ljhZQI7j zYk}{r63Iz@YwmuJ#++xK{Xi}4(&0fv0EN)~2M!#dhH9ztEHEK~ix8twhk|EI>Jbg^ z<_;N8w;Fkew|EcMZw;^2m}L=K2jMc5-S+TzHtvTq-e;z+QJc@^WHj8gHCnfQzt->> zR%Yhiq8HoLLcPDX<=FoaG%7nC+VJ6nwqH=tDYGBGp!6B9XD@IVPmdpi@o~UqGDglE zCV)X`FXX@2Wj*!I9`Nrs8x+m_gM%ZxM4X(QnC2NSD#-k&7*8)Zu4Z5eKN!p=qlk|U zUx8mmTtwuqM7WuW`|MX)OUo1 zlOBtJJwAI^2+#l&7Ux(tr`+dh4LpYCm#!6ovMw2=m85k)$P3m3o*6^p+eZhP@$Z@` z?}W;Jt~hdYy>_0zu%5nt+QZ8r{Loj0bT_Y}d?0QssP3+%9Xf8=oIn#HXvn9cX?_qG z*zRlFKJ_S$p{uzXnwsE3yH$W2AJ+3`4m7p4Mji~eR|n3ziQX!wqvJK#jb>iHI2FL< z3HYJ%0o2eBqLh#Mnl)=64|UH0ed@2T${pD+L#&`v2G=ws1&d0)hWOS5)tWQ4GG%lApDA-_aFfIN4%erGoF zxEd@ye>7DJzjgN^Gw4ax6O$@N!6QmaYw&TeKX~wf$Me_JfWjc}BFjW?xy(gtYo@Fp zhD_fj&P32oT%fqO*ThG~oVPgpgDczWD?m`ZhpJ~$wB)TDKYXZ$mO@&MZ{3r;JkoUK z8=e3rUhK$I9-JQ-X#Z8l;}O)FX~5jm)5908z2n>Nn;X~^b#?FYWCA(?^s_P6P7DnA zLQ+v59~Z{61<7P8(&_BzI6Ki(8tQNvtv&QYzai?y&+)=uc`MM4pEzm&iZN;jy%)bL zHCf!4It!*h{2@J3ZVdaAMOs=qE)N9YVsDvYVi81)9MhWhTefenGi(Jyf!xNJI50HS zkN#9W_ z^H{>Dpn}S+l@@sA3PqEXTCuY=Ih@wk9_f?$RF;E11#UCv6IYy*{`F;3-uVwIVVfcR zLY?=mBeJLEbATb*)fu(Ic;!T&yHx90ctkw0)oIr}#rhmuu?Yy6o!X~zTrFJk-6dCi zZC@Ogo&5aA!pcmls7U*6D~TH2&6xCV>=|T1-8{>X=3lfE0T2#8)d`hr6|t;bxzb~4 zrZp}PUs@%o!QiV%IIC(;4K~j>5%Vif*_vBe^b=%~=sERfH{a^ak7?S+nm6!{x(NxP zLirYSpWJ`3ja~Wf%#nMa1KDJDV9ROi+@+xSz0mtx4dB+dHCrcp$MRhHZ~ta9&t0yq zAX(qx(5ZKT{DqAk85tdoPq>33 z)B#ft6%u(B%$99mj5@{3TRzFW)0S!3J~xi)srD-0IkcrbGp-%hP6M?};8aX|Iy*b# z!CdTrfLi!9D+X?fojzIsfFHiyPdf^REx&#lIzP>ex)KDDMSZ@o*NcDde)bzLIg?ST8tLVqrU20V;k!jd zHlZVLOayS(-^dl0QrT*SrXEuB$TKOIliwvPW43VDL_7sijlpv@!mt?*?cJ+(PR-HP z#kuSxZFGO3ZEu7W8{aJu^;N4@`8Deo+GILTCTC@3)pF7>D}+z&I`NQ4nLkVDluIY& zhpeRy(myHin<_*60-Q=gT9%Ftm&MMv92M4|2ah7Meq!xD(7*F7b`(zv3L-qdxlMkO z&2i0}Y5Q9t3vuS_j(zRtmm<%nopv2hYYW}xJ;ZoptaX_Es;AtshRq|!e*5Xur@5?v z0-=jyJiIx=1T6M{t(gtz1Og%uKcc~UKR?AQ@!E=#}H>@_{ncKRF=?iHUsx8_%4^Hh=3W4fy%fh0w}FhYUrlr;EqR z`T6yPplnB)b~+In!W(v)r%G~kLyg~S)y$(t;a%Vn2f zMB?cUKbJJAT*V^g@Rs}d{Bdvcrv*>XCcF<#_QQRIVqq~hriRo`A5N{zx=I> z_bA+tZBsvfn9q*W&b*&Gn4|q7@>@#p83FS?0Vdenm2}?+wU#+VC`SWM9q+rkt z#=U&hE0Rt;x&<%IwEo_{;m$%KSQ7Cc3re!_&29|7eE>yZ`)aF-ii#8zDyj`T0#WRV zn5YsQqsPFwBlB3ukK##7H?%UolbY?h=EuUPm~0w0$ShKT*h54pk~dG?xR@je@kTfQ zJX3*fZ`P!rkAkv_iiS%!8pLOaO{?piot?R9r$R088SY7Yx>eYtZ=s@7!w@7wB)n<9 z52i7r63Cz2+$MJ3Pw{N1_@hAs81V3R(mZ4?+1qPKQe>fwhl*-HX3MQrKi49r`lw&Q zb!lGAZSI=@4F~yduu7BFwnly3U2?3u^-{oQfv|U+7mPgSN0RwgN0ey0g#C=0t%euz z9c1+g{dJ$b#AA`4iO6_wpJ`*cw|8PvPGVd;ENhrzacmE--@F-*he}=0#QXlciefJ%2o8Ch8=`G`&FVo!f!*|JU0fbS9+tqYvrY*-bMLT`- zjSXx;Fw`pQ>W+=D8Cv>ec-=}{iosz~nGHx&Y5r~76z9uhEGj0(gr*rLaqA0QJ%zel z#nU=k%2R2Y%F>tLxD^0^@r!--=nIi!(srSBcU@AlmiiAkO(@-hw5^sR>?bp-Vkori z`}V01GV6i)!+SpH;pw^0aahfF)D`kQ*LZi6XUk4$=`-it5Qk|(pyCbn9cn82s|(Q-Dy} z3)}LgT@I_%wJp!rHbI;*Zcb1p(EXTe?M0~ z1JW-Pec4BnPM?6!5F)@L)1e-zcfPJo3$&bx01w5|3JR|GVSjD?Kr&e!2FNMN;Eb5f zPT`s@elfmQQ!J6(2tg3L%q$@j-|X{5`R`Ldw>6r{^cjwp1;J+fvzNMxFP|LP|5~G^ z%<^N#R_TSWA{mCor^0qHFkA)rIont1YiDOiKXV^KwJ}QM$JtULd>&uO2>y!8Z|mx+ zfEjZxPn;PZ8Hq&{2LN~-WR0dWPxt5XUuxsuEu`=biL)Q7aj>_q{p!|AwEMH51)%9n zFzh$3j)l-_it+-z@(=_Y(hOW&T!_35q^>#gT)%^MuKjB0+_e^lz531j88>g*#Hrly z_HFnyliBUCEFL}1D;MOjmzeS=!eU2xihURERL`*G|EoF8p1r=FL4B*$hcu>l4<$6e zEYQ%O+Hu5jg{LWThr};USU2azP8*OlL zX|DGtoC!(_s7plGC1N#jr!c)74QS*6xCumGa&S!k`t>4_=0uCa9z57iwQk#Wkf6xn zfRn1cEFMjX$C!N;$M~djjrtf&!(!v(uOT49dr05-#EJE=1v%gB4-1Q{upK2_vG49l zX?0%90-oB7HzlvxF`7VBB*++SY;tZc^7#o}-7Uz@0K?LKdK>xvklXYNSi_{hgeQf0 zr*jQm=qmxmL?%VRnX43%-s$J|iN<;m|W9N|@#*pTP zl^VI*Ny5b2+j}j`0eWb2p>sc`rsx?NugAp1_=ut!LPDd!SI}`=W#H7Sq|Lgdb$94l zQuL#V2j~{Ykj3sDxWoZ1f_uWk%-;?H3Uzts)?aqp~zmggQJ(gdHd0)Dt1Qc-KS3d>KU6zl*9 zyb2NT`2di8ga#dxDf&1b`{$qE`(fsV98^(*qK{nFO#*4qwO*mMC~)?xeV4raEf5Ml z(b=CoeR{W;7+vtFKKr~-*OT2epx4)Qfoa`d6;)Lx0a$I}DXeK!K66PIW9YkRzXH@Ae5`GA1OAx5aWQp}Vr#(rNyUGTit5$+ztj7Ouo|C0P}9H{_7;Tz89?XQ;nI$V-66 zjQ7n2NIdqP-?5&bA<+|$08RB4xI8tuN%f%X_s^?I(Z=cLIC#*&hIRVJ?c3|1PTazJ z^r1iAlW^Dt+->+ZQp<IPu0d=vXKrL_8y-KtcE!q-bP*6#8MiqxU-@#(L61|2 z_elF9PL*!K#rr&}Mn-H1)o_x38&zKS!oe5v1%P7PhWh2&yY>;$#_en-wIt0>(NX;QGq7lz5FX#ZYC^p!Ln~W z?ez0p{RUgG1Gu(lJ7ZF@SJIHcA>K2xb)*XsFC3KB_wnO1A+893J#qbUPSmP-6+8i< zs*fuF-Z6K@(#({7I5jmiwBDtk;BLQ6Y}&l314RY@W~FETu+p0d1Ls(G?te3V7YP^W zL^?UH=C_6K-?ahA6VDK~uFYS@ASz^tEeidVnqM!7UR_ZXJgSpZb?W@**qLx%cz zohJP4#mTA-aO-Fh&b3=!blqc6uok+Buu`&$vT_A1m+t@?>+*CZ@K6|UfBaBjZQ!e@ zy_y1KrU_pvw|1Omb3I_$O91A5_FrCeG}J+HG#+VARB6=?{gH2X=Fp+i zv*nh6vqJZ>W(8EoO;vd|4E-#Iy({FpW82oP#2G^HCP&3Q;-;6J>+_(xsxp^IBn(lw z0)X`T-`w4elwT!Oi|EzH#jl`r~WgK_Zk z(!iG|Is@7crJ>Z6gH=+XQ3z}vUR8&*|_hnx`3<{YB1_lx+C*d&o34e?%%q=EWkQlt?5?zvZCw9)fNWvjRsX=r(kQlq<-E ziM4{thv)EA0}mXA-R}4Z9lJ7_E`V z_tl7;1S0Br5m`ZDNiXzctf%%xy@3&F{huriz-3@tqRpH2T4uiP@d!$H`~6|i0Xvw5 z^o=-$02ncTr0`*};cjluWM*RWg~xh6CA?YsAp3Y7Pd~!D+*T(joo1^k+B<0|plZ+y zfEySLxY>3WCEA~Hx)m50CShL85!QY=D(UvW(w59C75)8cb9gnAj+PmFO?{!+597*g z2Pn95R7uDk(Kj_UYifeoY7m}O7(s={t11lgOU?7ebhKE*I8hl&O@WsC{ezCtPN*}& zm7ijd+|*j;$ljBXoLtr0YZR7r{Dmc&q(U9`AvFz+da3{@tICk;?AQC2?a)R>C`2hp zzP{PDC3Vu7;xPDjn4r>!aUQAKi;$yh2O?jAPeXTQhF5(Zr!1fcsreUZzhQhQ!yVRB zfHT9y<5l7J5MVrYM$xNl^O2~UNnw-+H;nuBN8U|PL(yZ@<7lQPHn?J61f!f>=hbJNpd2~5m)PP1rdC0E9u1#M2zdWB*h{%+0DhJ)G-5_<9Osks7p z5*n$?Q;gT+N%jJ@`*>*9*A!WVDdH#&D!h@@F*l^M9T*tsL&_^IZ>lW#gX;UC0~DkY zf+OBN&U(n=9ZR_4F2UpPm#$AavR)o;l(qMk0+W3n9pQ#Gf0Ccil$g_?B?<2~aI46< zqs;-^B(h4nmBc(t)8)b~EczUz1O!w^no20&M)#Y0dabneVr(kDY^&ZuvhpDz>Vwvl zS8$k=6%T3WH)Oqg(TXH)s%Y&nfH(KkbI*#4kLc*kmYa6wS#j#Wd;7K;o=&o3DHM-T z_mEvok9pZH*cmH_^4xEaChw&{Gtbl2%KrVMWEMWnUek_OJv0}vvmCW0t z#uqNoxx2fo>!VeLz$P{_3U!9LmpFR-#0f!lwO~Hl;IA|#zch+7o);CVG~ep%jXL%7 z*eg6C-tb=R{EgH3@QxFc6TJ@_rsabB%h#o?+LvKacw%I>O#5ev=FCI>64onIol_Xv zP=0ZbLs(eY4&e^-m5Yze6(!wRkC((MF&9|Q|-xVfLS8UkGSy* zt3K|hfQ^40#Zg&NXc18yGb*)Ixx08I&a6l%y?`nZHoN%CffyMg>oo2FfPL8#;T+8? zB$VC8@a@dEzLve53D( zlqXJwC81UFA9_%Y;>X2VAP(O_c+|l)HuGOaYtx^iB>`l9KR!^_~)`B$D7a+*xTs`J{ zjb&kaWF>t2fo=K~&@vioYvoX58DPJvOkggi0kz0Lao?T#JC9A>{D4zTTMT=b1F+%qAuxQUz~rr%E043jkBC(S|T4 z^XNypNhzmh9V!4swYR-3=4$yM!=GBYU;vzg&S>5fR0zz!M|t7v(}plU(;tIxVR_sr zidseSb0E?PLR!+~JW4ANNAXuzQiMn{eu37@aG$0))cy)`yU5Qn*wRMyMc>SQv=6He;l00!Ml^ewqr*S0zIGb9Qg8gBBY01 z^b%Cktc-2*<{PjYkia>WI7N~czdjd1=~KwEy?AlYR;I5=Dbk)igh>wPMb!P;{ZC(# zB(3s6`!9aY1B*ZVgG1Fj7{fzD$pD>tRCqWO(sj4q4nbJJLug8$+{d$yS@85>4-bzD zdyobs+iKfO}b$p zLZ@%?y8ZqAF;KM~jWSsSQuzJ0XO}pUG~@iSgse|}lo%cACSSPsrx%nMrqK%9HBqMF zB413Rp$oEzj#q-EBx-H{Kw=g|u{DGp-1gKWSmkP$goFeM+wrI()OW7)%9Lx6_xEb% z&`;&)lV?Gx_<}jMZrXGWxgX|sW`Qva3w%57iXr63Hb4tbQu9P`xwJkt``7~%3G`nL zH~9~Rh@|bhKh=%Nu4W6tV-R)@LkyI+!Vp{qmWrv?8{)xnObU*V*VfjO0RcwZQ78Z} z@o!v9bC5{htb6rH-1f0qLhWk0%}0GsnxhD=hi-BDGXtNehX+^m0@84IEFu?u6NgzK< zu>6nNM%j%mAAx9~P7!QGa$#gB5s^0GR@Gz2s(e<{k=YwWomMQ&j%yCr1wkvz(9frR zdhTuL#VWXix85G~T69tF*d6V`aldTQ5bDT1u?w3KPFpQYZ;Z`cczYC5E+;aie$5B~ zQDMU-ma#~>&+d_4oIHZCKQ(qxHJAZY?c8iYO6ApEz_uTUnX9UKJ*2c*Gt<%Rf6k9( zD_G%kl5sys9NK2=%8H6q#ND5)eu`u$;Cfh^JHTw?2d2x#UO)TRc>H)PUVTE7*x&JB zn5#L{n4~W=4vdWOrh2~$+)5l?jrdb|Ehcc=xI7GJl9a6diPACn4`k=bwle5zK zV4%}uttSUxU$7nTdcFxqEn?LHXNZAqLhVQ7$EIQnD|`jNiIs%?(>FF2z`&_^wC8U4te~D}5)=`B0lE}(hZU;H&!)yl_E)l%@jHj_}V$qsIrLUDNC|kY9?uKG6 zI5HuGR0DopK-gH5eicM98sH!PEpK`eauBd~bGISGZ+PaR>Rr7~;~ioo42)*BIT41l zDOSK9xx_RkY^|Ltn^sXqd(Li!dEf(}cI;g+kzfG$ETJ}4Y>*+tk&Ol61%(TOyLYc4 z*>C8Mx?e2I0L(}bq+WeL$y~q`j5u#_Oro}=kmhDB{IsB z2et>;v>x3tETb1^29IqM8Qk!sVL?GcZ1*fi*CuCYZ@}h2(=@iS^2fXlBC8k$*$6s9 z`kP#QS}8wFX`~Wg;*nrn&j-koNd075lg!c~B4=i9zLSrScIVEW2b{ldfxgc*0M}&= z2p3O57IfVh^STIVc!EdCU@!DcqVkh8Gv@CgNXa@nib4>(gp8AqP$7(aA`lXfOU2q$ zdCQh9#>f!IHKjrI+;^^i3lRYE!iSN|RSpC8i$2iMj>`B;AV6`ho;)-iw}mB*_GMX3u_?j3?;xB}(+- z`|nbXdI7!)zk$e^i;IhsXktE2s;a6)3?-iT$at21J|D8HySC-?NlI>m5ppdyb|)s5 zC`Cj>-Z1|F)eAjtvW)ai93-YcPHIcK&IaTceIp~8)3j23kS-Tw4L!?vaTlNS&Fje8P^Wd}+8=?k?O2(sG3&TyJq>cJe%%qSUx7hF*qalq+EqzcHTrWh({g5 zCzeNxArXNuuNl2WmVIYe;VmdJ-a=GzPyh$`^z~lpHFBSW@Zr^SSkp1&>fKXV+t57wI z-)mhqO?x9H131A7J5&j+n54?uIykw`lteScz*uEzkmF-^7|xdNuNiQk^1dHJe1tb*}MtmnC&53r5+{^*{FVvXO`wmS08PBp3q9vI@fsjh3Wgs__ zzFqHrI9l3sFAklsZ82Zo$UnK3&71uEj*eGWRjsCoi!3a>>|X~D(3^XpqqCC^7cD3Z zO1RHvs3oc}DNAb`kzvt#H-t4}3nWRNXD6J2SkH~1ELsQzCAxVn&FI{(IggKMKZX{P z4(ZnAnVhxP%xHLXO@iHn`PuRG2v2Lw@IE}`ek#_vuH&53!`ABOPGb=%W$1)7dU|@? zd?G;je{|P{bcFci5Y_nf22;m3 zk}JoOsC+QcYIhi{SO4{JJ7R5jqNB50q!*{^gcQc$->Ao0M<}#=K11F&|MUfl>&Rxx z*(}^DDg;D6mMAG8AmB^npUgsqfX#6p-b*u)!o}JzalL@RoPT9!u3ev8Vx8Jd6z>?q zC(@d&$3mH=c2CkNt=fy$(0`^H?Y;b5e>NXzeG=_?GtQ3-n*g~-gKzGE zc_~_-%>9|LnWsMluvaROI~kEg?e_&7O!vr&`0_X*Xju=N_CszqzJ?&Cu=u)Wn9K771WRv=U}fcn=x8iv?ofW353G zr$rzvw4~7cx0ml|#0MeuFCw`aB}iS$d3cnlm3w)H2bq)cQ~Vv@IfK5%v}v~0vT7q; zuE*~FL*I`wJPdv8m$Jh3AZ=eU4l*}qc1b!46`AJ(zEO`;=S3`$O#T94oEThyyAzsf z9c~V34&Aknxce?{)5wMr#|oakTH0fhDL~iI&QIlr=Ej6H7-_`ZeDMh-B_(9y9kUQ+ zFU`XvD&IF<#=d+R?}TARj2|5y^vkT?ieV6N%cNhPzpnXZ2piqZ{`S#6$2C?tKqPiBe@qY;9{ zBe;Q0uh+M*i0X9-2onQ$I}wDLDoaXoEQGBMX4eRdC~@jG>%q;yBwB8cUaJ4MX+(dL ztz|;=WIcL5m$DIZO-M}#)a#&ELEmD<_9fHseS?FbqnJgKL*8x@HZ{3|0fv{t2{tm= z^s>5|+!pW?wE`APtetT*q5@?Y`h`zHO)AR#u_Z9F&mcU6vS9-C*69Y^7O`p9@fWD~ zB&(A+ss=D6e!AFs9UfRU-jjH+xcq??IV9TEU!iqSB2`EnJp!Q6|9Q2tu?XZpK;u56 zjlsi~RTfXw3O{uv1ouL$XE|^M8|6h^U3#0tJ5+t5!+|{;pFgi3=a#OWegg(cA3CH0 zxXUfWRx}F0qE{#gA2zpi0*7{$d$WNXRiHi4q8;JFjY?p)qM}=u=?E0X82-Z@_vH(;eVF!Y9aeh*@SVu_$0IYNc z_yC4u*B3dD(;~)!xlCS0`B`$jk%uEk8T!k5Odk1?-g6jlk%O^{t`gU$ZHJR@IkIIU zj7KJMF&%RJ-d@?hC6fym0>J*r;5330tI6*HM!z|&gRmJyntmXNEiztG^>5z>oNhpJ z93DZ)_2kgm268a|_OM}teEs^BF|8H8G?^?05A7QoN}e3@&xPS~6M7jZ z4-YlC56^!3c5DIk>Xl@{fdC>^-0{Y~>7Zio4&rQ5$`lc&;mI1ELb)PpgLoug#IuK6B9RY_OpiC#J4C4z|%FT&1Wvk z9D%8imR*f*Ok`PF<~{Qf`&s`9Kub&F0);4>RT#(k6V)mAV#Ua>UvRJzQYb*@#$fh% zNEJZ1xUYkITL>?*tq>eZT7+C+0|ghn1=l+;LOviDT@Fbid_~CQS3m(VVHJmtfo#i>zovH6TBr|2O+yWb z^b&8Zhi?L-QROxQ7{u_#X2Jyr-00;d=gv`KcK~A-X_ZTPgY`h-x`B5kwiikP8PvsX z3h0ST8tFRSK(uy!m8)^V5(mb)5XmI(2o3~!@l4#94NNE~16~zVD115Yb2d(*2Ifet zlB<3mOS$@h-X(>BjkEqORxpj(krw-!Zl%hFt=zz>=L!<(j9L|fZ4T^ zi)$4g>Fd|8uOudNlfMnV#JK&UPE&PF4Rcpb|L4zlA|j|hsnX}63&83msK+;Z{FWCR zt{8cVVHVn~Iq)bX#bGO~5WDd4dV2Z=|Ax|L59iI?SO<(nRzg|8I1I@l;sTynOcq*# zsQHd;N{3Ifk&O93jK#Xc&sdLf0mx`CuuE@m7gxmU@pT2WpfOxRV>u1l}eQSyu3pnb6x|~<(9xRQhD*4OnM0- zh@p;pR$66~|Dh%7dgLZHl!=32;!MbgpwAqTkRZ3K(X6fHH3Wu(40Dg?_Fosf{kc3W zC69zmP?k0M8qoVlJ`<?Vf3oN)Qh%-QU+?aZ=)y{9fO}@#aIwb|~A+-01Na`ApD~hQosy>W#>> zieW2jOWuw@`~9D%3VlSef3UdXm}m(`6o8QA}T= zyD-4!!N1}FF+t$myKmoBlmo;GAQRFNd6CWQ=T2N3k~T6}-ukbPUGkn`m29IU=iixn zzm!F^0l~XhnsAE~fM%rIp}%LaQ3HnmU#~bmP)T;z|MMp#qM!QTw-Ns5rSyXcy8NF% z|9}1ZKnubkF(^`Qr9$wh~;s1q4_cNE5i6fZVP~+>A$&SO6|mw3Zh!iY%c)-A1xa2T*Wzr=D{%ZdKd+K>N9gto z>Sn1E(T4jmX&eF+1eguJYz(=IT#7)1R?sXCxZLkmxtjT4QB)%}jypSiAXN0hMWbCE zu;MUwh4a_8tDqlozy-wB09a6YUd?o*uk7mnRnJ#bQJww%xth#hpm9>cd?B~(V3tRK zh&42u1q6OC&9Pxlilp>#Q%-tYnFVA_?BQF$QE?FR{BGaYPJIW4WeUNWthgPb6}~=X zKy7AzVS)Uror6OakdAg*`JN?EHQ{Rtb+x#J(u^wLpSu}DM*r$a+_P8^%{YaC62A3aspU7kbobspKLBW=tb!IaIy(6ANy*X^jUF5IETmD4^YW^@lI&`( z84cp!xABEkRWlQ&%rM%D$j%?-8%Fl+ygs7uB7Uk(djgu`UaXNXNOPoI-IoAdvIrRZ z1On3SmTW(W%H%E%)0y937(_{YHM;vhHMIHELr!urp4KkR0;xW@fxTDfVT6P@=|o89 z5CxXN0Qlpm+wzu{JXk=!tvl7|S1rzV+CIa*Mx>JS^QQ~9ZRBXa4)>BcO$ued5w$=R ze6s{?7eHJSs0Q@2ZP)_*iKjMN6#{v!-M)ViypWO zEx8XfPk580FG`$1d%8JiS0^36uhH>9cH%y;(OIakq0@!$-(ALEN17O`CyP5K2%7;h zz4Z}DPaf_K61uAp`3vtnYik<}RviaOO{Q*8MaZne{~_#6z`4%f_HQj(RMSS=)F@H1 zv}liZsxMl|646SfJ?)EV(OB9DjTXvMNSjDhDy2dtCfc-#Hl-2~spoZReskaV^W4w> z-*NnoW9BzAe7~R1`+Y6vd0ywmXAz4OIwh#qvCQ;peq8;`ts(Y3I~vT%@P}3JGyA%> z(Ylyq6BCmcq8l9ZuG@b-!BxNVVjwb*#&Al1YCd7+MOrKX6&_!%#uqB|4)jFVMV(8b zoxL9PeGH##Syh>f;F%v5oovJfj8OYKFQx#pXW!yc!9HGIcUQFTH>DPJ~n7(BH+nXU+Qc;nZI$MNJwty8QD;#qj)#>um#4Fa?%Q zPp0tCHH#D)09`4@n?sF^mLdT)IOfhM55s|Xr~J17{b;+mzP9u;Mf$7XcS=09x16;g zJv+;Vr?fwHi<(h*(@$Jb!4SHw9X@DKJ478GD1a6WY-w%81doj3iT6|A%ViYO5BPWw z2X2oNL!<+Y4#=02)*ZG;Ri%yc)9vlP^PHqnMlWBF_V?Zs2c5Yv*LM*?n1>j(mnVU- zj?`ihy5GNl$%?c*+PM+h^dnCFU=Iy}^rp`_^=2x9gsXhLNthH_R1sSORgn9XX$zRT zy^|r_Xm;WvhD{A9!}U!?m`U(b?Rhj_cmVQ|P*>U!5by}1-qJ-o(wi5qWxQ|m2w`TUjgXeBeV37-^!3yLn6|~57Pa#GDo)Uv9{`#=%xi3s7C<@@ z9NzyaD4(cX4qrB0D;bHTISXBlR!`rIP=*XIU%q_kR&ikYOAkn)%ucyK9L1uJBV!^{ zx0i`MruoB6Ko1Xt0*A%ZEb&s~%-{98!&he-rD$^znQIm)#M$O2*ARJ})v51rf1)6E zwi*6!>6BePqSoF_Bg`i)E2}vf!!H7{&e?0>&6)q61*9_%6ct&XN)GU8Uy%w;_qFNxNi)D6d5p!zIFH@P(CL4qOJ%9f`HhWc219}N4 zL4hm@P~zwcDvC3YxUk8i5d}x-hSjTA?~NdGMmvObZX_Q`z!StkGFyx+-NwcSUUCfg zMoRL8(5(MI17hVH>2$}84sAPeqH1GtTM84w0VoZ@PoNaGfM5z10S-x1f9&{)(gLwW zW88&YfJcflDL@cOW-Ozt5As9}2tP88` zNlAlcbTzM~2Bsfos=YhF_yc2$WiE;nE{s&Ggfd~_s11>vuKD{}tvA zHrM_JwY}y_D%VDQ+q74P7`kdc13_ydUfQR7gYk%;Y24GtwxnrKV712Zaw-Wc!KqAw zBHt`ve$gOv8mc8HM-yUw+w~iW_F9NQV{U%Mn6EJt@2VVn8>dd3&s4At&mqj4+3gGr z4D5|qD(S}fz(u>e!-!O(kyFNI%yTDh#Q)lwwxzUp4zkO6*>nU$LVNAb{%dWUc=f4F zHO#!Zy9?Fsmi(_)_+TSE$NDMfI&$54KV+A31Yq{{Ux__@y)#}=Hw6H068L1sPcI?rcHAm4u z2uTGjd}cSt+SQHt`9FMX7v!X+nY0`18X?9)VvOu>;9Nd7zzr>3;EY~D&EGve!f1jb zn2V1&Nl8d<>$iwL=8pix&BHuw1ofHm@_|RTr=A( z9p_4VHT^Zy54tt_HzJ2sbUGR##iS>+i>lDt5ff2j94{AK+91`=)YRve%Q&?J-i?UK zxUOnDrrA%SL?e-JhKRV?F)c>JOraPlBnb_Lv_m(`d55P^SIU0^W8z=&5$kPYiMWVS zo=x#9LRK@A(r+F}83*o25XTBw5lC8${7x^p-;>#M`@hZ}(wgA#KNAg4+Tzj7a-gR01l<%#j#kWa7!hep zNGha#4{DWJ_r(jJBS_q8i%98&@k-s(9-?K1;Zo%uSVGD@j>Cw(Ua?i%-R zBUeY~(gzc2(f4rpCnu-yk`6;iQ?>M)5IRikXFW?j|NL_{rTQCObwGmyPuPm9i{?rC zx*hS6vDdC&H_d_ZKb$k}A%SXdp)X}OU~$HW$pM`k`DdFDHTw^FC(1^e;)Kmbe4oI# zLuY=k{2W%DLmMl^p24xuf3cP~ZmG2}kL3e8Pt7a8Q_k_LFWDC_Td~3ze$6TGq|ZNf zi1nZ~E!MQ|Csv6aaj=aXlDVH4hMZz#^asU+31fH+%MkEvj;DYN?N1u=k;5xB zj|^0+yl(v4Z`(NClo*jK+#=c|mh$gMLJG{t$;}N6PF&h~u8Y)rg+}D$KXDC*NrZnHBYsqb7t>J=j3CZO-OdILEXkdZykRLRDKr)|Lw{Jy`5)%-bDV_hi8X50z& z@iiV+?ZI#THB&DTYm4;>HXN?9LRAs!{|5 zFm-bnlwy?4@ebViPso}Xr+Y!I7Ipz_sNJBYok6+lAu9|ny3b7%t>~w2yAOXFw~u*P z*NTaD_1|v5dk0z{*9a1!7>J%bcTR+2ya&kd%koRFEMy$L5;0`R?JeMl z-^|F+Ir}~FM*B6b>+ffF^3+1WS`y*SMYCNTbm>2?iOMO(7AmmTEH?jKAF5bvX+01@ z8m%p@PvIuRN~W8(?h8P1gzC;T$GVxrKz2b>Ed^~HoZoZe7wD{P?(F53zn!&?EZcGd@#%^K!SxUp`5KG~v>jf9rJP#!a*QGwP*$Xz1hG^o6e^{0rlzSJP0=wK zt@$(}{s*wyZvc9+Q%;Za)VFo8$Z{QT4Z%Svyecm0id6kfdB(XJL-?tarXap-3 z&sVQnH9*)@205DkVRY_673Zw?tZR+PAl^CP+~QPCtQDI?NMVnVkU!+HsH=;dRD*oM z9Zzd;5N|QxkoKNiGC3J~6%RkYc{AmG^~bK1Fp7N!!yD+B=Xre*J|M}+1ObG@tDE1U zznr7p(TPTD$x@PZc0F}1l-OyH#@e{i> zlvjR53$cZ#ylx!`M>X~RXWhlWvonF*1t}!`UD4^p#J1!|)tFukQi*rIKoB$OJm)V7 zHG*9YE9ERjPD(-H)0nw4|CfLb`v0k;d~b*P`)hm$nM%djXi~wV-DC60PmA;^1E&Qw zY#}syP)-d=C4H*(yum5sA_vH+=t8M<*a$<+Q80CyE76czFMdi2uk|b4zzM1?%AoF& zz7g3xnc;5)0;^U#5?#apU8_$%OP6hfYqH*eB{=PU5(wl(cd{t+ASR2S#7z4==9O+q z$j28ix{x#51`ouBoLK1@v7J^}$11V&g{1pxcb1^WUdZ_FgXIQdbqT`u{Q2|F=`gk< zJ&SE^aQe74cfq7dlcIBbWYL3bW;IdTym#+j1FyfH3-Oq9xyM^M&s~V(Tb01Fgj2ha?@4=@K9k zNU(cBGbt=aqq6&iD9bDFG@25Acr#f{kcknY7L}6Brw4byM*e5e*#T~!4` zfBL}%&Nb;{pY|dkHb}vyD^?b{YvTPV2l^8#n-`#MuJ=V?gow)6MaJSeK7~6ExHvm| zQfSH8R9G2&lpwLL#d-0G72iSnUVtEq3f`}Hh@qjF14bdl)2`t!php6x+LGkNq1%)y z^bZ(ZTw<@y%2Lqdiz__I2Wy1nHy4?%RyADbthl*uTZeY-4pELoT80`io|}JenQViI z#HhEmd;=bU&n*%E2&ITmS*ytIROcf9$YbcEPIeq^xtLi1)al$SK`T82FG3OGiM5|+ z>7;a7YLGK<15q1^aX?R9ZS8S$*5Np3x@c<3hQZ>owT`GR)AyoF5MX<5)*p%#zNswP z(8;y4#B4Ja+Mw1${Iqjs8_y84ca)S3(6_eL!>Dx@Ps7=AAR`?nD+!=dDE@uBv*ms| z?dPCn`xcK0E(M)3Z`rfhy`;8>j;vLA8At4f(7D-kMl{_=^gT>e1V&b@d(q>WnrLni zGU=*LvLT!WPiO1Yr9Wu7Oz%5RqZt+hOV^{9l|2YBA|ncmPrTBOQsM@W{tzu);sJ(H zRn1q|1ZiAZ9D|>>_q-&^HiENFv>t8h%6`%JzQLw!ek3Iav!-TW&ugH?&;7f%)`sd2 ziT>{Xm#Ph5GvVs!@x1_~#7ryfJMwf`p|G4y#dNhg3Gm8oNdu#KF)BG=L7&mww%vd7 z(>E88U*Jxxsn))pOEn;KITrR($&vyxnswfIAG)hI<3kpY5HV>tp44*}zn+TjH_wu9 z_?*l1lD0my8%1rv{tC*A7UNwOQR;BU6?I4WP6h)~v?$}Ys?;sZ9iP|tUS6Kf?7xSr z^YB|;vq#JE{!u~`@`3A@#}6J{W^q@mO8sN`tJPAvQOxu@lXck3r}Wm{22?88Ozn+O zXPDq^oKHq;RyC}!Q~HE{X6x3iUJ@b3vJB%^xyaL~R^%r|s~bg`!S#@LwB9`i1wQpa z-6nc6j1t|?vCYnoj*bhTUTDvccD4kGvoIL|JW;z(qP_8a++cQb_~#|JuRRGLJITOS zOTSTIVNOSmbyySG$j&+Q_wEbM`~qqiT}yKkS4y-oj5M>YKVzxzOc*_aH~EdI!Qv_b+I;yTa@ zy`xrmlb`{FlMQ9rW5eRb?sNZ9UYv_d^rX89IOFL`=TPO#QfuW$n z(po&*1zPX0W!4e=gho(7i-D%Y!Vu8eg-?>L0|wBFQebF5z5DYcjqC_+vat(&(B$Nf zCS3WLRx?iYlw~QJ;?ZdO9(9v&g{EJ{l2n!>?K zxc_D}>6LnAm=M_rO&%5Z=mlo81%}Nx2V|=uPqbM=)O!K3fgA)drxJ_s^K<92>DvEB zMX{!Y9{VGUk-tcOxAmjbjE(vG=g=dAvrixV`YMV&%lISuyzd(DRXc;@Q~B=L$-7{! zLU}}%cI~iM)O-I?8qJ`M@?Q`Y|DCbEu=PxNCm4U|LPPhBLfZqTZ2Z72;}$*b+m^7A#-v)YJkZkA5vWjsziv=+9s8u#t?M&~mQt{Az zer084lxowzVYNYYymAVaJp*ki+Ds=t{D4$k@ujTHYTct*cHsxLw6uCyZ__X`GBVEm zWwAKUuj@;j6>*!>tr~C7i>GdFYgjdcEBAu`aC!U{$|q6!;FZ7o_x$b?QJKje4a7&Y zsYzvqP6&G$Xcw&0xz6(oV)D@YR45$|$iL)kV24|g@p(D`b zw6CoR3w^}hd`8WAtBZfg&_nv(r4)7Ki^gn)@#PkHZ)~&@41W6`LpzYpj3sZbjKN6h zcch!G4i?j03ssX5@k5U8k&f&>xI%k>_|uzm?n;?pq*ft{%~3|lm<|X@#rqW;=FLTm zAzwO6;LC%I_6rUU>YMK}ST&r2rdt0Gh zW|OvE?*oq@%w+Yakaf%xO#Ac{g`Hrr(45*sht@EAC;I9a%!6rlh-RNjTh2IRK6}4y zl<^zhw8bfB%t|GZ0td+c3bw_}_N%ZnQEu4KtnMcw>1N=#V-9mD)#rVC^0p*1JhiK* zPRys~O$whJWzU1Q{Z3!s(fl;4nBP6-&40Bz)2c%IY22ODIgQM%MP;PrlJVo*3rD@7eL!)V{M==)7BwC}Qkc9i#~J#K&RnRO{8 zrgRe-h_w^N%?+f#CRy1qT!PgZ9QEy{^RYqGb{>djyoc=}hBxPT+P)pTRpPF3M8~hm zwS~S(O}!yKdPJMo8xvSF7JjeX`ouGg)@%Jn0as;cIWY5Hed`pX-D*>!Pq>=SR#`?X zEfGgH@4X4V%@Ln+Y2#34pqo<*!J{{ztl>h7bBoUVwz{5UyUKV1ZTU9)$yH#HlgLSY zk9wgSt9k(UdT|w0FQ}tuV_@<*H%vu&#Zd~!6diRg# zSL)$-(g2_Go(aiyI-}VZ^kPaL!?<)$RviNE)HqaX<;Q3Qc8aXXTvQD)Z{W~AlNn^P zP1%J}e@P;5zD=;QVBthZY9{e*Y?6a@!dBXyPCW7G22&Bj5=}P#5>@qxK#T%3;AdVA z5o*Sa<-`x=m}O@+HIJdUuq=u)=;XF+Edy3M4ws{n$K>jL3}5~mUWSIN-d`p;GYQ#q z?QqOxC`wYf-AWhQo1BG?5{Dg0l%kuC-5(p5TE~DIx5Iv$bIM5dC% zmg23z46^Pn?bSs11wv2DcI~3_R;4%T%`D9|y5ioaoK?nnWBtT)!}EUjY9s0&=vYerT<^srJ%+WnF;dT^xL6K^$X}p3nQw2#0gxN8H*MPnJw77VC7r%Egb0rPE5P# zBWNBjZMcZZ)=*kjnbF5))g{^6Anp2fF^T2uj0DWZBmhf(CETezcOHymTh=lJ3UK?a zxCtbcKe=9bvSt>3*7C+I4#2A@Pwh)OduY{ocI}|l? z`H_%07_*YkHi^dIUpo6lMtP(E<386;Xrsh~d2DPq4gW2x71UFfUaZE&Sp=x2i)nKe zmCX$PJu1e*FzA+&p7YqI`su^lITtY>ZJlJKn?5<$o860L2Cbf_Ga?%y+wVe;?!y*LqWX{pjxq`*+mXzBP5+CzBN;kglJbqy(7<49nb>5z z^tUaup9Sm#Pi8V;eOsa0|K4FHt5 zc46%o!4BI*IOEhn%y|&!>^tUB;m41=C{<7fU3w7QL^Q_$qe$`EibH&EpLJ#PqyksY zjQcS#+KXf@SwAeE3z=CHdV~dmNH(XQf*aVuKT}%MI=+lKoQH|W`n z){B^fI46yj4o*MX)#!_ol1nZ_XxcN*e_HD>W!cZ-wZi_(mW2HBjMi)KeYcW5s0&enPhR3p3#_i`ES4M%_KtMZByBs;0TE3x}gRVnDHr=c;*^?=X(XXl-2 zn)mr7g;(-G8mEUp1fryI6D9=NiPylGU4QK0dR+xOh+fr;UZV8j#HT5BeJ)khSyB=W zqFlQ$4gc0N+sUraMG^_{V_FtoXJiY}&(0#hGq1Dn7Eu2R))=bKz#;;pH`|fPXU_B$ zJoA(hS}Am^G5JA01Xp!7n=~QdGCN{ZxDNH+C@?}6XvMZtwj#8=WVG@s(c0JO&u7lu zV&>gtT2jiE)Zy#aR(|Rt6Y%heiaFEwq%l4u3+aHTdNXNf*}iO>S5(-`fxkH-utu6-{1NKI*6R`5p626hFX`p8lNs@B&ODj6X3~{rcu_|QGASLh0HDYVRe^m zOuL9S3LvYUr1vkEdpN88;dktu`;U3LSo9!&@jW{fX$qaKG5wtLt0cGTvxUC>*pem= zNYU=of}9G+;!-aorr^PyC@z#y{v9w}{Tu&{>W-MtClaUIA23?miXA__m{ZePK2+F_ zN5q0{l;+3sr}_IQgd*X)H*EeQ7qlteAfh#|WDpGWzf_0BzK-q|@=%PwzkC^uY8w}o ztsLx^pmb*l)LieAH>_P=ml6-#=!8^Aj;9Yj?$nvLP~ z$dlNsDvEuoPqiJ!x(l3gAPV;?&hsG%{Q4>*+$%B%u3XP{*m;9d`=i&g7<4K2HEWhz z2#Bb-gp4%5ia8zUSNcA&*_-kG@(>n2N2Ie*i#;5A3KsN*<%R_uoi;T~N&t4Rafwh$ zUo}{8gTUFxt!jm|9q}7!D@8XBzBP;5Sllg0K&DB7k-D&Gj8|Sq;v8^?devTU%Bc~h zv!53b;l)>j2qoHH;DW6br`nFI*Ajo9QN7s4_ma0w`5*AMc{1vgU1)Q}KSJd=q?wtx zkKkY-=1HDFPl5BUU8opO!jdaOiq$?yboiNuyrAeuqw}Ze_GY6am~wGlf148y-c(UK zj)}=19-e6kvD<6F^FP+~ty?VKXnd)cVCNXL>+NrlA!P+kWskC?VotfZC&-tiiis)f z`T}}a*4w>m+T~-b`gO3dk_GC$*L<1*qNFCh`+Zx#p%9o@SzTe|R&|;?I-&;{WJn1@ z{nlfpdL{--R3O`U+-mLn>6t-xf3K-|L7>E(c5KPd$u!~k8l9qs(D=E!ry0Pc%v~b0 zc*!dXs_r_QNv4*ylT71gG7Y6X`AmvhtqNjcdZP_mE5BDRQ`o=oQ&K&A^JIs>^vpxM zeXjoUHXTdPRp-LDxlS`?bOsUh;8MLHD*3z5K>>D{JB+%;x~lDC=jf%6sdm7&@+N-% z+LPll$k4DW;{ySIv}$GPbomX;kLIPYpJ-76fA~k9b2*_F36stL+orxdOB&^eQo+^5 zpm-;c-MBG^=D&PsrH%-`e(Ayc>nTS_lK%`B3EyaUgl?I%XwK<`1~ z8qKj&y|cVHPhVk=KY#ASSPisK14KtBl{g3*V0s-K7RReW#Y8ox;IudGP@L7 zoUzi+@O68|gi)@pq1C~R%c0tL&|W?WDZ5Bic1-x1fdwZIQx=Sf&ni>y%Dt~{Zrh=Q z4~4Q6T^$lGQSI2Lhb6IwSk@zoKAz|ivut?UCRF5D#%vYwj$s?LcU2s*!~;xz2LNQ(>Br`5&;h^{bb-0*@!?<9gBISmnl(#9oOprpUoZijb1w8d z_;oWb-f_!>tmZsMRxz)K{;)XS`cu5t;KA*wmNrq2*?*W2V&sjd=yPoFOl>_gxPNn{ zR$|;GI&Td{=@>+o#NJ4o^ZvI;J|qt7=+Zfh5pGBoBZ#B0S1U$IflCzjp%R#9;FtiF z-Hwc_|7n?**Dw?F+PSPi3ioE9V6D@nXoY)3bUk*#OH>INj@|mbcGZZjy-(6@p|0bcV8?0GW;=W0bZ?E%J)(;79iH{s>L|w6dJJXRnkAwK4b$j z?zj<_x|c~(o|^Y8NNF8?}zsZXCLK0C| z1RdD00F8#wIRr@U=_y7CT}3EB1&y8h7|Zr0(#$bD4V4MQGyTx=ytCk?tVHwK*#yC2 zdtR=1d<$_zrBh#7Ioe_9X($S*>!o;3Ug09eGglbh8aB39pfbgaGkbn_iZrIEqb47f zk@1-FYP-M0_ls9$U)E_o7hd*{VVx3Kx6^tsvr00UrXVWFpkx~L&c+E(FS+kRo>xG6 z@HdS>Dv?Ue*Lv1=c+{lBbpgg2b}rufcYfogv>9vL%)XiBpPiPDnWJ%fm~%#eG|v_! zUz!8)Z9;c+nfBT0-APQz#04L2VA2VP!M`g1b|`_@e0kMOd>=?i3YF0;IcUK0W{&f0G6G zqBe<{8KDf(@O3)CWkk96cqaLulXX5)Khg$Rxx~T?g>!dY_m~XVi-ap&$&@`fc3r|m z8YtkIiQ5HyP00IE^zm7tlYB zvaZ-{%d1vVNu>^1CR=tD$;QT-*5BQ4)8K{85;JrT!F6Jt$!D-bvty0JS;4&fK<*;O zR-k<>KctX8`|o36z!4|Kc-B`>T-;;NF1sYxB3Xw71lgW4sHMK`CGOU&gS{UChNfTf zr*3w0Z5&=2qoiv%d1%GRF)MYli&pUacRY$_rF8??8iLzUaV}y&%=y_W(fve3jJs30 zYUN7VDE8)t;rO5%;TQU2Q5CQ1N_^yFfCT>?wm-l}900`UyR1rqIT5{ZZ}@>x`^WN^ zTBpG#X27_2C|^xF%w8F6-feZ$@%sBzX?u z{S9^pI;}(9AmdMTUYR?klwhtrFhBB+JM%qaAEYGf31u13ifR~F zT;U=&JPj}SNZ%q;wjQxJ*3pfj(2UQ&_L;)Ud%~xzXwpc#AuF^+MFmyP=cTriW(1zu zE2f$)?Yp>u4KsrDkG&Y0a|=$_iwk$t$v_NCp?bIF=eCl*7}!@3@~|5kv>bBa>3>uf z$-b)FA>zSBi5mGSai3HL0It&LY7b-jk1BagWW_O_d{>4+R3R>|3Kq?CPx_bys%iTL;^NAplSzxuBVm&d^&sA5kM>56p2T%R$;H$@ zD8f(U$Zin}2rdhySV?u@b=+69wi2(ACDj`IKEAVm;KUV&u0wqBJdk>>N)c7GPGQ60Y1Q$31_%*_4ySu1A_&jPFVe{l3{KQodx5_8RE z&T4I4ZPl&kCcSGe&LXsIF;6B;MwPc)^DYuppN#>Pm$8u$@kAQ9s%B!TM$trqwB~8z zLfb3m_vZd0>&*(7WC*I>r=tzg9bh%(J0*Yrb;FxAX|m{u3Kx9O&uXhAR#kCN=w;$-?sECm%p`!q(W)J{b zW2tu--L{??_omj`gC)U*>+g}lcXEK#ZXRfo@n=>k`)1{JN&lDRZ8joruKC)=`tl({ zL)E#&CoJQ%cPGrhL*4-Pw8-ug4Ij0uV9j0Lh#*WB;!wp~9kXdWO07R>qP$ui`oJI% z)0^g~z~pxeUBE0Km7d9GYA)TOA(he9pQ->fr8D`2SXTGAf!-49Z5-H_Boy&^v^H&{ z9A{Jht>pYiS!B6xG3zV@Lx@@1tF#wI9WenB@pW{3McsTiK7aexo7`$zKtR^M+}_k} zT$|$#Ne1wS7?$Eo+Cv&V?xc4Czf`9tG?|6+g@%Xt2O@?c-RN$}!rkRE7v~hB3Yh;< zE$S0w3kOeAKu8$~a-w?X?AdM9k*Q7=or^04zZ2n3(jrDsOQT<2gj1wJr;O0heOnhg<@vcXfp2V=82 z#c$p`NAO1tw==^Hs2xAtdSQD~sMUx2ybeDE%Gn6GgrApHd=w#&xbtgw>(%~DZ}I5l zN+p;+hQ?NB$h2h|E%C`ybr+0eJMRtJbPJ}!j1mLWom`(i`w2N?^f<$;z!8kWK7QWe z93$Mn!{bN2x}l-3-wXk<|20(Inuo%&3r&^baLsvj|zQo!b zy2T4`*{Rd<(yxLMKnt7n0aHx!o-&w#qnK5i^1$-*7n~v_{U2Fj_kgI0C1Gley)wmS z5B~?CyPA#ftA}FRA*17lK};)P0_G>fz|zk@6Qd$|Jk?l;h{H>D&oPdmWB&nlm4fN_3Nif zCmwhWmn^$^%R5uC$wFy03YM@3pe#)^zqtUxgcTEv#8&lD4X=Hi{~FVR)wu+RL$o3$ z1AZ_&YkZ#-8s!#N3Gdnb>$LJHOVnF*C+8 z(kFj*9ZzQtQJ7OTwGq1Uh)J(!EMDBR;@lB~q+=#Wjvj5hF83M$TBg2c7$BN&;h^J} zE?vqQKsXY!ZS7a@-){%Wjv8j6Bv7w?Qu%BdAWHunO~X3Q#xgS#3QDtknt=Wg>aK~q ze0^IxCZ0OA`+VuNjYWSn^l(bU$tgqq*Wq{sp|O=(L{Y%V&OEk0(`d%pxWjw2W07Y5 zmPgWwixBv;!=~6X=jBjZ)-`9iEx)e@_LNg2%?g!9(8_4Z&_MJsi<}3XA_?g`9;L9G z)wTD1bR}=U96VoenW|q5sj@5gbznk(#SVHt0z1)PcF-dtVbeXu>_U8HXMkxybcrmRK&N?5TD(2rjg=e0n3{#Z}8~@7CagMuFS)VIs}m z3D=d`0@cQ}mA(^&-R+;`r=V!!j{)eh|= zx817fgVk#c9(?24MJ`o*PQ`4i4%3bn@A(IwLqs|y^O?EbR(o0~eXCj=(|CN0;j56< z)6$dBNcdmaXyy3Ms5^nS?89T*;{&vIT$p{E(%I&GsA!(}ePL4o6&63e&|`IVzG6RQ znt$ZWgpt!+-%yk$4EwER_R;N)#YH8;4=fckJF`}o+^PpKbLq<&w2P15WrV)qL5iCp zUAK%4rhgz`rIOrASGGvU4|POd`?s9L$?GN+P`PelJ0|_3mXA!J@b2y`*ITe)fug`y z=(JwbLteWk1Pm9HoH)OYzH}zi9i8rVLCZwQhR1|j+VaqZgZnRNElv6M>UVTc^HvU? z>r4#!OkN(>DvxO19GND^y?a)@cR)YlAMw1Tq-RCBg9D&3uTp#t#IOJ}!yXThh?BQ* zdVZnS%MDmuNHv{$LkGGX2(>$Jf6v9O7n2*V6aZP~YnW^hT#ULh!ty*oc z=+MA!{UANtlf2rdp-B42^JG-fyKQ30A@=f&Dz12&qfE%uNvO7hc$IAe{+0A}GOi{a zTBLdck`Ae0#N=EwD_k|}d6_;nBwfP5am|gizsfKLz8XgBe}43`k%H9KZ|q ze#_Q&OmKNpEK?FN0W=^Lyh}6jCmQSdKbMFUj_|7@#gUKawr%rQ23LSio6Umgxp$6v zzV3?mbX^@PY*l#`;kiF#%ox9=SbX`R@2~M{ck)RulP6@b$f3|W^bQ@q)lwtDF=iNWiNfuC4 zluy32(Jj642G5!*7YO)Ai%_m>c&oko*bHXHb&t&#|MgFaL-6Ic=Pq6-d_tU$8rsuC z<9L0?cKo$w@?si!yJ^#`OLqppF8R5IV$fSyi-v~+@Lc_ z7$SGgyt@1_737;er%_x(sm}zk30p(!Bf>VC<;wtps3o)=ll#GCiq-&4WdUW2*kY&F zt4|ugLCi-L5Oi|z9hOJ*opXx~YSO^ArgojirB!2K{+HuVfT&-;e&KZRtC%k(8 z?wyZ_O;GNJU5lp~yu!4M{EOg^LRw*tJ__RcmzpA#?~8>*ToaWYg z&3eu-R|z`*aD0bQI&A>)1FwtY3EK#uZ%|Xl%@+M5g95_nP>zaO9B-EH=rRn=Qdu}! z)EJUdhHoP^OY>#U9tvqTQ@%1P)}h}#53m_hP91I&GL_N4kSf_bKsHje`fbs|g}vFQ z6!}tKBlWM0x@Zr!Zc!gS*&le14RmmHL~8OIr(8VT`}S?kcamQZ3-0+BMu>L+2LSf;0|gGov+H_*<*DG z)j}H8$0_7-1RXg7@&#bfXJRtJDZp;6fNv&i|76zDBKHP>&3 zw}i9q=ww3{fkauo(*=YC%hMG=#42i19V&m>M>6Rb{3~7r#7ElO2K3TBD!v?{m61h( z-yDMW;(7cZmv*!tqGyzezF&h86sO9#lW@QG*Zjm`&vs_uVUF}m${foDzmW}%)dhp1 z@@b?0B-tsw6=P{C%rJf{nLaJ`CS%HeA2%+qTIxDS!N)(8@Nx*)KYV{n(nsKHMa9}| zr^w)f`5+^5ZQoQEk-M6b$yq5-c;0<&b$mDPrRq1UhfVkY`ZiT_Px`$de?;FT+X!3( zJ=p)5wNI1k^6+^ks?Ol%nx|9E+a1TvC*;`4^zeC4ArD;>FR{GrO)>>z#E3s*IIM>( z&ii-n(q*J&yGUx_`RdOqM@-AP5T+7N;2evJ%DDS_IO1@QH1+(}qetg{U84C-4v6pu zWsgU~`^qCC@jd4ujDlufTdLpEVp#8);vv%S2#zQ;jfeT!vJfI7!;%XqjxnZpEYpxF zox*BEQM$F;FslQM?&x{M7M=oGevUqE?OAEu$rME)NhfcDoz?o31n=D3S(XX8X2r|y z)FgMyCo}<{*{g+}$#9*-9=0bsGF;ku;KRO&>?5rQ@*SW#PSnk@H*H%eFl%nMB{*2z z#57M{0WA?XS9|rzQvqvAYr@AN=arfGz`drcnprUwuzHni|DtDjLQG28u(oz>(fu`8 z+{ku5BnG>tE-m|xpdFm&3$*5zYN6yr~iT=?U10LBc(qV zvcU~oh+`LGSC=dU4=xHB6t*25BPHv>*Q=1_p$6(J>eTc_+1c3`CzBeVE_?Cp36g^LmETjtC42{-LnBkbUn)e4GWqoz(Pv z*ts__l=#f|6B7Sh$?%F{jxC-|Hq9C4_!l}Y>mjf9?Iruqg8%$B>`3LvnU^*)bCA2Z zYcIRLeB|H%w(#z@yurQD)g|{Q&`9*3uo(tPPuj!sWjcDObp7{4q3q~ia+1POh9!?5 zIHLF24V55dLyLp$_A|Om;UK6a=Afcs7oTI9#Rm%z-|_X+h|DteWo*4^dB`BhR?8IYs7*2wMXe>fjj`d^%ruUY5@OKml8!&BihCW`^xY^n zAB6L1MLLH^Q_w5fagJmtY@| z;Q!!;Tk@NEFU!wJoy;V;y;&P&m7nF|ipV=*HdB`0aT|5~f=cAOn@g$-OrLt+P`9!D zdn+_cVR>+0Mc+iu&I?#E72V*Ytb^eBp~!7d{r=+3n?~e03F~;#+N_->#_Xg;nS-eK zO0r;7uO6ItLypW=nuaUTNw`5wn$jiE%j<{wFW^s?rfMrK=S#XzQQz>~I`2s@UHJOV z8!wJS0qi&eD*H|PzC!`?`MZV!M&%Us&e+>)7fk329{jv#DHq4g4%DC8hG8)Avlj^u z*ymwLk%wjz_Iy2v=QU^YGM~M6q559OGql%K3d`8o%bJ)*L>cP^`4oi`y~HYwZZjME zVe#vsmyfKOzQ4nOg^k!xMFy@5R%!LtV+uE}&xXpSvgYErX{={7qyYO4wj%6WS5YFe zv6nQQqE8hWqJ@957<4n~!asN&eCsXn2PeK0bIulng9jy2hdJ3^l?Bcj)xm7TkRQQG zxQa#toNxXv{XOXd8_VaTj2wd!$I3M1J_~n<+qKK4kWMi?DM#edOLtQOw5)$aST>8X zTb=I1f_hADAf~1=Y(N1#3st`TG5hcnyqB5a>0(m^d?u@Q0^L=k=rFhqa)23f6Yh7u z?Qd`IpHzofl=-|cl9uVSu^j8?G)RyE&%v;D+&A{_-`@m7OL1&o^r+vt^XHElWw9Gq zOyrp5?gD*vBrjbSFZ?xNQ3ooM9h9wyxy@0I=Lb+-M9?Ve6ion-DH#N`v zgY}0^=_bYet^W^oH>OSGYf)7a#3l`XYt?O!3}@D^N}|k>8C?S0-}7pVjwF=X<6_D= zxbh!-E15dYGUKS;r5oi;Rd~^!k1N3A76@cGSz-rh8XI0)kR60aB^}ov*}`$yDoW|A z6hy|SqoSgWY`0k`SG*0|^Xz^W0~4R1g~!>f&-vvjEY`20NaQwL=MVv%bgn4BssS{ikf4xb*guX;0e?PC)-4{{dpCh@2&TWRWwc{LHS;$JSYz z$!39nw5p``tmW0P{W5JUo?J|l@AB|a3cODARqZo-6FDhfR%pxCBL|B<+dV9dZ+K%rK@wAWQW>mz+FbKl>!L0ejpJ zU;jXFp}+duqYLQtCcNykJm-3yc?gwvRAmfbaVHp-+T30Cai*XP z@32^1wK!DB1k8v$|6}T3 zvk~E8R>?$XbDB8LkO7sl65Pu1?fch1V=1XIWiO;-i&m{RBZ2T8CSuU=4c|(m7zwh8 zd8@R~eb}vC1Rb@vUmWv?$)La5Sn21Xz(1oHdjEjBOGd&sblUH~I%g&CapJn1-50cS z|7_ZRGk4&aL#L9-(bK*$aaG&t*B1fWEW}eCj+=jGjnL_+un0Dn;}iR(zpYM3;JQFf z)s0^t&Xutd(YORwf3uo4TFav3rO{d~{Z}UY0}uGhpqoOEfyL==uNL=OvOS+F>ofue z;lf4LEO0+uZf7WIx<%K=pknldFKFNys~m{AO2F$u$X`;KNbJLyDd9=%Vw;RCOYcYF0@LYFsKr+M>TVIeANhbUlFtK#mYdGkJH z8x}8GwcN_5f3W#B`VF;pk%^?TaIi5kgg?BqiPJ&HXYk#l)GH=iK~b`V<6_iNzg~)Q=? zd{5?g?>g4R#3kPrEC+b-i(%v}#Z$#&T7DoY_OvKYB%D2KlXMY}n^i5FbUtSJo*yiB z_d-iceF#u&vItYR+Ko{}L>+ZQNGgiIKY>&|Vq0IXSGO)qt1rUftI+KJBlck{L(P$j z2kv?H@j1WnFO$ag-#=PYn5EI`zJq#i$n?hH@W}oTU>W%C;pEhe{&}LRK>)L7c8vfCjY%yjIf}5t}+jr=Y`b+2L ziC&*Gk5X=yLhA!hR4hU}>L>;Wxzv+n{!17|xjz~N}Q++xT$&%_u{{rs+ zz9?fY2d-K+zEl>1hSrwkH7haYYW4V%`=v2%E*h)*$5mFY0mq4Xl0`w5(68(5qL9QP znKiHCQNk`VKYC5}ii+yY;yraDsLkI|m%^SNrR34k zW3*1wQ_s71A4`WXh6iUIMqo+2I4E>7QQARRF_TYSR(AXc zGHWFOgblrv&fC9gR}B37b;?=_60%~&wc$T+Gh|2znqN_bT{TsYxAdr2iS1wdkF_p3 zaj1b3t-JNHUHFHN+JDl3;wG$^dd6SN{6WZTur+{qtv7 zU6JTvI->8RtgKusbB(%0FJU%|`t~ZtRKIr6PEB>}VVr~;&IGlgP4VYGYCLw1N&g#V(0Im5y06A~6A>Y4e zMR7wV;I3%bYWRJbM~Z!AUsrsSRt!aW0rX+{Ey;J+uDxZS`@DO2=4jzcaiS8ZrQ;h@ zs!I$RQu3Vzy1q3fWn;=~?JP(Etv-yLwKDvzrG?`9*8f@=Ko=Lb>l(_ry5Nl#3kfG3 z%KM}IQbeBMc?s9SCe`eyEHbo=qskV_oDTw{M=woAQc9wCj9f-2vyIB!q5C)9z>0;G zwJhPwJhO;Y$zN}w+)%xC&s22NX0!H{{0#_%rS)-bP>udLluv!BvVu%QhHt>jid=CX zB;QQDa{r!pYohms`&rBqwE)DM`<)+!EEYe#lj8FO>QOxbhM(-b#fKCVdo z8|)5LntV^-Erm}KHW*~v$Q3Rh2ufFjeK$Y?sxw`oZbCnXiM_v9}!sn$@zgSt?)tHC)3S3JHDVql<748)@HONKz?Hbt2zS; zy(zjVO9lSxPoOHVnK$rzi`K38d`uBO8vZYwpcQ7EjF13`t^xUYtb}j)4_RD^N*7X6 zCLF=$=nIyixDAY{^J)NtQ}U(pg}=4a#MoGf9+C4RToXC4latePezZ)MF@1vnasAG^ zb}P^=`a9ojvY)z2N)e{;#;6Wwv8137T+3Dnq_+^Ws5e?t!E$$Aaz9$s@3OvH7#4=w zJcriIlCfTyBZh0 zahub}x$i1p?O)P+ZE4~AVmPr%j1R>&BS6>oH+*34LeC|%N1)gJ^sTc7$RkGbTZ~2W zc8CMXJ!%N{B}IN=p%Yf49jM482+ng4MzxRJJ*r=NfX_5qe3=(w!`O6HDbJ9496ENa z3F(H7E3!d|*AiBtV8le+X!zu+30XDCI(qPXyERwM7vO*sVasY!r*ZW zWUZ;rmg|skq5Q{KefsoGe$pAu#)TC2IMqd@o?W+Yo!oXfg!o~-#xpQq z+XMjlX@}tK{STIE`k2nP6KG3$_x-)?>7!Xl*-`du+Ei83OU_)fq&X4|MX42!ObUod z>#BbJ!9{ruc5w^O;!@2JnfBnSde$+YH@<&#c9Ab9SWKj9c}*q=x5&WNqTwVCu*!P$ zrFu7A{DW>`hyagGC4%S##)%^7Ic%T*WB7p6VE0T#DEu>hV@54U+K#{a!H*kpHPP(D z`U6w}hZuHdHm>cH+9~d06F)k|nfTxAPIsE0rOTs+xDy06V-X|Dr&*|$5VMg7*M=aG z26kt?csBdyP>Z_`1_vH|PIKsgU3zvfjhzD+DCr}wYB_8o9}B_roWGg3I&I+*aNUHkSgkPq+PKd3x982I15dgL@2 zzYw$$?kv-GI4?=Iw4=D#|N5--WpIZ?g&~CtZcWTaS0EcX68s;nSh-SQDtYSRPJ?uY z5De3xGz9nvJWKUGOfVt|3Q8?lkdl1y+ySFQiV_x-Au4H zPR%jbpPp$zCn!WO^Mnw`hGtz8<85Kg%8}&UUmZ3U8O|czjo_GW^B3ARq8khC( zZ|sl=eEr}4^b;3Tcuk3@P%g+D{zQokDQ0nYp`Ea}ytaGxD=)>z_Y-$nYIOmqz_>s> zrNIDX3yRu$UT_?sOX@#aGsKk@8vw2*HO(R8Cwq6XqM{K4S$i%{g#NzDXfK6_OwR~b zf-a9i7G+U4gX$!2F=JAeR_p(Z*SBnlxSO-`fnQ_XDMSY;H=wM1>& zH_oCYS~zlC(L0fukGr~_*OA(YX;{%cfDPgw=0Wcu8w?pE5_tq!^cz+UYHFS`-$U^s zUk>dU{k0`1$_rp_{HES%-8=wyRA{7Er2$M#Tt4;i_p{4f~=ryW*cax|*@h<`)Vcsn>1wUEUav^sA`D0q2^&~O?CFZw)K`&7FBlJ<61$yz$DsH|n^ zosOJ!M@rC2^pyndE3Qns-;w8d2&OW<{Jums6X`(Dx1u*LkmjmB6>SZ6HclqqF8`Y}k@D-R#G7xHYMo{AD5HkFybNfNGs5_Zp-VkD;GsD2Q0U@yNqBt1-tCe9Z< zsq6=lXvaOC+Nke83-rPYV)?&2s4rRYEM=$+I5S}3YTcR(raYxqoxqpxD)te?!skd% zzm@0?9omU?#I?RP3@W05uZszz{a;#YZ7IPJ1({n+48Qq-^(ws9(YT7*f8eKmqCAw- z&8X0dI=4?$sx)o76-FNB=lC*pBI{KEUAY+OBo-|D&*nxe{|z_8-ttCpAXVtj`FC(yV#on8FI2h_Yv|Nhn`A1K9f zhUw3;&gLN2tkfJy_XuPx6L7Q&lCWq?eI7O5>;c^@C&}J!+ktT{Aux6{|706&X%fDQ zZ_7-dI5!`kI#8C3fNgUUF7w~ZmR!wl-R3Om-l(q3>k33muI_Mq3_Ipm7qD8~m0F&k~zuCQQ`OEVvE$x(Cx5l%mZkMcXnT-ZOD{Rb{%9 zfs7hb)~vx8jtJqX{ZhC>x;#&VHcGOX3iXP=rf(h`JGu@JWDgOy8AFx@%h{G?n>(X$ zZ9+ZwXL$JRO<7a@=vYsP^MTYYRvo%Z{NBl z)9Va7whwjtYRB0hVH0=-U6#zKOE{rdQknnAYP%3F6y{TK?Ut&aF)y(@$Mk6gXV!P! zI^{X^b!b3ZrqSD~5WbVRMp!%SkVt_zQ#I`wftZS;%>xJDJ%AoBDNlp0?fo^Br_BV6 z5(S}HT8JNgK8v4skdqfpkaD3^5%{siKRLw0K3A9`P6pTB#A4#{%W2oH$vq4Ei{wn9j0)*^ z{BcSt#wDcRv)BN|%aYclyw~>mB69;m44VSENQF5(D*pyTb2(5JRQAmT3c9Y!yBKFi zb|AlWmc+{+{pbII!__w-U*P{4r7BCl_-o3wiyJC>?Ma8ZF{W4hv}c^g_j`1iZOT=B zZh?m)3)A%xF?Uf+GPkytyP9y|uTFvz<1itH+sE%DoLei70>tLw%moHkBUrg2ZWD}V zdKCbO+^P7^lN`1Z5wz?V%w1eTk&N-6z3T4 z{dYi)eb_&ahpaMFBqP$iL`Ftwt5iz66qN=lG75w53I~tdxodX(uJ6 zrTKjw-R}GOJ-0>Sq@PS@YGV=nQHDU|fW&c>uSHaF2%H|>)oG2J*u?=~KEI@Xs zHbaa(M6Q}h1lEbyQ}f*VPNf#f+(P8~!vnzKhD&$`t{zv66oPmRD>j5f#Xxbz0{F-E_E1mo2M&h6F4Z`lP9WObyWa-j}<@fM5Iwq0qgCHq| z?sGWmIE+qy2)`V~v-59}7ohsLK=3gHI!O|st}ofk01WsEf4Z-Y;^Y^uZ*yP^n>KGQ zx6A>XP4yPdufP*jDBayhV~@dEVZHb&DsM+6?;E9X@?=j}rwA%-lA&O+WBMe+$^=ZW zW2oi-)pQyDR>KB*J#_vLIY+5hF~bgA zqAMY+f=alEW>`QVz#}DP+<1;U6)FNC0(((juG!p+3MbWM$Yb#1J-YEBG(p}I2bP#3 zoYTB@n8`O6F85n?6R5-(l9LD;fz+YIZWluW1I&tXX)0_6V~LrC%8AaX(+Jih2f(gD zz;GDjs}VUg=v#oQJ$k<}8VSD5AZ5JUXm9-SLtGP@bPuzHjWop=zxsO*&E=r|Jz{AC zQyFP^0ARtFayS~t-zkVrVQS={-$vg=B=F`{bueb&&FNq*o{1m3q$V7UXxJ$2K^LZD&NkWG*oCk~{?hp>sBKLy-JTWB)DFF`}yHzRnO z!1Bb+>4!1(2^dJk8^B$j78}FZ941#lf%Q-`paoU~Wiyx)xXKcFZ|NWYgBN2xv@S^v zD^E0pW|_8@;b--ty6O4>Y#cHZm&Nb@xxk>+`1h15C!0DFeyIM;aT?X@9)tiFl2Vd^ z=$=@Dyb(b9F_P7@;phW$3jVUp_?eV60Y_9ugF|>@Z^A?~Jb`x420hBibcfae<<;Uv zi^2!bLr9C&L)s@y>PR>@isLjK)D#SBL5AIU?v!bVufN!JO-wz>#qba8L5%A&?RPsI zba!F&t49vYEr_bX4`0U78~0^92JE7Llt*2!yDws&nwkQ3bn=NW;^|A&zJF}(=@D_? z1`%gu9{K;YCb|8fT~{#^*mqAOo740&bc_WfRfiyp8~7(%}sGG zNiGD|N4+m;U7%;eMl-dx_CWPW>TO^V1n60+GSTS`*Y8cj#m9F|N`r8H3GH`^UmNft z@_zumd4NTVsU<}OfB=0)EZq9C2};-jwR=QB1DHxUU~?kTar#ms8e}?fr!b=c;z&na z<0TmRp#;Dbkg7aqD5W33$ZZ=q38}+&8rp;g`9(zqU?vm;=;4|n69;7c=IeGu22!{P zrdv>)T0qfHNU&(`x_cdR4sqU6%Rr_Ebl+$>%qJ(tYm`e#K?JB*hilJWptZcoxL;q^ z);{~t-uD9hGtP>&nGu%o82rB}6D@jcP-%)Feh4s6qeSsRBzV`iKSqU%z}j_C=0Tdx zgeQ+nkOw+(be*JB*=UmI1;ROcJp1WWiyk}R4-qYgP%@()ZxP$0t^H9V^MNqscp_+& z5H-4M0X5)iL4?LNq>EA~i-ACCHg!u$xOIM|Lx3mLoN<~aeGD@x=dt~fd3`^C%);zH zC7=V@ftK_+AP|%iZX@MUaFbG8KInlW_+ERy&n9}86A;^@6V zT*q-|T;S`uO8crd6D=!@2p$y~;CTxuD<8#^<^kO7(DH9DOK$yQkCY2lxJw~w^RMHF zZa4^41R`R>z7%1G%ZEXG*+nf<##q1`K5P!a(5j_4umpnrFskth4Yi|SWdS6I%2zD7 zM56R)bACQPW#ep=5o{9^qbCE5JwbF801I?W${SIk^T}=$kJ+;*juiGbmEB7&q2f<) z9Ew-#YwKuk);{DEf58gg4zi4R7oD}U^Xs<k*%7>Hf zPMunWjz9qK+)~0>M&=T9Y->6pebhuwi*=|CZc0H|TvUv+kr`5PUJ9p3R2JU3=Y&XI zT^%b5GzG~G^se!%f@kB@SZR4~Z)`Mk3^a?_4_JZfD>^)(@Mfv&g!u$nfutb8nUUIz z3Jv|gVyO8Js|se2O|Nj}(UsBB(K4=i0OCV*=ad)|HN6em=Q~F)D&XBPF(KrWo=Je7 zm3DN>K}5*G^8szU7XaQP`Ud{R=+?<`_6jj@w}xI#qqc!6s6vQEuRv5nDL*Q8hK7by zGlqLHA%{kC2-%EIj9;7*%M&(!6Wzhoz*EHCOA-};W~St8J`Q#No6$CX3{HHZrJXBn z4N)nfwcFqU=oC_y*=Xc+KEFrr35EmWxsa9&u%o1HW2p{ zJVh*@Lq37>^n)j`ge!)xi{heyl3Rg28^{m}`EX4aCIWPb81R4Y#|;*+7|%YjA_E_l z>U#NP6c;pR&ng?@U}1w4dG;TW9N-9=2}gO~!Q7l2N*>WX4uvqL2jOfWk0B>rsR20J%R&eMp@}r2SwKNFJD%HbF8pL$kT-v7z_(} zM(IuH2+hGN5&?-y>EmvO5fU1P^R;i|EHuY82Pulxxh`md6|k53cB#1$TMVwF z38z5~#XB$(7sNq*Zr2yk@9&3>26#ub-d(I5LX2uYef;>55F}+Dt9>AVGGi+4p*uzp z&B6hJc@%?4(SXddOt*Bqf1>^eGL&B54U_GXcaP%WU4_3pCHVtRrq2=~OE69tD39=zA_4DGpl{8a#u z{K^WC)HNY)CD@2+QoL9Y$U(jZ)`WLu+<1+Bi5a&oS`4`U*p zFj~^pR8=c$N0YbUSnsHaW<}D@ble{_i&V>W2!$r~C-n8G12}U4s|eGpT%ig?HlCif zPY+yz5T=lOk-8yxYr?g%rJP1+pbq9aYF|{P^Dz`Xspn&yNg8LiC}~oej zc!Y$MPaM1-_pBDpl92Lo6wKB`+R-W;)I0ezuSVg78kEjj-)=hrj%#jiBml?r(!F?` z!G(IF5WBSz0=F}}0E7eXqgXlU6DXMp{E={N8z5^UlU3%nE)vNQM&BC3}qv_`}Ep-k{6f4!?Qko`P6Y3 z;7Cp31@yI*AJ;^%UHXfPXqFgQF_*+$^9_p%t9SQ639XgwgR7?zTN+Px0i2!JK+F?Z z0C!k+-{E~I=~R;9I3@2-DWR|(> zns9`kgJx!$x=)66o{B2lX2KYQ3xe{}Y0P9q9Z)S#RQ+_&Sr6R}`{a|8;bHu!R_h<- zt5G7kxpAOS+TD}}u<1Br4&jx*3B5{8y$M=X1cqG3nV|o(n=F=~9dR-M8bKi);B)}O zf7FiOaLZ95IsjF!FkvE=Lc}f(CUlHG!no^^p&pY%&56h=r16wbCjR2GN}K;do;BSA zZ{J?4Jd%ya3A8!sbQrp{B}Oij6Ozz>w`{zAUmO1jk&U=>DPon&XQ9Q0tVixR-P(@T z*W*Nacy5IQ$Ho9YuaVJFx@y=*fsAnQbI0=77udXS{b}cO{{RjhQLa?jqe(BaA=>yB zJKwBh&w5(+fZvB_n8yS5P$rZBTmzp_|0)X~o%!`1K8_D~vm3sy_n z#42l^Z5-T0^a9LQNNNRPIfh&!6mf198Mv_{SnkT`wHm7h-U`$o_=Iv7H~elaPZFI{ zNfI%P{n-m)c5MF$4Irbo9P7%xi8yV<(_Es&I9s+CSPV2cnS2ajYTw>80qse|1thE> zGlP9DQks8fN$yG~tWBiR{RetK|A!D{^dj<-xAfXSF23r{op`v~&s6`QyV(qG!aMHv z>qy}jTFX&LCwfg@Mjcyg)52H%`oPGaD_D-oW>jCG{Ht1h;PyR^Zd(?p9*l5X_#IfQ z%K>tjSXHPRMXi%ILKWH3(XnRhR&90>kE`V%&y@KTK+1ZL#v7zQY{?T+8JU?9$L?_c z{0-kp^i4GV3#A04T(bycq(}xpQUzbW7=8Z{tU^;Dg%Pv^=6g{g&bQE`1(rCkSR_n! z{Gz|Ge#BWrb6lZo*|`fN7bpUBKF(wP+U>{_MrRht>v;|mL14L80s;c+r;I5Ggk}X2 zPxDt$%++Kf6CeT|*3+{;mV$GS{;R}`s5^|6TZ;>y6dcwEs3q=;&a|$S`m@YQe;E)5cQweY1+YyNqMbh!ZC#)15mN=O3GI zsyTBOcw1p+{O+35n-4dy-}Og-UzjVCyu9EE9=~bl&M}T3w`OS>`RNzJA}F3_ZZp5b z={&27QpvLt^P`U(T|HI{93F)VLPJBKnQ`%F`soCizZ-qNmgc{!WWKhv=$73?w&QE# zW%w9Lbqm?Qh?FnryS=`nJ>#k7;PhEhqjSQ)UJMK1xV1-RHtg}HLOgS!kj&9BFP zQMj5iBiUN(&Y@T@q>fj&F_oxKRAv;MU%(;hlI6D^yhL9*Z+cE=+)M@7CBQvSC6ug2 z%&nyzyu_{<(K+1Lb)qoW0B(@--+tMBC->pVdWk7f6iZjCCQLqbY@So(*9Y`E^WrNYr;vpz7g_`*kcE-dj4Hz+NCAd(EzimeM7(Zpl)} zHFOn4ohUNrR`a$fZMVhb`S$7iEI}%WLf;apceh^pn*Lc^xea__jUOv6-4GmLQ%u~j z)zrd&z`kUVfk_yQ^y7o?Y7Cun?AG6%&U4{e%Q2rn&=LN8kq|h4BWTW zmMncO=5n@3U0pw3U6$!?Ym%Be>jnm3$ z-O_jZib`TprJl!FZt_KajyrX=xAEn5^!+E!HCdYKUgPVA?h2iH;49Qm{uzGyhxLpL z&2>pLY4e!7Sw)5806+=EtQBtr@tZ$6kfe0OG7?_H}L&UDQ&fZObnwDBkNEb`pR71~2m;?j&$}m;O=e z-B6J*7u$QC5_f!W1vd~o-f}Y^#WdBj?D04w2|j~b2Z3CyD9aR3cA6eNO8LP^u2UJ& z)O*oyF3=-32J=GN$XM&a6Ji2rWy%Mb74|yB3g&lLRiSZI?m}OH1R$A_ozrVwgj>CD z-v#_cN>?bJpqp9}wDU9%IVWfE9sP>n5j?^NxLv8!?%Q^hAs*eT(^eASnd*1%u&PPU z`3L30q}I9c*h92$MC7KZLl^9wYh#b#*tW^)QFb85J^n!f4+RAU4&}aGkik7_K{*Xc zDo3G8fo*?WNpZwthb=n4s(8f2io^d^g+-YCcjT1D^Tr(iZf#Qsg<;1t9Dr~l%}3Fn zJ|gs1Y}pQlKP%gew@U&hl#|+L<(y=x95s zG+evS2=)oc?NS7{!!Pevr4--*67$Xx-M*3o8Cg$4cVnfM!;*0(%iSanQ(9izEkA05 z0_Hw%&3Z8YDQOn6sp;tfIScIczv>pFj|Vm@w0yTVS{WK)|5ug+9D-t3eK*~MgcEGM zLG$UDj*|Er!JnkoC2<}3Idn!BX-djwV74n`k_sM{nlIzv;B&93shRrL(ydE`@C8^f zns6$Pv<+pge5#NE#wRIpZWHxy2>Ry&f$r$lUt!^!8>|H z77e_Al%cuvY9BNV5dRCGO$47YpI<%H3({ewJI_eztTnv*g!?)XS+OMMA~e#wv6=|@ zNKqW^2HV898Hh{zs1Qqt#JQ<>YGYmH0A&D&uc(?h?Ly#MJ=XAI7|@-*AS)V>h)BWm zfR!HWz1p7gw5MuSD~^TA$~%~+@1-M-q4X~xBL^1dpFq*!r|6P=gT&t)aUtTK%r+?* z8FzSRNL}ck1Dm$sujJMZR~#|C)q8~D<+Lvp5dz9_7o|Yf=Od}@!TZSnzs{PNwAaUf zwsx`ZQVxnD#TdT+4KsWnnk`##4jiEG&?N-XW59$~cQ4}a<&)vKdya&+L}!oJ0QGs3 z>jlhO_(dLw9<6YH)^cC;c9=)>)OW`tQ}_fR<#D-vjr#2e1yyZ!jsoWY%E>si|NFWC zBYBf?yYfg%=E@Ym%VpoWM%rB`n2KtMy=z0X-1&OM4#IPH+2_CmxtT!AZ{<ULEQP@L4*8l( z3tMz2Hr!k-<#+?=&6IKjf{NgZb2!HRUJ;kzbA`byd+YAOQ2hcCw3t@>V1kg*%TWlV zK}*z6=rX%5r`kTU&Gk?2=bKW)d944ZB`V)TN+gP%C?snuf&kb%p5pP`c~zOHx&x^{ z5>6vJ2ecWf{m1K}jAECSj7~RsvHl#yBLWbRl{YV-n zQ5c9VWWmTTdV+KrM>sxN{Dh#)6>?A`Dh2~7^p7P_F0^l#q-_f^_3=BbIG_sCW7F2F z`SAKR%sv=df~LYSY*{Sz_0;(AeuZo_pmrgGfqj`B(X~Lr8CyAlVjL;X?t)0i@x;X% zUzsNujrne1O?)lt&@~nSowhoFt)Fs zW)yfL@`X#5$Whx96J_?#(sB|d2;AV#C~ODCP_?eHJkLIa zl|422#bOiALFJig_>s-1vBJ zWG=_#7+!<3SO5(DVhQx!(ElZTXHPGHTbstiLl-1C0o}vX>}+ZvxQ4oWdKNK`uWHAjXc=C?ub>J@nBV`-F8^IvWRtTvH zWrw)gV12K1FFjCkU=^f4msRi_gtDb zBmB`LeJpoHov}Hy*164%WC$ylP4%WDuQt61y%96qc-x*%zY$9UxKUaAzM^PtVz?;F zZeR&;C)_4eV-^o&ZiGmU5u10%5B{2t3&8E9M!U9>#oqKTDsal!qhM`(!)Z*={4(D4 zm~Y2cz}y65c9_!kz-&*(HwlEOMmtj!2|~}p!Ega1+#6b!i}w%cW1~CHBQ6LRbf3Pm z#l#J`|8AhPIjsLm=kVMv*9ri16zA`Id=UHsMTA%)rI+S$Mk|MLM@2`ImWnj>2zpDf zO)tdu4aZ-P*bk%>9s-&`E_i$y#Cg!#nL?%PTSq!l=zX)dMOxNedWLARqo(7Ty zv|WI#fWCn5sdkJsO$)KYGvakW4uRuyFh{x)#d5g(QAyBagtZvqT*HzUC;#8>P;)v=HN1*JVOr;+p<44?bl=#eQT5crJ` z&bZjLm5vZ%lcNIF%4@Zv9uTaM6Y6rg03Y@p%2^oT4d^=Vj1<;7<_@odlnlDc_0Qg6 zs0$#xR27O{;6`ze#*7N*&KTOvnG`)FTiXFl4YB$2NQep32MI9` z95_HiOf<;<2r=bkWSGDb$DI1^a2RbXB|C~*Rmi9L?2(rzY>@h+yx}HRQi>oGVh$_o zOFX#Kn2&%_0m>ubVdCrKqWkFc0H-YmtEUMnhm3)sv=EXy0|!rPk2$bbq?C~TPkF!; zLLdU|zwg9-M6NsjI0hFaV}2{zEOitYFbv=I@0Fu~ZT`*Sz`}fhZ4rZw4$T=EZSih-Fr^8?qiaYf!sp=NUx(ms zHWbtE?cUx)@)Jss1vo9X@A|WX2~^uu5FsvFxcxaOh!A2I{2RbQp;MgYPh`zL1P3ZbHmI%M#7Y(0g)jJ(cn zo_m@vG|~-Y_`B!N*NNHmnxxVm9C|w|Bch@bCXa4ee&~3@u*+&}4vqtVYbCkBTere( zIm8Z6xsecYfO{+w@d{8#hNn3}7eaUh zd3@u4Gh!(M4+{+%Rl^if2kdV$H~@59TJjkmP!6EtslhG-O$ku!0C%-(NheF%0!+F# zSYxM6H_MccY30sE0O{`3uf~)WV2i|@SYujgyeGiuw%}jgU0w4)^^9zt1D-0Y5ET)IoPON`0a8U|$N|62Rt!2(}&G9bvBV9U179LJJO#<(_4AwwzM%RrZC@xegkH&zDw{wuhRD1|m) z#JALfCWBF$WqKRE+PJzLhtv-7c+a>pjTgTCrDC4f86&ENERlsv{Yqn^zU3Ki8h#ol zxN+l;K3OxKLpF)SlT$Bt@4xyTB>jlfHlVOd7#CaPMOaxqCDwOLlfkL_1g|VTFn|sV zYys$-1H!DF&*0?|I7|X_@-#q zw_SU@2w0l_AD<{Zod(>(zz|z845CUAZ=`B<8BT5B^)JA1=%^TfROFNU$E>B?8vWGh zpS&&{E87~(wI=}Ry}+o`W{dKLWU7YTDI78w>vRg~f|6|$I(;;69kZijt}8S8`6Fq@@t2PkFXjd<)EMwq({7J}y~MLxd*zVCK=oQJ8#b2`pE z?UwzPw0j&h06XUV-=4xLjj91MM_~EUjRsSVuC+emXUSBEGocVWA{io-0N-jXV0Y|& z@^?Y4r1$hbSPkqcl3CD`Yi7Rhb06L;l#nzv2=_e~4XOL?0HLiclx6=vF;doiYjB~k zK%npnq}>PT=sLa&83(;U;wQPu&;SB`dDO@0R)`i5x3&yc`Z>hdf=_&2RHPW40a}GL zLr|Yz0k%SEQ}C=jG;9Xxw;U!UQbv?RcZQ3sC2Jf5g-L{qx)BX;dQt*q@Z$$gjQv)J z2yX@Y2Hn{E|4$|sB7rH0jsmu5eL-CF5(gUm7MD>mzP6jJ#FX?ElmHLf!4-cZZa^G@ z6dqjkv#5~{l~%w_--~ht1U_%s)o)-*Y3^PTt_{zqXOt02nl=i1gM~-KAs=`WN`_TW za4b_O7Ha)Jp?lG!^a33Pu*8Z}OMk@W*9@#vs&~*M7U9685v7i0^h()*@?Kdprv`&% z*#q(gK2C1c(lGU>QlWg$1~CI?q3SfzJC<;0Fib7vehw7iuK*U&LaHNZX7WFP^;m?$ z5j&nn9ij4tDDyG|xq56n|8j5=&SN_--dku6*;|nGYb!xMzL^x(3p9WvVz{QsIPo{; z=x=h-pzrI~m_SDqKY>}O=P*Z*5*bCUE9c-JD6ie=_8n&w`3%W`0awZYSdpNVCZz%T z!)=Bv#=($59n8JJ0eS_82Q!5Ju=CQ)-b%a(T+*Lv_y14kQZM)o3KH70N8qAK?BC2K z(X~MyMOe?hsK2|$c{gufjJgZnV$dBNxP@pAqN6^yUKPNpMVPurrZxN-^!0+;59d+9 zHrhb;*DG}bkgY+nOAurNSecJnbEmdh>Mb#8m`hfifA zqef}-N`)$VcJoIwca44GY?!bR%1XS@dPZV!e%Z4WJAqB7BhK7n;kfiBuqq^QJFFh6 zvd`}Ap#{AR^?JKIH8NP-Q+hvstm*_GGH0RwX@)D)RkzZHlDG3p&br#Duq;}& z!NqRH3X6RGwNl2;g?pF~>L~Hh(l$%5u1r{%iDTb_${Q)|#;oh#%vl~hCwrODq@vx{ zj=L*%7uqGH-ZAy@4sf}f>s0+?aE8LrUj8>1ZmO^y?wP${fx(b+=yc~3p7$$tzJ1wM znA!ey57WTcQTdb8X9{naf5Ss7&pZ8W^~F3mA`Og$B9j(YnOuouL=0^WR-LtK)v7x&X=dS>ri94x$k?$#ZLm+u}KaX88zD`&tH@NoRickO^jyDL@8 zKZ}bS>^ig{IM`reuEd24Vtsx7lF|;6p+rR4C#*3M40)@&%JotjZ{g71hwZ*HR-o^aH&B}zW#FRume0U`3 z%p+J;(Q1Y3XsUbM=y3UqF=7i&{fe5tZucL)6bLR975i2^iei86HDO|A$R+nRe{wRq z{qUCF)+G-kSz8SDBs`UtpQ+`%VWGHqZQ}DgpT<~6CajWO(!&;P+pd?@lM~9V_Vc7> z*HM`lK0-Jd z>d}9o)$ZKhzgcotoCY|`7HPfCoE;o((g`^~Jw1MF4*axovKPdL!C!}M3v3<n8KJB0jN?+f$#+`Kt< zRa2q#2=~uN{H3v3LI<4p*9^a2eL&19uJ4S+4(*KI>(lzsi(X&RYO3s|s<>pT+mTVtA=IDEfX&Mugvb?O$iD?Z)vt`Qyoemft z;n&)-nuKUxhc3)eI|Gd4hLe%%-@*r(89SmWSu;|2cv>T>M)NxRx`NImdt1<)^Sjl$M65sklE~ zIAii;Q`^Ib|D>}rW}*IuU{w0xv|G)oD;8@m{y))Lw^{m(OhtuN|)W6>!`z=%Jzhe#m$A~4n z#bvc<4y-*dy*OT%$XD{+`~IE>O7s8e5C8k~T9+Sh43A$gZKdPC$uQ1;Y{7pg-T(VF zwR8@Pf>Y!8_hV^pe)WIcFl)}Wg=Kj^0baxI&Hm-8$`jPo<`^=>bO|6z zBfj;fEn65(28%gD|N6meK0z2w^9dvFYAg-`Gz8er&*@8hi}Lxj6C3R7KovK_zB>KZ zz*kB__Xk6!(WZ<$WNPW?Frzz1o5t&re&P!kdX)7cNGozOBgP0H(G0i(NJZcJ6BxV- z?A#Qn9STjaqGqHaM56sxQdMPUqJ#%D(;uJaH_?PE{FIkyWN4rturQE6MpkzT0fOb!e;?W_>w%JfHc`K z<^GzINm;`Kkde`h+2fE115ri*nD(<=Af@Cc0isRbkPjb6MHh+yF30S4nf@_J$Kgfr zAVhS7$3Z%g<{G=tuzC<44*9xJy*eTtXrvtaGD@^JT(JwoLCGgf9US~@jCuf6wuD1F z4>wYNkhRSiKqPZ;N}sWm(VDQI_yms%#|{JblDMEOO#YylSN!#=^ThFN+-1Pdghb!@GZb`>s7#GLhnX9J<}#46 zlUxlH{f08wy$E6G}cctGxxxK_5@J6grCCY1dBIl>C78ni&2x!XE(C!= z3TEO5u~@D7ru_i~LjM%(d;YNG86-`@phtmGJE5G+E1q=;5Ihaxo)Yxo%acY7-S9Qg zC5?EdhRefn@=DoUW67&_zZ0e3|HWr-h4xw&9D;8@Xyop_X})udq+~$t+t6K^F+B{Y z2;vZsF~r0Kx#Bgz_RD&`Kv=;m7j(CI@)M>Y{{rvBa}T#mV3 zU0+GN5!k&>(TLc#NFH@F%*yuRrpZG*nBCCqESiqRp$Z2hsK9c|{ECOjC8u}=FnGoA zXL_93$ma$SmRuM4lM^c_j$6p!*&1?&168Hbw^i1GIGnMkDG-Y?D$kFB^o~Tf0!6j` zPtF1GWiFrjgoZo^Wr@+uNqX7nWg}tw{3E^?#(q3o?)TZ7w`isDI^9HBr8~TEb!A@y zeqRkY$bLXNg99*A+v?6`+-B$|h2FnpqU^c;rN&p9yp85_1``y9n_VWxco0LO**Glv z$&18&IAJRY(!uIKY;v+9YVLy75_2$gp=&>421W+EJ#oBDFEN~Ogptvj?+70+FG;>@ zK5amZ69zqQsK3%wij*LHTScrok}T7pW%z{Atka_*pPT+ikgzWqXCWj3sHZZ+(8^O%qiAh_PjGfK59GAZM;Z z5$?SV%ReC?e8JipvkpZJ({LRitgu465#0iSge4Ql?9@bhT&bQ-R~`JC?}4U}2`)<@yZD3U2%0o1s}`Cm-H1~)!Q zCN=i0TZ=St2h9VZ_LA`Z8fSzt5CdQ#ZGvH4bSfZ@DPH0n3K4oa$|;txwID-m+Rk0O z_SRBbCSYQ=4GJPtqme%#$X>I+*%;wb?$E6(H_@uW#5BOm^1Zl!nsHurAj&f);xw|n zK?g2G-a`qC_+3&rs?0kpwN&t+uN2=NfrZ>{C*|Y~DQr(0g8|dJOFuqJ<}EHYfPteh z#l&UimaV^!9}vqIFrO=TnNR!T`SW9w$`*h2C(GAeo5yu^?Uh;6o;@>IrnOg9)vF`u zYGB|e0SCEFi(5_TiNjEZc=L5A8!&$MLkI6MjBvdAw_@*C#$(I3oZE)#4=F*?$ks2U zfq=SlLtQnIS_KGou~(SwAF|!X17j2|rFzZa=HmnlLn+j{`}!F$M#3O?jjlFSMG;Q_S6lvmr40Wpv{u0+agQ*pAof;=fK zJ!JicIK{$sI&WTz^Vtaq<5)yZ&!FZ(hJ2!+9;{!Ke~*C$i~&txh{Rn}F26$63TX~d zj1lcg_%^6gnV4WGjC#(dsD5AE4X3H68HhH@NJHt_nn80#p>aTjk2|;XuA!GRlunVk?9L z>n1J5@$)GOuMO99#19AalW>prBFB{er)&>uc@` z+#QP8lBs?QthMBtPlj_@NOkGE@6f650U9o!46!uM;N8*5=4NIo3-7srDx86D?}pqW zNHeL1_T?RiTDlQeDZ|?Z92=IIyBXxrSTi=EJ;|^$Q8qhY-McVp?qG(_ly2ncGwLNRGQzbGalDhIyS>Hq{&)#?(1;+|eOO3$>u*bduDY#3wa~CJw z`KQ};C^6zt|5{NhriB$yC-y9XANv``+b4ac~3Tlcz!gZx&2Gm$S zj^#}OjUvFY$>n2%8U-h|O4FX3E6bm%pAFb(WY}$?Z)1p=hImf$B=I6+kAi5VZ(&8n zma>)-S6iqXa7}uc;r6f{vQn6eT5cV?trmV+^WEuar_qAod1%htP-B4{Fc=&_ z<;Z~t(qWEG$}qf)h!7ivohz{Ril^eLq_oh26oUWl?W|hQiwHTmu3(L~{F;*`I89}_ z?4nbngEqt}qm@IIa|u*AHv9)1Inxsb?}Uclr11x+*3h0}Hp~K|vf(inJytyrLdBWe zw=)5ZY{I=wqGMQTFfd^{`a}BfsFdJgM7S%K-VFS7q)c8%HVusHh`76ig7gK2>H=gV zG9MohyW}$dG$J($-oM{CDz!|}S55iL5G>KBFy8}Oi|P0ilyL{kA6i)rP<9lO_dI?$ z8bTEmN|a=Tk3bzX*ayTFu0nLF(63KMvTt%wMEU83XAdraFaSZL%p@OS(BZA^M7VLcnfljGbKNJ8s z+4UE{yHS};Au4Y%^fR$D4HuLg4rGj`3tNS3G8ULhD9~ka7{96IaGVK6?9map8FpKn&@@rr#8u9-UA%u)N`Wh&t(Acsd z*M?vQa??XUm*@>V$pctfGa3gx@jV!}hs*B}MAMkr;~hUQo(F0-v~YXi(M1t?3-61x z7PVZp>VwrjhlF>=7>gNmb+E5x}xNlTM2 zdu&7ygPRRhD5rWRoFtt4n4#oRQrmka+D)Oly-3lUrS&Q7buVAi*ueI(EBKVNR;)O% zb60k_)kjz9BZ;b%5{$7?_+QLS=N2r8G0EP}W!ac|62mv%kB&4A)Meh-t3>rCzKgbC z@%Pr!TrJ4dB>PV2yp5Z8^vIE>S{UI_CSrRZGBb02pCWIR`5wU_Rl%3tc)oh za^y~fS+?VQtF#jzP!@>iWY7qr#z#P`54JVvOtoVIry&Y@33d+efabWs$PCNJC0uY3 zjx{NU%Xi;JA$$rmP9-3oh0>FLGSu@Qo}E1w;Ig&!4JgRd*w{EZzTuuFjSn((F|}vb z*3_}djqKpOAU|pZA%=Ux4G)Dpwxs7ioPWF2g2XJzFxfL*LLXq9b6!(;qG!=!jyZ(d zvlwA$_N9c~>@|U??cysl@DL)-A@A>f-Ugr^@RN9Jq#jXIp5)#LnL`0-1i>>3t)%l0 z)#XhMh)&$bVRf2=MaBUQHy8LPSg+DSJY2@^tPF$Z}hY*5U`401Yj58;&H$eWzF_@badu5lO@djU;lrzr!X zM}D^N^@Ci`r*=p;7-y8{h`N$eNvd~ZqRrqS$^@0n0hF%;`4C0esEtQ{gki7rw-bUf z<(BV4BfBL7{LllhM215Ww+%hps0Ix2+r8dt*;0qFbsl%A{Vo{|hB_sx0a6!CHGpcI zZ=5uJR-__C(w%-~5vb$VvQ1(n8{RU3SLL4}X4`TjN(}{E)#_bHhCq?YG0@!6A&A2_ z?n@v)*49-Ru#J9R4A1cd6bgTy5MngtC_6(QyZG7+%DIp@YZ0IS%H3}fLnF(6ltyxT5oCWRpQc$%i zb$H_IO?pHCVsW5sGjq0H-VlKKO zRw5=W3r{q>e^#F_BJtG4L}{-o`&EB-W7~rjY}!}-hjrWn`=cVlBJ20QH@6H9o+*B3 z2m@w689+KTbFHLN<6wl%moKT!dlsx*RGVS74t7B$sTr$2=N_midl#?oR=R|L&cKf< z?F+{jU(%>4Rool+STHeRqJ~@8>_bvzAFsY-CW5dam&5||5 zS|WZf^L+1?wNg^svg^8%xNJkS>wWCso453>K38h@JAZx>)T?O&zchw}0z^!Ve;MaX zl@%+0bsil4Y4qR#CVZP$aBrj?1T9p^xDnsbQS0+~Lbu@Q2Z!~M%%E#}=ouoT@&A%U<9Exg}T0Pn*R-&ZBrkA*XEkNCUjYH2ti_gV1 zq&uFxB;{rgT(ycgb+o=`-++MiRMV@uZsW?vJ5rC#mAmllR%no5!odvH7`^nk`n4b=#lU#bu&Fil=AzHY4!Gm08Mdd^I~J?YpG; z`4u^(opTDBr=hthfKf7jc$bypwTe$i4uV0rSS?(BY|D@WHiqSw+TBPfb$vbg)Aj?2lBS4bRMdNHvvIc4sf)_G z5qCAq=vjNpZ~Z)qXvX2?0-J|e57<=e9P zIM5?((tx9NK*`AQN5N(2B?#q@9ukAbfaD}Vw> z9yP&rPKrAET4?y(<5F9T|0n;e2^SGd=KqNRTW`K>JL-?}0U(NkU!>r8*3lKUAH4_U zB^eET*AIMPMHqdz-L+he@@Fz(RDn$=7ZGQPw_*NTtX1=Wa&V zEk>c#I>r9LTY}2v1zN3B<0EGSY9ZY~mu!l|h$K#MWF=My0fYw_qCn^@G6p218}d-p zP+|{_NdR`p0}F9tuWjuU(;3jDy8U3S<^jT9Tm%xlQf*!6$T?oEQwlDm;_jvLvws9|a zcgdm?m7o1MFRFLt4t-^1c;sF>6zSpp{^!ta)0bUuH>SSX_-<%OLgIpmUHey?mp{9L z?Y`#HsOS&4a%lJ--d#!&Y{X62Y*eA5SIX8&#FekQ&S83tpd3 zXP1}HO7If2(}=I)lrm$kJ=1kV`;q#a3({HVOWDq2%9I$gOEP?XzS?;*{i-ipDDAb< z-5SHrLFPO(yx?)J>+@v*=jOP8#ZT&^6ovi69h1>{#J!E1UB>0U~q+a*=%S4%+TXQOUI80!TGh5m#@s$j5uzf8Z55+E2Q!cng`sX;mUp^ z!wr*pRSpujZJ~@N=o2Z53RqDs2ya`s>!Bat-i3nns8kt;QVl zg6a06VYs?>GoDkh9YR4PPm&ayB!9V=uRS9JH7@y=0A94~^|Ftj0+UI3c30X}Qy@?; zziufO?Jn&+b^{orDFWRUXR3_=o5Bf6rOyj*(C`pC*B0BYaSb)O2_=G5534F5+O1O z3gn1RX(Al4$XYY}5UBP1US-d*s<^|y>Y0evGZ-yX`u(UH3=d(pxhCO3wa7oDEvFft zyb_^(G$TX&T$kl91sxDOoUmOZrNN?dnK{ZN7%%R=FgZB=Igr&&uzHlT&Nwp{HbB&# zUd{`MVnze{3Z;-Ym%6-saG;jZDnT|si9464MfSV>acGhkHh!k_F(Wng%H6vwa3IB{ zzRJ)!bQpA$=EE~q=k<~n_%L)eo}Mx--#)}GA(P9mrsZ@(_2!j-c(9OfJK#s~-)O`I zC(Nm{8yK|{zZ$RLX7#H1lnw%6>{qi-h@Czr*$e(?yVhA1_dw?I^oVZ##|BpvT*lTO zYdDZ$vwKqZiu|$!LbpEk`)xr;r~ z*Keg320j`ZR?1`2H24MKI}J%fqR}Q-5=s!p>wpdGpN02BUPu|?OuVy}?l@5{x5Oe&Lr^1U|7M*ez4^dB zm%U5Jy-$&l)z3ht+`w@68#iYH%zP4O2t&^i-_DtR4ZU;0 z0F@laKWu=vUX)sJw_ScEVgX#w1DqR*^Vu*FdA7X@#6SR~H&GC0%bUQ3kQWgAKxa4J z!Q4SR9A3ivpD>vhaoY2|MX!p(_LC#0t{^*|BLK&u|D0M1fiH>ZL6*8MbhJ+ALKY{* z`cO1bWE(;JNF|7{q9KLY=9ItN*Y=Jz-Ow8+4=`oJEq>KFKxn$6WIOlO6C5p8twK$ECG(R72B+Nv%cV*npx(JQbQ@UD@y+QLhhwAf5YzM zvF~e$r%u~5oK=rX>%W&`SYy9}&$&hY6fF(16sA}H314Uv0%`fn=t{Lx+~ zD#{M(fg^VU5EQK zSr|8Z^J2(fNN~MU+WBDrS7h2bac(+vsmp7E5x_z$A(ps&{(6mYCYqXwvT6++VaWHP z$%jY;cf$%~-B_y`UquPjps23k&%X}22&ySa%^wYR2f?Obx zk#;oR|EG_8K(MLK5yj2~#rZPP(>rlarg2T2{f!++%)F1O8= z9U5IeCSn6`NnSh`Qzdh7CDEo{tH;+Nz$#`r=mZl^ z(T)R8vmYHSEae17T*cfRaMtdnSFCnk$l684e( zNZEbQ_DSajJynsji*9ncd6dRoL%ic5d{T^SyUH)~6C!*J6_^KSWSm_-IXoR76QD?8 zf&>`DWAMZVMFTx$xJ9n4&qQ{ytl#C7Vto_Srr}=5r4rhPOu3~FRkW14_85?94ke&@ zf5~kO%D99HUqz@xA6%I|xlI0q`4uYXe|>x5$~X?>hzvsgp+gJi&67t>KJ#)r)D_eO zQStI33v{Lk6`HPgU1U?hK}x)7Zl)9deniV$T*>s+XSQ?FcxzBjOJJ@2==iC%y~iii zX|$=n)Gwmv4yg?wgqXoZQ@%l&Gr0$}O_Ym^+&?(Yea!_M4A>yL8y1V}a5Xg7oy_N8 z_QiC_1+c%b0GAi}$N3vhBT@`_guPS`6?c2^@;d9y#kdR$QO(g%nHO2nsK#hK8rjC7 zEStuJol^)_XOng1{`+>=-Qf@nxE5EVwFCl45x(21B6JuWIIrA@T_ROHR3X|%3J-zo zg;=bkg^iA=ygmHJjV)=SLXN04;_b#(m0oq&YC7>)`9 z=^w`pLzbO17Nb^nR+f8F>)T-MaZu~InT@E<*}Z=c4({vCIL10>j>dug`{xXPMCHt0 zJb(xiQ5VE;SE4G{j@Mz_Zw8f6g;Pii?I~+f+v|Y6t2jA>nsS22vy$}UtI+v%;=|1? zI$&TBi-nX3+fwzeLA;+%6onpb+!(&=@moc*$IsZF#Z8X9=L0D7&)jTyb~gUo*^vHJ zShEZ=4~&X6gSR<$FSf9_INp<8h-d#Buqk|*NQj8~HUOq%jRSWse5SwZ8PK4K^Ya%a zWYT=Yh+>}HpW5bd3+km2AuFZUb`#MPC}?lAHKZTY4|yvRIN1B1o%>55Vt;DeVYaEV zKHD_j2N$2`1b@ef6&n5#RN}G5ew(Ad?y(TnauL8Wa6isz0)EB_CoG7nj&VeZ$)o|D z4Eq;%6jx(5kvccDpY4-s)biamKEky-1PC;VeK4i-htFio65Wv)V9wo z^RREDhn+>-!@|NY;K1!fPacbV=3dhvqM;XkF+l;@iK{;rDcMQ(UFZ+1_*DECCEE8k z6{b{+jN>CV)28m>P_Kulr*_i8EG^_8t>HXoZock^J+!BoRUJ(rPwW!yR^P!%K|&Ydm5Gg9$qWQ65r zR^Fq1u~kXN-^U%CetVAuWR8Wkn6F!%bElqv?CY`gk*f6rN#+gl)6zR0J>2uwWwdvI zaYJjTqd^7QS^ok8l!Az`1( zlC5>Q-X%$94yrrqj5O@=l}=8c%w43zNPVAvu2tp5j|4#5)@L1a-gie!iB!iQ&>!C{ zteSY!)6aSHvF?{c)f>)g918E+b}ip2{&8pH+MwTGyXy+N(=1(P1&zHCsTlg5KN&cp z`m?cdt+;*QSR-gV{fiFii@cUgIbJoii_>XJ{+O4KT_0bQS@~t-S(hC{eOfNgL;FT1 zv|=m68gjL>_2YOsQ!T$rl#U8110P_n(@)TlT{YOI*2L*PG=L(o6P8D%$7SJV1tY6R zEkLKN3t9)UVf9Zan9ja^wExBDk+VMpR?moNnkll)C{4O&RPq9^LwvTgWOzC-XR2*%_{dR9?nkrF$h1h(lueS($ge}&IT#Syf`;|wJGIctn9{u5% z7mFnf5#`J}0jI#`Z{NbD?E9kL7Z0L>iRf{H5iQYv9M-nQ_YWYE`BRn?OtPQ_@|Sv* z-q~<>1f8pRF>%&sxN$(L^gLVevq5BJfkk6|R>UYHtEG4qPOsOh}&&S$nLbuR~ zs_MH@{NT_k97xr9ADQj)Sy{B&-vp|s!e8%pVc>PZg?1nyopqT#vG>s(gbg7dDDrpN zmk$qi&-`I~_N*?Z4r#SdL`Ftdp^~~IwP4jQekbY9o$8dAH@BzT*L%8gisp(~s<3L2~Isql&3L}rr-x)8!E;XY(1d?~{y$w?7PQ#?{ zFCvm74o?=dd2weRk7ig@iX@(AG3c)WW7GR%3>y^V&^OFc(VHQI9djC zitc4g;h%JcJ$rUP&^UyD1CG;B{uMF)IHpW-KSxYJEV5kUBF8;G(+Pj(C0glU z&}WmW0^A#pev&!NO!6VF|0_+TU*`V< zQ&CnWmC;i6%1Ty|nOU~1G;FD4Bs)@8!yYADB$6m2t0j^dNlq4#QMTJ{ZOi6kn4>Rtj@-}2kAf@Q#4!Mj&nrWou+pY-{&wcn)P*3 zrlV&hVyvAVkwpMhjqr9a-30KkHrwn?%X zh-P`0UPzofePQs!vy*`-4U=UI+vrX2rC#WNa~T`>@WG3=&;XUXFw-vF*m>|whuaoD zy)|aQMxXeJ`)c4}-e%)iaa7)WI=gWUEI1hg*Zu?zuI$q@mqEBTiXuyus7w;A`!tUW zAxTzou(UgTXc3sy#O-s_XZ3->V}9GP?M7G_lVOtvoUM6yclRKGMteX-8g;$ZIXVhU zBritr8OYogJ$&srRLRnR+3B%@Z>M41Z}opxBq-77|>@MjeicMr%q^)xxR9Dk&V1 z9@nxryXsA7p?X!WF(`vv)^MU`SMv&`92e9%2t1AJIq{B@{01?sP%wcM1j>kP-6_ar zS>>0eqZCd9C*kEkX_}$N2n^ZKs5%}JO+aHjG9etrz5Pgd4#qY?vp{@pvDkKSWZ17w z*owP}-LRvy!ZhzSOp@35AT^U@UMo;uKzmI5u~W{GN{@Z7v{;*qAF9X1)_dx(f6aZ| zP`Vkm4dkmLL$_rbwq>VKR20rdbi)Ea7<`v$#}k09S3pUnjN_?KqqrWPkMfKJRPP%D z+6M;*CfKK6(aX7l4u-Uw>%xbjy2Rco)YXaV{L#5yIc@AmJ=6#9S|(!e)VzCW6lX_b zv{V&RrLg~S{Yc*L#1^fwV}|qbE$|k>3s7VbP*k^03TN5oz2?XCHB2(>|^uALmk3PSBf?Y~&I%g#{GdeHN8y zz@R&6Md-b${DJ74f`q8BGd;|Gqo>{_%tbu7N|}y!%A^{r*RDCH2#;;-XfiN~2f{{| zUv5|?32D>AGS0heVFNH@)Bm1mElJW&Gcyy@X@e|n*oq+kx2exLj5+L~{~eevKwo7& zo({2pT0=JQHV_+eJJC4KEpTGNuCoW3(#^e?FflQ%v8BSJz%&B}L35*^DYCu^ZAFA-$iRfE zVdFoMIeiG!ji5JL1YPS4Qu=W|MrW+1Z~%ay*I=_ zxCsL3vtI-EcqajUu?~ zXuX%jb{-gT0leK_SpmBX_A?(gG3s_T>x-yF>eaeE7JXFbo}n|eo=xK0;>~c4JzK98 z#_u#$I6GkQz)ttw%DG`0|9wFZ>81Pze;zlP@{7?3LUW#QQYECu3p8U?aUK##`MGm1 zY}vFaEvGwUj8G8n4|g84dPwMD>Lg~#*XZ%7DD!ek<3;i$oVt(A+Fk`zNY_=is-sAJ z_t{TRv|WF`HNa!axwyD(?7qW}PsLG&Tra@{t3*{iS-onN>sd@lm?(U@HRXj1%VgC~ zPfNSWLQ6>EFlv7*zsBMxPhNK(^rBs8w6CaaP?sG#wyU&BGFkQ_32x9X_v*~2_LF>H zloL0w0%=XO76qI(SQX0ANfyo#Ns7VR2*+K<2;oY;zl8J0fSv_b2lcDyg}$4?rA9Xy zCQZES8k?8Ye6nL55qCp2M^Y7)b&{2?;Fo{Nishq%4e00s52$Q>u5bmc5xD;!C z+LngCFKwyHWAb^54}fB!SFJ@|8TqXpaSW0i#Apc)+5v#;Q!yTcsTvYg1J2?)>g`kL z9f-tm00U!}6kTA#6c7~)fFM#Zbt{hds^tYb*jXO}PjnLINMMhNQ8^0?a-dzQ zON?qZzt7ji`i`?0LeH)OFZCq>;Sp}x&!dAf2eCvzz%WtO=h z>jIpPYM3Sc?Rye#0pTQ_gMBEPagSFtdw zqOxH_zmPeL`;8kqyfJCX@64V$yas0)DkhW|ip$u|kRAGURPcbLRsP&Hz^xKP0bI;^ zV(-d2+`heLc(;-VjMzdzKSK_PKw7o9ep}@SVF_lYtYQbl-1;7)#qH_&wQt+o4bRtn z{tpR>;N-dzl^?q8{xgp9k_R~(>)x_1etEIB?yrte)+D6_fA+@@zKajvp$44({Blc( z)+;<=TZ(23ZKGP1y>2*m(z7MAb(tKWiCFZOeds3l;?|&R{dcBufU0F*th6%8zbH_P;*HwrWpeHyEQJ3YfWC))^0Pj zsr|>6MAX9^)Gd+4EA#^SqB3TEds2&L7+XfDhV#Xt=9=tWX6%f@Wh(@@dV0VC?13_u z3e14_@YbbkLZ$iy(-K2?HYhKk1$*uF`XQTj z*uY=~(}%Sm;0qpx_=SNLYY`P2iQvzR$v_zZv9nL8A4JIAWOPe+pb|U}arfso;i-#D zJYk#jXyGmgs}otoS4o?iQUL)woLXM?yEs&JLdO_uSg6fBHphnJ$z$TsAC(*LyWwD) zL;E9Uai=K0Ab`n$N>re4>&?^i&>vIVDz*BaA@mB?Gpv=n`{qM}d8c%{hSssPSFYzW zaoa+fr`4{UkmMM#N44rGWQeaM1J|aXcy#Lb^1b8&`?p(v_mp3QaZby;u>};f;fbA$^`{9Q|1*3NjB z(%r-QMfER}W!z|?#8Y^5>Xir}WTee}>{DK?cZcCvm3wuP3r@f5?QZ30wFF8g+OUN7 z@0Zc@8~ICLYg&u9SN8I=ZalF5(B?Dw!l&=&uwDqiwdn0NF_D_`InTD~B|EM=?`GNx z`ThH8d1Gk*OuP`Okt>py2clWCMCufUOc`mE<#x@pU1Dv{LBYHddT}=sAna^S%J=8? z$&fpd;2;kVQOT0c;k%9RIZVO2Gg^J+_aw(od0%?T)%kXF6B8mH$8$FIUo|hz$phsU zFshEz8}K>NXt~`Oh5_RfOe@&)AVe0(f-at3mz51L3mau)CSIi5zX}*t3Sgm?J)hJgK!;IRmWwEM=W!cuP z&mAW*&lN)4x8mJIQGVbVB77kJa^&|y3m7#ql5T!xZtN2?%23J0KP!v9D+LlJ9gOUv z$4EpEdh4K%gH39#F~I~Pz_Dp9KS#J#fbXClSOb=~2pF*#EQir^%>2$A2s@0mS!w?0 z$&;_nqt6jsc2V z>=yfc(B>-u6>Z5i7A9;s&M}D+e%Nd0%;-lZ zfEpwkcFm{x#l_ROP{%60rTt$j)1o&ULP8B#Ppb*(H}4)vie=-i`;OtW za@wLd(Ey_J-50W|CxNfPB2@bBxsx^}QomkYn=>8T5HQbBmvJXiw9Y(udQ94ZabP7^|cNq!8#B-A|u_b z5&2QK$#e(qAwyRuAVN`8l{KeFF!+vgiFL;zwFP@WKI(WmJH1|-36Kj32TvGu{u%c9 zq@N2K^{>nhVM{|*5Tc_x34+8f74$Q47$k|C`15z-edl!d5&awe$I(#k8HO08xS9OE~6wK$;OZ3Gl1g2SjIZb`-nWGBI+O@ z0ua;b!X+yB$)(A!RAg8k*curwz+fOH44Pus=V~7u)3AK)oz;mYW3DlF0OAIe4T)1# z2}|=1H?$hN2Co;7yX3ei@~MwW?;Mk0VLEVBIhs}E1RQjDqr?qgCr&qbMDiH7O!qhX6p&3&vk48p2i=e<16 zY%*MDlO&to>gHAv7Z+Ev$Pe0^-yoZeyW1_`4V@9dQ<3nf&O`5J@+{36CAI7AahG?a zJ4>6BgHTZ{n=`3$-s#L4SL)=fIVZ^=)B>kac#}WYKThB@5K}mnSSiTB0pJcY6mQpC zS@A&FqHUx?)wChk@odiApR8r`h)AMxfOUEex=0DjRon#Tf&}6#gs2po;6sg!VSEi0 za7N@=P49&D#IUAuwVnB$Rs360_!LtGPE5a8J0;k_5*zE^5yWc4cyBOGVPs$MGfj$= z*2mPE5+_m@J9BIXnraeS3bzPM{H|ltmW8zT*wYJKru)v_{raJOq$9!E+LC*0?!{~G zp9?1jPTxk4{%f#_3`SF`X_a6i``iT8MH5{zHwp_5GIj!vkGM6Q2me6)bBpp&0zs{Q z16%Dkkc3*-+OuxV&acjCI>pzrlfzI~%VDQdhZIj@s5tN-w95>~?};{D>jxbyWXH^>$7#68v8O)!_fKL#(`w<6 z|2vA!aVRG7^&OqaM2>@JiRFN@^<_fLh@Wsp^OqL6=Yqz%+cKK(us!v1FzeI= zX!d!urXJ{U4K_)YC9KaE;H=-tTvUyf_w%h=MwiG^T!nwGTct`lNnZa96pJ|p4~SfMI>g-0hK@^)NDo!a@)xyVah`cV`PK+2%Un5OvnQ9RWCMm zYE6Ei@nbm*Wy`RSBt&yXRVOWPfxRJvnu+cZs*}X57I(}+ZeF7SCe7kp-2fS~=|a&V zTI0~x1hg9`)>>UwT=>M3Sf{En;^HrXL5jHjFwk9raGl(l$BjuX!~C-6&e*8rINQhA zPiS&(iJu4io<7ICaU;7OsE;2@tuLadu-r|feU4f7eCz`LQaurTq3FtxEycU%8t z^+S7#s*T8S@F7+4=Tx3*e*&C9N@h4n??fLX^R&(PVT9zl<55*d0cKf-POS?0IHG;< z>3imV_LIKm`LLb-iY6K*z(xp4gJ2M{9ze6FxI^u$SA-!VV{;f3x1a7-R<>f}qY8Ft zi=!~ti9Oy~nq*+5#ZylUT||CwNvgfE`^C5&g0vKKI}eD|7FHtSET-*`Jm?#yc)m`Q zdD_qRJVMPz(*+1b%wgvO$>5t-3 zO|ZeFv40%? zaj+^!-k7BxX(DjT1#Y|?0wM(@$toaawK$kiH8IpZC?S)bpfg!rQ5Mt<@vCp3Xc4Vj zrRr8utDz<`85-PB9nO3aT27k1oC1gp8hu3MOj5T*_0?iSL@Mlz^JLBs-5Pxaejx78 zGiyK;Mq7$d3p+Od-u}_WZh6=C?Sfu+G&1X_nLSI(%1&Xk4XA`xGo#HR+!nfp?0BYa z+Z>z6z#d}+B|POQ|J(cSy*c{#=uHRt#-v>hf>u+6SsCYBy?@Deoo(O7qN7Q2PO+DY z0u!5(WO=+uvK_Y3xcl=_yYw#%G=xC>n&p6)4%RKJiSsz`=Yzg~J`6q5Gu{YANQRAc zp<2v!?^~e)pU~O~|A<;xbsUqt7Rs#jQMQWj+X>x<#{EsA(tQI*2eI2e_8u$NXYp}2 z-{DP!X1(#u^)A+NJ(*NsA!`=l;(ic=kkjFB;z19Ff!hi0=mA7K+FNBQwmOOL9VXzh z7MN!6G_a9ZF*v1QF}Hd^0}Kk>R_vl4 z7Q4oT`ziX+{!lkDP~byunz5dqf0w5gv4{BJ65F1Cw4rS1N7BY%pp!QhwgHF$R*}bP zWg2xQX<1pN)R;)2yq<4r6@!xd%5^SunJ8;PAWn&yO;Do$J=o-}0&X1mPJ&qiZ~43_zBN`Ih*|URH(Gd3~?Y zx7F<=Q4BRfMJPB9+lQpMjY(tA6zDnYX4NU9OFstW%V}p-GeD%l(N4>=fP{UdPjxp!uod#4Myv=Bo zpV|NFY1v35@o3;hJtj^lRG}ZoQ^Hl7(doqi85fW%x&^=(;n3baZW7v}c4l-i^!M-I z261^&={l*35QB1Kf9Ceowy!dVelz@?Q4Y_EecUEW#;PlV8(ozx*NIzKz~JF&N_|a? zW2Y6>eD~~RT^D8g@Ez+SnBoN7U;EU@yI^9jSARPMOe(Omett)@jTfFAq1*!3orVVQ z*8g1bc>;0Ehf>+^b6=qOCv>O6l$8ONZ$Pzij)p@*4WcI2Fbm_>>UIp)K+V~5=_Q6s zG|pn)%LEcyv$o~w;i%EUnsIDy{{9r&<=MFci4sotT^9R$Dn# z!L6S`s)W~zEnucbH#QU8v}Ua5J_!WL=-Q-!V`bSQg*c!qz+LDTz$htNBnb zXN~c3LOg74;Cj0KAO$GQ6e54GM34Ig^=9GRBo`!<3EAgxst*@LPN!N7NQqOi0dL)& zEbrG*gh!q~AyYKO{n9yUo`#~wcJbw|<$Mrj{2l4-KKvK!B&^JNw`bBMROk2by=3Jj z6p9Ct>2;!`R6HGkK-fY?p-`4GfN}skX})9rs$zLW(7ynF{^W#j#%r}P*-}D8t-67U z6T68;e-N~HI`~bD0FnW_Ga4@eJr#Q6A*wwwsp@5bSif=AQyv0SOruX=eT5+a6@{R( z0JgTN3RTZ{V_&}pKrl&z$<$Gl#?}|M#RI~o85bK+{j^kSGDofDvF07#F5-Y4n$MKd zIUS+YY4Xd>Cftj7Vo90;{FYls9~=If+6KSAm-sd7n@%m}zvnLwj9M~+H*#47GD*Ml zfRv%SaDz3@p?EaV3dz@37Dj{>g4lEDCdC3F_94briBB{#6~VSssqZU-)QTQX_&`e% z<)GmtLGXj|Fp;P2^7}J+IFwZwn|mmY>BDruY$HoO_q_|J_Jmw+Xk`w|db$g7JGWA2 zpT7zlYQ-qdmT)=1udl*Zsxg?u<(DjAyq6@twc#lsdrx+u@dZr6kdcF)&cf}sjdvJ} z%!(ai{_;gufBB*``jaTRxLMoK#^?+3s9<5k3N9jL9JLpzWNH>o5!y3E>zN~#v4HXZ zwIH`QO+zbne9CVuQjk>LF)SMDFmh4x5u6b`3Jgj4W)ljU^H8t3n(B77HWudWco3ya ztj5spwin?aLY|);+tyD**LlSGZa+`qW?CwowDunq+v*7afREDh%_P@I2p;P!_#vAl zKWvp`zC?KmTl0%?u|iAl5J*FI%SczCr4H1T*a5$IgTg%chXv5@vhoC*&pZR@sUxNJ zI?&Ti*46~^<{din^Uqs`hEXKEdcr1%ZUOHR@l|T=+O;*z3KSc6>=5#J$Z_qx=l6!> zbrACG~+QgR1Lhe`6)t@;bQjk%!uZmnVrsfrgQjL^TdJQL5chgy%zO&ZG6+7 zobMPj{UP43xgVW{Wua#4NEy3GlwmBp*fqHdPnxc8e)Cl6uWxKg(xd?({wIh|H_zP( zddfqoIw@Mzxtngq5QlVas5pw+9VC3WA7uO4e*fga0~4r5m}kd(Z-P8e$D=~@Uc_cX z$ZS76-DR~qaJ!CzZFKo1bo;4t%_=I1vCebH({qeZ-#O@|x^eS1_yl72N{5Im(PiX< zob0_!K<|HGNI-}TG_wKdGr!@@BR|Rc{$c6$nM>lOxB&RV{*l3BlFih2;0H=X9dL`V z5>j>y*YzHjQ^^psdpVgt!${)Wi#i zYA}Wk20EGtR7w#ErRYm*2S~= z#h3LB{Z{n2|8u2}+4wAeB7mtBZKisZU|r640GtpS(`g)|^vA3gVYX;D?JvfS(b&mz z4c8tY@HSe62LLkxat5Z1$A0lrZQ(aK1ZafHhxAlSJ8+Ue z%RYzSD0~gF(rmg5EOXVUU@;^Ch`h{CX@Zl)Y@EK{$Q}4jj8^f$osOKNYkbgY+-kUy zpo^y~>};|-h5aV%a3sn&pc1Do$sQ05C@aY_2B(I}LY?M0=;vFQBL>)GXlw}cMWvT4 z<*a!AvYIJY`1O=L9bSyf+}&rnmXVQ5Y#-m`W*jL(|f(-@gA%*eFK8tCE z<>llk7WHe{(|^$|$PDfw82Hq{tdF-!=!y3w&WT};uWzyjCQ3MDbQV^v`vk?C;f4(g zy%v_1TJchhWE2`nCL-Ry&uh2SfC(WnS-5u0;VtNuY4apn_YUd`t ztoFDhp;+lXPey4B?ixpU5V6_a zzhO6*E?I6D2`;7DV&qscrZuB^byool4a8c|h!qS0u6q&yQ9u|E0YYW?vvX`K zD`wv)hs2VwxVIn?`6Ok0$I7o@ zP#eyA`ux>L{gAnGmhm4D`0=^?>CimHiP!Mx4-4H(Yr-&>2r~1q8_H)LOZ!Nqh3`Qj zr@9^s@y5v>=vTPuG8(Q;=IswOVMw}WELv>)=;w0d^Jzw2&!W-oWBXp`+bZ@r9iiKp z>{B*rhOpr(v?N4BiW3a$f!NimWHuA&8ra=Fkt;IP?lvs0T5O;rb{X zWd?e8eeably&Qt*==z(Jr3cR1WJ=P$b&Z5$$L47qn$(zF)PA%EIone3>J#qz32o7l zNzL2uF_FRt3#GHJ>P6tE!+OTKS0Xh&K}5ytDeOJgB>_6))lfqWT0Y|JbRNxC#iw_e zHZk!1g&(R04B!@O_KbFdn99`mN2$PC z9+~C7JONUKp)w^5#W7|8fA-QWd#|M$?wRP4h|0UhD~>qJ*F8IAbu>m+xq%8l3}fdX zu%%iUWkr#;uWE7l+Aa~LuYWibjG$?D{yK4TI%e{?G=v2>6gR-_lmEVAx&>8Dbfl#L zAf_#Wk-Dy<%`{Pd34%X1U{nrQ{QMk-vi|(mZIg$r3Q|UKH@YKA*lj^w?Iu%)xab1J+U|@rD)RA>&St^@bs6lF`;_XGpHvq=5u<+VK{QA3j>)X8>x=& z2-4x5;dXGqYgTKTwaByBp~Pc=9uSQFofinuki|4POb_!L zXSo4Xr7gr1)|dV{*j(dWxxQkX(S3T>!o1Dp`5&B}*)Si(@Q}dJML6A_t6H+@aC6Y- z-F&RVvzWJ;NF=eXwR%PVK$k-JFh~{FEWz1rv-OdfTr!ueH;deDp*dI|LPoL*(^i&RwN2iNFWpt`8si^5rsWqT4fJ6cof> zgCsTSPPCv)EWjLg`q6d1>HzJp{1xWS%}?2q@le1j@1^$&3ew|=W_q?ilEe|&b|{JE z;UEsH_p5#RG6mHEv6}3UhbmSpS#AfR%a?xQ@etuXVaV!!tuSyU`Y3^ag zWK`UA3oiX{cGnl)jl|&-)^pJbGCUm72m!v*9}jgFu?S6T9mUwV&4yXDs!Rx?ys}3n zGzEIp4;5aLY17uMi^iZ0@ma{E8{Gno*~pk((l??22b>*T_?raJ0aSa1Rc~$aelt82 zfS#t|9f!#Xgek`pqQni>3tpR>=`)&(SxZo*lj9F)O%n_1Y}&$_liW#5@f<9PPFp#v|B$34QY%OaHpu00uzU zHHM*O=p9vO#KwAC(P`9r83(P^KA6NQ9AdonJ9QS#Hs1|U>DejX&Uik!#MRhjRO4yn-78PeMvyn?a~8pt&Wcg)le_#8CtGip((Ai~%TQwz!-x^jLl_ z3ZUsOtm8=f4{s90dD!;Z`IG7e)0w!!zyHjOqj^H+5iu4eTj%BzA{T#}SA1O3nt#?Q z$4UZ0QJHbQa>i~F+raODsccm3FW?7UG)|rY4B=Bh6qR`IAi=i(Og5jc6}EkFB_w9A zaE>tj3R_Vf{`vwjPQaltfQ@L(nXzFvPs3}X{=qbdv5;0TJ?T1Nt;!!`84m8uj5hfVnM~S= zAJMCpzUS{!J8(l13?D2E7?<)1_7|D#E_pOmYzLwrT5;mP&U>tYT~SGioT9kCqv`c;GjS%Qe2i4 z93JEr6X_%>$Y%hZ0j@~Fh>dqO?Jbr9Srk>92l2=FmglNg)R*_7hPL}qu$$N>V}22i zd3`tpfXh|mli?7*4q78@mD%?L$05GLKK2q*9h`oa(1#N@6jVjmpu~yRfZBG?1nIm7 z;_w-RS1FT0+6Q|IPSmUl-!859{v5Qb_)T&F-XzP*1K0oS0ZWQTN>ivfS};pW%-dXV zyXKge77l$S7Q)2KCL5t@aKwlZw>?4;!s<(4RXj$THf#1`CIA!q*Kt>eE0Rz!!`tO2 z28w7CpNzwK(K0K%M^s_=R<$o>s~I#k*&j~%jkC&m8}zl=PI{SVUS}&!+O#4kRrdYG zwVPj`36>jQOIHf>6JB@Fc~!I9$&`CMDKXAnER+0O?s8JuFKzpyfB%^1G3x?~s1H(~ zlUdI^c(-y_PL5J1$Ms=Ns~*GK@OYcUsT7fWf9d63ruX=g$4N)`Zc3MZztP|=0!RYc zAoW>~-){<8Gc$~Cut*#{s0#>i-ep9S@`0mo(4NU(*XLPxu zchjbnso&Q23BNJTEm`!WL;ha=qI$0>Ra6+BJCd)t^0S8;P4;`%ey+5^(p1Mh%$Ps_ zGavH(J2D6HNVAv43x=3xs+vbnub%CzBu8ta=7kP?d^s7F;mQeYLY2YM0B`{inD=G&nP5%&3HSw7S|L|3s9rXQfo z;1^FrT6VONu50Dr9=Q8=SpQ88oQDA(Zc6gg%0u1wGAyCp;hm3ZJ?uB?c4;OIx<@fp z9G;y~f$U1Z;`pBWg~Hd?95@f6b8wo`lNltmT*QSFgNb+)-qtIFl_HgpNln^-7)WU7 zG<1zJQPp5VVGX{Xy7MmV>trD8et^p5m(@wwnK=XnwSLWMWQw(a?}ZlT{OAW!dgQqR zm}Xq+sjWRc{at$L9$;HI9&!@jab25cIHsYOV#Z?DzSo}6gf}6Dn{KlXDjCQDxTU!> z*-yC;4xaniW;Ob3F;4uCU?C|No{U-H1`b7C%^pokrju$5^4<M5CnReqy)&rTueGaDJL%mg1DdBr={m$$FFi%29 z0|(;B&?erN7_a~dmKN@jN0O6#E~9w4hF#mPaN-T3Xs)2QV{_Z|<~=Eu@iuQ8f5zg; z{!TjAX#gDUBgp7!*|xC@Sb~(abf)J{lyL9|V#Dp;fN_<(_kCdhGt>|eW7rO3Kn$f3 z6AOJqJyjGzDD=@j-K8BK5Heu?`S z8`*1`$ut~Ej7L{`q`fy81tw93C2CDvfc}-l7{A2O(YfhviURm9A$j;iA4NHi?5|*K z&~v!oABYnG<(1P|i5vxgl=CNn;1+bmIVfp@q#%s3w!PYE6BCnE6qqRWBOiCRma?%Y!H18jJ4`Ok5DnQb>`^Tj=GeUl=NNO<=b2|`0h5({bPsJ8fe*= z<9;*kT6wkR#-=(F@}y0*33rDK)($^|vsw`}xj2ODMKCcEhz*?B>!aSf);NaabMo`W z-Y;N^K`$L<%h#y_T}fh|NDc!Dv6rN%McWO=7%ow{=LZ{id^TQUQz)M<>F#AshXR9G z&Jd9m)^Pp$P?+{_Cy*?@{yL(S0KKJEmfygR><|Jklj0LDuB!m;#YpVM9V7G+II%UT zo#8Z2iB4b_HH9HnPQ1pDJNhfi^{PXnAH0Zj<+v9f*h27ikX4|o*50XQX31}asj=5B1{)#wArh&aIm zXQ?#N57*+CNP0Pu8RE!%Z&rBZQ!pb38NdcJ@MGz~7Z8O+>WZRP3D~9exO^${?uo@Z ziA*MI1m)@*wn2>A;TOI_sz>ra@J;RB6Mcf|>u1G={BBk(*W0@i^66G zet8d}=ts0|pmZx6@9fD`z095*=Ql+aBhGCaOVb6+V~NOUlC@Nhc>l`J%IP%&M` zw<9)YyeJtl5)vPASDJN#n@t4e-&`c=o^@DggB(#%+(|R*^%B)V5Hdz~1>eJOeR* zdkAc!4gf@m-(bWDCx)8NPG(eDfPMn;F+#Trg#r_|&W>6F%}J0;;{Hb1I8x7Jv<6)z z$r*vR^ZDn`7VZ>j>|~L%@zIhM-KiMh%;)v*BS09FX7zxQ3*;1fGhc zk(A;DTgUS)G2HtKO$Mg?Q3gf&H`j`8tYk_^(5!<2&urKU2VOme@iB>j12Yel5*ENFzioRU1a}jYxd!18bLf?zJxFc z2v8i#IrZv9Oig3btJlMFaVJkZEzeC)()ep+dNIVtIvlfkDc?f-$}hp8{l`oC%L$i* zf(GV!H*RxWE}ik2ZIP%_OqCx=dnxz*o!V%O&)JfzZrQ|$rJ`Wj0 zOOUNY44bpA%uW$ay6We8z6eMBIoCgUR^Pc?YmeOVGUc)u!>?2CHeT)i+26V-r{>7F zV|&I=0i_$)UmtLP9qE!1^=PLw*KpKIsW_`o?Qx7qeXO*Iip~P$La@`C_A~vVV7;KB z-qblg{-2_FT$Y2MCA5cQaiK7jhOzGX-{V9>|H5CTS8&lkYK@_{(YmWtozD0lI1=*7 z&?#cASj$)YSG{2NxQwy~^MrL^ktZ*j{t zPG3n;K;9k+6hs8VLj#(<^S^59UsHojEAg7!OZ*VA3TUoE#jpc?YoWk)yLjpBi7*D1 zc8RL|&TKh)mKdJA)vCBh(py4Te6_g3)`mN*t-j5KkI9=ZI$=S9W%j>UOPqEN$7?Pb zQvn?%9v9MFv+&UAi!MRWE0sU3gp^^Ipr!aMV@t_J+!w zw*>VwQ;weXbVCSbn&=Bm@crM*ns4Apex^Y^J&W~K-97bIT}5ZF_r(c2Pyco{FY#c! z=lb7A zojQSxCT#lWZjt?!yoSQ8wa(|{HTvu3t+)8AHB)9i24=Lm*u~a$tb4xdh^FS}+M=S^ zXmwFOsT-Lk!kA{q=(R-`C$G=HIGXCeMA96|%pEy_X7j*)8sVI#jl4KinP| zttI{<>i_%cG{IM+T*FQo9ARn2t5p+DMhCx{&L|YP-yXiei64rDb0`|E|9esE)C;LM z(Wfh$+%#q2e7SnkIb`L&37d@eFdeOR!dd)E+U9?j-#_1qd@;)lg;8BU=vms?&RBC* z1eQpxHdaw)Rn!}HiJ{e5t&_v_HeK9~=!=5IXm%v)5j}iEI%ctS9t+a{_g*AK?B*K2 z&S&|sDB|bMmc8l^1x`fc3ySgN6b`CiPLCZf{O2nLiv0TyMo>oY7ZVTf`lvqM*T%#2 z5OAWhVt{KEjb^HNFG1oM6PUz_4+eSZW>sr_C*L(%m)9*i&A7Hsm&zvxa^DU^z@%Q5=A(6|MRX9+y8yZaf9-1 z(5I*Qx5Np%jlZm|y&~|Rx6)w!_mT*vPbq3)6k$u>BJyJ(%Zo?QN&BBWVIThQ+Y+70 zyP5A?6q`m8t7@?fzhP?y)3zOMW8_Mbi+SbWKRx|QuX;i&S!2heyDeR;s!mRBG`H_2%(<5%{H6n*Zk;3ctu6Wl4e6z~=zGp-ae3+h+0%X43tYE&p=~ z$v>AgkGSh)>Xlh$>aol96pieLL$O+(4H>!pe|}gu_SDbF=`ykKRUsy-*2C}XlymXp zT70{AR~R3{CA4JEojy(hQ&fbuUdHgVLl-)Mt9qT*fA9X^Yn($8F>t7BmqYXpl+JcR zD3~|w);9CR1B`dDL9$fW9Dlu@ZcC)3DEV{OVi8vGzYnm;byggcXM@AMxp` zd&1x-rxg9?7>=dB80wLsvgh_C0^n7QhWJR2EbQZetwLyxML3%VndLeGx_GipR zw!Q<CJyBoaPO2A6hfZJ*vr-V8dNW9SJTiOpkQLm^e1Nb;RcxP zQGn&{L0*$WE15i4%m4E#3`Ggjjc6fQiw7*DC+&m7NqbRo(^1A2zXl7iC)F4$H@f!t z@$}W2nk+NK-g8f3IBL&8?`oTeI}hqSf(y}c>|)g5_6bk74BMw{1AYv(Zjkc&Wp%3B zZc_|xL6KIK$|gqZ^JH;~Me5}a=s>}OdFy#sQ-=RuFl#Ez3lr4qjvG}xSGtdHXmINd z1+HP2!PuUO7i)3x)B+#7Hm##^hEemK2R(pvjH17e0rsi;p z?nlb>hzRcETj2Kc6g>;VP_^53irZ-6j|7Y5f*X1Me2-}VFcLyO!1Y`PyC?6|38c6F z@0I4t$#ZNUsYOv(vgL;c>!qRK6Vuq9z_uf=Jr&Qksnhb1(ZVUTN*ii7?1(HLd&I;e za4=L%nMUD;F!nYq745DH$!9ZaiZ*n)2kI(D*Dad{nYN2)H$Q|eQv z+s`K*`rpoM`+rKlHJ}OXguHc8-5N54tiD+XPLa#Y5}F$zZHH{XKG9 zRgS@`2;Hx~A6ZquePasDh}L+qRgGHz+gtk4$8d&inGKQCfWUh~?sm#&?kJvCQjb>4)EM7lXEi(c1I6{e6=M)} zXtMrZe}FGtH4yN%9WOhjLjDV`{omd0zkh)3bOEpKz`dfDEh6{ZPukw|;z?VWQI7s% zmEzyhAPAuhp>2w8OE_LdQ+4kfu8~l@c=Kn}^iHP5twnP?r2K)&CZ1EoP8#qxq~gEN zY3oK{Q({|7KdKe4-sy^wB)c&kJetwU+Fof|{D8%b^N+v!)OX^FigGnH^g#3`rl*xL z1*TU#4$*A)GdH@U$p>F7ZrFucyPId+-QPsZ z7FD<4gaT=epdt;7G5qmDmb74I7k~D(BNi$&R1x$9@h9HQr>8tF1zZ_*f8Udv8x$3l z$P{a6Sy`HMy6T&=0fYL74p9Kdx{5ZH*!V+Y^d?St7gVIMnjSP5-$en}P-mEtVlH_P zJoSiqI2c~E!ss*4MoMd`Ly+7xGcr-?vi9VcF9l7p4D)nbm6xtEL~$lL=X~R0%iHlc#et^*GY*(ic`ko@|Cc5%%|4$g z?)Nf!bumI_TTjCb*2i=1YEaOhJ@Gt8lb)ZO8u-#b+@>>JH=P6DbXdq2jW<(5>Z%0X zMxsgR>;^KPd+eJkKp8T_=rrY~{9&vnNT4_4?8{9B~G}4xcx`&DT=xcm- z#%;Mtu`I}4hRG2J1|2;h{~xhPe*(<=TU?I*Bi|R)by{Ayl+aEIL#}Sz-Zun z&_Lwm^EJq&Q@U`*L{gH(zuJAuPZ}+L1vlar1dzg)94jR2q8Z>#GTH|;^3|=~O0H+` zsm-n}P*_@!a`_`g(Kivn5if1Key{m6Ug<1omHr02Wb5p%83*G^=9W=OfG1^6djzZc z7gdYv_3vpbq1~VEp>~3EHRg|AfUZTPnLz1vSjQbWcyJQZu5|DY)MN4l&LKi70Iz#Y zYkNPFaWS2p7!=_*S*&`o=wlJnj$@-D0D@LMv}MshzYS5x<0y_>>8 zL9B8XHn3fhVc3Qzf%BD5E)?avL|18>J$X49#WO=4#_hB+(ZWG4K9PvkJmnHfsya`( z<-mag_a)D|6S@?H|F&sb-g5l-b# z+!-X!yOpRy8=I}*QWXFeyHSU&st&xip(WqP3lbNL4mmg;>6DsEAPRc#s}s8Hq7>th zi<5kF@NU)*cTo7=m14~6dKyQ+m1>ivJk)zvp;Fw*L+1d;2SotIlNfB%z`KShJe(S6 zI*h+DQ(4k zhnWwF?*qqv>)^E@BDMOzlJ{zc|4c<01O@K$YFP?}G}- z?O!{Bm^gLVChLPwWLBezh}QVbcNG1gSWa$deyaP6tJt6pH=l!A00-6cwl*fRapoCa z{VZVoFwJObfscBZcB0G{XfwCW$VyAsROoTNf1ta1i-5r)C`R=CPPg8gdw1LJV}25M za6Lp2T%pX@Y-fJ(8Wv`-%W_iSOYB&^b~dVboXCaj-^O|n9c?e*woHv!<>LE>R0+nG z6`nx=r(s$n!7yNrU{OvIA0I@l&(Ku+Ons7vtd<#tUw21z|b`LU7 zBd&T1TYb^+2SzwCcT9uPsZQ6}VsQVM?z9Jtl+rYB?vx3AtSX!H;ogTfvc;iXxBYC_vr~$KwzNNXKD*5b?lZ`Kst7}GhNYAR{r;5 z5Wr%{te6&5-<6KSJhj;(cA4&t$bH$1tky(i(VDcHiVUynf{KIdAU+p3seYXrTlU zwH?q}Lq+{{vcjvxcX-pPyK=9hyyhm}N%m4u9Ix~a0iTrc$K3(Oep`zK46;wmN^8Rz z`0peu1qG-Pa%ybcxoK6e+0*k&tz6`-rXQU?FQBg~@)P7r=WQz2$w)4bU(-2R@YDzg zL&^?aG zUL;?J0N{B1QVjSdP7|9#yyXc9N2R969aA9boS2!carE=+F7alqe0p{_ugFHFwHvlJ zJca*AcMI*F&aEiMcKR%^!d2Xczj_ z2YOu+$Cd*6$g{*_61O>!XiY#{aiE+*X>tXwDK_O0)j$NJzp?*L258Wb+Nf`}hzsKS z{TbHxf!_|_)Yz%HKi@3wYoaYI|EE@LB*)s**W#vg;8XS(=T{HDX1G#uDNrKUi0BUz zMTspyJhZ*ey?+;*``DG*F^!l4jLo2t>H{R3BXgDq?j00Bt0kP^01EPgYI*sg^U5+4 zT)=kt`aV2A5-Tj@I<$se)Xw$!mG?WY@y7}a+x0ff3~XeKxMf&>n*=@o=M^E!BB&8P z$-2$_eo@5w#NdwgEK~sKG6R&z9+!OaC~@tZkNoHbHZ$oFRu7v%dqc?;?}BuuO8)^&x6X>?(_XErcWJ$O6j%+ z7jA%uJRO)ys#B+(zrdDl98Y8l(qj(MD(GbWLPnN~g#{4>*F}yJQ_mmmj<5o{F5zh8 zumGm-GWNnB-Q%s_-#Slq2x-gWvPoU)Uw7XykH71QRb3>Muo6VeO&Gh0sVU9xd2sXH zc#<`b;%zwpaOE&|9`Jf39ff`O?#Z?Oim8WQP&1tW*{^OeJN=o>zuaGQfWlzPCE^8C5l;Wt`$Y+_1K)nkYHwA%cnc2P-9? zi}*~R+H;JQFi@a0c!3Uj&B#HB1%Grn33fd(Fa7nQ%#DZp=rYw~+ZB-Xf86pd){mt) zjg59<2=FCf)&G0h{4J-na~^Y6C|74EB~2d@J9M=rgN1!Lew;_3^ui4PjqS2o_D|3B zY=67FpeZ)QONJLu4aN$+!E|rdxylWQwl0oZbb<75@n)|d3LWjUm>@u`{L^s5dw1P+9MB83S{>KVHp(M~ zVXCBB8^}DS+MCSNJLDe73Y_^h=z%lMl{!qr*~LYi_pROJsaFLj-?3FZY{A$Bne$Ja zB~$t)`}O(7S4Q6F6cqdx9#!rgJA&w>ala+5q1!MxwJNZ?KvFYMRj=`ZjHk17347hf zn9=dv@^V=$)yz3x0n;L0BEJ4$gVH^%^~e9m)mMOZm2GbWih*Dv9VVh8D1t~D2ug`` zgGz&dNJ(R%4k;4SC0)|e79t>B(jrQSq%_}qbmsnNKAy+t&K(E%opbitd#$(D!2If~ z8^pzchTWl6WZjU{|LxmG{jppvWE<}M1e#8YLnH6=%L=o7r(T~e&~aVe>&57SYAaO0 zW)mjE#M?3Q`vnzjCRwNDk}r`({HiAboB!`i+7pDsuoNjT$xLfpTfhw-Hsu%vmAp&> zUHi0U>(=wveC-FXZFti3{8kMcRcV^1RDI<6#*3t?l~P{}{fq5MgSV2NE*5iLJ8Hxg zCa7ZjQynPO$yctf94q}hNZyo71?_}k7M&?Yo<}3a%d1BdkDeax%GCYqUf6kgWkoKg zv#)lL>_mnRcJ~;k#XB)(Tsj2@*e$eMYp4*8`YhnbZB!3LP*2ZwMTIStl+-!Txp@pW z!TRxhj%lnlZkzjd)^uYcA$KsZGO~Zb#l?qFm;oN|qvmaSW*S0B%xh9+r-q?J@~?h^ zJjagl4eELlH^M^(A;|69w|AO3qV#-g^%hyW=T?3`@YHxl=kyu_fiT=kA(yuA$ zTA4PTXJnRPq8sW-3;mwgL9c^S%4oWO9&Tg8moHNUrkBWx)vv(_L`{^{YOQ&N-|K>8 z>$fBF{dbPe$O}*x|NHv%kl4)&4sQyL|EzqpoAscQpNJa0>ODP7iR2c*w)BZ}M6IOo zZCrUt$eF!4bvniD9pZutU1)mgc`l33E48I(<=fb0a2T0x)?zD&vSFPc>(R13sfxXe zAa~kLxrtyba=1|VG_a}=-Q1s3R$>F*nK&!&!b>K8m({HwG9a2 zv!3`O*O~_f+|Hct?ru5cM5^f?XJbr3xQzVeS3T`BgXH6QV?I%Q-?)2HXMFc8sK`BL zaBYcR7@i~a@~};34Uo85 z_xFXFu&`{JJZOKOnMCOB!nGWk(`jGRpXpY73#xoR1@+p4!D=JQg1WG9t&QV5SYK|4 zGB?uCO4Z7azhIiIRg`z3lkwou<9fT%GiTQsQxGvBcSes|S}snWYNCA=xWd1-w(7`Z z(!2#yGGgR`<+he+)rJ_*XnwhAwox&UN$ZrxGg(EPe7hz_%G9nre~B4=p|)QQr#%Bh z_|p;FNes9WbYmbv+!5E7nd)SPa^IN`MulYJv2om< zyY)#sE?krfPKW_&*ycJ z+9lDajOHQC_F{cH1W;qh=}S$hl+ZVj8D|3IU|y*$3eCY53JPu`){l2ieHEc)W{rtG zobL#|U{ne8-^2ac%|3B)WBqxU&k~guo_Xdl7A%jEqnWX-^!@`?2k1^BB;cPfe@UQ7 zRmGlEoRFaC)5(mBI9oFjF{h=u?0|bg#2|r zt64~UiD;7r&sd0q9^FW26>zE^Cn^o3okQBP8Merecpc|9MUD7{%!T$BEOEA5wIJ}- zcE0HlVf~(%>=vA2Qg`mqmFD%~f6*@@o6?^*Z+S&<^p<2;7-gq+==|t=?a>#{hYuej znd~98=p~DeKCjLs`jlNt_uorI?iiNHP<0fuM|AVloj?u=omWw_A0KT?FqgYz%zjb! zshRF@RTRK7mM}s4-BN1{8xBkP`*yJ*osxi1xt<@1z0{tyQ0ThOQ@!!UGs5}M;a=K? z;PZG*??dBJ%{-OcL#xKZ23oVkwsjRbGh$10hrIp!8A4bK*pZm9iBWEZ+xK&GFg28z zFBi*fcV;qmsPV={T&^7SWzbEw=iWAc{;GnnfVpY!q`OGzN1>}r1AIKUMMM=+?!7t* z>CDt?8pdr8A8$~va5->5R5k7w+5h%Zu(Cues4oqqut!KbqTUSrzB-%RrDoAr9n$ByEe4d*qB*A6|Pp>Yd{TO7#e=`U@PKO-o3p$JpC`a(;c z%Nf;Guk;!{J#z84``XaV%qzOr#e?|6*wb^?eu<|xOxQyTu;&A1cR|Q_T+f)j18{-E zjvfXA@gA=#vYZXE*eV}}srv+obo`3rr*5V2c7!WNTMu8Fo2?;eC zkT*i52!S!`-3zbGu3XtdNaMnU9cjR=JknuTA(!Dr8&k?h`cgsq%)M8Nt` zgG*UBMy6Hr&w4!*trZG>Wc$?sYEz<7{KS|le^}(a`b+Q54$??`+oo;{+}+9&ml^ST zPQL)oPfxwbzx9`|u9t!Y^ZcXx`-eR__~h}{KoDKRB~LZK+byu=EmAT zP&zhzUTkZJ+Cx!MQ7Q^LsvUeQmXcQyan{_ztF&Bw&6<4fvRK@>z!P?`X#;>zk!^C#mNqM>#_+_Tb~-r)Q$| z+bJmggy%7x6q#fVz}X3f0~f8fCW{}7awAFj(Cko=u1?y2Z57bovltbHo=c$-DRx6Dg1bCQ8+>4mR1lLPk4wCwRXM< zgSg`_^yg-a_xJ_#as!D;s0}-1l62{sIO%-9uqqt=$iQ+s1LkYz%d^!e3Qi`=kO9UW_nXsx|@hJdN=r zrqlKeY|EV_B&afWZR{Db8uZ@b@e!eD+w(tM|e1->uWI$^t&x!u={zD zWn~3{{szQQOYiYc(+gL5Nb{QuN`~%!8w~o!G<*XS(eKaWgqCsX;#5fw+n2bA zzKx(r^t_n)%&n^!hmlWnfAbDjlMa-&?s0MY$@3DI{9FF>Vz84FFNUVPf}i$;s+NSP znqNd#))F#x?6VC*Y_Y2stLJ}wulH8qs9cibmux$(k83O0-zOhCuM5w!p50eeY$YvC zxwe3;n@HQOvxk0E2kgnQn`l31>g{Qcb97seD@+(WoHtVv(-IHoV>sMV7~|n!*&=4L z{lz9CzbeY?N^1pBg?9q&me!r#%&%`x#q^v?0eJB(PKruHkAa{%++BW!UpV|D13KB$ zmE3XY)AnE!;CnyvxfSz?m!%N|Pt_&~S2(HY9$=7LoOD`Mzl0@1kb z5p}0*aFiy-JR=8bV<(Yy2$Neqe>}wM_vg0<-}`Kw2FI#VPjNv!^X}bbfDxaw&GNs3AIv9F6>2!9UY9H@GtZRi_?6n+gW9zY2DwPbKpsw}u>Y#>n zD?{qz3Y!oXQy!dcIEDEA23r^i&fb}2AK|(6WR%a`XlVu&AnYYqCW<6~RDm7#iFY0t zQ{$PReuq%k+e1HZgh3ed^SK(#tu%Xb$qLrmbGGUqQ~r>cshg?ad4@^AiEb3NWu!&v z1?*Q4qL`7qL2nt#W_k+}c9@2vjVDj-Q{{t|9?sX;_%!*X`gq;TshzJ#Gu0~^@KO`b zVLBdbcJOkNdavG8z4)Tap;53KzvR*bHkqG5h2FKbsc>&Fz>0!>)D3#UEiS!qbW1Ns z%slRUFZaGlp~)L!-6Go)m`1!2O}zN4aU6^UA@mzW?XSXknn&}MStBNZk9QI<{}5t~ z_7cE6aMLYI#HNN9fXHY@>)t#I-lUH!?Yy-a+7s%H+*mm*;R1FaLu^KGFMQhdHuF1H zm%}f8bH+2bcCzHN3SWf4@D#>?-JUB8R6o{G5-~VBH3iv9Ymh&=1HYEh35t8Awma z772eZY#IrR4l?C z-^kMk>prGpbVp;_hpd6t*>HZVP2jZdBY%VttV8gI_`%~HrX6M) z`7|5j_w0Jc^B)PMAF#>;jTOpCMLB8g+ZEeRA;R5XLMincX-^Q>wyLHh_6Ue12n)bN z->`QGJn;VOP_=E)ZU`$-dA@_PU9$kZ5v$Nnat{I&hZBf8K%{Mc=1b;KcXq;9!Rc)< zpY4?j{F)EJ82!o64>+{(1QE@=620|}^f#lA*HbX`%4CfdvOTcnl`Ny6_mKCw4=3;a zH54#!@k<~~!Jwdy*EdARItvthNx2Uq|Mnez4q*h)EOTMTO2sE=1;3BDqabFzP&q9&n81z6&}L{QExOW567dO7HBr@gQbTXejZ{=FE*{|Fz8FO9jF@n@9zBwSmjHZBK4H?V>2W>_oM`T zQ*5)uxFj2os*To@3B5u>jDZ&e;U&e`C&JKRf|)s8Lk)yS$z|~eEy?-2cVAy;MYnID zp@S7qj4Y9H#HO~%3sz_Tbgh!VXtcGj4P7}Lj#)qO9B--E&dfb(c1k%8d;ZjCdQWCv z3MFA7J$-A0rk%lzNjJdE2Q0Mv$ws+D;4kiLj2l(WyR{eMybLQrtRToy2)>>0C|-D* z1&13_KHp*!A@XWVGN!>Ms-Z=y`NjAR3DLjid32FEo4!PzNkxE>0DZ}N@E|s z-boY0wLz=!3fI1q*HTE6QK;WwNlukw^de_6;J zq#{gI#J>XVV2|*B~4HSta%l zyZVk^OLAM-m}Z!+?Dis{rHso=ltqw{@k7Ot37x-S?}&@I8zptcx2L{CeLbvlA^{G@ z8>q2E=7aky8lqgBr|6`rKSU}D-2O_^k!P0jyKqvPEs1P!kzOx3_u&5h+w&{-m@~o< zdGKJL|8d%51x2w2;R4WbQVaDs_=pD5xIOye>Z2klU)cM6b5^{+n0oY^!7r*^MRq&D zkBTB43Xz4WTYsJ)$b7{lGMGT=w>^(Cb$Po-f=$#s-;+17`F!!WvWhd9A_^MxN6 zk|PP4gfYsbEuD&%cDO9p{Vz|?4`|U~_I9hU$4n$iB1sE%97dXFNeo;OI{RUCt)$sm z|4QD}%OlC98y=BH%3>$KjQ}I!4B+8WyxYa8w)=-&YTA@|UpljXGWJcKqcXx#Q_4_D!Y#DF+I!n;pNaD2sWZ98O`A~l zQ~-V;C4pe0JlS#PVWt7ipkKcG|~rkr0G(DCxWucHr7?1iTI8u{EES_5^F8Cz*ij1IU*bQgu{ zvw+)q@*j~Sab|IQ5>oE8?amdRlo7msPqNZcz!6M)h%L%Ws$+|0so;#1X4av{K=gRs zn3ap1^v)qe^MP6p88r=*hQtg?W7%+?;WFta7zYlpoccfdXvm}Dwi1pfxX}LjqtC)^Xz$}(Qg*scsiPp;4?Vq?`@I^ z{r0IL7NBx{(Ks%IxM5IBUTF#vv@=I?ennSxv+C>H`wza^#4O<p+|**+V`A}NOO_~E&P#$MC|&F zDe~_xZjv0p{e8CS-=>KnkGBL{^B_}yfGVyz;6}5r-z@Q4*of3PHZR6liJ5^VpA$|# zqQK~9%a_PFY5zV=i2uPY+Z7xkUlDyk!2O@MfxZ96zcFouZqXc$X_l8dwCA_2w1rc` z!g%Y@v1O>2|G@tK;{Pc;)EIE@N~P~qHzve8mDKvpLeB0s!SVare}9AVe+(%8`ot>z zT&Zm6F8B1Rsp)X||2#W!yZ#Ld$psRi5I0|(x9DYQPf~hu-J8G7B)>05_`e^4czo=< zaRWaZLG`I0yRHbJ`kx0J!}G@=_xEk6k|!RLu^7RuoBh~Z^5?(SyZLXqR1C*G6kqNm&#bT4Mbp)NY#ICNH7hto`bAUNU$D1WuLCu$oTkCusLjJmoB*@_XHsu zuB7|+lfo*|%ZnA({wE&%Z_uCnF!8I@6;dAEOU#3dMl#@KetuAoF%6dlm-CKYyDC4V zKE5;%B&5oNgq@|-N3a-q|JyL+KTO;^Zn8M9biY}=1j+)XfgV15eb_a!=nRApac8`A zy9K-5&7ZqLy8ZK2rAR!NJD*NSM20lZNix%m$Lbyuup#&4en7jca#rl4b@0B?zM#AL z#Qhxp?<3_QzLox|e8mlM?)Qo5@>Rqefhnr>wDjMvUh?1i-^(K>E>B$7@6U@v+>=ZH z-^1@CmMCRFi2Tf*_7Qdo);$ML6~x8OUi}}-+_>f6?u6KQYy0d07Y@xFc68QW z9X=t$-lr+8L}(zFS)P0mb?rLz&;y|y51N=*PjJW!iIgJvzG|#J`r5G@#)gkOMMR8W z%O5zv&HJC1(fvJM#wtp}4RFPp8!o$N5>Oy))pc1@Yl;xC=SIKXWGQw@?Kyf-jQ!n6 z0>E+M#`jNzUuRd`f3`4oQR1l3r^%Bvpo{aYhPT|eyixNU{bAE1&h`d1!4FVBZ6J{h z;CNaJJ`0CUR{GZdk8jcZlH8tHu^;=AdpukP5AEZB=vsZcKd;owoZ?J>$ze2W`@J_1 zzRd&Aw{G3~cG82^v?JDKWmjM!+04;uVmw#W%i^*!R|l?P52BY|tGu6eL^gC&fMkF- z;mFe+UeLp$(gIot@z5hetOtOF@CJZ(1P4oo+;fae+)c43jEV@RMNI?Uwg<>hh-?lZ zVIfgH_ZZ?&E$(YfM?$Yf%x}X<`e8B5q&66eptg z82BM29j{=wk9;d}@-dyWzS5dk0Su;#d>hZW% zaSRK5Xi>Vj2?Ss{yl+S*V0YY30$nbhpe+Zo^iu4KkmN>;qa;$STQhWgpnzlK!5;YM zOaB(J=B#`}2lw%o7v2hRAQRW!yYu0(5djx5G5Ru+1HuFhl_Rl7t+Ui=PVzTQKbCpP z*bGq$2#?=Gg80?z*VosEi(_1q6ra+Po;32$dUX#8xm)SxkT(JA9rPv-tYOjGMgQ(V z3GMky(@x9d`NTApOK)SK01!o;+J|A(Ko6d9J8vQ4*5t$S2fRyJ1f5Btro z`+L8(U6O3PTwz4+X;8;mvY*({^@^N+P(%p3rW@Ot^olU6#BSIiuJEyly$Ol0;-SiE zJmdITeFuB1cka?Z_W99O|E<#D0!sDikkCP}y8)8OhCC?pUm%+hNP`E|3I}mrBs)QW zz_fG&xpD%7$hV@AnyV#>#NS`^v?v%p zb;&E3XmdJ~#-2K*&Wsc1<408DZfR-5G~)iX5CD@Sb&%+ykupIf*9qjAdjT^UVgf-+ z+6(RU5S{=yvrJ3NPs2l702?Z1sPBbW)A;VTm*kr__pg+D+@0^*k(oJ#43!;Kg#ltz zbqueXlk0;5iG+*cs=Y*_Jk=Y1zdETw69!Cq`{aG6?S&~sK zv2S^@Y#HN2@z?0%m~WTJ$uEeN-`j9WZ_AcXfnMj^9cd(^1s7N4o|H6o(VI0cx@ghT zhCN>v8Pq#-IMPY>IhzTxp91T8oNSh6jZZAj$TEvKC=POIUIT*B0)kr0vV3ordfHk6 znaGQ&xi(7RieQcuk>OePnHYecrdc2lk7^U(>b-ke z(s456nl_1}_xwDykd&09j%9=FkXTHiK8kP0LDdqVqCFf`;pIP7ygZ$faY*9n)2HA* z11E}Su9kUHk!%qni#;!r4^gdIdscZp9}?GsZZv!*E(>brVeoslv#SU{ioe(3?@wKV z93=NrzMi`WrBr#c5mjai)NJXS2iGBeMRw=DN3^pDXfD+1MC6xA;!br${>r>K`F57J z6}yTN(r`@Lv*P6C~w3gn!>vC&kJ63XQZ*;Yo}R343F0}GobxK7g7`L zdYJa^-I}v-!ANpS4z?(X#*kdox!LSGlZLpwY^X6u%1`Nbd7Bwv=W zG+3lu%7QHt&XlWlLNlIA`lo%1FuYk95oMUI7~$vVr^%vFa7Vw}rmfpyWlHWZ45MQn z&8`z^0{^L{J-~Tg4Iw)jc4;~7x0Yb><~8p+%M52$^$!{kF_=jj87+#V!OPv{jh|W2 z`TQdKm&nRB6uGCJ(@eia-4hpHdp%Lyzx};=WX~08>1L0N;uwiYmt>#}dIds=`?Kq@ zPtbOrQ-Zm%b#T;It&LNQ68FY%4;{H1*~1gV_nge}p19jWB+?9!H>0-XN1z7fI4XiB zU4(rlfL{^lATqL?`@`F}aTQBDz8%(VnzMuOG}ozl;v{3|C!L~ugQH9puOGQ`bsOka~2%#(y;m{@DF{gWNJQpEk! zdhc!w63kp@G;e*z2QOmuRjr~CtZD5!VpbimMU!~{M;|+STp0@=&PioB`lyP$4T#gX zIq`<*Wk+P7O3KRCHM}5k>k_?A{b?|)w_Yhty=BxYMJdI=C{oz5b@mJKG3!|btP@o< z6p0BG$;joF(gI zM0Dhu!ThdKxT1NhbAG%q>++89vzG5%Ro;9E1A%5{*A@NY!zBrMu)`xQX(@ST9mx)J z3~JtB_r0;D%8}}{U1oKDxsJ`{U=(W4Xm=`xM6=K{K)&Sz`;W*5$K>}qx20s3Mer+# zUiQ3(%_aIA4hz_%l`%R}DPEfX@;Y+UY_Q}VC|8!=M_%o#K9ixVu(+VQ!xQjn%8Nz!(LNZ8SBes>sC34R!?BCCLNLdpe;Q<3GL9(|M`-$qifKoYU50?|c=DX9Yh*g4~mYSA!&~kfGclv%&_o2Bqox0uE@Dos(-b%t{>m5C0 z4I8PJqZ!xgT9L&CY1b<9o_r>mUH`FkK`k`OZQdvntRti7robz3jOy(yC>=__^%v6?y1*iX#TG zDWA!KEpmKLC|tm%YFfNg8k{&~=P`72qIeCb9m0RFE|O1z55-8Sl?{}{v-SGA%oxY0 zKa)}TnRVum&hhp7A8JWcxZLZqnu|&`7Oj#gUKat}`ZE?isRlBk2K;>3J2x!GwxKy(w;FU@Ih$(J1atM@D{D0+Wb_r|R67p?4b_)Iq_oZTuCJ-cf1GdW zb)E65h3UnNkA|NB zhTw4NfEWqQTLxZdR1f-i8qZ&PhEu|tW_3=dDYaGqnB+kT83w-jrLL!}vOJ3MCsgvn z*h+szdou~7hYS8PZb{C?-V*@pNjg&N%0GS_iS-freb}6g=I_?cLW?Tj@ZQS@$!U6Num>=0=wZB9YHiR8fy~s8V zGV~ZY9Y;kHDppbYB+FdAaS2lxjTx*5!$E7g#d4iJt15eLH3v$}L^NflK#GY>8QdUV z%zt^mh=Z@md56%~slu}LwdD{I=fdd8s@m{er>UFa&;X7qr#I($G1^T3yx}Y~B^tn~ z)nTcLmvN%d^c5DJpMDoMV^e}tL)dU&-K(;NZ`&&LYh6oMrlovLSrCP|h9FsqMs%L( z@T?7Efuc4G|GUsM#k{v;5yMiffLa)MtE^70pd=_<3)Dak;?c`G2zQ@tQPCL&pNbbf zh%ob{F`i+cSg>@S`4N*3j z3UvtEKJhTkOBW3!=%X8OqdNL+ZYLx)%~)WS@-yrp@patdNw%noGl`NQI~+@LVVp~$ z8pls45SqZJ7O)+A5z9p>7wh~Lht4p!rDhUSEj_@|csps3)_tKxfZ zCk?qT?HzgkX4+uxbDPwTd8(($`&M4II(l?Xi`v%%!kV3^&`qhED|RHF?kp#gq= zF+C*?#^XA!!vl;KpYJ&4o3u!78>m&9F{oj3CUQ$?PaC{uUT&yhQNUcp*lvIkX*vb+ z8_WyJcizrX$Ku)b>oFWociP!0kLc{Xp@UBF(4X&LWb*v~uWPQ%{o{LnB0@8>z zth$q0ep3$jnin&U!JNzDHGSS%ih62F}2_`9om_v3UIarqd|J*u_NKd$_|U2D)eZF`126NU@jMQt zTkqe$=Y_p1ZFQ8(W~}~g!}_R2*>FXq>zQ!f0lVJee28#TK_?YBtSt`i-LpscY#vOw zOYk<$jb+zK`hj2?v|Wurq)cyp&udFv?~fZuzDHcIdrb04N-0@U4!ddY&2kC}d7_$k z{-p(L=em`nHu3*lmd!*XX96dJ%>nze%tr`r%f zAye_E&^W(#k?5BUm2dD!U03wGD5~Yp65t;)GN@#K^n?s*?I?vWW`4KK8;g{SsE2M_ z6pGzZi8}F#t{LAne5@F zIfwYPvQ=Wp-BMqu1vC`=O}eSdDIa|pGkOQti^AuN?X3>WZ23}%ZU?@_rK(q_BeOAs z$+)YUYcymu!)~@FoKJS$d1!x71uF*Tom*Rojb(=Sd=e9Ru8}vYUAyKRe>FTA`vYCF z-KMG@Y0~_ts3?xU3wE~UYelAgN?L`<7gjfEM|MWt`&A)H6ahR4TYwn$1&h@nvz<}b z!c+%FH~4-3^34h3TUhdgU4I0q%pw*;Fk&;RgqrDspZX}=9R?rlpmfeCUCF|bpnhBL zT?fUDP{l0`#riNgTa?atn-}+O3aXF|JKOMTS)Yi4s5}z+>01u3vjN(KdQbY^Wb{Jb z$3kHLOa+LQbmM)YdE1~Y@Yvgd$;q|p#nX~hbSKaEI?Z^!^h_Ir4=%COyr|~K)Nz$G z?v4Bz!`&LJ&Oh&Qn6vEhQ_Rwna9*ElOKyAl6q7x;BphbO^KG72j*Ikl+fj|HeDqd= z5x={33Z1tpa%Hivmv;6GS#D<>knQu>&@7?j-HtQB875<)CANteKIVo{F zIdWt}6+CioebHyXbUPAX!PVFOm_nWqBxcHKBTY+C)FeRNcUWslHXS|vIHm*Gj2bu} zjBF|h^RZ*u@n`c~+(4dqRK{id9ZFLz;EtN<7QFcoq2v=&uQ$yxCK@*x zbQJUJn*RLqMN9I^m1|SqdNvz5Pt7*Trd)cuTi&6tvp;>JT>%@GJbYz`j7vhpmrHS? zy;q*K>$M50u3HL2?`n*~sBm?@vqZz`3|TWJo+lB>V*8gM_R7rjWfTs1qJC3fSwE_CotJHSZ+)r19fnStfH;O6`@Q(MCs=pnzul{1UGGMkZ!+*X zgIQN5c>3u_AJ>``-T_6-(GmAy8E?tV?{P>uc=DJ8Kuf)Y)H^wiZuF#j+H2c|J%IS8N!T`eE689EF_KUPF)KIR8^TCU+h zPs_mTYQ6F~?q{55a(wBXwN1}vUIg(64g9i6|J=Fzb?D|l3&Gyw6}wyUzR+HRh;IpT|Fb;^-D z8dz{^k(>GK-8UAd)t_%>4h4o<%#VCwyQ)zOjb2xZZ~CG4t;1(RWgbf>i*W%96kV?E zwD=`pq=9(o?z{b7?xk^8efCH!K@m(D*{+)g8LNXybn zG)|Obm|(6_A+VXFhRp9wXw5aP9Iej04DQA-6+n8jT1YNfS28iY&Ndv$TuPIY6lT{q5CxDIq z;+}NTQTt|`?&4UF4iDEE3ahhZQK(uN&@OD^V|EU&4zD7nRkjekpGf+fB8#mFUP<_6Z26Q#p5Kb+%)?6YosXWX_#A6SIzDwIf#}6rG%k zb?pRCqnJ=c!3g5#4o}%}VCN=1slja(LC0xzjW!<>Qo>>5=@$BUBqpfb|G1$MddaJ& z8XDBRHBjC5_oA#a>5TVkGX)EL4b@prmsnzr4yQ`NXQ2cx2kX)3qmlZGZ-vk#ILwX5 zseCL=9knQy*ndO0EG-)lbN6qKUdG8p z-!b9x3nw$zM)7-OFA+ARj*m#h=WpG^rngnc08fZlcTMWc@fHYZA;y|~?qrB3!> z7iFc@usqccjJTF6R@_O z*>|r2eR#FWoXC|S&DldUG(&6Onbc=KgxU}r-my!-IGYCB){(-siRa|VXLGyN4%30m z%PdW8r_1hal*I`W`_^u|G6EEB=2}WxF#E-3qDxLDglB4@Jz4Na7+K-O+07Go?xeT( zn;|6K-8Ne~K%%4pN4n_pn|rANYT2LrMC;Z4-o1OLSmv?;lflIN{KLXh(dwi?_b%e~ zoVipeve?;M@Uh?#mz7L5{F(Hq{tkDM+S2?)r=gLcO6uIpBp)Ag!%~sWq$G=*@5x1x zEaJ$W1!g<~bta3CF#4m3vUL~XUtLxVm;pLbx@_L08(tP39KN1tw-(pX!lfNSyCpj{3^Y;)6>TX}^=J}LD(!0}m{ZXroI@f$8d-Xk zx6(fe){;udwit$^vj(R&mAiKO`*u;@TH=s}EU5v`g@eSzHh-{`@yLB2{m5uB%kK%w z;>eM~5aFJ0+}-(L!?ab-m83%a7T?dm^zB<$#Pc+JKm&(QGCb*A!5P!e()5|1cCTJ| zWPYuZq43n)UBlYQCPPD71rl8DNeXHbp!=979QcD((#lXh0Yv4ECx`h33gQqz3V*r4@0T@qzt4SsCVr*xM0Kw zET2FOvmT0#wkE}<6k5xz7TPEQ78av99*+?#qU23e7A0}Lv>czN3a7XR>v~t@G(YyD zG1^N_eJHesO+p~jOKZ#W>_}``+pYSPe(e^%UYGGZN8ZDiwhGvI2@{x!s?&=_Sbc}c z!u7nAp@H1bZ4La^qf~=Czaj>tyS8tH$%6X$fPKXMZ>g2abNrTzmXX0T;}fH+p-pZH zGb`;|LpG31Zz7i7>&en(${P(h9x*h)Mg9@RUdjr9-*PAf70O&zXOY)7+Nxn;<5V=^ z#n*$W0$w~At;W%R8H{j8smnpxswJuegQseifPXttI6It{we50UUu8IX-A#57hPM&o z;a9KxyKe;AOpGFTV_mO-f>a5;tJ?&ss4gb2iq(N!@S-pVL`0aMB|Klh&oTJRoo8zJ zz^%Cyi4+`$r(uwjoDQn{p_#?n$;sH*SgqQ=2__58;vqbWm=_949VicyizW+?$L?YZ z%iUN=tHY2)fRG}CZw6tfaxU!7vO1@4`@vYH8QaMZBO#LW6Z=n6e7AxUycN%9#0ZlO zjlgGN=vG+gOnTXxgY(a~n+dQrb`sTjvsr$3p#JDa*W#ykA{9!$7_W8_W5|D2w*uaC z>WF!VQxp@E#9^9uq2KoVp+vC*vZtm5!kfh6ICe_3m$ywb785{J@fKCf(@zk9PL9zt z;tfjEE)n1h8sY1qd0-_{+jij2jT`9?+$GYFc@E^C7=G{|j)9j<@N(fHzI$@yopI-B zC#2?1Uhq9+O0psL(>Jt^yg7z7VMzeE`dSLmzHa^C_g4;*me9Gd&&l7e;omag1;f~a zqncWCqIUN#y4?0#KufOViJE{~EL5!LDMh_ z2Q%D&u`8Cmca)O+4m01A1CoKaCSdx;@jHWDzW#Tn3e1z_<0!|+ZdFF;vm~6_<_Dc7 zLkC>!*Xme=xf%BFSL-#>n-O-KF&qQdIDPbFNci&6(}ROfUgygqNk|rCu4!|TxH;mT zNsnIrbkOH6rHA$z40y$PR!5}6d^kLR{ipj3G$GA}2FbF(>oy8~>k4MOAxyJwg66@>svtsNSE~Cw zcgD$)m?n;sA%O#B_ zk(C7j5$SMY(JePNa<45+xf`{UP%J9xFs3ox(c9H!N?I{mzdQvZd1+ehNqPpa42 ziD;5;^zFvaWd{YzHs5Bc`@tkqYH{W2)z;eZb>*V%+qNm7D0gN!crIy}I?S`XL~!3s zGY;VTo-CUb*+Glxsm!lqtO*o9fbCT`-2Izhr~oX2tS7x8RQ-`{gPY08hdWF&cxMSY zMYSbbGrk;Po?qV|i$g&{mzTMNiVAc@t|m(;(TrKtN8OVh{L}5fIk&}wjJyKJr0&AG zF0Qf_c?9lEFReJK{5XD0@|c!DhDzT~gX!HtW6AFl+gmHao<0l{aaK1DW|^5gz4zRd z9$3gya{9hp?0)ne1Y1QZ=teR%rc6)jIxL?gcTfNaJA`ZuEH1ZboH4U*2f1@=w zzrhzl4STHbBH1uS!m>@nw{ns2$rZKSnY(`0j}*Q-f?E}NWEym0xk;{D*-t(1mj2SR z=r!L{-~3obi^n_ilrp7t%+)gQ#PvD9D9bVH?x@$E9*h(T$4o#!rkb+$qfs5OWd13k zQI|P!aB|jWioMb24KF?V{prk9y314B?OG62XdD&sFYTR}m8k`sbo|Trb0uMeFb#yZ z&Ablrc*Fju7MlP8L(OzEXaV$Xv*OSx?W#9#h3rJ>%==7h{PKD z4oI?`SkhkJzOD4>^DU{RLpYymE~Z!b3|?0{|5hGk(fdKI<0={R$KK@K=ohcMCs!og zFRRWFEyt>5Rl}PsANN;m3I0On?jZB8BM>;0-h9O7yp*)uujwQb%nWQp!ArU`l1nS^ zGgp6z<@P57MSpc_520X1>|sc3iCwQq$@<&P+Tnr@vqqx(W`K%o(adD3auBCLG;s=8 zFBarvBUsH8tv8i!xAU*tP5n}WN_4&8k1F`5-#zycHZVH3-Y6w9Sv)Ke>rT}oqEOxj z#B;R!SMM)#XIYWp*aCP>lg8Iq`i(I9TS0k;&UaFh@2td1Oofb2Z3!Uzw2i|U*b3ZDFgVSYG7C0&MJ}$ zPLsa_VQAOz2xo4KJyLjK{78;A{Hn&XfYYz=b()Ret#EwpyhBt5JxO%-kIc%kSB2M6-^0GrbJ5L2dg5xAsO zIzL#f8y2ywOg{Lldwex;8b;-YZ_=Il#G-*^YuY$%@m`Bbi!1BhH}$^=*#aVx%9f3OUuax1jDo-Fn6NjvH)T_MG`IGZc@$!YHaIf)-`n^=rM5iabq-XvA15%2k|^jiGzk z5@jm92~vlH#$&`$L;8b9UBPt>={z|%*3;dP*E#MmTY03VScb7=$#p$}7~@QU;61ME z&T|vp8Y;hrW6?PzV}4el?$589YW-h3%}?jJt}Gh*3?4d?U^JcZyg5gI&)itID67-L zy*%^oZ&_pmKuqRPmnI=f%)NRNRX^D>%dfH>!g^bbp#>ccF->oP^dbc&Mh5ThY(pQU z>m&huVH7!DYV-Ac_t#nbI|jg@8%8tA%!ii0KbLJTv9n0i%&n?-MZC4l;;m!^My3&( zh$Yx8((HOHb%^F&&D5@bT-5mc}(rP&~dR`5rnW6q=Z#o1sTbAk>2^dO}?WJvqRBb zr3>#G2)zcuJ=o{+5@~a@*sAsE>jFT9r2yAPu%PcDV?@mn9TCw~=35nmkaFkC&hNV8 zfdIt5`7lD^^ma3=bxwsBV**H&qe4PmvteMKMsdZKIk2Abpxnuy`ST+GIf0uP65NP1 zVrCF^lV!X%BZ?=~vMz1j&O{LDV3ZXBe-cj`r?Wh$3oFM;`vVDLQ}1eyc@}o~^;Bqm zaC>Jmq-8h!UgCKUHbx2hw;#~+Xzb~61`OLQM|A5@wvBh^*X`_B?oE^vZ~}!k))lNG zwc~YhZGp>ji^_<74X=8>OG&K7OyG%*VttS5eh}3n%is5yb?4R8Pu3U)w>M;pZf=1H z%8}DdZ0)`5x#6t|<7G8pZk<^zSdk_ENXX;0M&mm6#bga}&sfsu1NZ5m4xVe2;#!HtF>rJ4iK5W$+*0kAj)D9w$t2*Iq@-kHkMpwsix);``3Ng)e9g7PJ9JVpG^@dNZH84Q zn7h1z5Bv-c%;VLWC^GHro$p9NA~&$I5Sv~yC4TwjJm?RH!En3TTEWRgH0jCk-o?bm z`1|@sowl@8BP;HCAz+^+0Pz~gd?`P)r?U`O4Pjj=Hi&6WIpbk}sbT`9J1 zZIJDCPAIe)p<6OL6N)v3AE|QO_LsS+>TD)>dM?K)e(F2%sL9k%+NDn{)wv3>K$)(# z3du6V?dlT%>rZM9B)yTo+GSTK?CqL?4J5^ESW5x|t%>eTFyUUX)Wzb~8!i@SK_;_= zetIu6b9gN8Ai=>KFS5EOD#eHIgS@B<&RGI}59+HjO)n5f$7lP{q#NgY$QiSc2&ZWY za&r1uc4QzoFTq!zH{O~3Pz*^7QT$defagm}3OOyxR`b$pbGjW}S_xisd6et@{A>_3 z$X7vYHYK;D6KBgw34J28lk^vpb78DHKAW>LbZcAu4!u7A9vEEA!&`k$O9mE zXKcH&q+iQ~yW83Tpk+CmcRR_x$(?lM(*@X74BOd^&|wr3YClYPConipL3BYqPBStv zMv7k!D@|I#D^g{W8&V6N;3PC}UmCnUJeoixBtfysIDj6`6Kp`*`q|YO7?ZEG%-m%3 z1yv5ru(tkJ!(~=u$VgGy21UCf+Np55>Nu)(^~*X?8fiOCiTV7!6YVo3dVx?YH#Te)9Rtu23jVAA+Hli&&w znSfCJM8It!fHiCm7`O3yiD%h zx4VU>zU(n+$qGkmHSU<%oLe73TJl~H7mtwE-0GX|rsf)84P zqQ{w{TAhQY1X)h%7{*Ir03d&YSu_Bo2+w>r0w^g3>~!A28(9kkr%fF0#CD%+)Nm05 z^_g2rk&*t#Rj!uRM5M)SqfOQ+bMdZ7r}rp_7FT^}7$^cftUTQwzs!g!mH6k`<~_16 z+#T^&^B|uC2O5ExR<_zadnwDEmH=TlM4G0*4}U>pj4+Z2!3NyP-i+Pbrnr zQpjjf*&-DhvbRdgCVSIXgfSwh+vh! zQ;4l;6bL}1%fh@?=>|4%{fjBO1r{o8tohJyZ=26e!wRD2 zqVIMQAHFXx^DNFRir@?_Q3A{XQkb3{DNWqCD{ZRNZw!B&(bYuwMj1*ECxN|(4=dsF zLqq#*f3S#h>qd)obFxbbSX5i|KcPNwSeN^jcOW;DXwP)kvxLL^UG95aR8LR1b3E_( zrdCyv=PS@2Ssk50*QeM54kGwgD(v+_1V+qonUznAliBV5{d82WoXTGt1k5};( z=3$z(Df`%5w}@qiRVqwuP`MGd&QN4Fzw*)}?v=qmtfPVzW@)MAy!YPU9iGOK=?6CB zmswpNaK-7>l)N?!C_R{a@_=9Sr6D_(NlO&T1EXo?)G?~DTU;D7 z2E`>B8&BW4d+TdOvGy_v@rF|U@uuQNH6~@Y$4R_BU*rBY7O*rk(qTa{IudbiTl20A zhurP~X+PWV5c77{o63CoHa!D{$ou>BGd2&Nf40oY<;I~6iV*$Mz(xV*-Z1VxdpLIQ zRv|qliF^&2wxAwM#y$?1OcZiAD+R{+w5}c7b#6q<-h=t5nHY-LuOM;gSydIoTeMTwn zUALbGpwqhh8&^Je)n$6g!ap>z{HJGsHV#y zpCFnaqKqfI+t+ZnzMt`Q@#pcpD+Zi+z?d20EMn|CkT!C*qRq)}%3@@{InTCu7H;j* zrQPPq%C-F-c_$mchSU2`(dvau$DI?o_I~t0G9R}`Gu@KQZe8&ulza;WQkJ1wgEGp- z0Ix&XNDxEsgV0IH4ZPRDu+{<0s1KCH;+_-ws z`xjoLctZA}K!j(+Y!rAm69y1bp|x8@?|->#NyREKtg>K!>v=zR7*dA;vipl>72rP@G`n@}*gPP{cnd?oyYY*{ZZ3 z#Es(Z^NG@iRIIC3EkA{2ISzpz@jlm$Ak=-y+e6pKn*g?T5p{7 zKN_MR!h8=(O95#vU~|U-6<$4C?wt#JEmiSa0LD-6(WMt%%L- z*?f=@21NwoJWRd9vIT6184ZmbqJ^;mF(1yPgq^c~y0G7&G0V2xg@!|qy7~jPD-Fw8 z-^ z==qBq*~D(3M!)cuLX;PT5W>=&3@-zzkEEoeIJC0TAZ`oAy^cb4#czLe6BAP`SR7K9 zA*&=NNw;uQ06;QSYQ$=R$FC9=l3Wc^+(ltgC5H$Sn~f|qHgfmA)|Mk@H}g2X3%7_kONunRteq4w>-7v&)REW`PnI2gh`94g zFMpa$Ao5N~JzK*u@*i&ci*J7Tc!~gmoG3*@w zHs~^W?88Y91vxpd(0GTMID^iJ7l#7TaIZTn-_bC+qV;4658fMD%Iq)2si^MW=>>^dmjy3w(euz)_0+8;4?H}o_p&%WiRsIBD%;*D zq9=RegF*4+vbXV2w#0=^PG)H#pz9n2jK8i{Y&~Iwvv4A`9PK`TG81bs^>D}yT~JN5 z{Q!F>jg6_EHcB3@EFkl(-b*tcO8d(C6w?}%yx9UNIO9yu_r)thgh`1f zH;w;Y&M(H9LXkaAP`Xsmzgz1-r%d!XcC{fw-8}2%`~1d|yaM*KReTcSMRaG+jFsM? zY+w1sn>}_uwm+A}V#>|y^ig?YRn>qeo^>JMFEHOmED#~A1P*5Ne5cK59 zWxdV&l!|!zzHr%Pvu0cJ@AvI7x1m2#@pU$pjgtS8RDpZfGJVaO8c8;qGB>VEkaU>n zCoZL@C`+-8E!v@Amx{{(KGavQY^;`A(x(e#`>o9K6TemyO7Opgo1w)NJeY*$W&;&d zCF*59?DBi^48M4qZ{@Vw%y359daM6iHrJ)WP^6LBPQDkc)v%o(l#zLCl+vKdcz=1O z@I=n!5{lS)K)b)Ej_fTQsP20h#%C)XJGS7wF$s17@S~smMrvZ!uj;|H+zg2c?bM6+ zkrwA`UNA85<=QR&YP$PxRGC8Axc-*p^%tyIp-^xh93}LmR)8O9G}MG!rZcSjd*j3D zIWAu8^w9;dEOqMNsdrIP^Q!Ay#S70;wvl^x{O?qzU@DjM;s_w&0K=ekiQM?X#RV9p zq=z;3#VVA9x$*J)SJ7F>U##TcueNcYyS>;vEx9Ojy6fi`FOEWCYsV8TSp%ObS-4I* zpt9V`ZypABR1ZHXCcqG_al)dW3&3OjYpWIF)~R6=V?s9SU-z=ktYaA4nNLGmwI(`s zDaG~0jlZAt68WTDSi-QkK4g`rHivhs7fl7=v%Pwh18E2;Yg{11NS(5+ceg#GwMb@g+jZG{Cfb%wvP-c~)?@9289r$d(si_dBZ( z&V6CID0}rvZTxH5OgaA#A?E8DtduYEiioV-ClPY;=l&UUR?cYm3kIE;1tz84iE0*C zohf3ir~#hz&}dLvOcfY@6(kf_@jI{CD9X(C-8+oylB9?>OuRuM;}wvVCc7>s{9V-B zJCYXaw$G$)pVv+aTiH+$Tc&gIiTXu#KR3HHbh*iqK3&vDj|ngt```LVz5e|RN`pQ~ zqn!C^L*$qng777$Nf@6aa4f+Q7hS26<*)>e*gvN_3n7udT!Q@V^6duc+x=ECZ_-e> zOGTO7$;uk9ObLFt>+fw^j@#5kc2fe|f%$76lUurHo%&b5)rVsC_g?a|r%-7J9}K=M zgGYItp5ue{zeksP39jg&&3p0HzZRHb(WRlk|4H^ORxj5dL(24D%_^uv=eMvd{(}p| z4!?hbiUIFx#-*GZcErx^%-NUk7wMht3;**IWcuW@6rrv#r)P*&t#Az9DDAbBa=~U! zhaLpxlIwq-6IVPZVizt)9Mpf-<2}l~VjJHV$6#>KL5vjhn~i7hLjn=J?tfl+4PN=@ zSrcO!Q^;#;72lN!SQV|T%d8QlSxRw9tPM-z6(^sBit+DTh>^FL-@x3NAzF*wQ8C7s zF6r_;mrctl*Ds`AU4C+j%j@v2F?>2UufMy*l4B|xDYJ#z^rwoU0eH5Z1DADg!(8Ha z%Bm-p;?DW}nVNDLXA(Aut)OgA#jgHqY+RSRV){&$G~*WZe`MU$IejDS^5%enO^T^; zgKl5CzGZEtT)2NfnL=rY?(z3{K19PoD%V-AqW16_-P`AFpasiepiro(w`uRA{9mu` z=#E!!cY$tZuix?$+V%xj3r*S1YU^FazQMJ?dGR7O`=*z#BV}n>_&MW!6fO`n9_3Gh z3TMKJ<9fg(?Xq{b>!8Ez<4>2a&2Bk(`IHt9`#Du{@yn}e9+GdFe-d zNK!c;S6@pUE= ztwZl+c(%NcbMxUW=wqdqDixmaZ)--KsQ{pI#EdVWHt0-{iS59d8Ap39o~Tn>pc-sz z2I5+Mec4LT762$u{Mk*0$%Ee#-mT|(x4qhX^kRsJi4+UHuE@808=O_vQ`*mw51|yV z)vtGTZNidO?&>D#l0ZAWcZY|CF{DJTq-+#^XP5nZnoz`6kXO6;a2@;3o!UmNCR-WK z9A537L6ZsXcI7M8lFhew#v`E5ccBkW@@C+<-MWBdf;E7iu};HyJ1djeoeE3|VB{0_ z?%l_wnNVxa{zxl7%e&{A)hBx8NYoW_($Y;_tJs#3;vE=^Ft8r4F#U>`J>foDa)5EQ4waK{qVHs{8wC6GACRNhrAVXy>kQxp0j;`z=gm>}%$v@aD1AZ@E@bhNHj` z3Ct5`%93R(+FK1=UxXtX4(1h~P+|SAyK9Y7gfz%30hajRYc9@1kqWLJ`O`~7)1O{0 z){#t0+e_JtbIbHV<{)D~#2#umaoDBp4DL?Hqywu5Hx1MTPwvKmo}~Yu>w^)1GVGme z?gyK8yV2Tb{+zdO>$)5hV@5>6Eu}cMaGkwpyGLsi;nI}@ppHEu0*cg5y&v$?>diH~ z5D+-P%~KgA@qNkTke>$)m0q!*gEmg>&86FfKE<_? zD>JCcNLJ%D?j34?rX*G)&(lEy0fm-=9&wAFfO5W zPdahuK_tf?Xoy3D0^Ftv7K(|le_8G!i68t?;Y*btBiaEgqzikrAgtHX6jk>RO5h$$g8x>G$KY>bXtp#m%dMlRU8haiGyIkBR!=>UZf0X5~Ax z$3Jg_mW#zC^=t~jLl}Zgx@*qSH8{kBRPRkQLTkHTnA$pvil%uI1;cYD`s*Wn$NB{8 z7SiWLr`y}kohcoJLsu=qQr~+B>HE=FgIu)8@eYJag8ycy4ev7B9}hh-cMcK}lbY@y zq#`u=p>oDgL=&g*Qgb_mgAQc$ac2X;Cc0|UVGBoUer}if^sdqO-Q^<1JrCg4-d6X# zYqT29n)ua&IWf6Pah4ALRR)S!O03$(YWe_A%Of{^SpsO&sPMvrjiNrxxp1I+61^^Q z>2}Ojpt*+A&l162vrqJ@+%q~umxK>pamSQ@+Hnvtr*n-~%*3A4vH(~TxY>k-+e&qh z9fK)%@?wf*kK6+$K_&2=ikS9=eF})yYji0Uwr|OqNf;A^`g-r8N)?=GH4ZYG%o~6m z_?e^~9ott`Sm@|XL|gZ7)ry@$#a%-PSuC;{Sy`Ae z_Hb%c!i*9B*&+pfEy%bKotf8}oYnu}z=~#Ly@0=!Esx(SwKyGc_)NU}wg{N&E~gXK zdoQyvuXDpuKEv9tU2g(vYC(_!_Ez*7#ie~QNsZB~6kbWu`26Rv^RST2q1H=EtIDn< z=I^f9rAr;4+qyG&dHWGKN#$b3`>kq-^T{LthHWomj11XzB2vC4P5>ZF-kbhk2KKS6 z&aK7TX=TPLqr*cB5H{B|*-D^I>ckYvYf&FA`NxP#v8vGDw8` z!wb33ZKGYaiB@NsS&!pXB@Sj4(1j08Tfht2 zhaGEJ{|C)xZapwJy$$J!NFFlW3IqC$6rSu+uUu7=1elAY?>`R3(0S% zO*y?=n%w{GytdQW({nZNo)QdWXpp!_O<96=QCx3${yC1d@5F{IJNe95ibqPSV2@QM z7$26hyVUMtS}Om4X64Wm)O2)5G;++VIIOzAe$vsiEc*7wzFBfzEP_dh_&-jsS?i1+ z?|B>%ESz=C%QMFMtcu5K1jU1)Rwk}aVnYX4c)9kgJt9oEia7qOtb@)Hn!@qvC!j;% z8%5@5j7fliK}AM#$Z#*@22~N~SYTD(c~$uf4N}^xF{>H-krY2^IsemPu=t;nCkLZh zVHp-zPBM-E{9tR8M!Gq_S{GC^d_Wa(u$KN3`MC}Y8rZZwh2L-v%h1VR2T`+(7q7{z zZT8QvG9E3KNGPg&r7xeX*Q9~=2zM+znFJwF$X3LUFIfBDdhvL}2Ix*|da;q0nycdD zRiRh|o6J+VX(;oOPF1>t&0O}yo60prE(l4rtatD=AYe##e}%m@671*aWY)cX?@lt8 zyYb|7S250ygNic5Dc!>wp-cF=AH(xrVOYPrLC^d&_<;?eJ31!rE0o}V9SLC6BZ;9M z`YJGHx@oW}>GYDtG{rGJj~_xS%R;VHz47?m4FAwGebr>7LpdzS1Z6yU9PH0{ufQ{X znCe5adFAOZQ^d;On)>}$z{`;5dLSWRD8J|2z|zo{R0S*6^0JhL9o+tqg;CJ@bWO9l z8)k4vw_$ZsRL=CQMS$=%@l1e81nPtj1^(0?C>staJZ{Lo>Un1ki;3E!QIf{c|KP|P zr(JjHYEo#oSx$GKCk|*AF3o6MU{8LIlYqsKXIDyn!yOP8fZcz=&Ft-1mxO}pABlNV>4z3GFheW0%fW= zC)z*J*JBhQPxXOBh&T=SCL4}nU-YmxGkZOM#NY|ST%yP;%tb3s8}`TEh%2;$Mqr*?z%$d zS7nJhpHF$!rRaxJjdb>)G^tCoj-A)aR*UdpEdOZJtf=zRypn)-Cm-*b6HJ%7F#5bJ zumY*6Yn%vsM*P+w8T3%$*S*oX>w$?2%}S$L03yy~mq329W5>JxF)h%X%(g8{Bv_lF ziq;1JNw@`KG0&}uTXg5w^W;We3q5gXB*>+esyM)J?0^~qg7PeS3i6l_X^c;XdiK<4 zcV3yDvU2to1>a(p*$F1JH@QaZ@owx{TDc4JnIsGG4aQVCM4!fi#EIY9Q#}`s=N12epJpD&>h1o%qz&GWA+(oCDu)pch|k zDZGRtDPab|@$awuOUa^V`AB zJbkrCQe`e-MdlOVfq4cuN$NK%OlaYAeRsQCz83o%L$qAeA){waE?ohf^lQW2sUMKT z7Ni80u-T~%)o6Q#X(K&H6b(mAGFtC&cFiIK=*|~6oj@lg9iH1m8tgbl#6de;Gu|IF z)b^R3o143^L)c;T;chPVH}B0<`#>IGzjt3L&5h0_@dgUtYFm%vHEbQ&9DQ zsyT^hH>?JmG!b)vuz0Q^n300ppyW(sM-h|we1{WguPagD>Uzswp;$%!ms z66}R6bFuzQcKE=59MMRhiF%pMmbyHC&wtCc=px=y@I4~QMGQkJJ2S-FU*f zf=XMXg#;~6MXLq{30_aJIeFipGQUr8GVhCG%wkGZUCrn~tf$E2_ClrJ66AtM!7r^g z=F5A{$ZihAbLJZNfvluY6S@4b_yh+VYT}&k93&%_m2!O@49fxky)ogbd7ociDOw9MO^ye&e z*jzJ4JOr~uQXzr$3ge{<87c&o#EaN{PW&#WQ$&bOQxDk_rq9agf!I-PV* z)M|@=&X2f-*^>z4sqqL9WR==>#P}=1mlfY!l7z+Dc0yBvwFwG@5?!Q-VVN;R#y|#F zMgM3)Wz<%|EAEBVS;+FP={$YC3EV*s)MO?9Y$`^Bu+ySN{!uH6eS5H}dWB(4GQde- zF??riN*)gkFETpF#SyIp-meehRSP)K1#5Ws+r!06R3siG9efOxb2JJelbU}vZVbbg zpboKP6@H6VO8(`Uif;#WG@86woJJqDO>s%pjP>^&~urg-J(ysoArb9`4-B|`v znySKp#4A*x^o8s#Lv4A9j6P7u>1EQi(DSA?SU%3%9$^{9VNmK4vj&~3&I?-4whe#7 zDXB8^_z`kCvZ=If2i!;tAV%aUP)w{}59|q6F4-orE6qg>pO{R#e_3a4DwtKZtJ{ zX}2e5Zg1B5$*?KA2+C!bbHW{Zdw1{FYnq)>^+1leMv6{>P{5A0y~| zKD8IzZsRJmbqy2c3bLU4!;MWe!%>Pvx-xCgOSM zs$%rAoY1t{QYYiXWntF<^CoS7$aC?=z%?0TN*^|jl9-oI8q@D3NDYf~MEv54xnsHE zxCYsM=BkDUTUstOTGtzk#KsVRs-vGPPjp|@6P>S=w;!15qFoYm!om+X@B+qqHvL~eMeq~)tzszdsPczw zFQql zNC=Kp|9H+MV*atr1mSh(3=O(Wj4x1<W zL-+-xhb8#C%(ZgH1@87I_;+>Q^&CmRGSTN8@gB~#hzq%BiJ2kA~P%aXWlmj@P&^L&9$F;9lnZny=uj=+7cP8Wlt5nM{3lVvKP|`Ge#N(39V2Sx@6utzH zeHx>rj|2Hu$9iLXora@e=9&ikib`SLp*7ZS)Ya_yR@A6jhVu^?MGFpFP}e=sVRNN!o|IcL-pp;)D;+tk=H9wbGORNdjdda zsJm&Bt%$G=$kGF=mCyYgE#DZ z0LSAxqr*;Ew>NRBg?-9hh(pe;gH1Sfg3K}Au3%*djidz{l?RSCdtaBWV&`*$u!65B zsW|Hhp>D4R+Do4koeJ}gR|%0sVEEA2aJ6K6D{q5)?Ck6WF`dh~aNQfJEMIjU>vM!e zkp_M+sd3KZ;^!&GuAi^8JJW2-`x&Y3S(qh)b|xxw$88_4JpNk2RJ>|)sU$qBk`eV~ zkAF0rD*+_hJ86UdopB0VSHLJV+Y2Sb;uk+b_1A6c%@Eg3Sr)oa=~T8umzkpL!ckLU z&4lBt0r>9fyMFB07X8at*=ysk)W5VcOxAByJ10DJ3wzmNle(~G=LOAX$C+6CfBVq^ z0v?F!Jv@v~CBeazJi%2cV!2pVTQw|Ad^%Bft^caeCLYIM`(LhY?2W)M73%e)W7 zy|VSdE0Sw9;w2|9pKRSIFgHFk=sQ$==cq(^x!q7TJ zM%1a(y{%a(hEL{M1&f70a_IV>QQaFcMBa%qI_WrJJVqwDsL%<6oyBwlBk>$0^EM9m z>Q(JWPEsgSaywjn*8Coc>)_QX!|@ui`wg}-SXp>wzU{sm)S)NrnpfF6`EAj)qvfhtp2kO$DGDRj^mPx4C4rJLO49GgS*hf8D8F`MTu%kqbz|*Dk zjX6iHDmvllob0QCjqPJrYo$oiemzXF#2Ke01C3$4!se%sEP#-!-5K|eRd*6_k$?Hn z(Hg2)QA8tLDK_V2rUbXZp#1w2){=W|rV5Jw0&ndZgDQP>wVR1oEmF2`WVWvHjBTin zGgklLUA#{z4gx4S<~X(w#aPbrSnNKQr5b&r_Q?}aW=igQTz_~kpf*Fj()lsv_|h}L zKG9orHam<{E!9Y0&(xZF%e334OXX1H#=|ABZQ93AhJeQ(yhIm9_3yLFcu!hp!40g9rQPEH{pe!&=nqvvZ93t`MphX( zt6sWPvgrw3d+t%$B^{C!_9M^?Mnm%DF%B;_VB(}Kb=f@u0+#!e0#XZdI1kFVD1KRW zi{3KZep~_7Oz2z%PcBJ_(+a@hwz&`U{<@m41h7Bim_O+N$-59&(r&l-ij8fg3 zoo?u>i0}+S_|Bl6OG4v-qDmUj`8&Y_fIpLsGi?;j9zT9OhIAae+&!DCb*ZPM<$Sm` z|KB?=vXhgVLUl8Ot7k4<*Xfz+?eZr^D^5&JEs;v7JviUK;hf0$vyi!28J->l-`FMj zx&)Y0FZbq9{L*oaNYaxg2I@CQvUd2wkKOxnn~7P{24I#8%johuTd!FRw@Z=yk?UH4 z5?k`fF%q)!UMm5-&j zs^bm(jYpE2?fbY8x|`p|I5ae5-`e3r>$K~H`+nh^qzVi3=6NTRywaGZVdO`Jv~W}s z9E|yCpRNbm1ZkQK(}DJ#TjEQc+KP`@%}!n$tk&6Sar-MtoVJXntf8>Y{;ja+u!~YO zR@3m&xMv8m7tJQbs*}fH?Gzg)hm>YqmRvRn|8fzq3-+20u>^0A&ja%|JrogidYK%Z z(ClmH=fd@UTrp(u2UfB$OrzB882$!~cuQUL!epqjMY~OCklp8>IU_g>RwDn z)APXt#DQj8{%kp>I{Vz;rj3}ZlNR9mjW5ZZi_1*9+#?s?bq^K{SY$4B8&-WCYul0Q zFxq;TRy}(iwvoDn%Oa;K_B6{df+r98C2c+1Ef=3V3cnUQVAX##xJ3`&ffgP0@&Vz ztY9N;ZNXU(0YN`ZWbE5j>C>0)Vrdeqh&X*7bs|$glb}ts)!nuB?L&FV*DCh-94mzZ znM);2)>CBYmO*7qgx`v_l?YqY@W`Ew&$XQ6N{zgNm?Fs8lWYtA!D4=upBp)Vxd=!` zvaSKp9*=pfkKGwLPMRK#pxQ{>a=8|aT^SR-;Us+`-lEIk-TT{jM5!cUt>vp@cbx$c z8{M1~6=>Vb?j&sS(m6m-8Cr%o!NDALSe2`wSKKWH7_{gqpB6%x?v#D^)VgEURTK~t zhft~$#eRK+_rcLBqoG9Tz=8A4=*5e$%y@Vo1gHIu7`{Z}ZM*H9T?oKwdvYh8a66O$ z)Fea9E8zlBMw4wDtyOPB?Yi+-z?`+11*Doki94j(Wg%NmZho%% zChpWM6;0(!iIt>AxaiL=|B?+>K+8bPcD~Y$ryJ?F#c(&qS30m{Meti(F@#~_jwpEg zmpW8+gc3SZVVI920nx|ycKVrCzmRl8PL6+ve^}UV#7L;c!<4J0eeHIgWq0uNW+zOf z2V41giJ`d}h_c?#0GlhTTUbP$HA;mSvZfmy6ET-aB$JVLYLLr(?a!_K-0d_JwyYZ? z_P+rJitIWF8eMPfJ>qud_SLI0_Q4b)l=EkCsZ7Qu11G1n7aD~|+BCUn4`waoK>im3 zcw-+x3;1INU_%P|CnS|@dc=EZnlqOIJ1b%~UL6dVK?4Reh}QSE*zw?Sc+JvCnc zvP)>ROd^9AN+8zZpT2Q(*@hjf=;)MjxA;1~P807MYIj^!UCc--BAvAyJLt0~zwATE z2yu=}`*4KA9YxgK4&wvGa&HpgoAo`Y@6{YHV`AU&X>;coek$_}Wy-y&Iutcs9mf}-LA`~e;gn;fjBovZ#>(Id% z)0}d$S%IX97M~i%`&Ymx$*2Q<%@Ft`6y)kDarJmr#)UYQH!t9SeH42Q(z9*!|0!qR zl9HWr?mdJgQVI-`JD`U8{~F?cQ9!>9al&uv`-!-nRGj22f}m;D_b(u!_&R~iO~W(M zZd&6-^5=Ry#8nhaFTK$NKxg0oRQdF>L?3vG2Chlf zCB^>yht%7`aF)klPJ^nARm)Zrv>qt>#~a8(!X`ZEN?huldc}5J0Q7(+mNVHjJnBdw z%n0^-Fe4|u`?OQfGI6OV<@fc8LLlUX9U10MBJc-;j1CNU0P>+(Pxiui{Z`QZ$`-RA zq4?mrp!v9|o7f$&JB)qP@zh;?9{y-_+zTKz4&h(0ie#>FQyTlZb@M;}ynu4I$G0gv zQNtQLNUUn6(wj^h!Ov^qvgm^G6_{Xc##zMi)j$S6pa(O!FeYa0)}nl)2`oVWYd8~@XDupno@!l5K0^jP z`y>+5vkwWJUV)B34)ix9NFLE}$7`ZpF z%)@2Aybx|`)J2L29K$UlQHq3_4Rjus>WAr+=*xEZK-7Ncz@ij*j5rp-;+Q9iBJAF? z>y=i@>G<5~Xr#Gy4jtGdh3Q=`!;>Axr}Bj=|ij;A6{zI=37(3nsD8Z7`19ALT14cv zp@;5hA3~ZQBf>e>m+y>cX2wanSk*V;gs?hSvm+5IGIlPmGjgAGdQsyQkE;NeExwfc zxM!v7k8c@PF$gsIu4h`CAW1BjALxHAr!KoV@6X;^@DxAaF{ZOnw51^G`-S&ZZr@A& zln=VCN{vw{c*XLRNp#C@Wx+yk&Wp-#R@Jb?HqNO?otb;7;yqt)niI*>BxsniLU=Ox ziN2f4%@22rOCLYElBi$P@wz6Qa=y`*kDjsR{>7$*+VCXaiKp#1Zv3EL+hU%rdXrO5 z&kW`^BsJwM9lmB_U=XbouNs;Sqo0C?KS5xDFM*$wCP^8g0#=S|chw;e8Fv(1wpB~Z zu}@g)Mn^3rPfA8XlxKjf8-mOSZ+|Qx6%rzM|88Z)tnn%5)V43ag_cx3EN;b1klHN72UsVGy4Ys`=)P0Ls-8?P!m!O!VQ{abgf3 z7Ofg__Vc^vCM>BFK76OB6TVz3NUP0Kxur4hy5C*Dc(ScnXK*-dz{6@@19%E%m4$kh^_n8zstRjK9sbrNw<)UZX|nr@?SgrBH|~ z!xO$+AFS2Fij;oqQe?6E)abmwGBVv!S|QshBwVVIKFe6l3NR7MJLS*DPCYB4)H9N9 z9MW!;eu^}wN4vBhWd63v$(YRj`=3T|>1~vJZ#SQR6nAr5*9M_m^bVtDOblZ$ytX_H zx`hL`)%UZ=1ba_X!~hx-Wu>Pj0D#S}zV7p_zz5d`S#k)Bg_j&3K6U2B;HBH`xV z!ql`}mu4&ST?90pMV3?P3f(zdQ;2S3yjV`$ z&CJ4egBDO4ul*xgr0fNdPs!m}-!BkmF_3lFv#luQoprP~HD!LhD?t|`kei6R)|bcf zvC^?gS+M=N^m05PWp>&dQQ|nxiso*<6eY99~y-GBnG>!UD{TPnATqj@pDoo z0f-z(a8?wmv$|bAIl{bYJ@Y_D5bA1{Z%(f`x4>(;9t|+MGab5RUAPM>aro>1<}HFn zq%?O_F0P2?=(qm3RLj&_^EZ{I2qDj7VWM{;%?%J=(McRib`Sp4=o$n?eW+O*x8GnB z!x^b-Ofaf#CRJ99{dlG6NGE%v#M6(o+m1v-Y*qKhA|f;%+!`TqmSvy5izF(xA9A-l zcygzu{ZfqzlGB%@hLnkKB*|d*1L<9i{dmV{po&n0QpB9s`Pb0=Mj~8ii5z_U-dU}S z3SR$g2+z-Fd_^sGK7mLw@lCdbv7Ra!)Da4Zq)_DCDc<$HE!m-znM)(-6tII5^8wN_ z0=7))sHpUWYRuAoJ?5+(Po8Kz-@s-7nQqeU{f8-USN{PCC7Gd*XY&^_mKrSO>T6VF zNUm=zQp`%53cgzU4+B+8B7{tabzMQ^+d-%rUFTo1(aB7vtn*hX9y=Lleeh< zlegdJB(I~KAa9ps`=pPnC)}MQw6%4QPv*?j`@_YQEYd`YNzhD8#+$q9J85^&uh!p` zcoK=vWq>G1yeRmZm`k^*dn-e3#toE9I6>%i>{#WqrBLik|2gbJybs8@_39(dFX0?l zSnvCpb}+g$y%_E|&Ao=^5KE=8z8qygkvMn`G**S$n6mTn#rxn&T^;|8r}6pIqz;y)y;gbr}C`NnU4O1<^zM&^tG|LAKNEtH63qm_i<}k=K9y< zaeFNW%(dN4#@@wL)l};u?|${KD|K_0`n+G&vskMQKNuYyb$7W;?XhBN<_ruJu7BT+ zEVbL?pD8g254P?~-~PC;G|0xm_tT|ERqSRDpFL@JCT7oeUnsP;)+xD3Zh~TWc-^lL ziGR4gg1oip<%vU%a4B>NubG@^j+=3rEpPLGk8O>?mR9q@XULp=Fx4Vmmef*|R z3zC$4oj+CNMryJqmY8SS%BSpeua0cZSa`d{)8d5o{Bvu4zY4c|_oSuHjM*|%Q!*Q0 zJ8@xFssLA9_UFu0b%@Nx#0~o&U9H+RM>{D4M?%bNKe_gMeT5t6; ze|>m(goDs#T+sDLu(094_+?;p#n+!rw3K17|B>OC-@q%qJ#C`Qz{UKum^xHho2xh| zC^=X4kf(*(%^Mq;V2x*IM`-uuWDZt7#mtF8<)KJ6de8f$Kg|tJZ;jkzUyZ$rB}}R| zwJh~L?C`nxyVO=)>)E_cfusFZOs%H+`b(Z4flI(oqquO5r!h~>1$kfPyDO;d7%DCe z_1i~;>&_ZajIVx-RkTUzUACjgzWEH#gUTJnyf0^F_T^vmQ095m)6?mB?ZfM1O`7qA zk23_T8;!e){ASAh#sn>FvK!|d52(thWrP*d1#GYBS}}UkySQ`Sn)=IUI;wLz(s8Ey zv{@F2Pud|zNNe|C(8NHs&U-(x&`ylOE{tbKy!Kcsm`US476Xx6>8v`_ie zmEqgD`)B?vMM^eVftgOQpKq|5+&-TrX`Sge<$J`2iJ>vAJjQO{2}$;j27cCv2tn~s zlnqzg+N=(XG!<6O1f{CFi`}^~{9)_;-O5MwT;KCE*Q|H7TQ-)KP?))aa}%B0&oTR} zT9HS(G(|)*Esl7hK~!()?^Ya$cGa!RDA&+|aywdSoEXG-Y0`w}AR z*#sY7ov@x58yf6+Lm!!ZRVU|%249e_O~2jGo1#Sqik~7QHG(!%{MW1hHaf^|CyzQq z`%StQx0C5{IagBEpP0Qnv;Uouj6IL)%^M2Iw%4e%<5aBpj~XO)oH<2uW7i^nAzCf# zXqDuWcA7u_HrW;|N0iI!w{ob)-iej6$h3W;diy+k=oh`D0`D<2O<*i#x|AHPHuPP< zx%CEj*vl1`nTn>hS>MuYFFm@kZ1P@sV`0A;V%$^j?9BUdcFfA}vdgN~tMjvZw0?YK z-uPt5t9>@3-J@~q_aWK5GkpX0R4Zq!vw1|9{IDJ@$#itI&zOimG!S?hbA|Cp#hp;_kjCkwML&?G0R> zh&b0(=TB)_`)6sOBFngI)Ir^_w4>~NW5a>P=>pjp45|C)R>|o;*Juj6mt>dNSGbl5 z-3EsY=3lp5P~3N3JgTQhz{mfUML~h|nRBHb>R7&myWy}RnE+r@6#z5d{t4^f)SAEV zw73YVzk4T_ZoWk^m2*>1S-D0)ljiMmiy;#Z)pQznX2DLY3!@3^Via}V=;doKeY%`l zuj_NU@TNiNW^Ogh`K%dgt&1UOnzkhk8d#}oT|%Y{Y9UE?{Z!|d@;=Y$#M_KCk6m5zBe1=`~U0aCm7Y&Z>-2?WYKAzfp z)|M|K%)K6MN<3_b!zS|bK1mf60Z(>SIcmCzfj7!2M&4srS_e`rt|Z#!3`$5GV)n@aKr7(VG^X28=%;MR zo30gccIDhm(mtlg9p-MVI^SHS&O9xO7WU?NIwa5;)86jhbxZKTfh|wX4vlmSxlB=Q z7ZGWD(|w=Eb92E=SN6VenX5v9r_(Z@J28IIu+|d2zuD(Lec|WJfzZ;Tk@Mb+1coB&?vcm zYRgh`(|mXAI*t2FDyd_eO0SorNyuAurI^0{xBv;c^c_dPjbt4=CK6v9k(W}{J2u%< zeZljtfQgpPN_&g!08gKTTD;l(gTq528b?yqgJ=5QJeqprqmMc6^NE8>w_!l5|LZ`p zRZiAgQ)UP5YQNh&^?CJ1P4T6h2jWs=jH`JL@$b$5CoH%yV!5uS+o$g{|2SPr_0tae z(I6ss;%7sJ@nG+@*21=h;X0v4mYkpCc7rCud$R0~+Vek2|M5z={_zsA*0=E@c=pNH zurSIlSF!!Ybh?Ms_200Cz6hoW%h7@%X`q8~zMhyCE4gDybp1 z8g;+S*!^{h5mUP5<@_4!vyQDIi;CF!Kjts796}^M++g>bCR6%y#CyHtx2ANXqVThn zw;ROUrf4QkmVamco^kc z+Xf*=&a25QF7Sz62zx1wg#dtM%|3SfRpnT8w(tE@`sQyS1C_obH8qUqJPeuBwsbUh zeOxtjt*y8nE!th*xdiM4PLcmu?KySzJLfHi^DRRRC7KOQsC$_Hc%00cup){%U)Z!K znQcbO`}_I0)UaH$1HeX2&boV8H?lDL_a{^4z5V^qtMVp>U3UBDu{r;9+TgNX3e^AC zsK$^on)*;8b*R@ym!>n3+`B(oxfmF%Req9ND_Qn>yOflblMCzKu3>SC@+k(?jkbU9 zV;sT;DEY?eh%@-L7@Lih`$P1>8vgc9Fm-oA>z(5E)?%lAmIe z*RDiiQaO^Rh|CB(cFYJmn#b?o|ByagBJif3Iy79yPrEwY&2sWJi_*$N)(!)rN)OL1 z7uYY|OA-vGR;hnoCV4BBC8fxpUmoy5IeJUAlE#nAh0&?v71HK=5zy`}ye+pI9JUg! z7e2QSi>@4GBa$w(23TM)YP};uix;xpbn%dKbraQ|d|f4S@G1ZDw2{vD*|VGU9S>$7 zK2CJoxM&~OfNPd*XI$ohfM*`*#!WKyL6qoq^FZiMEJnB?`CdJJ$&f0?XOH`ml<=Tx zFQiyNLPc7v-I)iX0XxY#GN^KAETM}4LhlFA)5-VOdAyy8tcWk7k0Uxb#UE1c~N{J0uzc6CEZ@Xqf~Q zQcl;K@R~M}h$C6Vl`=XZJFN^Uf1!w$c~?GxOrE|k`{FBs)%~cNCYK7fsjeJo&sX9; z!bKU4-FIdN)ewII#)&l2LkC~&-eRgZd+UjCAEwWX$c8{T@dDX zI6Tv}^yfa)8%EcuGuOY6xcIg$?O}_@a@VEz-m*RPL}R2=V6uj%vLw$oA2dO8U&5J= z`$KxWP2{b9eM&50c!;>qBL-@8LNSvFSrRH8>VlXj;)kUF(YmdSc>4C73pDDUL0<@7 zy|V2R+5nqLCmWIi0q?1RLyzctVmvq#B%%o{%1V%I6aP&>$pBFBlOz16;<>dr8=W1- zOIK2!9W2gf-F@oby)Dfm|Nfg_#fPV8`BKcg+wP$Iz#^M;k0@wb0t%c4?9AAYyNWx? zC8IJ*e1m8&dlC<%)hMyH!!0(;{zj<8C2;LD4MV~AwBl^wDEp@P1a_Wr-` zzX$;$o+&d3`#gTz9iMw;p~2Dp`(?^-tVLJYq%Aw2qO?>2bg=F70$(c*RbQL7{M>xF zMpTD-n=>}mbqt6d7QccZ48qTZGJ&N4%bY2E6_4PZ*lyFz{==jPQ9plcYpeZqPXw(~ zkmK;ZdJA-#T%%sAj;K7OoSKwA3JU?3jYY;|9H}}awbk=iYLjcj;(p4adsSxI-$X}S z=*z43dgar49m`w~3M&x09X9hB((2t@=FJ3kA1gyCSgq`6vk(QCMNP_tg z$!rF8{(ITj*a|m|l4fAahQDHx({C>B*^fStxk$LRp zHGBm}-r%>u_BQSWJ&Bp-9a36hJ&H#{7Wiu@6Ktul)Y$U{jl99b3u5VjaMM%*`pVkz zdG6K(hja&Fe2Lj2zh?XLO<2Y$?g^R~lWa^!3e}Royt_}?xO|E=NafqNrw?8`JLeuM z2`om$hV#?rAajcBGwkNnk6;qyIDpnT9{28@hsmNbFcJO0B{Gpc1k7jLz6AEGbf(fq z-KG`ttWlUj)HE~}Nu*UMto!y(zlx?+YsdmITk@je-1aAI1NLV<=}%}o6wf9^Ml!xy z1;XMsWe3jX2tHyvE;94uki-lg^a+Ofh8(BNkVd#agE}omn(VR)K@-zHJ?#{*4@4Rf z(i#wq0tJB}*%$9`HT|&fQ>cci)Zm-`f`E-Qi^~vMDC_# z?Cz>+XNvx?>enYEp;S!1d~QM&<0)1B{Crr7AaOoqY#ODBR|_N zJO9$c5{(jwz47JRKr%68AF2!o{|rHL!g3xFUqAke(irx-Rk2H_;5D|(UfRCIRLjq9 z4yhRX8wM3=gT)Y?wb(b)H2>ia#PU3RctP*vi4)VjsUt&h21=hjs|1;mcGop4kCA8m zq?LNb>zL9I!_$M&?%p(qay4w4jhPW~D2~nao1&TY*!o-Kxs%;U?ob+NT#{yVN5nKW)F(k{`m~hP zkp4WlTu+^89cE<<-3V!Ra?zBZq;jJ;wne>jRVc^i4KPJUYQz}(~E46{`o$~3A2b_ozazXSN;l2l^gfpvdO-6 z8n3;2XPk65ZMiTQR96xrW5Y6^_TAADcEG|fLHq%ERs8d7+&_Q($hK$CXVbRDw~=L7 ztbkY4)_RFV)PGZtm3y^e?%y%OaBe04W z90v7khzq)rjL$ndmB0k4-i`w7NmG{dU?FJxVQa>UGh$c!+|3mgJie|Y0v==C&dbny z_VR(6f_S%kTBp^r()#8nCx1QhHz|C-pZK>(9^`g-Y4e3VG4d>_FQTw>hB#r81(n!{ zgXGtMrZ2K5kz=Q@T*4B3d-HXF;1 zSa!<>>|0*yKr&ovSlwHfK-T zatqX1K`XyjY5Dde>t9f5w520ts|jgN8)Zp)Bnl)ZvW?O*3w`Ul2A}oC#XSJ5msU_N zOz){}>6u125^I$vnluWq?%gX`htNIbx-5>-EXkY+-ap)xGLmyk!(8EFlFEUaITPm- z%hIn0Z>CPvaB&>DCB7q1f{`-37ZLGG_>Aj#B{C7`$^q9|X&b7Bx3W_s$Uf9s$xm7* z+gm+_Cw=qc3=FKN zmrma4T63S8xeq17V&5R*Zzt8uVtJMz+=N_OQ#}{#zFGkjD8ATsRE!@%W)sPvIPE!D zpBfJ~o2j1|+-k2h(Svm?6`3h2v-v=K#5VcF;>T@4b0BP|JYRS3?^V2AF8&V#>yKsI zMO%_rfdkMcy~(-}FMeb>-#&yMBXQ}nLly)V>i>tS?*Qle?f!owR7wdM8D)>m$mUa_ z>`z9rm5fA^y)})Dva<_igk+UjS(PoL60%pwmia&TN6+{7cRknjT=ms^-RC~{>%7kE zoD-w&wcrhP=Re>m=yd{JiP+7blII2h9REz#`8V_~tOP_TFw*{)qYrA@UIki`8Az7q zK%oyyD@3#KlT3&uEVqB=^&5oog~Z#d_$^$cyre5eMT369-w*Wn*lNqp2TluBA_J+xOmn&4$v1#5?~!y#II9 z;abSlZldwC>ryNN{(Lc$#~NXh!9~zzzG*6k@%GDe17@s#n+4DOprJR=WAl<)XmAq@ zRz5cX(voLTs>lQLMA~D4#D#TGhZfP@(0hV;3o0zWnz;3i*8H2?o=13~*I;|jJH86} z;9uZ}cY|{u(MS+7W3lPbDdPf^Vg2#UgZv(vIEqSWIX+tzqGmT8(2(v0AQ_NzsC%vaz6c8U!3v}b zg~?*g7sd4mPe33AiuT;@^>9Y zJ^R^AILz@wRYdDBJ`^UvUztzRYXrrrr_3CUc1-74k#f5DDV$B3sz7s-nmxXS(r%%AP$RIOeWRyQ*rvJjsL|H|pp} zKV`kW^*1tEu&z$!QckU(35HvNgV-EtPp6v%bU2Z9-4 zJhcQ^Scbbq<-+~X@6?Aj3nj?QCGdYq*=s|4b-b1C$7>r?`I{asshPhDD0$PKXYyaa z{;r%7NTvUHAVSwZYypPhhA1n>nU&nSa#}xXWA6ry4bpD+)Fz`dq3H8JS2Kw?QR17=Kf3Ir9MWS46Yw~%JD&?3sYSNf}?of`hR!c zi@auq^*-~PUtfL992qTHvReCl5aS`{d10WKkpWPM!S7K65kz`-;1|(P>SLG|h~c&e z^FB^Icx1XqIYHd14=N7OBQKo$#IEp)NQpYUa`WB>o8REJe-^}O)ZFQB--c8V4=;Ku zVR)YZI(rei*9`pYwz^ih5dne@np8iz~ z2jKdjl4Cz~E`?-utistBQhCCRpg-98R$!O6cP|qk**bYC`yZj?LrUsr?@s$l?6eYL zpIH9KHsOd+>nZ=u&nD)bIs4P7sPZ<3hu*wn!~A9T(A<%QY0qUTkdOW4_TL954n{}X zU;SIJX&9%ZeMX>Pv718q>hI5E*$b@1hQNXGN*M%)#~z_x^yKsiTZO6XKL7WR39BVF z9-cei7j$w=y7?FS=g-=pV0kR~Hr*A<_dD*U&%iQf0X5XKq8(3+@x1?UeMnK;JZ#}% z{$TXgL8(k(+Y<2{4yaJ*Jxf@N|MI1&IJDCK4#Xx(ok`$N1a#_Kp{Eu6(762H!=Th7 zMygg2$fQee|D&@t=Z=h>&jAc~I^$(|en>LOrZ*Y3L-Bt_Y`dp9sn#`-ghtj`#K>k#bX{}xsrh2j2*6bD7LTuI9UUqYbs$W-%ZZo*&7 zR{4ZbT3We18`w29ZS7y4+zH^~ zsE*R=c@*C3ePur6O9Bz#|Gf}Kus;Q}8h#+Qg^ZU(g{OGGmtBu^pdiKzCqZX7e%$fL zfe`w5{Ku<5Za{7kFFE@5V z>_G}zdHFrcIeMq6Uuhg;g?LK%9Ot=z!5QJ>Vz&usF_;X(x$D=DX1wr}`Xn(BXEwHc z{LlSVdKhL~Ay~uA!utPjWn;pFKCeM;@?3PgZC832vx!;ETfcxv_BR8;l)X%WCO1T8Vy5Ms?U3 z`%XhcrASKaOuuK#SrLCmx!nPG5l=;~;EZR|w=!m6sy|3dqe#zWke2BmOm^`&(LS~A z*`@x;*~P8)^b6d2T_#<{Jw9goc}oUUa$0&xhGkPdtrVeIx#C`iBKeeQ-}_nZ`V*~{ zgr$hzMvu#{Ma4&-)l9H>T^m^WQ{!=I4~|Qk zU7v21oa%ck$v8P~aM$`$1HqpBb1i3tedv2LxQLUY-yZl?RD*PLItrFhJ#aZEa z0pWGRn@63?`lxkQ57#_7{pefKgU{OC(Qieq9jWhp8Sn5-ut&t#H8}bM2ad2eS2ri$#=a zNlD*J?SIA%T*k1`$1{bIA3mrYoIWIn?dRV8O==D>mJ$9N0qy;=Bx(5`8Y}kN)L7(L zR?+%fEi85I#icUBmdGRpOwd`@>OFRP6yhDI7+zH`)fs(`$ES0t`rrEZDb=6#amo2Wpuu*EL+sstX0+*OMSCz zYR4(y^5$=XyRX1Jh<3lH-g90amq;Icrd>KhoMvVJgQoqv!6e_O_lx^68l@#?7ysZyn25p6SHzo zSkDoRrz$IYH=NH#BCh3|=H|y?7TJ@_)xJJ3V^IM5yRbr+ztHaPZq?XJrEtH{z==tX z(F0Lq8Rg}Y!&oQ7vl{yY2XxDbeE|a8yg-NSTp+;@@vCiQ?{KGy=LDz4nCl(kK)w{ zHm!m1@G8_rc$kbm3t-{%WF8eW4QQ`O^txGVEg$KT5ax&zn4Afnn8(WwmoV#6ecqpn6f#--EKM}{8_(hA^Ppa^GCtb zR#LPbK6#nU$^+}&zwflSv~1S%6>tQ9lcUWPQqgv4H8^Pf^+o*NkZ#4Ep4r*JygWwU zl9jgxM8Wx49R#3@%Rt|3PCHAN$@SZn`OjLuqTAzs+uUgW@x;tb==S#ZWoQuycUA~G z)gs9rpODaCJPU*ELUlByI3MQNWdAbk>M*W-KXI4zd#T*AuCIk2)s@FT2CL#FOZ6yy zd~T+aUD9{+@!PRkE6K~F!Im`%4#@u@>^WSe*C@Xk1Io?}Lw+w9>h2Uw=Y#cY;ce*! z1O$Kv2)PUtNySQWeyHEhs$Y2Z_Hw=>jIa%Vw|P+F=V7zIU-bEOeYWC6Ij`1-G@Xg4 zc$pp^c)4WPkFru6zbf|rY53=Dkq^IqjR+p2=cJ~8NH%RMB>^;W zCeRF4{rU%9)JyV4n-Wbz8cZONn$mmr5z*~`>0_*}cjs#-_wiCG`7Y#UC7ES>nC(;P9 zdmf&1nH{-fV&XKlm}{mxBawf@Nk=p?AMcx-$#o_zwy?=W3wdrg&`Z4ucf@TcdroDE zG(uy?S9s3oNWS9@Pt`8Ugv`D^H@4jS(;=Emmt5>sSXjHCx_a0^50U@SzsD6s|M&_t zn`{wj?A5%ewf)A8Uf@?wnK83+h8XXOmvriFimWFOuBWPAO;CuLm~O0cu;^E`tCPa; z-n(wG6LIW3>gUg&-~1Dxz*IO3ZHe>n;>&3QYUV|$0B4BPNJyxTNsK9&((+i+E4J;) zG-PL|>g$WnBgSlmb@)xtH^68jVYO&xe>$~>hULC!hYlW|OkTeWqWLqw&@jq3^*WILq0|;VpO=IE{i^!-;_U6Jdjg)GY|=99ryauR85w6-D!N#&5b09ydj2UC{K-yR zD{L4rIk%lb+q7X^VdwAKFzXKexpU`wXL`PWXBha~;x+{RI>QO@NYuzUdV^0HnTvH2TOpQBwpbRweK+lE;Em0kO` zO@>=ugZ8Womq9SEs0a!PcGn-*U&hIKxdP|I*`0633NsagpByl|CS>r215y_CaSDFE z@6__t3}ix9=p;3+mt5;_mN=j2tbN6TSp1AIoods)5O2=UHu~-A>+5Vketa=H^j>oJ zjLp0bhqAB;2?@zOA>@rUIp6CGBaC*rntsNP+{x3V*|+-Rn6QtKerEZ z=#BK4eaW+8$rsn*X}j>x^E4j;>35Uh+h2Dj7n@F5z>I`Ys9+5#_w(}dN_6f}aqP7( ztpg8t{G{PE^q|qlUw8DGY>E)25?`AEMB===JGqeQx;8L5sWUk>iBM6s_x2ux6Dkn8 z@zh0X$usoz^@)gz9)ZMa5KL04hs-3kkoyM;E}D}W!f-;ny2KtA23nCS-`8cnA=l}w z3N||U_bA4vw(FbXVM-20-SguIBRMl5dsx(H!Hg@-Npca6K3Wbs2M)joe=_c0KFc^i zk@mE7Yw(aB6@4@JVGdc{V?VY2I(h+e2>tiQ8Yt#g6`-xt@DxZ)krHO4D!6%$$gHP1 zA=an2)i-9x9m7AcJ>f1VdZfLFuKjC5@Uv&C`Xt!!KP!$$R^0iVbn!O1vfIxS8!I8V zE9ipBS(_YAVxO!yT6;V48zxCS(>xavY zmw5S!S=q~r`{F??gk6R0^v#foxqN3%J$oH}+nm=EnPD0l?LTFYWa(Pk68q1`5!g8Y zY;Je}-Fs)tjWv=OMI_X0ic;TCI5yB;y1+2GmkeK%&2iFjCZE%1tM}#E$aKD&(%2`} z-OrfKg&zIh1A`YCW~BxG`O})RBC9K1Ig6}?ntEQ}0)GrA{s=ynCa)r^`Qw+>j1p0% z>8@YV6#&1IYI^e15tx+YtGaz}rrcq6X0 zgryx!SM0SEOuoe_ag2~C35(H)2;-A2qNgSCf&Kk~$;kjD0~t=SS+$1QbgJtFNt6S>;To#z}tE*)jcu%zo zxuoU`Jx^o5x;Pg2DssEB9L z^Q-E)nd#XW*YrV7l@M3DzV5N+w4F@bduI+Z^+ zD|ic+$`=x{x8}o95|XDqu{j%pw4BcS|91fBM#0_M_P!xiCMVZv@6$0qTU;r(xX!mX zWWW1+j*x4|d9g6xwuMTehCVE{wO|kh!P~TklF&U;>-*^%${%1D9 zD1Kp7DWOcGO8eSD$6;jd>@NAdy85-qG2J7it{$XQ4>9v)$CSs97D-ZtcP%C=3BC3s zE^75S@l!!rI;Rfdm)_eb>Zz+~Sy25X;(AV%%&)yoM&!@88zkWjz=L3+JkekJEsK7= zpJ;mez0}2p_Ow+}yHt@on0X@ zCV&t(sA|IRr0#)uG>NhOXQGGEK@All4suMa2<)e&B@lT7;{OF1swfgQ*KH?BqxxPR zGKDAQJn`!Qu6=psQWrwSGAYd#7s8op#142=<=pI^ksW?Xz_MPNixd zp#1-T9fmJrn1w*%fFuMdQX?c-C)pe~7Ob_qho4i!V%QpFN#BdUrn-)dq6bdbOpA}{ z*n@u{BolE*qK!xC``X%RYHCO+e{{!q__(>Q5bui-=h(~+G&hjtFnc@1oE$!a%SrH3!D?V}#}z2XEGa|sOw7#9 zAtYa1-`@UMpL42<>Ga+BF)1=EmFsB)i)|aEnps19rlt zM?aIXQILv>j~p9VQ{G%u*jbD-A45?)DE2I%b60K6Aq6JLSG#Qv9`XwW@l-ve$cK9e zwp|n5hk~frZ{LJ@laA0__Pm*ynP(pal#D&5UiNn1UZ0qSmAwqorB{Zxx7sTE0;RZ?1TDOG62Sg;g*kpq2T~Su7U#LbDIzcRk-UsLLH%(kZDAii~tH9!IGsDMKdv;>v*-Psrj_X>eBelZwL9kjFnndPf6 zUd8d_K5j+6Xx03I>o1drVDQ$!a3s(HagBaM)G2{b7$4@92&KdhZr{}e-*E`S@E8;~ zdz!!q@QT5M4uMdS-EgyfCdL#R?Swa2#+sa-1>zgykw-q~^XJo?TZX_pMHh9s-3e7) zdnNm`Wu)dWF*@Gx?ETAmZc2WBex84!Q&X@+<)j96)h0-~oNk(xyV`rtKQe=e=Z4wF zk2q|+L>?BWf$BWd6Vut>ze5mHHr&0Czq6j--qjUtDnAs+J_LbQW7!T0@xkVM8eYL7 z$kR>tBC=RWpWQhB!P`!oa2#hm^cOBLhQ_gU_^)MYqr9Fe~fV z4`PupI7ZrZy(9KTY98^k7B6Ssx@{x({C ze`7g0`ZC#*&v!Y;%(Bl9mb3smF)S^Bk+FcWjoc3_w$}i2ow+XvJpX$%BMzg{YL^KS zy!_b5$l4l$6N7y?z|)O;l%IV8&9L-Mm}<1N09{mAfrWCo7~bC3#|+w!jX0Nl?@@kk z=kL0FwE6CJ{PnNOL9<&p>jzSn5Ci$KIE(rj!LsElqjHdaI{6yxL$^aHfJVRMy^Wie z&eAHK@UK?}z~=nH5s?s!@m)8^Qn$h1MsIv?^*vfsQv>6gsy9cK6zWs9mtKCW@Nn|< zfEO%)UXlCEw!!bS7H*agYzaA2fGY$Ek^0&KeC!ca9%1ek zIU^V+Ak28tJhuIvQ=vo7lS_dr>aPm+V4)exru8K{IW8n^AhCV+Wot~LnxU`)UNXb4 zYOZQy2%KTq)=IAsI$MCGA-F4%1}5s1zfIOxq1^zrbUjJ$=7V_%d?NKjduOX>+@qz@ zFvbVyIOhp{POkh?v$<-fpaEjtO!^b2GMQQOu}(hNxwm`Cl)>4oPR!1RA+Kq=_K~ih zu6nI*t%h~`Ff%iAdruD?%!Rl4dAm_y{>~xqvpi4=j!?Eiczu^m~*jf~bnwXdvtQtYrJGigw z58ix6(B(7fl&({Z!N?b2R<~R?Knf!mkt=@!I=CC2G%VuDx0rc59A*(yn#&Bg`HVs| zp4==Q_OX_hBlLZjf9boG|BmqR37aEheDKS5{;fckQj1Zh8Os3n;IqhiQv7vxcJ^LU zIgsf5ehcft#>N({T8CVLBxvNXB1SDaIT`(zA>^iILBulIh`yKORMyM-Lw;*DAq|tW zvn+)_ySrobld^RA3=IwIJIiL`o^}_PlqmB>f0@4A+Z{70`QUP)mBuTR^3(Z^cE`qm znaXrQzIU|1y#IpT#5Z}SGS{uBk7P|N1{>l%ikrRFw5Pdn_f#S_t4h;_&-!9`1Mp;Z z(lRm)&Lbg#Z&&-h*x9avy3Dazyr&k9)eezfXqY^*_UXL*5$i-p<;_*U9XHRdaNni0 zx9H?!-I-@Cm1!w?);KmcR&hgsL)dV_@ph;|CfaL`?MigCmVgrc4N)QiFHbQRT5HDg z-Ph-XPRGua{?ndA2Wd~6k{mH7KF(??q1tMH0MGa$J%BGp;D8hyo-kkOSP8|Wo9+Gm zECbssrNhy1)wt!Ixt*=*8RAT;G_(CTa~}(BTLHac^)5d@|0>8O0E`g6K=G~ZTlLE~ zdg#`=`lh-fGm*qn89E;7oirkEajO_+Mxbo0!VXRXW8c4{?VU@%Yc@ZSvxdOYZvS)m z043#^$@Kg8I3T|~5Tf8B;PB0(Ev%p4RzXCty+LQH9yGC^EaT#vh8S`IAl-yH<#Y>H zR#rl$5t*You>c39SH%!*eqe$_l~mP{GhUw3i;F>IA9>~HfE)e#= z!FQ50o&Cpz^(`Lu_kXO1WOwT9UU0a;1}95cc>oveVdC4n1(LP5ee%5zRat=+tOzTZ z*)E?gyCEha;ZSM@ApQ57MnNUHZfK&D)H4d#W<`}Lu``YyXn4E#imEw1$`9?raygv9LvBT-u*S%AtviY&oM7UwJRI4B9 zs%|wcz_)?ND@|JPf&JGzQwZLn9t3P1jfkj&o`1JLHoOJ7V*N?z;IwV93Zgh@j>+wv z2>(eGx`9QTCPPO|*E=AK!9O0c7P3h ztMNS*T=DVAKACyO??g{S#lv7D>I(&4FUeP)?JA5MaIB>|A7Zcyh*N=@Q9&i*?P!cq z{VT7&Y13Gjot~SE`YokDZ>w=oZ_Z3Z;R#D2!nLwsN8HW^XtyDH2X8Xg${eK2w`e_l zqdS~>`(&+#1g)QXCK2$w_wLmlB;HR8iUq>q4bu*IC}Ci^$TWBtR*i`_U@6ECg&4Sv zJUMUma}|sTPS8*XZ;P`HYk+vDV4{b*5R9CVq?B7~d$qv|5mbTshr3G)u*;6XAkt|9 zdf-mH^^t%c+CHJ}l-=5ymG-P%eg70%p+>>)rNt#jPg^k`p1omg(wF5vl@;i6EPg0U zT%)}=mT!7K$qS<%m!eMfhLe^o(XpPvA_m4GbTPi8J85<$N6 zd27DY4teGmaVGQ9`kpr}{5udT{PRMhk{4nay7br`Se9A_>qIJc_NNN!!GVPI+&$LK zUvVxd@dquCWQMmcd|R%v|)z!5g@cB^$-JX}1%T)S8co>2*W8;qUYab5PL(7+rMzDyG8cLayz5r*#C$V*e z>Oq3ZKxcgGLtLZTtq-Ik4*eC5`K=JZmgI~AWVw~-(rsWtoDC&4-KJBPnuQ9 z=7F$$sjN|`TDEGvE59B^hG?Cm`Sq30pKpk3EG{alU9H~Pii11e4+nJ7b^+}mE+M^# zT=yRxJz#BIZPf?xBJs4qP|;Vms=v)Mr3c|i=jzO~yCQHRkLk;Ntv=E0BI7ABngU0Q z+L*cL2``nJvTT$Lq)M?&J?Ri_ebDxnq9_?U;GRUeCY4YZ7-f{+@WW@d?~(4{NFvm) z%|8(GKJfx-+N`!<%g|PD%{UB$Uf`SH$ubBH>QE#hqVr??Hn^)=NDjOH#2afx@5oej`#)3l5X1uJ#(2`17gS75{|@j;(yd3fL8)3J?OKFx-KTsSo7CjYEqmJKltteO!L^od@%9W?C3@ z|GrcUF~Y2ky?t}p01-LUVf4?2QH05G%4)?~O6}7&Zj|<`!3|4R4xbX;K zh)b_7Qy~pSKf*yadk_vP&X_=omunlZs+xemo466ZFQ+b^$o69Qc<-}k*%N_~S153` zuPt+-I(Ax7c5BJzR@A14J!z)qi}aVXBVR|~T$%xrfDlf?`9cGwRfJ@7JEW{;W@ZXN z=IcI4VMgx-dnY{%{c-J!e$|nbt>4xb5X{X(_dG=~L-iDSIai=jBq2j=0lR_c%d!-p z-r-tmtq_ov6I25zpAN9A9(qO(d9-?&GJ)YELM#dqVx8=SRnUoeKhb&8Y->_@zp&t7 z$^K*Xna-q;-|3<)@W_ds;0XHmR^;mEh(NMHHmnT;kNpso@%*M+Q~C{vS%_dx%gEpi zlV6`e8&AzOL;$u&`11#NgbI-20%s4r=*-NG;N*T?kTN|s{vvXU0l&59=(7dL@IANu zUBTXl4Efn>jgxZRe0&f4JmIjW#h$DV!Ditx<1W+?^1jlN~C(uJSyG^f*fVO26C3q zr{)+D$8*zPFnd~-;^UwQEG47apv1P2m5)ghTetnqD?&tXU)K#kIJ zc++=Qu0k)A77GD1)2+~&YB}&d92aV;0B-nh{mJ`wd$8q}8_bZ|2)Jn5Qd+f~8!{cq z5%g74MnEol6PESZ21N4r8|(oq0HBDIa4`K1F-5_xD=~+3;U=je$Zn?eS117`vpD@y zIo+f<$#gfuWf$0)-ldZ)ZfGm1=H{moKzzt@;n>?m-h?^3gl_kOaRquTZqD!d zJ2}bVvlFGNR8$nQO_E7MoYtA7t*MVRB%?^af!}$fsZxFO$enfuh%*~w;WGF*j`q&O zUvApi*j)x$$gNvqn-We|mbTAV>_CduxAptBpI_~#3yMa)-?o&M*-qQ>IM`#69Kxz5 z2EbDi&QRUg=vjFZ(X(270*da(vIeBTFS8e=OR25qEKg_j*tmD~yS?}^eJ>tlZBco7 z&p~u+I(<3fntZsYXUU-us5D}{K$dv|9yl7xW{NvF;fn9m5xJyWdX-EO5?1GxwF{o5 z@j}|6Lhj`tQ|#Zx6!zrRip_?m$ioNm0*T%06vo~Uo>%I18TedL zp!!u%kM_t3{#9!H&EoY69X%Ir6-9mhF_%+Tx-YmeK2`ImvITJ9wQg05zXOf~ZDIHu zVpxOKYKTLIShojRuYz~A==Otr!lQ7%&0)vyma%m*5d3OKqn$;C_CQ;vRa0P`+zk$C z3Ht$!qBhDj5^|OppWz?Hq@nw$FKQ5F*=A?ZM5Nm;4hZLQWUr1ikH1T^O155K7p0St zyu59=pnIxR1Q$w0pOJ?G^?8sWNwI>iC-?+eKjIw>6A^fcCI_>dp{vx{VySQwJ@;YEov zum`-qB{VX%p;!7jj@Al(LcT%grB$mUK%u$tyu7>%1W&@I60uYrcp={lxM^01rw6`h zE5KWa64dZY6r$u(-LDd~|HLJ@wTi}WZNVn8lHVfo>R&t_oRFcJHZ5-Y-|%H-U;Eewj}GhWZcmfoT7$ z5m{CM^BtF3WoC+Wii(RZ`&R3ZIfMkZUmrJHh={EPC{@)bPiN|WWqthMvD4`!S#U{V z2K4N9xirkmD;x%uZDC$kaYNs+V0VarT~&|8rRLn|43nim)l4O9h6Y@!i0j z-_FKT=Q7G-J$9^y#0LsDzc#`UUO%cF*kGwt2&cc!Rib!!D$lI&rs@ZamBgi$-^Usc zzdii+S+Z0$(HA>VogF;J_V84-HSuu;^le}}EwzHK&R}(;E8jOd*;bxy2)HK8`YkwK z5iqT+08*Mw5AsGhc4S1yBem646pHM^e;*?!+s_hP&&9Lv&nx5BpkyI6a~qqYuRK^J zm#}IdWHOZ3$BoUZ`g}KLCR6B6UOo&!Nx$2tG`YK~yxc1Sf?wDn=;MCk>Wx}TN{HXz z;>y+h{n!mfGqWrA&K}IFdwofu`#{E+xdS%}=B>JDMb7LlG@qu6Z^XgpBI3;HSl zhiG@dcPDr<`{s3C($J?(HZ4_vON4CHQ(IK#&zQ~hHK0YFuh=YBvR`|L$6DZ$s-d{uoD+`IG+83;$*mk zK(QVauzXCd?aI=#05&pm3P!rySr2|`3Uo?RE#H<){Q)Aqw!M3lvyK5WMM*oQ2o69N z#!$FPuyP0A#e_A;i_k$+=9|cu031NXEXoz23~cv2{K9}@ZQ)=?u1p-P3{DW)sJgC> zj^YiqvHPkHX4$DCkt+u8+}=*UxLcp}XP)%taW>hb*=OWe?`%9W)_zdQL4xZ-uF89a zofRJV1#%S}Dw`l3wXT>@5(*|cBr6PPzg4NWkf`mD@1J{84XCQOLjhc(TXB_8$-|AQO+7Wzu=5=&t(N+C<;0P+r^AQ}AStF&+Ore2GWj&R% zE-1dRX10cy25~4EQW9-PcXEGoU{xyGH z_G2kzr#4{Kjlj0TA-FglCb#mfLTDpM%lr8r)D{~bjy71_s}k^ApPlJLvxdD7Lbyj2 zE^oNDhOfJC^vqLlak%huvEHJ~9&A@V^V7-6b~GVb@k2^Rf$>?5#M)LOYhony((0c z!tp{7|9c=Ok{YMlb){%-qGzOkFt40TTprg4={TggqHVh+`e2N7l1SA8q4e7mkk5zc zMSmV*7(VEYQ}FGrqlL4JOC2}?3z*nffOx@2fYJ%!6%cpPf>4W(sK7Sh9rjP|ZXh4+?;MR2frdhwf(VK|k2A=*8@tK|cAC@5Wn zS)#0vc^{rt0LiiB-;u~+5J33-hJ2c3CiHmqH$*TG#~YPhGx4c{^qm{9XDXqGLN8n{ zYzYkk6*?bJN<-;5F=iXhJDH`12t62?(f~9&)6TNl4lO7KVRvvC^cUNI?;aRnh3?3f zi2rc>KuT8&_4iNt5%*$7=t&oVGF1|!vi z?@D1x2FY`XB(|JN+9qPQ*Z_tF4C|z<>u$oUgu{0de4+kSdmWV&WE!H~9i^s6;cfFpiG(|2tgd* zF&F^S6W7@1J{$@hp>=H!NU~K;5w7Gzrj+_HLtFgG?Hl$j#>3YTvbI}mlCbE1_fo@? z3HxOr{%7T`ZCe+u2&nvi8c(WX9bnM>a7le{*fpwdpnTy#X8jhp?5jYmfAM@*4R;L( z?vMxRQY6O{orYe5!ctmnJ=ej9pRnH`18tm#Y7ueK1oqz1-kzYXy=t6+xX<>T1q*ID zvQEY`f|;hFf7a~oPhVj1^iY-JF?=2;TXF_5J(da`X5ESkP0o?1y@5LUGedTBtDPLEA*26e;!Jt z-+Kw9?hP<}+Cp^4>^OACBnU>wnjc-Rki0thF_2S@&*Y*qLBq=Z?uXBhjW-UPwcJyu z9WTDrr}%WPM(&W9=sF&s}b6&OY0{M5a=ej^#@{fA!GAsy9ix=_{dn60%JG#Ls9{S^ zAsXVnViX%bif}nC2P)~j=0x#r`J77{+mbkgy{Cyo-#am*qA_iWA3u_}roXkcv^)=a z2i5XRtw__qdmW@{!*PyIL1suFik1qk!mGd1>Z`9yiksd&K0Umx z#w{5lUGD$E1gbQh4j^i!fKqhOw5>oVcL5Nd7m_{b3N5|ii%lVG!@5#CnU&MBc(1PZ zIn6n(_C+eRoZ6$9d8tJsv*J~FOFMKr>fXWgpH#Yn-N@Kng} z=tjPH5g0S}B&0VOvS+XNawxxP;useFQo3>9Mbbnayam*LnGlJ8a+1ScA>1m( z#}(mGHszNu<|ZZrskLN9!X$?R-wp-y4}m_X(fu9hi%#ajpCuPQu@4_~a6gB1K9%;X zeQx210JY45yrO>x$|@zeRM24rl?(`!bho$@qW|$Vu?6r{3BVnK_-YG zU|YmeN>8M|MHfwhs;TE08J6nwV!hRY?fC1!wf-NQ3-wc%7Hr{d@En9SEidVA;*Aah zx&G^UM#}>SXja{E_MhfAM1^C_d9mWAsHM(aND!|L(N)t!pFl@KI{hb5;Eu394JgM= z&%mHE*8>bS=;E9Rh%vVEx8*!a=2*2Rn|$~JZ^FZckeuzAZpySurP&=()9Fr7;*5-Mt8#nn~W&CLz!0x1HB z;R}lpE~rE(PHRd!23-9Z6yH%Tj??YLbym#ZmANa2(R{hF7xyVNq1A@`KJJKc2%)3}b!f@R_)LiKX#{bme;EN~2%tq98w=EpaeQ=`o;K=P zN5}ZDv1Zy_690~QUy%ADSuM@b!(%rCLGtx7cJ;e;isVG?V` zrC;sYF%0jGXCXXHc1ibV7y4#3KHByl@ls5NcPP_{S)PY;+ZF%RO65*~{=;6xn1@V=~tm5!2=wU-MY=c0Xa+nFsf48F zTK{Sl9r|ky6;uc%|L4vj8cRDcJyj$Y@;8iy5{sP?k~9YE6i8t#wygF^Ob!#J-T#6G z+ksa6T6%{b)+q+>@CBMxvBHcQqjc>oaMCDk$8NegL`Szwk0>N0Fm&?#i?GBdoWTN9 zB5)5LLU**O4}e_8nAH;`gjy-uCZD?ad@^##Q(NFD)Y*n>pCSaUz-GRM=6-6o6Oq~lsUt7QEpnIY8#^kggn^IT z6?)-?psIC-AC%DvP_aAEE;9LS^a_@#q;k!pdFFS>#1!Mf;FaZ2vhy1ojYh_mjP!vM zGtE1*PV}&%i)woLaK*|#c z1hWO4z4PGr)60FUW?l06C+AB-QaDslH5^g_N3ehqK+uj{Zhuj6*fnFbH>jM*%G3;w zRowP{+;tjpw>)bKPD;v{(lF2HVOOSAW2zs!7auOI-m+H=A(KQ=Se!)|@8mqH#Iv#W zTsiS(bPXO`7v)*8<;-F!uYmT5`!~j#K37x~7VaU>35loR?2;^%z{e&(U6D;0muwBd zbWec|)I$->(`^qB8lVJA$1p0h`RdHM-qEQBVxqZF~j&)r=WVvscoM4+wrf8tD zLOe|6f}LO39rHUYAVOVD!OL}QxuymXX`O;8C9ylykOYw(CZ*-BpV@;?g42${$nS(C z$bjG~)5D;*jv0-E2eTtYnx3({*v4#MRR@^kM#=Itw|J5NUaW3NoD@XK=s}=7hl)xi z0&MWcm)lLCi+$mD^ZIq(M#zI;^hmbsuZ#zmwK#4)VAU-?74?e&$UDT47u*{BxYPG8a>Zx9 zMR<-g<&(gxv9qH>w(NMYkzuJ;56$&)$o-;xx|(MN(mj)rle2q_N!-f~C%6d|=Cobl z>b)X1mkP3^l{Om^GG)>_%=YJ}3y`3*l#1#(fZ0ApSMw*K3+Hf)}SCbIS)s0 z*-|S~{E$#erlvQ*9{NT2;9~LDzXEJ+OvLf31hm5}3n)We5r14&)ed#&I8DHCA&^jX zpHwqr1ock@2O;)Hm6mKbj+x z6wkWHX*Vk+3IXohkqEV2o)x?>fouj+MGygamC&tD9j!W)TnABHY=^~5?W{FFP@=(v z$Wy`2s1xuf#M@w8Jy(iS+wMbIh@K|T;ay8a2``kF7v>TJiSxGDN}t=n+AneidJsdJ zn+|V*n+=7*IYQ{~--0If>(@58y!*@zvtx*J=gosS7b7&e_P=PKtJiU*C?`j(q46wz z;BCjei*AXXok89sbJvNbA<&AE z5iWBaPJfsiv#DL&d1m-FrMC8sZYY~qQcqzKvDU2Boe#e~|BWm)#-jnJVe8-!j?{4d zfOQ&RHYjyg=L9*Y(b*LAEjEGM58BzD+i8)~eA6ZKF1GM+ww&Z(UMvi+oB&)2gGjc$6b(lV5tP(Wsh?1=X!7D3t`_%|I z!+ur$xO1-`)sucV;A#j22+T)B8r?hsFx~y4j}5@jau|M>f$GEPF?TFV^ZfY?etL0H z(I4|-HRJNjN8aWk$(V&Gr<}_bfH8>wYapdFK8((CAUm1ie{QuYJDcMWhXplI5GLZJvyws&-Bf4Bi3w2dBZy5r@*iwW>lbo_|-*oxFrURqXK zo86P@s;d_42;d=SZk)(}iVc!*&;cA49QstKBMoL17;*N4{Er{MGIJ)43nGA5wo z2xhKxqQLRF3Q4R$W7W*|20Nuxx>y4#SBBy3JC83WX)2|(4!2lf#nV7T1|;yKh!kjrnhOSJ^Wvj|yTWI)jtI zKLV+HQ!nW~C%KX(9WvI5ijx>f((X!N*L3E4_6h_MWu79ib~qJ;<8Z#n8dw!xY2QkH zfr{Cf=7uTsnx7^FlSkO%j_7%l1F)ptt!JY_LPKmhJL<#7U}yT~qx9mOa(MDRNkmxv zZW(zns@KByM*?;;v)53`H{!Wo1dRgPn-g>(wH-uh zSkF62WMkLGQuJzN9ZLlfIC_)kh~22{^Ucur{u6Y6y}h@NYAX>0UQfqdrQ z2O;>#;2h{@v;Wm^W@T;>PM@l;EBmXv$XD6%`;(0rV>eh*#dcq(0+|ACzB!KSiK?aM z`KVVlnY@!vkAFzISoZMjR{X?p+c53_zR?IF>86Z_=7u_1zfF|AHk{~mZ@F_CnHS}# zu_2zYg`mVb2^kK=PAn~;Itv)sns2TI&%cZ?G^UzU%o#L$z@gO3Q>~NSYUMYyEFg#W zE9{1b!LFIA_iqs`oZ!|va7e!lI)(AV=Q>6x+J>|E!j2axI`~Z>F^w}p_T=Bu_~S}Z zzT)*pq}-pL;As{ivbi8m^=W1{&zbaK7FWwbf9VszTwX4{X##j3Up~vSavz%4n zfm~4i5~dt2-PZOa;x7iQCq;-=t_*zIz`G=AXIXVmjdKgb1?yn}SmXV4Va2oavzO_p{azD4cF)G@A40HfKx< z$Lr;-&O-%PZGeJt(YXv&XWBQPxqn6~^0B4g34VcsN1Wo`zZV%=%KuqhRN1_n->MrG z6`axpeH)Z=!@RWt#Z}OwyBj;VE0LOQ+dFs}89Ua|dYD*2%Mm0+ucOsBezL4KNJzn~ zw-cmt_*?c=RHzyX%G@^9euAH5D21N}kaRMlgyl()Cu=vrj$S})7=8eh^23lpa)XCI z_P~{%Ha<0b>HiV-9^hQJZye|kp=3n%s*voJy%WmbJ5(acD4Wd6UXi^=_DVvwQWPN~ z$_iyB+1clQe!c&5opYUYuH$;ItM_{I{(j%_Joj_opZoLq+?xi!J~5w^FZRmB$xa;d zOC`;$0R#xUR)>y8GbYlh}$Oy3Y z2BF&R-gNQr0eCmzB#A(B`>*al6O202CN>JLuKj)If9n>TCWruDEtZsm1Ww3W6+uv2 zFmoF01h$eLP@;_5E`B@Rma|@fodx)yojcfy?zaVuNx(lEvFtskf~YD&d5M+3>U5h(sT3j^V^7qfQM zQTO5Wg#W@o{^@T{|C6>&8tOg%1@fX*Kv!j>!Hym3NzUGx7&&Gv&eG|>f5p4?%)$JX z)%rePzQdiYBQJ%{hK&KW8LTGh_s5HUkqFRU@CK{xY4~pui1@e)>@a{g|0i#g1J|Wd zd{r1`K8*#`{Xu4et)It_e+SyD6C)t;R2AX8Kp%Nv$049g|FL@takX;S)1PTH(Y`q>YBzfz+06R@^2{Cy8ehQHlw)sCbZeVHpVem_gzQ%YN+e&M8PN=;(V9DfsZj^S)ftEd@a#ZSiSqPJzug7I zdYgelD#oLE$-D}*CY?yd2PA%k3Z95b19=*fI2LzRyh18QBq|bIY5|X%pT9JBLE9*f zq+O_dVr4}d$bzqB4MwJJjz;=L2f8Xbx<>7_%d->N4Y}OlvwMI2FPL#%)DXs9y$XeW>k^Ql_+w}(q#V$r zy`oasRK^LFp>4W?P`7`ViF9^z)=*iYePOk=ha_CER9BPtuHOYN@+vBDJ~kj$jmh@p zG%$OklUg?NQI4mm2qYaN?8-r{SP6cpoz#&hoxBy&oTbB)2F5QVIXO}SB8#B%dj|HU z`b^3$i{Q~x4!%k?HLjfm0kj8~qwGlI4P6{CPhzI`CC=*C>vJU>c5b0sQn0%)%WwBF z-!`K3C-RylTKGW~GYz?)!Iy(1eoJQ9^&0%Znf;Acs^&b%kz9cSsyXirN1!A2*PD~6i(O|lY^H_mK59U6_uIE8N3RP(a zn@ad@<%FAuM`2;YB%)*de9Q++q(hzR4EcTVjlMm81W+GswGU7S)WzREfIlKlTCm!^ z9H_@45l)bOzs$IbMHY^nf+X}RI)Nn4Wla86|5>|j1!*q+F=dADOH?Jv>tyeNb8_?6 zt$}tn!Na>R=5j%%fk)W^cx?i(p$!`zr>+Ac#wqGFk#1oDY-Nix6o{9Nt&W@jKSX_q zMjjp-3MD^+9#L#K%?xF^CzcjJ13+&W($66bfMpt+oUdoBl-)C^DIJ`8T>Hg7u%BWp z@XnnNE#;v-4C=>>Mvu8D|8$Xh)stQ8`4Jb(bKpiYmwYu2tSTB_12{r#qP>KyTzJeI zgiT!z@b6KRN&jg}{s}6U3zgkYjYqXJRC~r|xOrwB$mb_uAH{0nM1G&Cli2n$3k$fm zGox=pT**!@GNXon={)Zg$wf29sMlOm1gTfge%&C(r+j9?-k? zKRw{#AtVjV)h&Pzpk{Y2^WD*J5OY`mT`9bejw`Zju^VfEvQDAWhTE|3f6iZA?)#`3%zr&xX-2!P73tIN0(uqO~ch% z?+`h7_Qo%5bu2o+!A9-maY9nYC#W8hpYa-QoJjCHszYH9YD3GZaN53)wXtQR4V?=@ zscOC2v!WVjRrAN99Po8My!FCSPn?UDtOXvchX)jwDBa8<-2~1AR*(-~;N&Qg0t$r8 zQp@;g(^u$AbT1hL?gmQ1+|p9+rGHYvS(%^xwKdj~nmOu^V7Ngu0wHasCqY~?{f{x! z=M2?crFW$f-aj+B#XI3U>m5$iv30Amm1pR}Y*RhY&|gaJ_~A#`0Z!5-Uw}Z24D&Fm z;8$h`Pcs~a=~bj9B9-{@#1mi`8orh68HfyIpxTi%g$a*7?}$nbft4w9`P zJD`6~a^a}gp3hlCR8#l!c%*w$z0w>tFihS~JTRIa!C13>I{xnB*G@f?Gcl}?63e$k zo&Fo%6espL0rK56XbFH3CJJ@@ZOFy3%mk#T<~F~niFAxJJx+cuh-FPz#}B(Ikqs zdskq@2VJGSJQx9=$YVkQD)1xIuMab;z@;25pZxA3yZVA>{CBQz0Phbd3+uHc3iWECL}5b;ZC{rS~a@=kdUxe`Qgpz=*uTjx%lK4&L??5P|X;` z93!=$i@u8Ppiwg(>H8A8=*6Xf#_LTJ%Kg2hsEEXIs3M9RPU`{fi|CZE2OQi;={1e? z2*`_JVH4$0=v)CzwPD=4c6meM)la=lX<}mHAB@%MNNs?no_|UPLerVI0P8%pINYC; zI|D^Y@wH1o^6Mo4ieL*4sUs_Q-L}!Xttr{G_Cd>rEK>F}C9!Yj`S!V!nnxO<@#dD|=f>o)6hI&G5nT9UA z7t*_*FRmE@SH2mTDisN!jF%v^^vTJ=Za)m+Pc!i{KoSG38&-));8e#1_rV#DU3y~J zm$Za;=CAzj+;G#Z$ZCgJOVz`n!3upga;o{iNvcX8?X`0AT=uMzUbfGV)q^B_eaEM> z;C6d1dEU6Pn7imZ;M_Lm;$q?z-d!$0y|4I&b-?9BEx?%1k%mt_UsuroaNiil4ZN~K zQE?SCfC9*kAvE;W?qca(cBD;%RxYxqJ0l0h%D@skJ#EjXwKKa)93>@46qYqSyfca% z?sD5)9~8a{!1`(E;RSTmT667&VtJ&MeK+bnfy-IfI0lVv8aRlL*h;NfY-*zvugqQ z1qo_@A@`HFw#lnX{N6gKty=|Hv?s{=S#RDPSBB{bZ#QU>N8ds?U#tUO1%mcE4r)nM zWT8IvVwwZ%Kur&!s8Cy=wd0?pwy&Fn+P7ouHyGSS!yK<4Ze>7>h%ur5a|{!(j0FLf z?>cp-doC?qT5|Ug&^?YqD$-MQ+UnhFCNsg%oepr*nmFER+WW_b_h5S{( zYx5t4t@y4yn1Q@G60zf8`KAsVBL&%jTqRguWOi-P)EL+U{e!tWy}Wu6Xs{wSJE)Jo zBo3l@Xl*OIxU9SHAsrOt+PZ^QNDJd-4(x|TEVL7EA)&x>aTMtN7y56wD!8@&2}&7u z8qxl9KXCfAVIH&fUfx6J%oS!c5%yurYRnVFg5n0r^ieEn1hdUoUO7a( zBnr@Vkds&4d>3x~;+BfeB2NfB*C>;T^gEf!BeJgb@E1+d>%hqV!RR#V03!SOWGg1f zE3k;XFg7k=#NJ%}nRzCGshxf=#ON23@+U)=}isZRVZ?c_%uCgsKlF9?+* zD4bKI#E`vixPYfSt|Zi#KM^j0q~M?R(h5E$X|{f`c+e>Xxmy;DPMJl?_rEa{q-9h}lW z-A6Ofjce=-yuH4?yiI}4IXR)38pX8C(SY&h)|_8W#lx5Y9@S9g zcKai8dxLU(S|vsTir$Srz`UO_SEm1;CWozvQa1x-1T7dtz>&r78VSlxI4bF?p|khE z{L2C2CPtgIKzw9L`R;@d%X~ci$=rb(*L@>r7xCn^N2?BW;XwPJVGQ zr>4y2Ak?i5^SSpMBhe`m1GOA$voxF~o-+)S$?L!h{GbdLaK=TU>g(sY)|wGP^G&&2T@sCM#(n^ zEf~SipH?7`eM(<>N)D_^z&3+498u+EL1El^=IC!HZI=Lv0%{A*Nlk`5B9j$|;Pygr z6xdO7Z#!kTs_w^Zz9#b%fZQa`!UAMBSPNW)t*H|Nb-`b{S9<*;STvsOxONCuPM`&v zje3v{k^C)k`LG#BdAayfS#`%TeFUa_yIUEB7?fC%dMivwK~J$m20HG8+$dxf`Cl9@ zwO8E@Ey;Y5xK@-9FzD%)xb8jJcAG7)htz_Uxt-M3BDAcSB4TZsz!kW;90tu`pg1saqB@xjoVrptiFi8e= zr+`VD@n=(FrD+{&NCe4l;jlRps(_S0#2t}B!F00>B=+#Xc3i6f{b38pNIF5~$nFE) z7)2MbZ(KHkxZ>sQ1p&zv&V>t<*X}rg`%20RDG@UR=0#B*R1o?X5#S8%*Hu)J!`6Yg zge;cJV5U}f6_9SS-qs9TFhB(Wm_ievZv2i_PXz=7PQi4TdngTGg+?noB1=Wy=tqhZ zWU15%a_g}ZF~0x*!r7}oSNU3CcVZJf*vvvU2Y>$DlLnF*Rxm(AjYKQ^8-;RFu+n_q zKuQ?k{f`^W1Yfz(H~f^1?&A9CpJLSxdwmCB+tr}9KQs|Z2X5ut8s2~HNRORp#?>#h zTcjt(Y|2Br^ujuI1JG;)E}{t6_S^~dZJSrq;7DCQeml3rY`&ESO4z{+j?2~u3QMV0MV_y zMN(_Xn*6^UeEaro8o3-JaW1gTQnv3yLxCCF4YC4{C|?h!u+vEz8ss3BtJ~Dz5iqsA zcjY@_wyLW~lKs55R|R-Iyk?Ui$J!4sb^)r!jJ07y0$u>-|H49{LV85385=M&BtX-0 z(ZUf({K!ljOBO@F+7Mv_8GM6zvfJ2;`BE7({C;z?UM?$$@mSDrYXR zOe2LZq8Xy{9~lQ&0pyIu_@Uo`(rRR9d&Q-etPmav4)&4Ee4wUfVpMeusV3b6B2383Q7>uy0t=?pzlobI>3kR?x(ei*bf<*gqw528Q&eS9n3x)Z}Ni1xd_h;bMK9P3?=1i?c~1Zyh~? zo}}#6H#$kweAj5Pq6y>@0O?D?Fyv%{N3|9-g7hpI5L&J|e>lGire|!Z0~@;w8?OWL z{xMO!ASfcwV^UTF+gjoLb`H$(P9ySdd@PgH44x!p#Z7;qD4~WKQeI7v-bBF1E61^o z9^7?wj7GTWYD%9EJ6cl6FhEifK2%#1MJxFV&V|MYM0ZwsPPUG%;^ki5A3ae1uCgx-7X70(+z4>)?c!^ zt>8vN9N$EW8A*K1NOF61`W+IYt0qBRDuA56G0&B_L?n5AuiOr9vn?)smL+i!`nIj5 z`lWUx}w4=FNYH=Dquc?whfw5fC(T%?+Q~pG?6M1t6K#IU|ZS|*V!>c1tpeg z%F6UCJgJYrOk;+wV*8(1ia+N4Et@^C5C00Kdn&j9mFkh4vd77ONp#}Aq1&HoZIO|h z#=*rkKY}7%Y(H8195(Vd>ry#}ivVWjoZDCkR9C&b!|LAi`nR+m9S_HR5(o|kBIG;m z1+fSWKDKEbK!gx_jC0CY!yL|q(QhvtRoxuux2GRw4K~_|cb4V^d;hFGpT;{E>;f%h zF?4PgLv4qQ5l*3%i#-b<QlNAOK30G|Dh0B)61dX=)`NAd7Sf-aBEr2?@a1kr*Q*w0T!zhiOsaQS>S9Ju zEd~$@VFqR3oa7$11ogl#t1}Uyx7#z#6!IXyQA2bWh~!*`aHpSMq0bHQ`DouK4e`4e zFHhpxv9KZ>6@9JCv}AO4y}&D#u;+@qszjmlw$rJY*`Im%=S(dDwuRFL{wFl#c{loj ziV0n)Rj^DHMt&_FVE)H_4IIP%Df$9@4D40Cvz@^$+tifH96ze8wRM0>KMVKvc`El~ zplSj7J<4x8p&|K%G(vX8t1ki_SJXVl+6x14?*!O=OqnZV_V2z4^Z>(!Jd_1x+s`CRJ`@YEKD-$1qLgLCj5z1E zGqIg`NGosS>zh!4QDx`6-nHW#?Dx6Tv{e?oReT5?_0vSbTpWfGpcXaKdd&r$r0D?W zx6W%jxH4tLeZ#1C0Du{})L0GNkrJhd7fwqwHjm;Kkr92{pFg(Og)e9841Z%Oc{eAO z)-1}@CM|A&{2eW_h}+g zB0)$zIsEl&iZecQ8P$$r{zDh|F?pHZyw|1TodnC4Xb#t=3rh|8Deb#zBez8x+*S?4FYrw#| z44<|3%i%l+f;GvIr(ns3E)H4DlL8VS8j93h&>F3Ife-tH1Q8c790lm}C}nwlEoS@r zUN!vOJwqvdtK!se@L|3*@;g(Xn1ssbxT>NkL4e&%%?Tts8%)rGq;DY$fkVpEOmMT> z1nBxciFa)dU9Lcmg>>JtDlD_^yRDDcCH+ty0ry?-HyRmC2(MX6`)F+bsO0C}db?u0 z91)2GQX3mEv5M(s9d30Nvh(jp*PHJjWuMEU#u^&T;!2FQG~ zNfEY#$sZVFgyK(vQzwyg!Ns2AJ>}m;BV=?MnN}!!ptyT`DrI+0mH^DrdNJ`auu`l6;VH*{0u%NVI`l}! z1*)NV9jf-dfBu9iqx01h1R1YBSX`Joy_n#_(B^VZKBr5-5)LrTARns!vUP20tu+-~ zx8oPMTY^ryIIXOVIwt%fNHElx`#!%htFJ4PL3YcC#Q&L~&S{xK7#4#UVE2#AWP;t} z3BuLQ4?!(d)lO<6rt#Iz)Eko=si2UD8-{&@@I~*@*ilT;%Pj!CE^4S)3SCHl;`TXy z^X?jbNuuQY*jCdMjzg*$+A&=_f4jGhGZ`?pl-Ls*JJtttHqDtp6=2g_*CvNDj*NWp zwW1DUj*{K<^g28Gt1jG2n+NvlkM=zv{a|O*1e9a1Ylvkje&gpa0Vv2##PYoxx{U}i zB*otp9^oJ15McDfuo==Fl;lHa0l{rEpi(e%1!V@<^s;%ilmbW$i`OSl(ExVI5cWJR zV*iSpH%^C}cb;TWdb^$+LcM!wns-B&8KHcb7bz>v9O1v}X%K)~G!|zDrPY9`s@s*Z zp&6S0<>;6p_PzKG>)(!|E;b!Q#lJOvmg6lZpM@3m^DKnF9prM2a9(sGTS)JU+y4kX%kCzaBq#8Dp1$Vh5^@t)eB^VMr?+lIQw)bNYP> zb0DRne}qyo?Q%%C<**Ss^uTtUAquFeUdqAkwMHmecP47o3hl>6?S@Y zlzxX8VelPY#2&g!U&_@yPJnVFddl>&VMJ2wfV-Gj1vK}p_& zeJ^X(x{s*|_uWQg4!I@yU%4urW4J-ur8Ivs^bdrEujo`lMg3xFrKSfJnk|AXL?eM0 z(38N2qP_xlf7f&atBxhNv5s@Lk3o|^h9)va{~kMJBfz=xFzQ{_CIxoD0bcRdIB;Yi z+arp-^iz0XrZTpI8!VV$rjUFUlKDUk-FvC%%CK~ zun>m?PW@m%Fd@GW@RZ>z7T8<#*f&;_+gz@Snw&+wigep74g2D{OCC;*?rV3s7 z)8O6pSH#lA<%>r7@KLspn>@h*-Vk{vfok5hORoOnp8~ueu!`D4zDgerOT(%+U1A|C z&Bf;)9DKs;*xgUtMaQ9%|3XX65)uG@&r4r4iUSW%kmzvhk>EvX*gjdd-^88W=cr^; z-Ji|L%X>M4r_YJ*7re9fH~LVii_Z<8R)Xb7YM0vBq$IX97DnPE;*ou>G+6Sz zR_=!LQzvW=(1CHy6=SlCK6ktpq#EP`mrvsIpMS z$|9##cP~`YO?L$w15fKzcgSQ6iIxA7O=7ujFH_l_VoWEUb zuND{SGl+bzXA={$a%<(Hv2pno$bAceAR~~eL%XeKHCU|aTnktzb^wNxuLf7zguV1;);xBHe-$EC_?bY)CHt9v+pFq-r2d!svfO zL-5|Yg7Nwl#kYkpOb4q(Mp8V)pSll|p*tqQmAeyh&Jk9MY+^f+-F3J*3_8=s#cnQ{ z6e%eeA?wRmyq=1%uG1*TsVZ?@#$~T@?|GHP&vyJ74(-hSXm|jA=*&W96whjR-=0fQ zMK}O*_(Q1o!%huostF70M^ZpyPk~M&%wo@eeM;jKhk4K1c3Tq#mty_Mk0~^IqKb#=>}k0?TvWhZ+@_9MC15W!CR{VOS8o~&|r!@ z;H+TE&=7=~BhXOY(hzlxWh4JkCP7!1-yj@rRxSg#U}WS4Q*Vh*OIGszCIb=)8n~d1 zojMz!Ea>F8#rAfWnnqAcmrJs!)5VaI9*1F)lRFv6){64?s0`qG~lC$`y^ zCVCeXKb?Rb~M=@^Z8uu#WcQ3*KQ|t&sc@1o>Os~U5CFrC%%a^w#mbg;d!loN5 zTz6|MadC-Zd(G^je9*Cnn6s8U1XB2yaQ-{`^<}VIH`Y2W(GQ}$bI>(qXBfP32T%W; zmIme1^%DW!0w@{fbOYcF>xcnetuZjhMy3FWfDdhirVg+iLrXH33zp=yf46Hy!lcZ~ z68EJxa!F5xVzt{+nbAF2KqJGs6*pmehY+h6X%Gh7_RQ|5kZJIYHr%nKhI!i^EJqd)a6F z_-Q?j%6fgWz8p+GbQI0$n3wm3>dPy?u)ND#kAA-c1MRR-7M|A6u0a?wGp` z86Xz`WiF9#Ikt!fizeQI3W^C?Fepkh9B)R(3&_wAg1ZD_0Yg*{2Vh!u+++jD!r^r= zssIsvSx|AH|4R~DYvl_}jL~xCzoX@3Cz$RwI)}it3Q@8PtBRfSW81by(i^T?uA3V~ zs0Omnr_~#v>Hfsm?d+%py|9l=DtN!Mtcm zyRmMh+(XXph{Jr%|6o%P+M4rAOA&}-iEJ}-2CeaclMXhNhEBg?>fUpBW9wVkJ(!}aC7z8emldkYh~3pyS#;{%^0q73Y;f)ivp5>I5|6Jt)(?a zxbxg#pbuNmP~QHin1hiILs#&-<-rDCD6d{uD@=*_Q12f%Q&)kwt>{ZbLlM6Y7|+>P zA$yiTP=WieSdOSMe}o@Xb)M(jK{>^ay& zM;~t7*up6(7Db>u>|hHnly4L)AdHifGe}+7a;j@-Uu@3Q3kp#pCr z6^*Ti!OspjN?`6-Wut+lNFAt!k7jgWWp~C+p7%R^YY&~lBb|TF6EzHxj~lt*H^Dow zq_K8Ri|@aGx>|NEX|LIhul`N0nLT|bIlp&*1U6`;zQAURqm|rj_K6PAsaw-hoAm#y zQ}1Ex*!!wM|586&*!;4Z(p-W5#s;!xVW;(k(cJ$NxKGhI8z#FfUEu}tgGAaWTXuRkA$1)DM~m2Rj8#3 zt!9;@CeChtos-l&SC96Q)IrKdOG~RG3j%p)PdjT>MdR~mn$si^vPS`rtiEk5tm=1O z-;HU7YSZpgt>q1(ouL8{lg!S3q`B5wC2hH#zmzG$0Z^Dqg2iISH(uHif zt77DJh?k2{T@TMTI@`?)TjiE&2RlftORe-gW|vxuyIo%=u>8T(SENgm^U5s!?~KTa5G!_Gai}sj);!uF^>4Tm;tV@ z%Tm9{dX{24S^wFUpl%3qQ1kYJg*&>u4#X_Mf9h0-HXs(*kwc9k$GS;mt@Rg9n#|vP zlAs|5j|^5-Blz~gWHyzx-+v`io`chhRx29cr7atz8Dqw^K4++f$~lddJrFu+FbvcD zqOs1;@+(p0cbq-tb752m8xm&;;BbRw3iI9<+b4FL$ z!rsIc0sdL3$YFh}cfV}Z)bZe}`%(#Sz)4|(9GN1<7&)ZSQZ@GiQUoo~&Z1Fk7TBWO z?t1`&S%!YCz74_)s5M(!S|CBViyg@8^V=mW0;>znwpDyP{VoFQjkHq%mGfXgju1Mc zf`fhE9EVG@$bUlyr@W@C>h6ax&C5Tp*z|m8a9VPkOc{Hf{rFgNw&c*8Gt_KhbEhzN zlh`U?BQB{48-4$^&apFT+i(aYzurzVcMnT*Y~TdZ)hiU1BxxJoCH@5X92m9Xh>?Jz zX8ataobo-%BNy`CVNXS2G-{OlrrlO09U-Y?S!B?y3xj&nj@<*@bE5A4@ZvaNSM=s5 zSxEkt4FRMHD<6&EZxP2f*io)wvxj6}M}K3EXp!gJ#|)`D{d_nNdQu0353}}ZqaG{pxWKiH}+xHfCz2EFSHsqeAZzh95Bl|)_VN{CARlo?=o~Y*MI&{R( zFP@ojG%GI1aY}<}7Vz3y-bh6PlhTl@DGn0oYgvm+ye{WKK;ND1?%DK(eVal4kZb!w z2m;(*n(&Suk=!hPllwIq02%ElRdS2>UqDXW$VosL;osz7-Jod#77~6JgsEgOZ@{hj}1yM`g*G>#6&=Nxx zorax^hkqwi^gPovk2NxT{ZK|1I}i zt3hORS`<6}hToeWvfO=6IHXwV_-LF5Gk6MpDTb)Fdq0tu=f1J)?w~#oxSt7G!|RJT z;8b7%SHp~ioh~O&i`h2Y&%rg;700>?pFH6jtci{WHd6*g13m}I`i{=&il((L)udBs zRbZ>E>_v4I(axv-2j(B%z#i-~8Kl=s^`V2>E#9b@U4lb+{}YU18<3`e5tbpB#oYC0 zJqluXP6|~xnbz5Cgr{=i7760o;m@z|cL@YF-TFavZ|;Gm<}LsKu(;HFkQ*5K?5dy} zpe=>O0QKB?H6Ha#TB&Z3g50nV_P*NO$54s#&+KMgum{YO<;21|v&Q@mc29uMq)Cc` z5Hjo=tGkmer<*3pk^+2aP4}0z3neDzkH2t)v4zo29InfN*Ald-Q{&iFOpY8R*rECP zCGoi}99zQqx>Yk{v$iR+)*oe`l0@)jipaR9OkRt0Mu$O(z9sK1D08f?1Qk59Y!Y6o zEsjBxOl4p9JNqlmaG%T0fdPWQKGj<=lq}cRe_O->fmfvNMK1C&N`zc5J1|j?-&ED( za!(y*ylAF;;YG5#u`m_6RNvib>yu_&vY+9_wbiok4ZXg_m&Gg4(4r97ANx*?^~2f& z6!mAkISRaYxwL4ExEwzhAe+4SK;TK9Km%mC%;EK(N&(w3^*i*-!l^uVVL{zn5y^2! z`fKH%({9GREAJO=uY{CGewoW4)ZuUpFkUI{L00yJ@Mrbsb$v%Y^3^uC4YJQ-hzzw( z*kjIePqyit2EARKK?4LmTThhid_*4MV1d#ZU;O!|`S5k=A&FDXk5XDcjeYy|rMT+W zR%G(1q=6B&DOH$e?{UE>@BOyd+nxSb z?A{fg4!GH0u!Z##y>pOP!m0RDJ&S_(bK%=JDfuv99IW!aK zey~VtSNxhI6SP$y8ez;NKWW~x>`TMwBUS84#5zY(IaCTGO~uYpR`XtT(zBA!ok#j^ zy}s*XA8=>~h%Y^%qQoDpq`O8VctJjXvf>p1@h`qyql`siw?*kq33Kz2mv>HsP5t0} z0Xh1q;R#j(RV@6ZMoh$SxJ(hvKB&Z-tZR+@J6dV$dJ+Dj2>&?F)q&|zMa5gP1j@zv z2f$%^2XYcBgnggFkEVuM$uTIAM>CLcTPG(2s41`?&HlfS<}xbfblxm@7IWd&vx@=k zq>QvLzcbW%|JgsstvQ+aE@Xn{ve6Z{un5&rp3Xc2hosO@L(*c2O5d|AEOt`Fk-BO` zA?;{t{XKAA#gTsvwHUbIV`teRk9P(DqMh!6qu^k53h;as6?wyM=z#qj{K!AVbR~P& zGH-B2;>vUIu%^V_n|jbFK+~(CbM*JK``Gpqrq+5lYRxMSU9QEiHH{UjcTe7`4(KuL zZ!j^547IhkO?b|6WX{5p>wZ?O0Y~v?mrb?!(f&GOboCG_omUw+V13;7_U$pK?WCoF zLqy^zgKk~N#mYDy`&5g(77S?d1GE)8wETXil10qQczg<$llxv|lJ;26c;o(3U^6B< zIMDPwrDA!`*LJfSJIm@75AK<}qdtq9nSYuuu;eB@1V0)HC|`NOVi*4`4JE!amGb7{ zk4Jf{o{THNP;@Je#Xj(ISKHrD$G_mT%RlG5g{33{l2bs7^TKn%<@@NK_vPpJ6Y`gf4=$O{Touo6iye4 z3h_+e!!Swa^nbW>aHBQEzS`cA3&X6^Vo`TN9#g?4qean!^kM~4W4=XFk# z(J<=pej%vIM6ahvLXZcHSKx;` z`tymu2T_hnN`~9T_$yh-1826L{#+cOeD{X7s;;$l-X-6-Y;8G}mgk%Q`-dLpLxH!q zzn*>kxS7!2b1p>k&)B7iJEPeNfuBF>nQ=K=JSo!MH)mzB(?qM+3rx^3Ke!^k*^43< z3ZQc*{9ZFGrGi-|C(%%=ow=XGpfiD=|Ght=S?3}9p?43Xhl0=UJveDZDUX+_UgXWP)Qu)pMy1>w>6foJe7Z z;~iwO>YVllMFC>l^lauA4v!*fnjdX1) zu=&CEO-Dyk_eLgQ7`_8Nn)Q4Qe`g>b;d7TcO`yx1efl9gFAopPc9q?;7thets{=Kw zqN2oqcR^mm+)R|GwOq9z+iBho$7!6s|(lY;$6GoG26YS-8{ zk6PyYzi!K!xlRU?FaViTd#eG2RcPSj6hJ^jBxH!x*M{`3)8JuP_N;y#nCzPSU`M*= zL+i;|IUIpT`k?F|q~zv9wP;ls;wn*v-llw3O)nhF@WjQ~+LMXenD@$sl zPs%I|#045WS`VLRm39R7{~hHE*?wTj|2H|ls7JVyc>0u%2wU-=mE-C2^S4{Bd%uoHp&}S0^MNs7>p_FT`{sOdbVJwY+m{`cv)QzIW{?eo)aC#=JGA2e7C-;}k z!VB&oQ=xm%Cg*LKyjgV}^n%Ba;flM?f6BeS0yckWGzl`=evRyVxwhiaw)N#GY5T5D zae7KPGQCvYT7;4IOpSz09AXD1iEqusSGBQ*m%GF@~5zM{NfxGV^F-|S%QFx*l7urx5m`e2QWz^ zASdS>qqOHKkTSjb^@|7W>Pdl;?B|!F$P$Q}s18Qw646aj6#rlr;uxZ-44TH z%l)GJOUi6<&wgt=qxH&F6)ht7@?zp@0xpi9MENj9EV%Ub+LT>>4>5K~>eT3)$xtqrzuV0KtLf(_iaPz8QQ(2$-X!8g3GT+h6 zp#5bhpBaWf-py2%D~Pq`x;LQ4FR}rwCMmKsQHM7<7TCN8GrIGBSZ4Z-DePLlu=AonlZ`FgZ~mgP_5_Gz(c_e!V$qwuMg%xTd^ zro9WN#oe0EQ18skr<}rFeHngF_mXruORP?gUHylqGU^k|AygJ2_?PNPNEs?s*s#F> z*X|6*!it_C16L&(b<}W0AN#QYmKn;4Gd_5Kr%7g=s);p2;G?nV2|0JTZjJM6NfQz_No#kq{5v`vC`h%yzccpoo zg*m2uW|h_(Wl}n&X~zr6wHVGcaiKR^ToxQ#PbunJpM4^*_$q~Q_b>r2vg{i zYpltQm%_nxkV@_G{#aorCl}#{9RK{##WoZB@J;2vFkv|ad=BU_r-%twQJ>nNd<6_z zltj}qTAS~DW{0`hU4Pd5prN1?*bktdg2&hVm<*882iH}5Z`z^k3oOhr0qX3J#v46m zz(hp2i4@*OuHpH|ZByFc{;VZDR$6C&bI0{nxwt@zJd550Wk~fZkIjsUtCz#b*i7(v zS9qS{vik8rTU8~FSS5JLnY{*Q2`~{nuN~^zW}ct@{(|Lut?1CZWVBd%&Sns>2-1b) z8kftr72Z&x(HLHAA%fCl_^)SKFFtb@Q%lw8X4a{&sw35x1J5H+_Qy>H$*yxMZ<~o$ zqsK}I3}Kh^-$Nc~CR4o%U<+G4k6a&(zpN+mwYvJ+IB}n$?Wv3jL^X!#i8m_v#bs5m z+w7n}@x%Z>lR3;_%n*|tW=*cC{M;=eWJo#e+Y|OwXBZg)4So1|0nTlq6maNxQaoz< z%^kfhcM+PtM2q7?Axb^Zif|jrI`1j8(l9Xx!_C1PxqhU$LlyctJUAzXlKl;x{elbY z_i0W}^nAX?ao#ZzP&$4#Hvap1qGp-C{tZ`r&Bm5LBE7dZwp&vLcts3ZaV>}w$Wtl} zxLVfsv|z&r+@34WM^0=GuBYi|k&(+PG#GF&zucu9TXt;p3f9xo)33Qc0NWyKnbyim zGRS1Zb20Dn&2HP+JcmH8)UBbV#a}{txBBa+(NVK6wTTrjcScd2`^^AsADq=M1}UvS z#%x8ud+tz9W^ti0OR?M$j;S_%ilNA;XH+DOSFDUj7v6p&B`hq4AtJd{+?gCcjFeGy zB$0`hH-vRr1WHQk{nBd;$Lm2L9y zR|auOnIs?k?p^|`4U0a+{C#Q{f=5oY;o1I%e#e5s0wr`udk-%oGoB}@6N zeY&Qs-G!65_nErcLf687gg-5)-2Kpd&b*VP*^Vz|1vBI2a#t$}BAStwfl9zhz( z{NksxNhYp(p%j9jT#4>UMeyqArSNb^Qjm+7odrFx*8FQ5R!j{*-9jY&jz$YXVMPn-S1uL=E3J1Z+z~IM*nJdrlH?S+ z_L8AeuH-mb3vmHDBDM7!I%kt2Qb<0`|K{;$_#5Jnacng&#L>ylYqDz9eQlPfPo-^e z&}J*%6_H$2Bk!x}iwpTuhCjLI+QJ}_hI?J_~6dhr)K z=|-V$1mOXf38V_fu2L!LqV|v>LJCv(zP`fnc*HCdX?`}PS__4aUKa;Fspe3{iir4A z1r|L&Hy&(EGb-~g)b)uwfk`l+jiO3+H$Q$h!NSjiMT28}e_5^9@i+bwfOB9a>d+;&Trsm2%jqv+MboXsTG6Rx`g4 zyW1FAv`M=o!#Ov}44(vczzboiBOoU{@IM};fC&I0^Az&!S{Q|sKf;l}{FvR_0o5$E zVUxaP{YCH;cnhk9YhPTpRwmI9hW9T;(aWS_QK1-frwjYoAJ}GiGGbOkdB9k2cH@!a zpmMTCi&$&rOA(`X3A2hp#GrO zS-MoptoS9BP$;f*Q?1$GDoPK8fMsV$97!Qk3|avaWZp6BVc6WG&-=^CoWB!)l`!Jb5q{>8tbj_;|#d9LPQ(Kv+B61$A1#1A#PzINSU` zjn2cnHO{cTGDXGLR1`_zsMUYDHKeo-rz(e?mtF}%iE4zvwDF+X8s2vySL&N3ZqHUq zl40w;pj*}X1<&S!q7)UQ43#r-f^TFe{{w^+HMr!U>#+|m>5te{&L5${qY+;~>h{V$ z1@-g#h0LIT@A|;jwy4aV&)g4Y72T6e(z>|lT>sqfz+11*4GN~DO&{!58Twhxns(;^ zJ=<#H$K*8+Zy7!+8S7BsJHcb0GQvof$GBJaZeaAo zZM8l*qt&g_1kU@s`fMHN^r{D?)ZhJ~PI%LI^{y>Q*C2IjyuK1*8)Qb`FxLFQ!=!Jr z`nFd8rih&xcE2fpcqaJ5!>Bt%2}i!v1rrs@^*Qv9P2|5f$~tr`UVmt0-Kdgl(UH0!bi7M(dYgm1+9v5EU*N^~0nQ?-m*evnI-q=;ZF)B(Li5!K?hu-H2b-5GHf zI&9B$t!46AOg)^Y2yJZcw%%t-QD5yX%Kb7|bB@J|5-g|+2y#1%NR*gOwxS;2 z+VMfQ39I1ubmy=I;Sio+-DBYVK;bw@ePtqkKY-C}m5uw53QM9!YjUeE$P?v{<9v{} z`;Oeqb4QV(M3aTnhdHMt;{{8Z&g=$%>sy9DBLZ6dG34{}@wn+uHV9|7d^mF%tr5$1R31L!wM}7M2nw z0_CvOK{ap`e34~U!*{4Em7&=L85I9clUUOfNd#^l92yZhZSz3KqG6PDwLNsVv^>)* zxx_R66TBJhK~!qx?M;ul_via1q#_ds&9kcG65ymJu6uw#@$4{S7k{k)Pb!V88Mzi` zC}T=({Sf4i-|rjKk3SB-qi|g`@tv#iBU{r;$|ina2JSqaaxv|nsb-z8rEd@qFQOBf ze%ifq5qpldk= zcFv@<`a&Ty1?pRu{<-7l5V8hU4S4zS-!eJ6t(0gD@Y#xqE9&zby$JsZUH=PXU}v#j z=PP>#g)o|b*>e6Nc zJVZYV1~bELp6}fwjv-SPVAia*W2s?ltT~)CXbi&JK-%7DBthT=-7{IpyydBfvpDWQHKtN0j# z{r-&H;Y{uxX#0f#1u@>1Kqh#oZtIyOJ%)?O5f;v7Szzx$t#SScER@{(g*VlrqN7o7 z8xTj3*9ZOn{X1?HeW;z1_l?nTv$nKZ{lc^^h;ukIk`Sk8zo#y!#=>jnl0iBRMLW!N^Ezs6;J6ry(h)v zR{43xLH=q2It2|&%Dru$z2VS4e7TWeNXr{BL{w8+_{U0Vx6%9K@v&zY^Cx2(nnVYw zX>nQYwDuiOBRFV)MDZAA{@1U!Xp!!>LW%-R01O7Ea-j(dK5LRRO-Wg~ zUqCYHq2bKwT-ieW7U~ja@zdScSB!V?QoQvwzJKlK(6pF&)HftqiC2E@1zS$LRlEII z+gJwsA4%TlW)kvH4=MKK#}3U2^KM_^yB|6@SvtKSBl>?Z^%g)`Zr>XyEiKZmv{E81 z5|YwLe54@VAX0)TB^}ZzNOyNgND3;5fOHAS0Z9RAsk>f(|2y|O&Kb|lIr!Gzd#$Hd z_eS}HU`-}8t8Pkt>w;t{Q9;Xf&!|3H+yw;-ZV^S;8Ox5Lx7CpnC)1GI`zCSp2syTm zbZ-fgP|Kh`FrMx^+@+PT^Ihj|92C*_pU<^ z$yU?c>kjwQstjD`q+3wEA-sBOM;aJa`4h$?PH%6;>F&>xGi5 zAjwek9tz8`@Fi1;99NLSi3A%ouF$4j<8g(VY8FSo=MYp0x6#P&;bq;3dN(p;?+g}s zNVn!iN5;t7M@Svfo`pG-q7Xjn@n+9U99ap~K1a^2n^w2EeE#(U0~M*TamKTDZq%8h zIsz>Iii>)eU!560art9-{k8G3wBHb3=7`~rOy)%v<^`?p<)ewUpijfJD4}2yFJESp z+KAE!P8SzW^v>FTkEE|f)G2Ca+xmntL_xa?7k9&{bks!>PXP6q!^^aL%7r<~qJS`_~2O%^=s4A1aXm2&=t8 zj^F9rh>TuEVg+0vI^pe*`2qwalYuHr#O(6o9LXrXBPJFBh>j^=7|fJIhtGmIO}+5e z|Mo#)>tOj(HYL)AL!X^}Me^dZrm@>Ct-@tnj_FHH)h@Kv?%tRc%cF4Lw{-EauCGSImp~d*1D!rOnnveN@4u!!Av##YEXA?r@2x*d^Ev@p%z8U zUf+@#MgG&h$sz-HRp(DqUl~+TMEdZjVp;oahi!U^tzqv20;vU0k-Wf1>_*RXhu?m@ zk$~qqW_u!|wa0a6q!Tmm#s8pq-sz&EQK}8%A(kzGX6i!RDIv~}<5_22`+10*WLe%n z;(g@OiH$_L*teB~X{)!6gcI2SxNJcC===*{!pphA>Ll`6!hwnA3U-7-7L2CZC**M|?8tNhQ9b zV81^Hw|i~Bsu}6oHJKDRqcW;Lv|9Xd<&4rLJ5xD3zqfeV`zv`)ivL&V^^3vq`cj>= zI@BHV&)*50lgLQE(BejgIOxAj3X2*!brv9Rs2OAV=W)*n13{XivnYlRg5dqfk3?g2Dq zq;?d)#Z-?ze1|_DM)hPBC1rL_V7Zv`2TXZU8tHkP#u@!`dqm)HFI~~Pz6SGsK5PVz z>z*mi>d2;HZPu5#j|2DQ@to2oJ-M^H<@F&0n^G3b4L&+UM*lLsV9k2Jt(w!epqQUa zERQiHQ(Mk^_1Jco9lBjcvuEB35A{TkuhlcT-D&+tH0m&#a6WKS!L8nmN$Dp;ZU&WO z(4FJ08yRJx=k3yEe|z@uPfHYoGo8Be_NP>08x^Q3P1$w56&pxLJbwI8CQ-NE-L$PM zfd%ch%k3G{n`O_{;&)St^!1io?k5`)wxO(M8WwRk9D?KDBv~t zZfUa4q;tw9?`i)V8Ly?%1nf6gA8^vq3W{0AKUUvbH+H`y6UDy%=?&%FQR$`IqTZ#^ z3AWs_s;pyPm#tv0*@*eH-DFw%VX*SjsoH4j@f;h}pSnP@X)5`^}Vf=&9xH$t4kgd)KNE~SoUb({YG?XdP(OlWGD|B>ER zXxCU!xulgAbK5^&FO~?teOPP-owh8e{dS3b%sF}`_i@^j%g@n`kMu=n?F*s;%ufzV z+LSGmpQ{efeLJ4kEWcw985Kw=Vvh$0D5t{-Y%2>09S(V_~wv zi4JtR3%gz)- zoN^$66%YLl5xSmp)}2yYMN6F`j94^%9>5ketUt*^1CI+}l%NM2I2h=!O zE4I)6VX!|px@RO|%m{vEH%5zxmComDG7Bf+qN80YD0%G zkK61-ovLQep2~Aadfhyok#5}M?xOReDZ-@0X<7%%kz*I-MXv6VONzdhqdK}~PhowH z5ir%q-6-rgKEF-ZI1jDs?pS1Xt$v>f2@6{fMK{5qu7Ougg{(%XGdg!_kUQQ@ZfwOK zwk4OredIZ1bvy`18#EIelD~jO=|&1oNEUhl#*|*3#@RqXZ5P+@N#|q z!RWljqF|0t1&NOfXL#03gSpK69#KdB*IRq07H>kn*y1b(1?n3HH|MpMa-%bbVxzyI z_~3hmUbxK@)`Q$~iJ<7>0j00`hZ0-+xyZu2MwZ+bM}EBboNrTpe0E@ootand{hYYJ zHDkkU&o)3pZE>KB)XFv>i!h?0r~e2(t}sPb45fG%@VqZUSuJpOmXX1T#BOzhzhftl0p6_Z5tjgA0%+((7eofQFN@U5_j3g8- z<1b7H)Qs7lB=Z3WA8q;OaoHyCNc>WV2X!x+FvX+&p)d*#Mx!}G!eDMkxABhk+^5C2 z0_}AG>E*gIzj3Jd>j92V;7Jq4Je5 zeXyo0hX8WJtq=tDDq5HvGm>gK;0O#1eBmU7kqxgEQ1gPc1;GDQJMd}g>bqx0F+)$Z z`MGXu%k}V{jc~GjgF1ydN7q_1E|o|i0LYV;Ui6gkThxj2AHQF;jB*nlS?yM+1Z7wC zG%*qH?DogY7Tb&Mmv4t&e(RJbAjdxb)A+$_d8T=1`kBYiD~(Ocq5h_4MEv}09}1Mh zdb|l$bljpZ0>pEiTFMq(a*ZD9B($Dy@laxtV}G`G%M8^o8|HzXogL&I_0dyP28h08 zuTcsZRh{}aBz^(S6{UqR-e13c)2;u9s~H+lQ#$c@Mg~2%Q830S{Kc4|WPWLhVf~*t z2Mf)nB)voF(5j`5pS?=06)NCi*ID2H5Yp#SI1b4n90#0H*8HU3?c5s68_&Az)@p|` zw-y#+DKd{Wq%JnBZ)eQebdwEE@2(AA+1a|@%w_+8iRRT@$iqBiGRuQ*KK48lHk@S{8*;j1P*Y6EO!E3ssH`-kz+x zB_a_~Qi8CQ1GfKrQ)uv}7?t9odtYx>iy1L=O&M+?4^hodd59YnZyrkFMpkG zA!^*)2U#<6NjuLEVvZb)tpqhTHd8KrF#c-)lstRS(0D#xzj?8JHi}v9lC6Wbj4f9K zhb6{+(Y|bL38$gpM|pFHg=|6H{w2cA6kM-MFv2Z=n+ND#%r?3r)J7_ikHn}jF{8NX z<H1eZP zVt-pjftiM1miKdC@jRzcK!>7IgF<9rEB(@kv>!9u`$%%tzl8V6$Z;OFfLqd4E8Z7Z zqf}vX*)<#mBlX;N2e|?66fE`v%b+e&>lI7Y!9Mv{$MEy&_^T#lomi6kh&=I`_#`Bp z`ow^zS-H$`9{Y2S{DnFq@Dv+N{LX)nDPcTs{W~)v7;sMZH3|jW*pYubG4Zc(esi3(BvZCo;NV!|NloS;Wi;IgZ85iN_4}^|cI^Oll zz=sbXQ00(r2goN~cTV}>QdM%z5!Gv)ZZUeSgXUUPG1jP>`jOw|9{t@>yLGAPxn#EGRd z{jl3hw+ktJbvYjA|8Yol!pvyV$HsN-?bng~Xf+2eWWTGw8X`ZV68b5`5?b zEER2~AAYix|L`33I6vuC00*;uo~8XsyI(3!-iEtaY#WaFFca?O|6jYnmjMy#7i!6-MX+G_Hl!}cX{PQB@`vw5z} z_#bIY+m7RtlA-!$b<2EFa-))>rI9B!%8OJe%@cF7Yvq>X3L^fWRj;3Xe&B-i<4By| z)o5R+5k5i43o$G!&^M zY%^n!>l!#=C(mloK2$pKMf(D>z5v{hWJEgNL8D3y+G*l+AXS);fgTFcPQ>SdZEEark+vAg3c) zuu!xG49fxxEbT$`Hz%im#$;cj+?V>qqm zN6c7fAC7Rq?7~P0FI7YN0Sy>;{LRf#+POOA9)o3v$MhcWlG{GngpMtoDk6`#yz)Dr z0ZSl3aD#zUux9PFrk#f-44W)D>uLyg`cl(nJ4XFE+xp>`UoQE+o^BK+2&co&>2)`pj{+-cl0e$wx-oVbu3lIA{|GsC85P3bu zNNzLj7&>VGhPLWyB*%DF0JwTRGJaa!Fw(U8vo4?jf47O+as#n7<(pVV<)M;HM|1g-XQGwqUH)5j zx8@ce}CcvjM2O;fa!)S0YtUwEr`|Y4_xovE z{2@Tc$xDg7frL8Hq+|K9z7MXL~O1Oz|7QX_4P@kh0xb@>uXQQcr)?8tGP&7S#2}O2&FPJJ+bVF;0v&d_QD{s z@l|%@b!aA-=_kSnQr7(|^pjF4MJEkn62hX6TU25DEoF!pj>YX3Xp9~TF4?^OKuj?H ztZ8V`F0-!`Zm!OC4q(mqpmyAWY;@!{ACl*<{sD;l$;%C+r(-C+MMw#$)aEMIZEc3o zviU1F3v+&H;Z5ls9#WQgD*shY8R_#oXfZ+Sm}o0q2z{I>>-Tt>DhJ9al5lGEGAZ9} zc*UuhprdMl#|C2~*k1tS-o3D}kn`!^DGLHx>`Wh+0JH!Ddsxs+p`1Pj*imcm@ZYVu zfwVeRx^n(?wM%mWO2G}j6Zd&Mg zgsZCP4qwy95vb-ix5K8f+FcF8>e#C4_*IuP_#_lgEjGCOQAy-*w{UkK-T4E1%s*jk zKTqQV>^Xuk``A!Xb+nEfM9|u|@KOj(8z(qg6RNyQpI=P=_s8Gi?$)k5OP@qwqBp7yeX!f$b zc@&7)G|>DzJEg_XcDfN{)qcVhS&#PkgppdcP=$Ot^xpZ;CC{2edE!~qLe1^UQI??l ztoi2RiCymEM((FISnl3i(6leO8K&~9-smTNeonmqmjTVcEQhHS-}ZCx<8<97JK0LO zUAg)Ncd=?9+_5mwLH4z_W(ULvkJz(}0qdv0-kEuMQ3H#qf@w69n##7Br3dp0bMD|7 zrytna{`a4o|1VCz3;kdUg}rTAF{6{+iznMpWk%4N&e^SR8r8n2c!&Nta{A|n%JR(v z?`yGWJF;Wnj^9bc8R_|?XbX`!BX!*`z^h*65ImuBLx6YCm+dto)A1(CJ|NdON>5Fh zZ@u(XzpCkzae~LQ=Z^Xe?%XX>ahkgT7;D7H-J#%O1mBz*n)WbZ25tDywK!_hlxdWl zP~-q-H@w}As;;?@6k5o}^0fw3hR7gVB=J4${Pc*0F~(xP?d4>X8wcadeNE72n_64r zAo?B{($liqG!Gc>4y1RrOY?AKHIoEYDw@{C+pTd?Z2x#Twnu=i&|k`Dcyh;&`Ig1= z&RrU zMSaUB9M}X54c_E40KzOREwPa6{{e&4O#730VhIwJH&<6XAiDB30+=CVsB%74G_BCu z8ZH(O%ovkV4o#p|NoIcy`^{&}>Ah3JC8%dHJ3!Tc3%^BUA3RZjr+JdN?~U1=gc3C_ zo@B_=)!Y=x$XrS)G@jq{oVyKt3o)!@U1S-H1JS>SnTZH|cY#U#iOglG^4QRQKi6Bj z*9zJiDDp)?*?HUA+S>lR^}lZ#s^sFSa$>P+kEAQQWSnLd#9}Tl+HEvZYD`$fs%%ef z#S9LVEY;9L3lc;{lPqnK6Rrr)alUQtA$oA@>(|6*s}H0M_tUDY??4s21 z*uRZaf7Q2uwlZb@m9;Y+z}<|gl;9-&UVB|iDD5g6DCB2(`mFxd%|KiZnAEtD?LwpS!|=~ThL zzA=B|!=Y9DbMUr^D)U3pw<&$(jIYJX?meaY;lCkut@pa0*ek!2hdR&ZLOJ@bfB)Lp zt{*%c>MIfa#Fsbdwh7s|v9(JO$j7WZV~tMj^Gklfhf`i5yr)JY)R7_K!zU<+g$6qe z1inf*HuT|WqjxOrngYQ?O+$l@Mlb4ucH8@limKhePE1IhJAc7NG z8mmoRJd;8SIz5kiHGRQyTcpPNj$c#aPvS3+GwVqJ^_RG(ia}Cn(FGJXpN@Ru6icZI z3hz*;$@1J0unnDwKuL3m&5j3dZ>w^@>Sl5Sgr3FC?$}t^{W<6M8>9}^w1A{aY-C!; z+1A?H8cu_?RjDxjL5N=7PX9d5?XqjpUyj>-(!CD6*|c)m74r#>gj()Ii!6wEEpjPj zdALiX&?DvVqu$(>5;p6!Vz(zffEQ(Xrn4?b8{^u`DpQjOH8gK7bm37TD;JqgRz(ws0yYG z&n<4mpAp3z8%UOn;`lkWOWv^md8fs&@-)vLBVkxjLH3rMc2D6{tpRJ*CNRp+%0 zqqfyfOL}~a?9;i<_wpJq%XgaVWMBapqBf$vNY_ApiV<7N+YB7~XV(MFc;`l+i*3BS zDs!*U!1t;oC#{pthyL$DiKvl@3MPEqadZwU(Sg*yS(EGPVh5^|o1Q@l_>9*hOkWm~ z(X~8^jl|kX4JLtSMVOHp#ZpRpuQnNl9r8YW5310&ILZ$C(=^4o)sCaeNYF1?~2r*9)XPDFY=veN3wP(RqNti_G6}dySOqK zUN38h=s?Xj2t(A4-qj#v7jwyV`LUh<6zhHhxg=YAOZ+Zru-1~laeYlmhz;?lDj#m$ zr_?UoX}#Y9_*O{8a_vX|=%|@8#~1fE^s?C58oK#CLB7z{BE-8W`r>%!YzvxYMkKwJ zZZd~<&x>|0Fx97<3;)e=6o=*6{Nt}Q8n+5`Oh-vmgA>0VjQF$=gbIHuDdI~VE9J9) z+#2s8&l$z9h!sXbTb7#?KJSe@Km>-LSzTL8xjfz9cOTo(Mp3}HlD)>3mX=ZzMCWjA zET#lcT!>Uwv>2_37c@)ioL=^V`1MNNPiW-3E3$D5EXJ;&gYcUpl;v$yftoFi&^xHc zl+z_YMR4+w*&Ks%Fsz6IjA2q8NqQ!C{fv^Wknp3})M~;MgI1FfJv-~6&ru%fZq_*I z(&Y;ljhE_v!v3xR?!MqeiG!~u;I;|o4L!5ESY^(rm6?R`HRhS*uiZr=Y%l*E(6S|R zqlVPa*-Wio5bJhHl3q)R2F7~^;x(?szT>rVaUp?%FW`RG&jSglu){tr?KL99Qc7n2 zwb}=JvvTxtiJ(4cRn+R-BLk-F$wijAkn5NZOPEbxrm|)X8X`kVt|x64?|DpR&yyXb zHL*3oR5L-Fz zFLJtEJE;U($HTYZXsBGa`#rsp5xekog4ap2r0XWyd%tsmpo(++zu;C@AJ6V8f*us` zMRREly+uAQA!1n>uB-EVNs-$hnp{!2Cpo0o%5{(zCwH+0iRoyA=*^Ll{LVEJ?3sIfj-51xE-P5b z0%Nv+NpF_ha19sB1yF${m;-@{hJ?3tBc9OrbNw3riGRQ~u=oJ-pU(vERr(&3syY2T z|<6Rg~`)#RZk8uN1^eJ<* z$-9)!Z&)zrnsef#DS;uhj96@Vqfw;CXGmF4?M6!Z6RR{i_Ge~~jWnzfPsu1d41_g* zu_}ALL`k3gbFgkDOrlIJYcUYCps1tzaN|`5FNL;1|Eo98E~gCm`3wgnlPIXiQsRAI zD2J3_P^z44eOdiae5;|SkquA3R=FpjbGf?^lLZQ@@FMYpGoqxtm9qhpaIe0i^PLuX zxzSep$BZFGFvMXv2II3a`b)4S0#Wnifw0jJ3W(;}#X{s81A3fEtawQ3t;6smDMKn?wYn22-_o)Dkal*QfPhv>pa_ zWe-W54wT;3E@HTqzCrf}TLFc7ru-b0#3y0&qsqFCCq;FUJbs{|wR%IB>c>R~pTiFI z7$>tEW9aL2 z{xs$0<{pFjFBrKRYC5`iS0mftfqa5-iH|l45ac{gNkMikHB_F;xpa7i)BxZ^rJvCu zU(<73I8!?FW1+(ELudkVt4 z6$pWD$7lL@mI9G3gg!(BI20FJ}>0eKOgN};;xp8WGdaT$|>c4$@ZKN<+wF{<65Tosx4PBlMUVcOz zng8TF(2-F|um^R3aeoI!=$4uxKMAPZFE?omWUHGY%>v9xu_&QQ?&ucEZ5IaFQs~0? zBXC;k|DLCZr!@4IX-wap(!71i(DgTfqI zQQ-SVMn+x%s(XaU1*@NJ|2WzCH91L*jFvfB4kAHt3jWKZ*0Vp5#YBq$@wc0EQjya+ zbw=mCFKngYOe-wB6QIe2wPMew*82MpEhye#|1UkN+y;VVc(|K~I^0P;Bco6O>(djz zEe!%k*jbXw=jnHyTL_!x`UI|}u*T`$0V9lK>+!a?SSeHb7#~@``TgV}swxY$&{{Jl z7ufDJAXkeJ$%gz1W4J!;?C|-|Zaxy3b-}D?zj&_QFg!C837S^z@p{s?G!=Nq1eL0q zY^?F5;=iX^y|wHt0yKY}``!1PSzF!u&L>$fp5^V8Q!`ZXJ8^&96)K;%q$T->9YaP- zJM|(J6py(sdQ&5{zmr{yV^mkta9V@(gdT{H4?zfdN|oPOf$sm|YRBiDNO==HG2*5~ z=E%d4#w&>V>aWPZYz5AE<$Tc6UL6$zndq?2@<_2BSJGHADyy{K{zy+#Xp=4`Wi)k} zShW|y;}&vrU%dXS`)OCq>jUSoRw@bT;ueb+ZNF5lYDKVvg0eS3_FB+}*CHCwb#T-Q%i~!Fmv0C+Hf}92G`Y9+Fg{Nvuu3{HLDQ| zRau5P9U7nCrWj3imk?43WqQ8UNUc{ExHk4?c>cZTIS(syNq*8?ZFa+oYts&l1SPw2 zl@S?p6b-=_H1{j;wX>y+8XP-8HY{ZhD8n%%>*E!UOf5)2R0%V4u2wNQqN7t(l?v03 z1Z#uk*k6?0BhKUsKYgL(3f?Gh5LrYSw$yr+puquiJ5}C4nc%&X#}8;q(JH8bpE-!JdV8AH%ekyMnk~ zN0OU1=97o4NIib!%Cy5@PNLFhKvX;|owVjGH5ZQ;t`-UoCdFq~%Kx4HS@-)=?b47t z#=+-%Mpk%pCVTBZa^=brq?F~t{_R6Us`xT!4)?rw;dD-6p(cdUBJ1i%>6xoiU0Bm=j^xP-Q0iyR}(*on>fTU?#AVs`v@H${N}06EIw=D4Re$KiE1a{E zLL4E3MQ=SXUkEN;jFn6~2>f>VKt6Mnbk+d@8e{3%hsd-7;mlQAg?*j<;V( zg@>)blAuEt9&<@cS;^wb7g2WRl$uOBwc<%3zUb_^nCy}4PG<=*)BhT7ANw#ME(;G{ z#wvV{TI#n-=A5b0*?UGMpw2*j{LV=nI)czn_s1C~W#Xe?BxnKi@$aXApSN6)>zAj-Q)^BZ`j_7;t0J+__Nu zGKV$}P$+5AHGCCZ9619h1Jj-laiz9+dMw)SV0M@BDUaF`CeVDEDA_$`B>7)H3UU^O zt#fARLc>XJCogc8c6L7>Emo;;XS3o#tST#??|)AX`qYdp<5-JiI+hN825EouukY1n z2NOmH3%W9j%*&Vm^HuNP}{v@x&aZ%?|6l^=EqW=Z*}x?zt>W*<73 za9dsM_vbf$0TcP030;@(yR_?et z_fHd{IR^-fC(#4KQ2Ahzp&pzve`8NW8tDwO3|^6dexN?1w6cvh zM*NSW!C*>ydJo-?9h`sg>Jg+aob5?n)=mwuy!!h48_s#~sZuuB%c4p3>A!L7n(5r; zYo-k~t0#B<)uH&CxwnQhY8^}ApyH0P9(W}%h2^&7`8@}OQ}R;$WZyM8CE0&^32VZw zs_SNbJ!0Mm1NCJjSdQtTyT=XfR%B0zEckv01df3IWhs;+=?I2208DUzB7pX7@(VNh z;Z}D}z`7&?b!v7JJ~0X!;DXgJ+^yl|(BBi3-(vcN~|qZEjF; znoO*HY*sHUo)^l|rP3(1LXB69y9-7h7!x{y7Q!907uR8GxX1zoH8a7`P|`HNixbhc zyaZFD_;@lIQ#ga)Z#B&9Ajt%8Gcru}kEJg6q%39{oDLkt#vbxLJbs&pxH0o0bf`UY zTrRsYh&K2FW%b)Pt2_BiUaYhPr8q8r+B)odsQ?7f63B1d_?z$Pt@MO%nom$Ze*AB5 zL8O{I5-{)Y_>8rSxoOMwq z!J36?0eNKqVfhoS2LuKT2be`J9{#tcru3vS89)}_Q!XJs<$=N!KL3OMrciTF1FKR?-cseRQB4jmk&Sr>QSYnrI9|+-X_q|%5nXNQD8Kc6iAEsT?r4ftp?))$P1DlecL`-f`njkWITG^>>WmmLbzd8 z-FHhNiQkIR3ROa^J!Hq%HlBRE-+6lFL9`w#W*H*dNcN&jcBZ><|&ifEW@jY%$A((_jro+CT8Q#;b{S$`Oy%~f2xDsnmwsq?{Bmm?MlH7X?#qTS`+KCWp%yEjt%WO(r zNXrNbCS*u($?(XCc44yC9c#U&jUkxmL~ih7UVue4$H;7yiSHuxgZ}xm{?agvzX8K9 zf`?r#$u1uW=a!Lt(HW;*Gyd*Y`i9C|&1?)4cQMrtwP)JF6o@@G+1xnaZDJ z4=??lT|J!IT{SJ*bka39We?XLr@R`4(NX=uS#AXXr_kHO$)&1=-E2N`o+CyBRy^lW zY{^0j2Htnseeout`M(pqpW5%Q8}RT4I@3r$TN^a3MKtx9s?>iaFkHuIuBx-a@!pY| zMFzD(tbs=&=V;iJiXd?r96??jX)YKr4;Kq@;SC8A4N6^#BNliFfs$jsW?5@+{6Z3l zStJ+*wq~(2U%%XUbNs2dhIGCiV!#u6khAiLwZ4w02P3y?D(kQ;(8~VB)Dj(^{*E^$ z%Xr|-E%t7{c<&zp^DpG#b4w zw#6wf!!Im9&Pp6(UP`R@6~9X_EpFj#E134EwbB4LkDLf%T5#fm`q?c!hQfuU3x5m# zs7Wg|ylY_^;U@4;hFpfP)HMGFR_hgZG79WuA#}pQd_IOjQ-@3{Un-6KhbMVBLD4Bs zpfV1INUHI2qiT;0P`?G!au;cv36ho%bjos~ygu;S{9b*rUg-C+-# znEMrdHg~s_YzP`Vby@jncPM-vdB0jf!UTUvwkq6{E^<%Q*QLa)lptPh1H!6t8o*l+ z7WT&+r$BKq^B%a`6FeZUf`XB=AFsJw^l3d+VZ~mjm6Vu2wfcCW^2+cQ&DFVSZhm!> zt?ux1lS%FaBGrN#+6?N~3k&W!rX&+iwH@|xS$L}#*K+V6ksd4j}q1POKuDm)ImV02m8xwK4aDqZmH8q+M&Gh+8=OY+^%$)Pn zYvt{?TKGo*(@X5m-+e^8a$ecXULE$(=45O;xdT(iAuHIA~w!?O8VseIrkvw%S} z`5`AR>YZycH{$u9^&M$37yl`#g9s+cc1$=`*mLcGVkZ$InHB1X5IJz;!C@57%9Qqb zrC|Sc67lp3Fg@ssMUM7WJRh9(MXB~8L}-=Gx<39NKK@!jSbwqVY1P}PU9k-x{BKqX zX61YGn6R1i3@l@470+ghH`0Y|9BCLOf$koS7nhD+TVAyr?`nY7g?ql|=aP z9Aqb}Hmd`!5q!Hl;zh@w(&bcTbTE@eRYoMQ`}+H%`zm%AqAy=v7mlo6(9@-O82$ULl9mCHOjynBh?>u&e=*hf zucRq*(dOL3uC5C#W4>|2G>#1yS&7P(WvYN{J5u7&$b;*?!j{4OLaO&wE>!i;TUUG) ziVlG1C01v1Xz=}CgOH%><6X^6^RuDfWyXq?zvp%ipGsp)`zyF}t2oxIS~3XgT)w&G z*`2NVhfN^9;{pr#5Q!%;Hu4Oqk>q$G|a zrlb4ubdQ0_R0qd>boHSCL_lq^z}X+w_NfgWKlclzkbLw^~THE&+1M z>6$FfZUBj^4ccea3tC1-XBP)#9pIuxk$bD&#*3sBi$RrE*_zy?5U>5Rlz}|{;)%pG_-pxSX2HYCgA)?j9auK2E8pw9XG({L9WpJ zHz;FLyw*yZNp-qzc&+j-w0=2BVKyi5HCP>B)^bINabesjkr6EqJ>EV%qo+!8x?E9AXV6C!Pi?w z7RaBZ^^hL2@)W^!T=F&-K2o7}jeIChyzAWFykFhIelz9Y8F+M+@V4Y&>=z8FvwVWg zGYu){^I#v%9U)`ZAqOu0+LuFxeovPl6$#BBd9rpK1%?%A)f1-+j6zIgt7xi%(=y=a zTu4&3G;RPiAeUDECuKQKZ?HNV2$d&`z6xSronEw8+)6ulBceFR{O9d14v9mx*hkMD zx!Xq~w8u}X@;?zpewEJAWeM`nv4_mgni3qdE`$Gob+X@zT;b*Kw_7VFWMDK>D~z1~ zzG0nj1ve+Am8j5|#V?({p0dbBq0lcOce}0?$g=tyeE2Gh1ZrTDQ6DrUiTpMGZUE!W zi!8Ftvq3c9V-=B#lfdg#kB7rubOK3wxS}XC<4rEBoA^TY!l#W}uFR!Ay;L^N8;){v z_AI|h74kT>vG#vh*5}LH5)!INq*+nz3DWg2+3Uf&k+IJGM2fFtkFO4G)LR%A zlKr4<vrtXM}kbTUyBqi>t@@%Kcj*UMa!y;*c8R)f2m3E0=MIa=O%Rzq#C%*Zyx6% z(Y*D!_5)APOq{crS8u;aLcPbKP)GowjDwY+?+Q^Nj>QLO|Zh`BXgI2Lc;V%sK1e%>#W8`D)qwJO^@4YzyCq)uF$(@Pq8Y< z+{#PpdUeY{=$WoAZh(#$kkE|M>`7SufxFVR-8nM2Mc6Vq1o<_zpizkm@t<3|Q}*XB ziTf0Z+AY8cKfY1D%cJ7Y?z;7cbu}dL>-S&J5>1K-Y2;-&jehY*vDfJ5B@;#3%b1EK zcOtZ~vhm@R>y)Jz*!}0=0nLaKFv)kCN5ltFS=m#$A?XY^!3IOV!}n|)Dq>?9pkQ_=9>p)IV z)Lhozr7#xJ;3fYtT#@#j&umr0!?#+R*a|E0AfEaqI~vSdOB+8$Sdc>l*72;t?T)|d zRGZ`D^s!${Xb&~m;WJM>pS4x)`Q3d7f)e2*t1bJpt+g9vC`fI>6*1ks=)ezW*RBgr zckP#)`Nh^UPClA1ru^{%gLa)Oj7K?HE!;{-PDj?g$bdC0&U0#SdP@3{jgT2lFIqi# z%q0v=>txjB*Z_;LXzrcrKMxqN3efa(nc^q5tfCFQ6H(vKNGAz7;@+#fUB9mSUQRq( zj5XK(J`;(h5CBO#UoaA=gSyH`sGOdall1lt$PZx4(flB87 zowcZmxW7egh1wHXH}K4!_YA{HJ~E#4=4*qeyc`O%AeW{L|E-aCz3$3S196dSBJ>sC zw1pO2ZbpAm#4&mfM*AtFk|(4ZrC#=|hKIhlg~y4*(%kvXOn=7pL`6^z#$>~2uOfT##0apK)#%E2@x6* zgl=@My!t8A6{oC$G+%=7CI@%3d$m>*U2eAK4Lzs2>7k+l=EWf2Cu$hdTd{W{3OGym z^)xU?ln4iDDnAr0CGj)l6$*LJKYT#<7)1!*6wB ztC#Yw-qX4XzkQj2Gx_R)GsI79Sez*4p%mr*w4Z3z z0}C`Su%KdUJuq`sfZ!4PMI>yVwQw$*ODSI4c+B?;Y=Ei?m!f^T=81w?WM%1KY;X$b z)a5Lgle)gu=4Ywe@`Bja?QQ*+ZzR{o@DMet$=~m9gq!h@ufxd!*@4S;mBSUfb2!pm zaU4DG38K|}4(85h`Q_CoF_24fw;#2R^)?Qz7>)3w{GL;>xS)NUzxKq*V%0c1xnAkP zxHkXHtd-U$nOoYR)YPsfOdDyk4;rw))TvpwTRngeqb*#tq1=G6prJ3CrtW~BZ#r2} z&2-xg5q3h10x({aL(7~^+^=%rf(BGjbaR1y*yq79Pa{y&<$^lqf_(Nf=W?CP!lqRV z=iQ+^UY?J42{b+xT3UJl4?QFICGwUBS5$~$yN256*J-wo3Q2LSzBpf*2{XR{QjioP zK?~axoC8W@SQ!kFv?gt{P~i*x!VqG5cr%Ax&WeNPAcLdN){1SWzK>M>@%8&dsFyt` z2}zrc$M=eaZ2vxG(K4X8Qn)X5I!2qJ!W2JBbKqFjBuBYqwuB1fxg-zVRx1&F2ViH$G5<92FNMP0)@g2PP9tw>e}UKYF@JUrkQzBi zg4Ui6wBFY*F19ayF9wle#R?+-L{&~v@>(IU1OQnMfYWSszooa-8>7E8QkRz8*nUl{ z&tSRh{7%k@MfbcDG4pDL6WV}P0-bL3FtO#-bJjqR>&f7HZ6-HgrJLd=4g5WR)pW!hq8Nvprg1XSM+Nl}n6iGNk3!*I zVDKsFT2#<~fwF(?Tj-yU$pAm|6(fWwB|8h$5Vum5LEg!rBY&>Bu*rO1 zA=qTy!l@q#(|jub)3IH{oL2UDtoQj#o8q=!*@F|Or~(~1ZDk{!m(a}^hSyC~usqJA zlm-nKYiue1x@&5!TQPGXY1+4*d&zf~gR$Qj#bie`N(tKq3~C=^*U=U8l>n~%_N9MP z)MD)+vvgLg%6PcpgW`Fviww{*JQ8P7bCQ*Cy<16wu`y8@I=}tof1Ta5EO$9`DlbC^ zKQdC9w*}j#;;N}FZ@8?$m)UeSnOuU<8hekNe#M>Ig}vB&3dXdYdy_o4@5}TlT(U-- zN_|!xfmxX7C>r)J*OaueD7gOruyvMURc&9mN4lh>8>9{m(jX`uf^51&x*L%O328wA z>5|-ZcS?76iL`Y0o!kGt-|qQxp67Vnu-961t}(}W-`~rz=@^x7V%S`wHjI!XjtUSi z3^^o{D(Jth+(gHo!x54k3l$#=m$;RAG&;&MCIR)TBYs-?ts*vuLVGfn=5npfMHWoq zeCrd_+hz67*9BC%yndP4OP6kl=LlKr1wpNpE(@`&Ih{>O|Lh;5!&kM*5em18{A5r-J!QBWy!i2v;$t%Uu&mWu^NsJPJUd-@NpzhP1NI~ zFF>=(QBY7khY=KTA$O>Z3YwTaEHFLEcX(MmJ~ywieHYNNf>#|Mid{2XU$gXGxYEg> z8w!;kEP3tdoq+<-TtR)oL#ccitk2W&R=~|w-nNc3x9;(e#{qxq-Eu9FJX0T&j$%;> zu%_eo8+ot?d+7L;Dyk!N%H>*#%77kcG(JOVgW_v@EjAISWqY6zuudxqe%7uhqI;YT z4>qD~9dzXLm>*pblJ?)CZ*qMOfSd-!|F2yBhr`CQtc?XI;j$l}`Xl0$4fvLP_ zN`TEUyf4@yFeCXeLb?k`yBm$~ZDX~W*~EeCLrvlDxbmVFNDH`M&Ckmtox_9uj7vN@ z0_?zCRXLHfYb827rvh=-+Z>9UjZ=^3!C+$;V=)|`+9?09NGdiWnD;{06ZF3qjOtji zZD!8M?H_|Gm`tGK)qr^dR1N4cT?@zMmMb%&@AZ|mlJ)iR;Tl^mpmbJhv^j65_k^=? z*iIgbC7GeW3uBosqkAJlq*C5yJxld$MgW#Xo4^qv+ps-0^UUnpq{^Z<((AHx;O0!n z;P?;zXEd1<_ZqLH^r`lkxMc}Mepsdr4yLpsi9rk4HokFB%)@$I3RItw+?XTtRPa;^ z!;_~b7TDhO4!8|Nmql%czm%N}v;)xW7uok`@uoCIV*o4;!%QhN1p)IEAZQM2QoxcO zvIpoZgAq)`QR%=HY1)VUbYqSHizJ4q*VgYD9dz1}phi+!YRruXXQzAs>=Ve1&WpoE zzhyZ&h^jxWjp?aotT7Wb+Tq7^g)8dYlc&y z&sIP^lQ`RKwJQ{g#FwwGtR?Nnua3NcK}hl-m(WLF zZa`5%Ot7WdkidX**|TPmosigV7fIR&h#Fe3+JdQ!C2^Q+?p~-8f)*%psl{{&C;FeF z$V=gUt>pACaGYz>HC;G>a#BJE#{G6(_H`S8ET0Yw)AMTzD4_x0-vtfHmNy zyzAxu@#QBMiQ>!eeSA_(4nUd@y^l^VX(ODLnswu`FzZ!wzcI?fX%I{93zj_dBV?;u zi(weJ^UftWLuP_q3DPjW?(NE?wB{a+l$sm(LDT4Bou|>Z3IBf{eI&QeuTSS?Z(-trwRwln;j_*uoj08H) z0Th`US_|h$HJagXxm#lYeb?Yws`Dd^!45t7V~O}aQnK8IGf314HF~`8;+q;F_*>(?r=w(Q``ZAE$J%kxtBFmO z-OfQl3i!$q)Lch4*eGi8_=QQ7)(4O3<8A}@mjRG8pl?8yjp~uTdzIEfnunS^sg=JH^m&yU3ax zEVpc$#9*INscCBhPyZBU5n7)b-Zd&A2wH3B_gx!L8(C%oXGnde2jqPu>CrC3v6wEi zI^&&k1EcD57k#C6V~(Yn2Ar7nVXi5yhWJwwE4TZ|S!A&%Ny(qR3p>a-NmiDY zs319+-1j_(YW*|SJv9RZgCopM3Jaxz87zrfkAq>+X27v)TYFlBS7O-KDqRBJ*tFL6 zzWD^9UH_`ta0a7zmw@ivMIL!r-;^7V6H=f3#FQ=>y#wW z$pKp;tgr&{D-1bFmGCjX`ADxth1J-u9)nc}PVL?Va@Nn}2B?B*>>??Ltzs&c`@)}_ zqHJ?qna7+f2os}TiG@g9hu(*qyJ>WJAE_X?MiKY(TRQS&B@O&=eF{e-)tHp5R)S8u zI%>7;qtAmY&48f-?zYa0TusSX(YLvvVg}h^T0K>x+Q4_7_uGyRl*k_mF(QTZk&f!# zbm<V)J9pbx(jjGTg1_r9Q|t|R`Z z)nr=j)J!XynV!01Ng>^)Y{qWu3RK-1aa)vjFN?n7d=PbXbk&ii+ys{c_nAygM5IPp zYGfV;ka=dvEms8G*B>a zh|+Jk5=xr>s_wGM&RU76PB6!h+xxD0KoDI4CmIywQ1_EvpY(WIkCMMs6) z8IubdM6bc%2(r0HNz4WT2H)Rdd!+Fbg`7IJ@}63(efIO{ivd1^ltL6SIT({a-hNa+ zfQJhm29J&3`s{!B>s)$JoAYvGhR;Qv*(~ZgtNcY+t8H7ISD(LFZowv2!|?fb=s?n_!e8y(^uOQi>Tj^v(Ky{W2wX zwD2ZUxt3i7`wEx*3mJ}E?b$3tMLLe}LoiXEK#~+)E_Ez~sKy3lcnO~K5-N2am4A>( zY|1+LO1CSEB!U5yRY1V!$e^7lgxFskZXul`U=@X3%77Im9fuyWZB0asln^S7z-}`? z?U9%qsV3TD3hgU^*H&-0f9(m$nlulXG=E!HcJD7-1ABHe7j^2acJJ=*F~MUGQEF){ zy~+9(?SBHad02Hj>cnh(^snLQ9v{67DgdRtz3VGUQvF4{$gWo;@lH(i_`Q~f@Q+S5) z{}Vbi0j19W?P2@}(kDXmUJzr^$Lb3uUgK)38}Y?<+tNlzypr?yOK7{}YU~q=QJE?n zadE#c2x=c(x`=lYN0*)z7vEnQ)y&5r%Ln^Mo^~cD!`(i(FBg6a#vw+_<>dVKhDlqb zugWrJu(&`6W7_uircj{K$KB&^)KM!MP5DQW=o3Mvd4NkFiQ@i+Me zqN&2vhB4cutiIeyqcje4aZhX!-Si$y@Xylxz;U>sfyeh(Y@Z}dtWUNKvjJs? zkYNCsqZU3%TBaq9I4T%ff~LR+a86R4y?(~~d3EVbQ^I&$d~(bNj*cc8u}MC|XF8~T z#^8NNFBplwkCx<2Wc4d8z0u4H9LVpUau&J`=6Uv)B4!r%D^qIpcMrqIBY{#&jdF0i|mwS`k5nchBd5+7?G~`tq)# zbyCnT02%BakQNCA3go<>qngAeYV!GaJI>!l4RIg)EI?i;{|1g|@aVcHdC42*L3oRd z*p5|qQVu)wIt_mM2fZJ?PHJMqIC_lM>i35`(5;#<#-C;#S01!Pq%|{w!N0D4d@1k- zxOvzfRfDF8D&is#9;;mRr}B57Ha<1e6hQ_@omdU7SFg47lEr$~u3%2>3VvY20S_TEP$)Rl zsc^G02l+D~^29>*w0BY!h0=aezUa)xuo56uVKcXi?+Hi(_p=ZvxD&CwA z-mdBN7d2#>zXJLwF5F?BMv{o3?m-Ys83mfW{?Nv~>^C;))g^SS)^)Pw+8(!`2R3ST z%L^9)!eEgVh79FbKTZQ}NYXMAmdFHQ`Uem&yPoFU6zL|7_jDBX?}bf&jda*4Reuwh zu`#4tsWq)@;O5cPvVflR*F@QEjv`aqy4yuO_(ucP!D%v&j!+jBKS)YyU%`akS_s*k zFm9JtSYc;(Y^G(!H^ZB9%K?}uA$H7?$A^bgh*EB2w`;tz*7$quu{D>pl2?+tK92+U zO#NQEM3tN=dc2?A*Uze9MXM53Ohs?Fbv-ku-?>8t^=~v%(3;}F1lA)hRWF!%lFHS{ zCvkGhO~(w4vGlUjs_I9h0qoW})a*PWx&?m4*kp;+XngpoWHe<4^ruDzlfPT{8R7g} z(@$^B+*3N*3xGt2xvTo1IDPp-I+fHiZW5P;(D3Q9`q&%0Yl?-eZ3DcoJO1ytib#pF zaI|F5c1`kDAOFC;t2W%3{V8|kib==bpAkHB&O9pPe37*|$?e94X9?y&u1+04{S~rD z_6`wF{RJ`f?E8K$*fU?bmF^WXrbFa8OfUH+H`PbRP3i{NT<}^az!!6^hnDrov&=Rs z5y7A{H>Co0++Z5c^$T`lLsEBXreXduumV7pRRr(k+P;EzJ(kJC$sg!r>mTmRmiGv7 zou)NHmli1JuKuSD@A(k_WRCl+K|UwH^r~yS`2Mc) zwohm&dh2ln_LOW)-F;wxNg!<@;jH~EEq8DaNqU*xWPgy-D{$RTx8#jO;>j5*Uk-t^ zn?b&$iZp|Xhs#tDDTOEtU~V!KdDSNCq<6ivMvi(+dkJP3-T$KmLomo`ij+8Oi4o5dxpBMr`N+#zA<&!Au6ZPo-o_h-^t%)~s#t|v?UHeo z8g21Clx`KfYS}6Cl+AAY4|l3ksl5jHBRd-(f!5W}nTvB*J+uf9&rp;W*8rD?pA|Vz z4P4Ibc&I^Et~W0iG(aM`n3jh8zcOQtCaY-;;%Ol-Og0O@KhLy6u;Y2zTDsPDqx=oq zO0rPzNT;-lv1Ci~(3JkwZT?&2B(&UNU}z1XZ~hd*?nVHB4%EWZO!(qL`YYc-9{75D z00OTyJ?#2zhL~UEXA_wPNvZbNA99<6Qm?i|IbI1&>pN)gO!)#%J3n&&FMW(U$NDUu zf1kH}*8fAo7rxA*LfmkMuS3?3{Pp5_Ql(FDSxH${qHPqR5}Ow>)--K0=Dvx=l|j#! zkrjw=NvP%U8k^k#)&(5LCBHEP3rbidx*`JgCc8Jx`3{@_7YI5Ps60A z)-&#q&E(D3b_wpv7tS4f6AqRoD`)19th_FZVC$@fodqsH;>>f{Bn6PY8+RVV^C&jG z5n=mj5FQDEi`>Ir3`SS*jY;OcK72#@PAelNkb^(Ob*1Zo@U}$`*Pu-ot#TUyOglNR zM82}Q>SMDyDaPi;ss0Cp;v?5#j=LQr)GD{qR_!D4Fz}9!P%F2qmXx;hFq)e5-_31d zu%A4t1`q`5bo-^d)H~6XwiTef5-8sCvkJmFYg06TB!t*FEwF;K#7;oN6R>&Xjt@*1 zhsIAVb{#^ZW! z<4aEOvUG@nUd1cJ1AjMna*RXv?KCrMqvNZyx?q1m0`CaGnJ9WZneA+c(n;!f>frf< zcV&62i&L(6-LlG6dqJj(gg7~vtoD z4(igXc_S>Y2+Dp7^6K75X@QwqA}(=M%N5o7(v9Za#{<@ezod}~dJLoX#UB4Hu|I=K zy@4biDX??OtC6@=>$Nnog{#$v6!xEArXXKj|J?zl z#|x+foKV@MO_$zMv)$G0Uohxay>JN3wkCd_%SEa568ge)77<6W5QaAno&+Ke7;_`9 zYu;Hk)<&EfifSpto?fj>*T+^1wrIdbDaKu|sMG)ci`S3|mpF}!GF*>zX&fW6QQwTt z+tz(($(iW(!D;P>NjSR>kke?9(V?MU^9~KM9mTu?*U1kPm9%#@oHPqJL)do)mOq`2 zSrZR5O&A}SoKOHSkxp(0ka<8Dx_(gCx|!OctapXRzGFDKKO5axTz%w&ab|Ah z^#~)7{*kDFQyV176yP?&3K+HT2JI^2Jj-a~m>_Ocjj&|1pHOiS>03BHKCdLTrc}+u zz;SRopiBz*#uIJZ?*3zuV5QyJ(63d#Ej>fc2D1$wCxao4jUF_bufWk2Z3d3yAeW-k zlrG9cNB{iOKDLncLUb@ZJ9M|h7;u;MGV-^|^3xyv5qd8hA$EKacn}&FTmmh^ju`2w z^6+K~T%Z4LuT}jul9rPvrE}vmZqS}yK)v3-0RqSyagX?PjQyniKl^ul$(ZX> zc-~uwghOXAxfK85cgo|(Juvi5g%s{a)~wmN9}g7qxQ;sG`!1QY790&Ap(xyc5Cn}D zmUnMzQ#j6;2`hXe*N{}XnD2G|M6vbJDi{X{o`ANL>&56!2ohUm5KuKuzh!J}scrNj zoN=Ana#;i2=+>FgUX+(e5>qvQ0HyAH0r!0F_+FAcOY){HXV$pG$%oP-ZQ6(7e`j3R z(#G%#E2*wmIb2{T{h*&;RhU;uByPlz(0#0jep0=%iPXU90}I8};G*nrH%qMG+mS45 zJ3oT?@p0qJa6`59)8O0g)-mnxqA;i$*p(fV3P~D@Tkkr}fJm%y;76Qq?8-_u_G~sl zP#`u3bIhe-RIp>KM=uw35*z6z5&BYHFLPqUh$lZofewKzOBogW_4(L+`!vjILk3(O zZkzF%Ffw=jPIg2l6Z#6wbuy*;zMG3aPYBkmE`fufZNMqe>7V2MdbXG`-Z( z;K&`Z&G7q6-noS9Cy=G^V)O$;dhjGO5TOSs)9OxA>$jUp#nidS+xaN5@VN?eai$f` z^CeX3&79nq9eVXe3;P}E)Org7o!C#SH$ti&`Kj^9(xU=7J6&c-(g$XU(qIe{LW>z$ z%Z*%EKZse2 z$LNBND83Z(_DB?^QithwF5t37}h|*Hi~`Vj(b2r}udak7wMUc(D<$gbeL6M46o9pFi&jdYOI<;c|EaOUG*vOi(qpRh<|xz77wTl0m+0ff4i zO9BcC4HA9c;t!2ed;Y#(R1)Z5+C-GJxv7nw1Osfoi~5SZF0{5mb89Ugu%HFL@!0t& zP$Vl+$CucZH~-Mm>6pv`8LVe&&pj?3G1nz;;^qHo1iUYH6h6A+V@ZvC$0gRE8~Hin zdJebd{Jl;>`pOXA5j~x!x;Q8Gzg?f;#54?kL&F9QVrFhCiOg!eu;g^9+}!I$5Kix@ zq4YjvVFg5#`-5@^7|QVVdTQ6=##I8wLGTGOu!ugxJDEEz zAAHF{5#a$6yfMpWZT4!xa?lCDfp3!TBu<7F?-^GqO01$vGn`@67w4(jEiD~LYY-48 zzbX^Yl1gyAZG;nv?)kVl<1WBOs6>;*CL*ix9?yTnGvd93<M+IS1}Spqz(5O*9j%qq0CCgtc@O)h9Y`Icl6APhLEvZ1wMC zWI%+WIUF3oFR(U@xC*^~x{_9u^Se8!+W(p?2gRRs>MtVrf^p`CU; zy|+65iCHcJAi|sh|KFKg>^A@{CXCXVr~2G%I&pWA_tRn`l9`dDaq82iaeZ`w@3qfMTAc=uU9y@e#T340ed-&@ zAZ)mPC=8=ih>f?~TPUpuBs%g_g}64^yc)LrkLvL_^aPBd$wo!a-t~jdN>G=v_rC6G z=jFlTNz$ly-rxVQ0gloN=2if}L13T3hXa2UdIbUlJ-{X#V_OEumV74 zjIJlC%RAN}e;jxUc9t1L3ibES8S_Q2au4}*( zmRh~A_!acpx)?Ts)VI`}^#_1~@CUL_LV^kpLB8kuXQY-$opB2gN4y(NSmj5PI?s4<9N#8^VTiE)-->1f ze%*JyjFw1MT3>+tL7KbJCb<^ne^cwbZGmppd!<+H!L+>NH4%M8feR^tRl-rhsz2W= zDjK`H6Q-r5fs9TV)DoD&NX1csRrv+Xe;5tS%YplM8BaGvvKo1vqTi+?= zzW|~m8EPE=JS)%<=@}av%YN2q%NMa<+Jpt%;`N&e6O1zcdZ_2%^wN8Nex7~TV!#2c zSdpgOVIYRal!&|>^y1rkp@t9E_cx<{A(PtP;fcYb=ULe6J!B4gu7;0phr7ESun%_s zwc(`a+)w|{u?>uPO%5P~j^~t7zf}ydbWF3bGD~{Bo23hCe=O`Si|2WI!h;I{ z&fYi`PEz>G$Y(90!hrfaru~!q!(X6hd-@U)lO{IE2%16Kj9+Ds~A^;ua?bLj!F_DJSks(!Tr4fW-@ z1L?BS=;9*aCB{``>0^c`MP!XbOk9S~n1ruehHnUK)ms)7R@%8T8vXHUT_HYbZwBRUqt8<_NSiNJw9Wu7IMh7%8>{{?s+aimKJg%BnqrkJ*1E~>2%91zKx zmIRFBiDpQfvu;MCHKFvH1NiQ;ta#PL@LU@za{DR1 zd>avhhtmVzT0B(n%s`;ue)fbU3c-`o6*|7R^}O6+B{jT>MuC}n+(q`mq+aao??V@TSzZ4>@ZyNhi}hCcs|EFtB0V-;)}Nhdw$Y=Z+E5kn*a^{r1WD82H)cNnz)4pBS0=aB8UNyH__`S zSWag;AVI|4eFG@wu=m~{#(k)++fiVF8Enu?&kiJ_H9+s`BC$y2@-yTi?XH>I9vBsIptrbH&p7Mv#o$fpIO07GoUzEg^`j7Sq6jT zdG1Nwg9|ES1j=iobV5r=nx+ZXiWy$Iw=(7|hQ@i_Wpv&my^HWREeQ?2v?i1NW~^sHV= zFV@!6__Cct6Kb4x@KX`y4rEaB{q8rYOaR879u^Tl1snO&sz~)obFeahO*z#0?7w`_ zkzkiEQK^+>Njl|?)Qdi{@+UC6!QayUwN!$X{q1Hk!&-Gefn6D)X`!RrxOjN5^kjHQ z8iH{U9!phGdY5@eEw690qX`_4JH`>nu;IZrhgy!K5W-~NRy+`y=1z%DlRopL)IDiE zK5EBSE%9~4Jk|*me-`$bMv7z4A_CB>0CWNDEZ0rLZ-JxS?80VG%BKBDrKMK;ub1+- z1GA}+=5+8xO4iI^hE`k%4NX8F1z&&L@1-EGrX|;3$xnISPfXgcPBUDmUUq73QC^v* zeNBq`to`uK-v_GhA-0dkhl8uVQyhog>%BdW*W+E_?uPRUL{e{|mnwwl%QB_Xh7@tQSY;7&c-jWG zel8Ia5kD_bNP8T4t%60DaWiB=`22RoebElEXQVRDfM)IE_yH_v*ik4=D#HaNp8t+h zU{7i*DPsQj?yv4kNDt8CKFdndr6wt^J*o;e-%1kJjW9YnGe>WH<4XMzzMjxPXW%CCc{VM*y``7i z<06c__3|9?P%yb?*aeMzL`sh$)uBiTd{$D(W(e*Id1$+(3@z>Nb6fbUw1M9%CRV9w ziffMS;Sx!xgq67D8IkLk!E^>Ls)S_%=^f48j=SZk5(2OO^zN;t=H%XZ%>=o;x%iYG zgd>hhvq6WNmD`_sg8O8iSir2oAy z9t^ws{OHPV_0rDcb~pbdZS^J%HCVh!93#~Qz#hGiu6#Kt{qCK-H~4*X3?q(;QtTV8 zW{=3o$nvfpeldzx>|aqmu2a?G|E%B5OF4EkymDJ?V+jugQN5FSS8cuzLf~(o9ISrp zr&|GivCA}UI2iZzs9^~FQhf#MsT=e0;Tye2&m&GtG7DDJ3%L?x*N4FU+#3%us3Inx zu04FkMB%?z-ndJRh>QyFqPJcS?%%jTdJ6>Y9n!S1aU=~TAy-QD+MFpSW8QB8QIcLg zhCoTlg_=XD0GbyV#6R4w)|7 z?kwMM+hA$&LF+Ipr?p1+6qdp$KRyW5`mdSruBpt2L8WvN!N1+E#USJB_I1i|^2(KJ#_d$;YTIr~YyYYDC9?I? zmcwJusrO;iktiJ=n!;JbQR^K@@vQUn129jg^-iS0K{-^KAVkHitjsA#4L3&zt!jOB z*N>^=@>o>aC?~I$85i(WYeE>B0Y{ghyl8 z@OItYMj;D*W+5TCTkSviByD@%>T0Par5_5Zh=)DNLG>1$bexSVXp#0m{QL~GSAos@ zCw)u5NHg`@F2mnm$9C6rh?cTBK~H2)&!4D#S1zk7tu{7AnLtd{-7ONHAj;$RQ}{ZH zuSi7Q<0ARvsKwRC{hSkI@xYjsd~jC+`|hgngAnyV%od=RH5zk-Kn1p84i@(ZJBNtd z=;>+o;^Jc4C(1BMM}ULYN}mN`*>(F@fK)Sa-sH^P_(lV0 z@xGzP-*CsztVdwWljfJMkM6`3YGi3~ox?un%lhTG6}kGt%dI-QC*c}KR?@~}kxZ+E ze6xkPboiW?EPVkD3Gm*>92<9!kFSmtvUGAb*v0>%o_hJr^_VS34xWKPT(NNoCXLC~ zdjL2(0dOUkyN_>iV1548^Iyv_^6mcBOPT1o$ugiwpgw;a*6`ML27gLd_)K2r0ox%jWb86ki$5_eaCOC6G_7Fo*iF5UX5xAQoi^#kd}P|0|?i^6})3m*UcQR$=4z z@pwR>l%p(tQlOMY997WLk|*OU?%9L_hq05B)7?iYh%yuYF)WJYMaDHE>=1CU*tyQ> z3u+iD!>0>F2cedlni~B!DpBvbOKu7wSJXs~Bg~@Wk`j{Ia6>~wDoXQ&H;gqNIL#tM%Vt>xe@M>&CTO6Ss^kJ`Q$7llV`A55!8c@ml<`sNnUX z?C{C!w-5<#Y}id5+q>M(`pR8HXlGKjaE93bo+{D0Kr*oM&gh>d&ot5dvXSaBXwd6feOO*yS1`QAGw@hP0$cred3wi@lPqi> z)Ur>*HX$uvYQ5JGsM;MKw;V2;u}v^nPuW%j4IeiRd(u9x%%8PRTf5C3g-Lc^av%5% ztysao$r<;r&2NcV{-m80qiSPga|d7Ypx5j%UUTz89F@c{xG|8!kj*x9atSr!aMK;^ z`xYJ}!xc#_623xk9o=7Z`{u^rQ`n*;G~6U5)F73K&Jq_NeTSFNguh3v{Z1BR)HI(k z4*K=k2Ocu+ioegytVl4Ohb%SOAxMpiS@G51R83rnfrf%YNx`LuSZS2uc&aA+;~AWz zC*S)1SwslpJ38^cS^UxM`0#L9Y0EERuoY~I)6&Z9JR36B3g7EtY6Z z#s3HDcb2X9J)`J3B1wl{R92hFA2J?^Nmp;T(yww7&VSjpgrMra#@ZM$L|<=6q+4?D zS*?iw91>`~l6gVOdhQ9^=A?3NOl=9!k?sL=TjcRN=E=jbyj=C7aGbNW_Vo4Y+3RbN zZG#Rc;CWtP6>*X22|GT+&O=9Jgh-d6>`jYN* z7kmS_a&4P+g~T&u9t%c^5DLPB;}1)H1)hauT+9JAej$Z36HJ^7pGO3XP8|_)&XQ2s z%Vx9gIGGy1);v9U>ZzF#C?JvS$0zJImiCkK6&<`X23PXN7O^Vn%aMAZDg-Um1)|5n z^E&Bqyq^gV_vs1){0Bq$oKP2(kHY_o6cWZ43;__h`dZd(4SsAH=aKS8_O)wVir~td z2L|UQ2*%E#a>TTM1ZAB@HSN_aF>@MDYZc>aNeXFM2PJsz$|bL++hfDt;|Q^XWvQ5d zE5NjQ+|0q070i_->Ot%AShwv$w?K`#mgUpK)cXf~f$g87Wb^2#!U9vOw-(}ku^U*A!H#bX=JYOqcm!cvvRSvVN8=Wq#HNdAe_n#Bl7OA z2%F8*I=zGv2RWplrR{b+=%n#@HJi*Uf$eWR^2iXBLU%U z2aHqdf;t{>6(e)Am!3u#beMaq_>1c6HK;sRjZjQ5Ew=D}C^gg>rYVFvdGd))9l&bs zim&`#V#Z9L(ID71<@Yngec8qIw!gp zpT$U^`=5J@{WJ*@%PyK!a`X$80TDQc=;QC7<9D z2>qDvrN-@&uwqr)d|G1sjlczrr#LElS6q?-g7G#=hcmz~a$OIxUOO5odz)2Wz;;sp z#beIbgM$PY7mrwyhS(Sa_eIwA$8^M+3-sjR<}j&*nsZ4gBWP#*_mW8B8=gOY7^lWX z{iNxQ8gC_>w*UTehVqBhRok^hEUEUG3TZnZM6H-=eF-lQ{n1QyO;>jeQdH zBsIGD>c5Q(73NpymK2=6 zX}Z}HIJgD;_lI^}M8E8ZgMwnXV?Ro!X8~lhiNZ?hjIVbURCiqWw`EU4h#ik;#SYgY z4(-4tVGq|H&!SmgSsB>SAgGx*i;=IC_Ag@uG?ic1yMxe@zaX;vxb><9yX`unt^VlI zOCqsGXZTX&O0VICIykEn!{r4&3Pk0XCF<*^zp6qT%4@Mhpya76+DO_bC`fMN_$w{d zL7x?%S_OP1CXvQ`FW&M|c7A9LxR4(_y`uQ_<<+icL* z-*)@bQs#Z;b$ka}DO-y=u1^4Q$9s~Hf9d804+#0^%{O)ikc`SBk@r2oSlhU^9 zp#!Gay`}yeXQN_bc;Gbw@}oMvR?aBzp?()-wNICfey5Bf0pl$+{b2I6n7%qOaX9|6 zYHbtLw;CE6?!z|5#vP~L_Dl7~R-)i3?BgufNcI4@PD_#4&Rs5y2zS?o{?R;`o6%q(&a2 zyD_||I6L>yHyu~*4L2<<8Md(yLC7EV`Gsdv610axaXr(+$O++<8@oe!T>@ML*niLH z{;fIWx0ZDX?nN#Ig#HqIlju2QH;+UZY-MO`OU?8?BR@-;^xb>lK}=$xZONkcmd_JM zbw3GD+sWe9a)M$C6$jxUyz~4sJ~;8quXoiyk6`6B6X#xRW|UxZ;dInh-GwxqsIoUF zbJ>d%LOYZooDWn;(*1KD_b0s-wYA8Z`nX%$evjKI$p&egSpBhrD<|mY9&>2>y^<*xh#aVI=)^)BaU=x0LRgwyy5tw2mk_*2bUyZy{H& zy)OTjw(tD@O>6M5r>UDhyJFUKvz21U#sZ$)-|-1W8|&S)sgVkfBQ%4G&DVcSzNQ?M zGf8L?43_x)s$-4_HvwsDmztZVku-#Oxcie6!nlOE@rXPqn70kxa_Vv;g5l2zB5sg1 z2Ao%)mA-q|IUYv5HG%sD-bSpo^h3p1yLnA;f}AA>9rrtiPJy_H545T1c&>#fuP$Po+Z+yyOHadR>_#_iq^Z?3(Qx>Vtyy@aOB>I`m=d^DBhY z(x{qB>@&`1wPzQVodv2XZC7oa4-yX5-cMmq_YURWPxQxghwLckY`f1gmGKYr8l9r3`-n|IDs7b|q7Q%`lN&UmR+7G9d-W(R|!ly6ONz z9%bWB&~94J_I!s^ha%u}z;hV*yD*nKIsD=qWvYv%kc`44#D?b>9Idm*3*K&%3vG`H zgf?E}I7MsG3cB0vT*=F%>JRo1cg5-rZRYNBiNOv1{I8|mKiGC^=6sLsd5j+0I+TN` zLT?Ym4*07`bid+fzV5~Nq^DE1o;8T%eIb8$Vh-MG$~@8Wm60-~3CHh=Fto}9$~XlI z1Tz+EM)Ph*-{T=IacBHu0fN@Vus7ub%CD19*Q2}sTk@gvq3+5~bz!yFfzG`8k}y#5 zn{#NNPYxgFIog+?pjh+>cLgc>C1<8E&Gf#tYc)*Oew^&AWeG`Kxpq_9AW*|Cd9g+< z5~|=6(!*9D7nkK2z3khhx8iAoHU~%FyW>uFds7txAok9B_L71hvE`rEpQ?Bt=JLgA zj~sTt-<-H-5oZ#8jf^xfc~dEe>R49uTxj}zD#>g)FRWxL&O*;IwRP1bTGo}CEVOjp z4r*gX+4%E^T0HB4@oH;pi<6(fj)EcHj3nmu<&Vww1E2{4hkhU`9{krl+Q|xK9Y%mt zQ}6D=7PI|i06y}IVNqo`%cnEG)8%UoIJH&MuQvUPdLFl2eXkeBWH#hd>mMi`-&$*8 zVNYn&5y@qrJv)5az{GAp_XNvX?L;Pj_8W$8os{%oruMe`!V6NXNRo1ja+Cr(&i>vq=fmtJTSRW<}kG1U{?e%Fk z`uof)*!B712EXASg=6v+oX6@uxakL#BIJgjG!oNA3iWaM9iTi>fD@R$?Bo2?o6}Lh zwxfrtw)4pXzgg_V+Z1ZJr0VFnw--}^a&HoF@^uJP-rC~#I4puDc7EoDW!33z)Ne;g z<-~dDRfOS@glF3e@h=~lIOTgnW~Ps%@RtRxbeZsLpO*FQT=CVI3I3ej==-IlrSUc& zfxH#z`*Es=@ynx(yQOVb6lt-mhS7uD2N=gv@#wCH|Iq#pmM@m20i}tRJx?2jNx3|I z7;&7ohDcHcU3wb^)NA#`dZ)o&Amw8D9=x^ z$2a><%53n7HA1$p?Hgt!7kNtL#(Zx0_L&eL$ν0u7`c>`1#)*BX~@T}3hKVxX0( zB9Y6SNJ&~ZO8BpCXscH@p4xR?!c-&Icl0$jR50!%O0o(b4=WbN*!y#{r}~QNsrSmC zQAPIQ(eESAs@~Qbvh;t|8ypR0b{6HaM49^sZ(cctV11TDIoJkU5joxYMQmgg5YE9J zgfoF^8R31|wDtPlG;|T5oD`pnD2joZPsV~eg}J9E>Dk#?$dwN$wX659V8g^FN}H{T zTm{&au+|SdSp0g%;Xz~aj!Mw^-yHh#Xxf^9>ZVWTb_Aup^bHG~ckf5<(A-|wf!N@8 z>c-}<^y;0}t&#D#eOm2>hA31fOlWOVkT>lO_iwvgnUxC@sfNPe4V&n##}f?f4pVi8 zRV*nNZ-S(Riz-88N(skR9t!d1xxS&BFz?zCyU>tHMRx|LGxJYXq*KA3QdF9UNZq-e zgh@gLvSckC0!5a{E$)Mj5#!RT+mzPci3cs8C#24_&DDKsMCs4gLm|DjHLS?eyir+N zq*ZA+Gz_V&tG#Yw>&QC)ho`p;i$ZI^hv_brZV&|NZb4E)N-62?l^9 z>Dlc%v>et47VH$tKmxNL=CYSA8XWHG9fA!%N3QYvpYd;;to1B(7&LuGrUIt>cOyGH zen&fQq3Z1iE$x`8?+bQJmVtBB@$CcPTd}7Nn~x5FAdh)n+HqTYxPmO+iTf~yd!Z)^ zzD}g3dyBgsLN7H!hR0wtGrIft2Hb- z8js-3k`X7rx~R%l-Cp^oNFvQL_56#E>eDBibw4Y`P5X)MvlM7~WIg97^Jw4;3o_M- z=%;JdC|HMAzHF8JZJmGizmwEA`~%Ey%HOD5NYBY%B)0@B+ z07}w5pR>=sf>khxipOC8^3!F9g}J#SSQ3T9^M>I+O$)Hjt-ko~BN`9e((D0NCDuQ^ zilX)V$KXGH&Iw2iFmHSJheNT4!l#g(Z2#qR&i^=X03@@V5m`RVx;ocu_kXB-;*Fzx z)BJF!z}^;;eg8X~2bGV4ZyPpw zfgOxJxQkL>111Z9|X!gM9{h!fQRKHbJw>OUz#~!F78G;j6f}uS|t$=R`o(>G}?1Qa?)NOP$ znpx>M31we(t@Ne1r0C@!KsJb3B@RSR&}bSssDVX!lJeijeiIrbsabJNw-n4NtgaE?P( zJAqK<8Q^?u)F2L&8J-a(%7BoXi>dXLoz2;%eBL$s@-|c%ei-GI|KB^jr}8V>hR3`$ z-)J+TCHcjvADxV+#G%CKZwWlmX*Q`7!`k3N8u!4go&WLD;fWB~Z&g-qC^~q(5WOf? zrb!>x&g!=iJtOe}xVcz>+t^EdjI~1l+rl^6#x|6G*G3}uj(3Aojsh{Ep~zrq0ibz; z{HWXFhMgqecT)WyVS~BjAG7byGmOv^!12JpTJabAcOw$uCU9=&;7#Ut{>~pCCcz<% zMbY=W+49Yu(rnvTzjk;!?D*s-x^maH63yEJ`>DJ&0^IaTy7ia}5 z^xL9hfoDei3nX}0sB>EHMISl?u$M$@w_x}@gu<600o~&T;ZiDYxTT|8)LEuu5rxmF z*dHYy*B}UOmEPLYYgI#8=_O&IzpDclEE&D1~C&n@@3^rcBK3sXU^8p7KTu`?_&eeYch*BE@ ze)o;>qj?P)rJ*SXeoe;@<9j@S197#!^0?q{BiQRS#M-b5R>L5)ZwR*|YF6qmJ$lz^ z_kC1;V|M-hKePqxO;znRzC?*%1_V#ARc3t#tdMMY>K7aU%^V>S(bbX|W&8%riwE|X zE~LSr*7ancwoscslz+U)H(r>Et_&=LRjxs3SO_-$;k&ibS6nO@wLQKFJ1wHe7jLE% zGk0;~E^nFEWGr1oDFRpjS;jGP07Aq1tQ6J^h9V0gX~NWU()&xcuBx!t!c#IN9FwcN zUUi`ZL<)^pmMB57W0sQ8Dh;dLMHLnMk_2^%3`7LPb)#o{T4;0MLsHdDHHmpy&;{HX zLu0KmHP5iWkxnzuzweb4;3Mgg>VEW&5Fq+`zaqL+BBk(Oyo}IUM2orfZe1agSQdI4 z3e^vUf`^Esus!2vf48z72tCF48~atYNp@DY(#+wtn$aZtVGeC9Z^9|};N3fLIhG;d z#}fwlhJVmd3j4Czu^?lcYghzm5ZcQYgwurF!)z?vC1yi9w3hF%R#YFFkivmf<6TN@4N~ z*22fh<%L^TmgkeE-O!D)h%hPeNLD9Z$kjhdHWlYAPUhHOjN_mqfG!~Qdx(@)NQpBT zImELjkBx^3m-IJ03jZ0~HCODqnPRffRK93)XrIRMs<J&Egyk56Ivvapff}90x%2c)s~LCmQ%3Q)=Bujm=ObL51J0|oJL?;&R}=n z1H%}*l_%J&;uP@LiGw&=5zBS#n~(u_4HNbYh|jo!%mYuvuHOsZ%-|LmzO*<~lEkaT zuG5VHCqNaT&Q!t`Sy5vOHMq?;_zxxX0m-zlW>hqKcvvwaFXHCL6NYRGxF2O;j^cUr zkSz!Bx2|C~!gw!UyEH6pY4fHA4(sRX`#gkD{8RHZ(vVH3+$o5RkX z)RmTug8llshSnsD?4FF4i^bz%Nr8QsbVFgs1r@slB(*4H@5hxo4T()do3b=L%Xy=L ztf^(m?O0D9g*aL)+jjbQ#djQ5AKE@bT|m(6i8Y>>c2UpVux<}L=zBFX^2$+wY^m;R#`(cvB%v!4T_rM1=guGrO$cMK`}K{)?XyVO_%*5OKjjsacbpU#7me zbE2h29H8MkULRjNzO&HNT)u?JKI}bJofDsR7Aas77~-$atqn9M*wy|pSoyJG%09+- zjLm#7bvP>F#R{%%!UL?M8wW{46s)<~(Dc91JcR+kH$IdBr*c~(E3oO&%k<%OSbl?1 zN|{v{azQOTS7YIH`S;VxHVH%CQW*FU(1W`e&TGxJEA%!pZ z-0EONFg)&|e5j=-Psd$q2VY_5P8zHpxvUk;aUTwZ$LpMD_)%W~rayi3WmDhu;`!Il z?_!h2iV{(jt|)(_>9LXxI(5HvyE-$pV@CQe8{&f*!-cZBPBU6i=^WQwmODN<;d8M+_FU)S2dz_M4@s*E9zB{8DCVEJm- zJK73G?sTVWvZ&~_?EVJ-tIj~E@h7-rZgUA7HiiY}x*rUt=hsW2g;eY*efzb+wW8oW z{>lK@w;rUVz3fM;dobS=c>Fv1hy~NmpRNYu+K0bu=`-eB1k~Z{WQQBV`(N?*XzH~v zXcMO@|HBJh-T8o#D^zh|AtR-icink9LRUlr?^wQYVMV(YlcygaGWMUJV-Xle)D;lIZD$)0#dE?EN{U%M0=9*^W zsui8vF_r4|;S1VRBc`=0G=$_4YXLc+IHn}3;An7dc z(aT_YP|WjZ*Az(o$q#T{}Gp}!DodfD$IYz1wM&MQb_tYu^4vq60Y#CNt;L1 zCi;gegOp%n-RZMN5nSUKeFMPw!inWdtR{-?gArg6k39y2;ov~;JiE9kRjnl@LOC!w zi4Q;`YPoYaKo*g}X*QPZLL}lh)L@QxUgl1)A|yN{l>6cMFV345}j#>{^3#1sm)#%`$dx^=U_=x;SPs>_wgz18Q8RzEp#Prgd#^ ze(g_RQp2grNpUfGJrASrn)u+Vt6jR#EFiwqY26e$^%=8fk0VaGk0uh*@dW$U{h{fs zd%>I26D6e+LvF}2h!;MR(=Ei`VfJ_ua&LvUl&_Gv9{<+;5Yrm?YLD^@p^lx_*OP)$ zBx0>M_&NgwiCR^OIC23XLHM4TNpWcmdkl1jYI*}iY-Pf@(R^f$C+8-XeDjBYu9oBB zBN!4J_ZF8DB#bO)F>DaVJcO?W(J~uSR1GgBqJ-egYq%_rw^n^69czlwj)b!?O zmTy!%+v}Ad8fL63{m$^M5R;K8S=W1}=fAFk)fozme`ylTAoeb8b3glGe1vVZS&E^r zT`ssBM-aPl{~0^+H{QsfewxT_hFu|o_cNueMQ^r=z99Yi(er&&3J;y4?1dkybo+dF z=+y1o<0NpVU?fph7+Et;=vLs*{@idEmJSMAoW@^Q?Sx+j zDEGZPKmoMghfOY=;p|-f3*Nl2dsjw3prV0YmhKYSszagwMJU(*+Cf*k-d@-m;fOpm zRs7;xMo+-&jk`uEY5p;<*g8IfE z-p6$98a5Rh7t@*a$e4*R=IPV@HaN^Eh0a<>TVUCY*h=i6t{EAKFjCiwrFi*xflFnYp9ruTdhqo8NQAzG!|J|VD z!I(vh6}q3GCPpdB7zgg)I<1PtcuruvOFc zu$o%3YkXznaU?@9uYs4~9G7qWBHn-%qUAo_?_9UoZK63?KcAeq$~1|u>*(3C0S9Qe zeV7XB_|_P)zzQ6VMsia|;npwgRFx_kejxr_R8-Kt=Hj@tDMo>4sJWJ{*?>DM^XnYqHC*xaqFv?EHlRk#nl}&MA!Q4+M_yMNR z*597Jyo>F26Tuj=RL4V1K@FU+V~kkP$4dcJp`e)mCLw4vo1IMj1U`@5D5k-KjubLR zU2aS$o8)PHzVMl60dvq-1Xzai^Tn;LPbB_5W z83k;Di)69DezLx8H@Hzup&b<-ijo3c!p$vm_VVeIb!+Tk!VngIbrG++ko5=+Y!Oic zXI>trNUR+khA$C~6Q{YwyB=0`+k>^2C4;1Z)YBz6kbi-~R?bU)94@R)I^fJ-qV@Xs z5epp&hV+C}7vvBJ4)kH8?CPi2Q(VbW!(Sd_z`K+Pin7`%S5n)-9(&49aORHpvG59{sJJ{RihtD{d|{sXZc_flA~ z1veYFtSy=UL2}}S_vm}{Xm`=Uy@R(n`|ebLxyM*E$_M*EG{FRyk<io~J3740*2k3W0?!7sHM!J{$ z0EkpqsEPwSb3P&XqzUn)IeoUW=`Lc9gK_V`>w|yV6j9p`sl^3(8(SAB(?hHoS&Gz@ zxfqh*t40_smT~O62rWW3dUcduU!U(l!WxE^tiESgKO?57qW2BA$fc6&-e+i!ku-2F z+gbX|xJnv#bmt8(xH?F%y7C~rDoORvl16S!x0xwdYnf`gYzkTAUW(Y@iZmVA2-Vuw z0&}N};ZyXO4^^Yh;?wGP&cPaP{PUNvh(iY$-YKw06M~oWrsacpE>w83ra^ut#|S!d z4$}6Mn_?C`R+(=ex+6Vxf%97zj#TmP0yq_0Mvr@K^vXA!&t@;rct7<``5=N?iiuD% z!QT851w9t$W2tiIyj^}6m!n~Av1MZ`v{Swqz2*-gs*06$5fASoBj2+xNaVkzom^p`S(0LoW7MkIj`)<2`L0?`f?j04b2%N1wLSo_(`wCvHNy1?4PVe^{DL#ymxCKE}(-IDAYw`x^LK!E$#6VAZ{g01&iJU05OVjAAdl?ROx&GwCUcNIt zbJPCB0a{#j%q;U+xPT;>KZo(fjZn()Fk2kqV^0}Zvzq<-kmf&+!$@?6B+`cuN$MgE zx?S3Rexax%OSrKp7QwG66?V@v)dA z?!DBPIFz$0Q5N(@Ptm|>7px(Al5}-s*H7FcZOrIcd*4Im-V-NACNPNa=NrfC2fPe$ zUd>M;JrYVIZOXY3um3BavxqSgNTg}K3Rm!&M;_cgj|zjKTU9sb_~i4xuK}7X6G7CD zyIxPnMNNM#%NQ;;=dv1h>~-L>7M`vSJBun1vmaPa+Exy_#=qq3xq4`n3Jbg02sUop zzVUZNfVf>?4nt|&PGZ(=x@A89m}yZdUf9?LKfxl=A8v*Jeu@wesVTvBueyNb0*8il zesbcu3Y6xFyjFUCr@hnx8ve`h-s@@qyhysZ6*qpV*R>Qfbz~Zd^J}2upd_b|NrH~N zwEvdoVO1WLZt?MwsM9RNS$DZ?<6fQs(dGB@vc@9m32DCDMo&%ye{Z?J^S5*+K$hl@ z>byx}+U8aTk{g<5bH0|P2jrt{>Q(#H#Ea$2NPz0xIORk!sOZQA-sf4eN-o`Kd_o6adv%3;FOdE_m9zkFVoPx6mHpUsJ!909Uhw>_|XtPH;i210Gn>2cEIJKLdx~Z z%1i6;^hTEPX7w(8=L(&Bja^E1C#)RvQNhbt4{sUK599W1sYJ|)n*7@i7%^JP|+GNq^Vj9^xye)ospZSoHGdh|;N^Jhvbo=-Nj_Pqnmc~O2LO2K@) z#ZIfBbOt?SVF8fQkRY013GI07dy$awUd_MlsMY8J^-2#@m-ot^J*w>86hotirEyKc zYFv+;lw_B^CL5Y9V^`gWrIqAWeQmbE??WN4EkzNmfAWnXW7w}+hRYlarG?>*sR)8E z#DxQZKsRM(StNLmsU=pC``*Wrt*7;DemJ;F-%#7v9BGHva#XcDO(|aMSbY8uqZ~Jh zVvToUV%Lb9?Z)@tX@3fL_}orpv67(^)(zA}CY99SSyW;`!p&n5AvP%fFN4v?iHT{H zVtV*Qa7F`RIr;x;4b#6#=@^fDTOt~z|CA0qgS$}L)u)`>(3+KiwVdMTU*7&+ zw}+Oe+s~{#%{v#I3w~~IP+Eec5LP;lmiSW9j3)Z<3UpkSaa=0YO+k_j2CP?25P+lF z2__Hk{Omf|>`~s`wS^zBVk@&~I9@^3RwW@lDoMkow6SU03X=K7G!&4vjGR)wVAZMm z++A??>$9e|v(d0*6vN7o({oE{aV{u(&ZTn7{v>T;V5o*K*nV>`Ph{49Nx*tPl6{dq zB4u8M0mj8bg?&OdI(jHK*c}~)=VcaG<-VPMiHw6rX-D<$bM;#k8DYRiGHB9$`w{xaJN~5n zNh?(Z6>#@``9Dpao?kE>y-CKg^}aPKj#V|p2h~|95Q*e0V~n^p=zen&AjZ(5oi{SCPk<5U~eK1US6t{p&*mMkBXoiVUAAJq)QYk`sS45lqPU)T*9ympO=` zzRk{%*;rVfe<0fYNr(vf)+vYw4(V{}YkP`5>)wtgnQ!EK@rX)P9eYPWPq{>_`nNN=Am0>$B7%tHJ z0!L}b#|jcAOvF{eh6z{pE#2dv49QO+t^BWT%_e<*A&)5N(QXr6ps$15wzm9C%SJ;; zNL}UTNHY8J3okW87wO=%+p3ZJ(qkch%kja;rHO0SMRHgQKdAuk3o4JS4JisY1IHBP z{Ll1ztg`8u1cp#m+Hr3FjolN9NAjcR#FC@jYC?+iu{E z&iE)Xs?0!fx20ImGHOh8PWb?}KTcdpPFugeu;nNysZd-U+uy+G93csa(oh$lwRIs= z_3)BABEl`pa48ouBWRlo&TjMRzq&$-KTurw?XIq*sK5KIE}0vV2lPG{*3gS8Oa8cW zJo9)>=dlzMW`@6Mhh~(HT^=(}7}&^9F2#TivM^NY{&do{!!Q3=MBP2Fb6Ss`N7Y^> zr)r@w)0wy-s<@ZxAZfaa2zH}MbnL@)gUG+9Wh4t^EmRERxzCMmyc<2>O z82YYByySX*m34Lf^S$`y%t>ce7)|reLTR^U_1`M`w#63uwlA@*aK0kT=IxmO{2H~j~-XgeCgFd?pFBss=ns?)o~jqMt?c>RipZQ3eB&?Wrr0^Hi5HZ zFbep_uOtkJZyZU`Bj++dhxPNHwJ#YDsMGoU*f6?_Af*cT|A&x<#AL>% z#Sm#Q-zhch3WXOq7m!nF-mmSv7GF-3S#uSsrP=*6!T^(57EAz@@DWefd zW|Wr}Oe7g|2f8fW_b2{;)~9DiSI-a3Pb;3%WG0@B{J^Kd{V-yOqj9?j^FxTknHN~> z>XS|c%kPU9ebMQ=QnUg)3%Nsn8>&$(8~rbRhNKyHdY=x25hjsknAkyE-ucgY)X%Ec8uhU&|w=t-8kHy>I{| zHFNqL0c;Q4V4Lpx+e(Er65g!e7=E_1xD3aKih5Qpc&jbl4~_ipaEAHQlt-(pO*~eo zZ_+6#0?FZ*qK0d4_r`@EEQZ~W9ea07Z6NgjLBxj_$ym%c=wu*7JQ6HiWsVQWc5sJu zTdI7o`++(i2<>UCJ`0!c3#X^;nS?zGQ$L-`E485?h7Pjp-_tl&9;f+`7C+DXG();a z@l40A+IkHj#GQxq5u-aRk2@^w=Tm5KZ>Ivpo(=@MjpCke*=}0_%H4tNaGsVxssD64 zbLZ8a%E@;=C<}|N)jQAwWc)PwmSK^4?Oq*^#m6ek^bz>}dBqar$Zt+sF3jKd>Eo7i z6*CbvXsPTsqyA_^xz8P>I~EL?i*qeK%zt-uy<|2(YzgkxbwG^?CM4g2<8iE_>{8|L z$y;*4;^%3;@^w!5M)qbfgPdbd%W^h)wZx;7N%OhMX;nZ3-CK>|7jeWXYq7~Cko^5a z%ooIxJaj4vX`rW}KF0`|Pn8+d@>Qzzl^){ZNPCY|*S+o`$bln{nNbS>c zsBTmX#UJ|?s5QCFqw|V&ug56P5=pk#b#ni%H1b0zG}t2H>Mh=~*oL{9`-Pt!CYh&^ zFw6YmOCU8dbf9Jzv$Vh9V|+`&`cU$n55wOk`NFng?5w1^;gg-HzOA2Zs<<~icaJX^A<_xT{-Xy^d!Rm}`LO1$r%mh4+DCL_?WGBKeXaRa{5 zuj`*@U$|vMp_gW5T|k+4Nx)U$$RvO#C<7Rr`668 z?-pap2ahTZIZC)Vn=jqf0F^xu!%9X1!i!b3M;@JyE#j6R1BLkdbwzzu2{m5q1iWf#8^EBcA z&%^2$$7|m-Z+wNzj^K24;@FUdg(ayGfq>>Ls`BGIan7SV^Y!@PdJ4fC7M!ahYOgJ! zSl4F~5i6FX3NnLG$h+6S{$oW+;_CgD)VOfdnp_VERVBM^%j_01QhkkY-_W=dFzedV z?%Qo_QSi`S>4K2kMp)yV?Y7`v-)6g{E_0`D??U>)sMF16=130f-y0SdE;K|DzhXLX zeZ9%UL?u#Gq?5p`22BAtIa2}d7XxB#x+gw+9bLG>n8|u7xtP$go>{plQKyhGv6W9j)&8b9In=u7YL%PRkakDz5qG~lZv_cC zh7w4#gDIIjDe`K$9%PBH!)AC-uMFl_{O>9jWbV8@-dViai(banh)fcEj!Pr@N|{%u$S%T-bvd)7Zz7Z2IpisYOsh zfuRXVbuYIDlbCz-fw2!L6IF7TyZd5Ed6sU+qE&(NiyQBm!cmBHg9BpD*(FDOo>P%f z_{i0Wdnvu(eAkdtzA{63hoF#MS#?K}Yy1nG;94nM%p*-52P^VyZzqbY%ls-ksq-a+(^o2Z^@354fBxME_cW&DT187AXDCKD>a}#$!0B&8o z95{&Z(M`XNq$*wmI`tfDVdc$bVQr5-iX&v1;ISaV6i%GKBq%cQt36aGk6Rt*j*&P8 z)JTyT8pMZnf6c-A%c+}JicB$--;&SWu;=@ICa;Dd>(rGy<}VU-u!7)v^T@xBqEoV8 z=F3b>@|+O?!#AN_5%8mZhd9K+QUHzV=9?C6CsvmEXNq)A_w`FKG?dV;M5u(7;%EOt z`2aR$<(XUP@8o{yxPY2oxM*h)@_+{OX@!+#>r#cQ!;m`44tx`yvl!seq!iKu8D2CQ zBk$jAMkXPT75Ptq*#Ew!O z$r)DT{5x0kDnsdF_kobwK2%y5KX#*uOnp+P2m3E5a!CyQ)QKs!Y4S5YSA1K7p3WH3 zuXh|Q*DDsZJ$4pKuE!h*bg?^-jPy(=0D}Utvt=3iesL5Y6Z0@T`#RE1A_6OkY~kxX z1BbTb*jIhNCUc=ybt4xp8x12D5v4m+7c|xcfU6;UriNGBZed8aGv;Vm6seK${X_V6 z$~f2-Kfh6R|8IRaZU)eyib&)C@ANi1$9X75*)(-=qwO1VkF5nO_sM?_=Fa_@b%HBd zro<=V5hyab;yEwh8gB@KV2zYU%g5L?Mc{WcN z#`b4?`hQbTNhjhk-Ndz|mC+cGE&2WiFt7wI_C`#etZb(pW)EhpJT0*7xDJGVmUQK1 zna|xP-$}6^3%WOY4}Mb9CIVs#2KVKXb=)VNXW6$kBFhgO>OVdnj;@MlKaE`f3BcS% zSOA;h0Ws8YX9XB%IZh~cd2kWNj^*7BmXTV%tG0b2&Y9vW<{+KNh)Dw!2eQOYMjF)6 z3dAYWgFF7hAeApI>B}1~o%zf>aUg>E{r}hL#~ZIDFK;7&4d9F{s7nyoRY9F_-asH-N9p^iJqZYx&b&WPo$l7EY@`98!(78_k8^Vhths8bo}CZ zIJe54w8~U`Vq35pn&L-8m+buYU5%5}Q7H~Vgg`N4HbO$DfiL)oIU#aOcp3lXo7{||A}Vgi#ACy41@dvKWa5*CZ~?P{(ngl|U(6+f8pqHWWdMhfY; zJ1@X#*DjxS!}`$>nO`8lL#tQs-FS~azGO4*%RXqr?v2R(>cGiX&KYsi<%FNAYh2w= zIfIUXbTG}Dcn{zUab3J*Bp^HK1ec;)6nPiyPQz>}Vm~A8jg@%u)3_$2MX@xWkZBlN z&IN7*-FI7c;yOGwS5oqeTSqoa^})qeQ$6=-XEu`>`nFVqYvemjaRlkp9D3iOGWrLN zQ0VK#&Ruiy0Q1UR+%8Mh%K_f=y*``ui{{Ti|7^^AQF7?7cx6laSt}@`(LCmXYXLi8 zl27sa%-!-(z2jAG}U{5@YuNX>7w_RCGW_QUBtD~&8zYu&+-;IZ;y%&3yNySe0vWMiF?8k?~({tU-#m7C9 zDzlM(dOF&TXCtl(#T6bJ#j_DQ4yP|)r~(yfOFMSrno$fWi@MqvxPUV5t9rXdpgPgnt0pbf1s_54{U)^{c#$S=tWtcU|=hEifK;s0I zf~(`?y5h5hlcIsD46J+UKnm3Z{BINyAk8BQ?Bm7$5@CHuxeYVn`{J|j+&HmCvfPsbycaV7Ay8-@rA zI2!Y*wf#o3LHawLQX)ulcw^)9!M|u!-?9;QONqqXs3E1!Dk&`1aLW||ZwO7MV9|WN z+t6jwsIaY{F_Ni|NuylVc+;hjPZU*>8v%oYv@tX4 z^AJoHwp6Lz_=TqS;#^1lvf)qENZ?0qPTe_MiMr2bJ(NIq&+UxQn1 zH5CMg%q`;We}C18c_06M1!di)ozgk013aY{+AmWS9RV(Ud7$q^PE0;;t9_3E0W&+8 zf|+0SddkbQ;{eNfZ_pS;%9?A+&_C&l@#e&@}up92Tva?U`%U7iRgo5>Cmvj%q@ zoOVQD%CxobLbDEbG-ca`eJ!>4mtj;j!2vf{Aru_dT_jmlvL>h?^+_fi#lgK+Mj1}0 zC8JsSe7DY#NXUC0Q^y0phT+0z*pVLhUeF{aAB|v#6n>jz1jrmGS_}fP)u4Tr42By> zq8#&U+i+%z(=wtg`+bIoN`^isk)uDlzrX(=eA{NN_;mMAn(kSpNLH8jr~VIeGLWgK zA9_Nsj6`2_sWIVSmn8JQF_P=0c=y4>s5mMLbD^X&pyo{OJzbeEDsjEfRL7_!PL9e) zj`YZDK4n-9J!)+>Cf?o-)f77j!ox{R<9M|1(7=)mhI__`;N3@i(%_HjbLHMrYK+U6G$LP_?7}%#U@CT`zz4Ik>8k zY=!^1C(yjylPR7%b7MAw%8Eob)wt*Wrf1}1>I7*FhjHG}ZcBJ#-+pKry+AwD_OAWz zxNM(Xd698WJ2}1Jd7~Mh)d8pXA(DQ1tfk$wcJloAXh8UsyS9!zdm3?|xmI zPlu=t8cVUp$5-VBrt7$0lOt*UsM+ zqWiL@!WQKnpYJqU&7(Bh&zT)*$n^~9TSI=EqJ=v@TNKIeWLEy+wDScYICEe`Q@#Z{ zqr>oz0zxDdmK{kz5_YHMWeOvEsQKc!-03;N+9eO?mhN2ve{7e7Cgj}i-P}(b$1j>k zsvZaV=d(}z@8c0!2%HA@>L(u>+X-Y8wa2g08a{4M_K zMj?a?yscA>d&uR>M6^ASH!egpC*rsE7_KI#{d&=r?4_`xPbj?cL5Z2Jo+r*r;b4Kw zot9EUh$(mRuU>PY^Rm9Z{m=W1hLohb;|&?v(Ksdb#VR^O8nT``iJqAoTw`(_noqoz zTHiQVmm#T#hpj4_C+8PYrNJFQI&vdEf{q@wV*X!VCZeqoPn%;?8`RAeDr)1~24lRKV%y-I1n|i;B2+EN}UheDi0;p!yxhr4eVe`7`>EgdB)N?EeDm zX06&%t{NcGJ1^7Fe4waSqrDb|kbv1quN@K`*|BgJ@Ju*_)Kh#m95r+%P_^_v zZDyHcSD!U>ZT`7B36Pg|jLp%(x+y%a&-jUs;_h1CAQbD1IG%YF8qxhPzKgn|O8sv9 zX}QyGzCq`+6W7xHb$&XSE<89U!+9d%T?g%p#UiP_<-l8BxVq963DG1UTD_OY&X;)_t4;kag$8UoB2>(v zb{WpCwb}#PO@L(@5pI=`j`a$V?7u~?k4+x~v2d&J1wUENPtOFb4O5!T9B{JFr847P z&1Zu{;Doc+#4Y96(K`Ru#^onHtlXr`NUh$rBYNxzA1eCzE``#c;}jl_t8{>4Rbc_6 z1%q1C>93;C_c3D3V^+}8L!ne;CueU&_ruj(Y)zJm%1c#smfK>IR|YTgQYxYv58QS( zet>IR_P?hBYNa}#LpZa#agNvYh{$13Wh&nXaDZmNGh}jX!&S?F^ z*}tBEa>@lI&^&x=FCH2HHH`dXYf zMxqs=jTgkmMn>Ruhx@!{mDc1D#dh0*XQOj>e>x?$<3VRtr@e1ks#Kji)x~Hp!eCMq zG%GoVDi<{~_15!W+e=kH@cBA2$2?yTHA3Pkrho8DA)<%-d4&n%p8bDA%X6vAb0-Z` z5~3_WqA0#Dqd2r6&m^A?{3i+Z>OchH z2G~6|y(fkyh)wa$FtL_>3j^srJe7LfIE(WH=)O=^a1zv^+4e9(_T(%;_aR4uMRt>FnLIUr@V`(%hVT%z+Tv?b+v_J`b?2JD(Zf0LY;_ z#whg;_rRlB)g|xvpJ3ch&w-($5v_?>z}HXGENTUB4?d0IV=7h{_DMDlN%p{weAX z@dLFu@Bp%15pqu~+iz^0KC!)Z`(t+N5FC==_Faq?Jz=UV_*R3S7GP8WL8LU_;F787 z2@b|9aZdas+c(Wwf_ZR1R_652%(MKU@hScht?|k4;04grQlxhlQ3c@@efaiB_OaU5 zA=oDMJ@+C3@i6GT3o#%eSn-EWca(P=Vpk4+!wPlJiQD7{fO+OR5pX($#qESIJc%)e z$QX*KL9bgO;fmE!F+}{SCJiq+5 zQM(@vwC(Efk$>T~`eV{m$&19(tOj;dlke|CPP^p^6!HrWras;oQT7QfBssN-A(CRE z3p6Ciu(fwYl~R1|bUf324(z-L&j7hvJ6Rv|3%qkGW1Lbi9xgBpc#VO@NmQ^AmR7bN zxr(0_6KIWaqIWbzEH`@aj~LBs~egI8w=Nh3Ph_<)o#5sXrk=iY+-V z%X@uG`c)IvdGOoxq{$CeK8w)OQW6&Zh-}*eKw}kdZ8;1|a5EL~xT0txw~US#Oh6i#rd+%Cw_BP^M1v`Y&`yKc zF17YYyq2Y0$ETcQVN`S~Ll$<%yGy6FOA8fu=>t{M+WY3vp2s20*X^*5KlcsW|GHke zk4CG4DS(q;uSTlwO7Ydu_pL_)XTJUrDPd}P=dLXiLLj`KSp|++Uj5Oi;K0UAblA|q z)qTf{%&OOj)Q!ZXv9dw=JEYi=jd!vr4S(pJcvm_B(T#Pu121;r9wT~$t_M^H*uVR7 z++GoOH-+MvO802jExl?VSA(j}tBZl)Dgm=L0HUTn(^xJCF`XeE-Ntis>5;#ouI7s8d0Zvc-WlIRT%S15;U&*#OIlml&q+2H@rfe1HEia;i z>VC#}#bc5op_p#a{4wtaRSHJ@bBQvA!oZ8xy4g%*dj)&Bw-fG@UKnwXEZuIQVg{UiNIjxS3gEScEa61E?OKLEL#a!M zG^Vks{AwM}$N>ydHa1>Yc5za!xk3flC; zjKl(_#A6K2K~SkWu3v82thPal2-DG~A<-%?1$L31^!7lx8&eEI03AH2n9U1a{|xW`GM6zCVqn~wuagK4{I>Z|CYI-{7y z&*QP$OFnTN6fc8j3*v*HGa|u{^OriJkOki1`S!hTGYg_iWZ%qZ60&1sW|RMGS1f_u z%)jaU{Aa3fMOZFd{lV3h#C;PI&c;Ia3P~_Pg(Y%s!d)U1Nu8IJeictkID&!0LDH^d zga-X#hw~ThIrCRnpKg6*Ww>8`J&jgOu!198VJaIOYh6P91+n4|ux10sBboqorGO*L z;q?__0&=a(tR4L(4`O$)J?8hpR$zfi|L}eukY5O^VR$#%JJm#b4YhE`T_nf#`Mek? zM5$aJ6ns~=cRB|Zm7wiuf-%%w^o|-gG9crV36*s)R_*Wk3SSi#I%*O?n~eh6qi4^p z(yNSx2>Q*{#jB5&kl_XjjU!~wy<(a_OZMI5Gw~3K-fGITPU;BRXDO>}eUgw>ZbLv* z!u9W6?x8Xni0$beIWW{Vn%vQA`lR3mr=?H8!3*7BTGt)9ua|(2NRQuQ#87eg>-RGa zMa>2)^}I`nZyO$DUinZ}V13#43(R{VUmihiXjnr{ok)4a`L8htF72-0HB|z)XimKUs%9rKQ(KW0qQUOFpJ1V>c{{=d`i@7sXE%0d4lrXXKPK*D^IzwarXb zgb~3H&z^DrMzc?g*%*Xi_-P!TeMl95T5X}ZT}e1>brk*!AB9$7?xbx~1L?EH2` zXov+pVD{zYT&cEJhave&TFR`&y;s88p?-X3L?}nfXAQZ7xEmggK`v`bRY6bICcjfj!dkL zUsCv-^P*nHpx=E@uFS3>;wfga@!Wj;va}-6u$WK1wMxxZO?~oxQ|>yD@idUjzsK!iNFz0`2yR&tZp50?)j)CTO2eVI_`oE1fklViKT@sJJe$kO;rxmjiouSb!p zDnl>lp&xpl<$fm!5OG7mU-Eq7bf~N<^$dk(&hXE?oL$ejTF3C}q%WFGWsz}ha;sO0oPps`QKMhvp8iW2n`=w9 zFz4_O6&lGpzxoqmWIgs}NX&?|tGu5PZV|J<9e$Hi@6xUN@YR<@ZCeMp;|OXcL5;$s zad+|n+cxy=!m5@H6Di>Lt6I-4Tz$qVQwP6fJ&d>;`u}J;3uwIG|Nm=~)6Fo$G}AHD z#u$caZr$D8&5Y@0>gLwn(@b~AOb;{N|I6q5|DCfq+u0oFzTWTadR?#A^Z9sM8#Ah< z$Vh>!^UqwQEPbf>fpXl>a%0t=)Fvd@EpE|11$+7Q)1C?nfpQyOhv5+D9I)dU3vldj z;3|)czv%v@UiX==ohVqm^Xz+UUCcc(3Twp$DaL^Du-)yC7f80t9BoY#-1_dL_Z79C z;{f-i#iHq_>`bZjLA-dQoMy~9UIK^T+2_%R4?|Tg`%EUA`RE!ZDrXDiUcNgY@qw+p zIy9o}Iuct>{>GJY>XsBrq&-<-JN`BrNMV4c_rFfVFVazgEUohO8g`p^>gR_Y4zcYv zbOQdssNdn`i{^J$)&JF)iHJ)X*zK2!47gXZqojY0cI65ETqsu}#^X;J8UM)eXQ)0@ z{UQ|iCUe?VFmA2l{L-2!Fx@PEl)n8HImVN7qbHedYr^q$lY=2`tk)M~iV)uBC8Jw4 z-C8f-=J$ycN1#=J1h&v0){B}ZbH1Q~ek3Xokjw{W6Z$frsveu&HPvb<5gPPkT$Bcj z+a$CVc8Z6{pbCTvYHNDi=CbdYXhFy9xwVznsDQd0{r$0UrAj=o8wkdWm3w_D3R6-0 z<`nxRM9s}*DmAY?gWcof;33n!q>X>7*qjX-jQF;!&_~&yt53u^tq(~fhNJ~*Zzsgv zBvOfXf`8M%O6TC)6q+P>#oz;s3Bwe1jp)Ta~4i`T4t1Pi;v|{nra-Lg~ZW?{?>n>Vg!j9*EBn;@&$D zV0IN>|GEl;En~`j`PZH*p8ex*V*ll_yIRb~SBCDZ?KvSU1=0Nq*u+0=kv4mr3&<0) zpBq8?zY?eDK#%youj(AZu>#ECfn55ws-+<~3;Q_ct=2|=TD z0C;aSn0Ri(68alMK7zMD$SKxPqE{t1A_hA7#-4@4fQhtEoGs8VN%pLhoCBwyD6>=mgqO0l`@`v|$?&}W*lpFd`8#x+4iQ2CO0I^FsnLfix!$H2wjh*_sFv z3PpM(_(E@$ZvQ%{C8(7pwsoXz0Luf2yZNPw+$eB1GC3nVBRQ3H*tFG6dNs+gi^-feaCab#El4E+5r@AZv~{ zeFCey7__HWNs%FbZA*Ba^#6)$ zog$~$4qscsu?ls!d)O`0q+-FuVg1=WCEX!*R2o`;0>AUAu0d|4Rm_?y8Jfo!%9OP!ZgL>;G@Ti)^K*4qWqKYiiely=kr-Q2TyfqM*fd(dr{QEJE zy;XmdQ)9EY0+ zJ*GXQV)Fq%A$A)Q%o+OW6Iw<__@;D81gM#;XSG6eso-R#B`M@&9Hvwa*K^Eea1gxI zmtanCJD*E6U<2+WCt#-05Oj{Qz^JEDlGaYOY0X9{Ht@ZNZigc3n!encnv1%eKL6p*m#27yh0gQ98Y0toUVhH3Ym$JK zlXQ)gm%DK+FXTMxkU!oNlZUBxaL+b#c5z!Zt#tBFn({Q&_1SFHdhw_LFe`hxPJUMc zy*6728~%wYiV+=tLR`cv8fHOYOytp&Qk%^wrl6oeFbWSvqN9DfT{lUFFOGd7Rok4m z*RYt4n2G-YPO*WvVrZCH%>Mm|)37dBC!>>laAQT+ZuCi2bOCyPO-<)M^!gAOy1aij z%xeg~+nX58aF^J_{rjh06UUx^R+RPCCI8uh?fd6&04H`dCdb z)i%azMVEQS&eX#ntaW@Uf2ih?emy~`WeiQ?^8KCY-5lrL@a?4e5N2TKNw!~Yq+2_T zx1N{*3_|D3&!V1|H@MNVWVuJQEhDVZZLzB1aTP7{h;nFI=+6cnizPQqtPhRfj{TN; z#c)JCUvY8V&G|FYij|#t?d+tI9hQ3CSU5EY#bB>J9Wmn06GlZ-J!kK5hb$4v*obBd zE?XB`m_M(iWM0h3Ltu{b(n1XTFX29VyYuTWb1U2%7Urr1B*1I*_fD?vF;iswQfd2Z zhC?qQ`22NXO)7~Wb~=0OTwVIp3ylI+w^0hPXq^A_3D-FIA?7b=97F4E0p+^OlG2I| zxxlhIw5Z~oD%+SA&xg1$q*As?4l8P+N z>b>?5Bnr2BMt{20aV2#dpzLyoAT4HA(8V}je&cZ!7t(3|1sX2*drHji{ju?Ca||SDB+y^gaR+{^m3pJ-!OGN3OR$^$-W9zeTkWq)#mO;( z1Q-D@oW=Z4+1)5T=W^GJ|I@tWkRz z&W)9=V-WKJF)JS1&cSW{i&#aHg=}072B(q%rgqPQ^=mFFU>BP!;%Old{FV)N+Yd_< z`WmGzt6dkKxe>{H!Xo%}enri)Ms=;ZO{P*Ez3E&ezE1Z%wadUxOjS+f2d!YwH z4TN1_T=p&tz=XPYKviwtbpR!kkuS)>qA_mB zL6yG8`KDw!*13xl7!MQ{$)7_W4*slqd96K&KAH)sHp^7(?R(z#V~8!FG$TV&Rc98- z*DTYo)PH&!OxJ>_(eDk$)0Yck^AAA=^9Q+FZ~Qv2R1V#Av?kqZv>*iY`kCi7k0d;; zYyFS5JICFtL_i=lJI)Fxa75G1^axyV}eW>MR#~2|n*5ITFl}c8{BE^x1)Iyv-W%X#i92 zpE{F&>+9rx)^yJOQnxyGc;(S}pE5cXaxnq4!Gqr~11#WxJ4~cP_;VR^YF4s~le!wERzg3=DQV|iVs0&+l~QRj#$0W%?K$K{rlMoDcaC?1{6MNoM7ca(T2 zBl~jADMp??e_&XZrc7I<5>{&P3qQS;hQu_c zEX|U2{IQDl1n^TXmumi9LEfIbdzC-C?r45Fzv%llb|s+?V->1OiEXfW!sk)$Gbb$K zRKX8{-2S6*%T;mG^Eru5@-q&Qy6wF?eVr1q!@2}=NJRJ}Y-lBI=VUNtXUPKGx){xL zW;$8ZR&Aw@3u2&wSjnZyS`(_=8TuujDz|%GmMe)qf3y}l&hyMEdYe0D@X<(ly02O( z=f>Q{!!KJO*vQ5uboG&KD2K<=o>ORA$^%XQWycu%ef&9cU>mxvF-Ka=Mrj+N^hmu) zlT66O-_@iu(#?oJSXw1amF)}IoOAn_*Ll6~-k{ay96p!HoI2M$27`jj*k5O9X5;#6 zzCX>JTQYsNSHai-SR`b;wEla}x#G?(FczvG-augpqSqO6>FQr{vT31{>fPx1@< zy41k;Zsvr6`H4Eo*z8$J_$6%ia^%haXg%4NaB%l^GSMCj-RBEkaC9iOuJH~%UprTG zo$YW^2=2@mzug4V9zf`cmH29INOlYWl8y|g|l|qys8F|}>w97dbnSpkpYd6c@ zvS8>!mp~tO_(;CM?%y4?6xeEw`W_^&ApbZy_}zCvUTY&+r}33^zGI94>69UVvJxHm zk$ydF1d6R?b zJiQL}n3y&m(&_CXFkX9E9$5yF{CIySjMpDhtXrU?RliiU_k96#C|0458p#5=iJFD8 zrwf6M)o+wSN&e8Z8H?2AIsNi@gH< zj)U1Yjk&vwJgUZ<7i>Tp-8Ly+vT?}h3j;_Q#?8uZrb-2=OO|oV!bQwkDT-jEm~{u) zweUFkUsvY=MqQ zKi^Z#LOk5=TLN-)wzAI-9yQo?WB-cs@f1HYaHK~X)J=-FuZriE=j56nqE{irVagBm z0zyQv13$ThJ2S`inaToi=Y@UFoe(P)?3a`3+bC;L!wIv{JnSMiMjH#@3^c$TQd0Ju^0;oS~p$ zc(NP=J=o~cO|$~s%1I?F3k}u=dk?IX4+XV$TXLv{07%%dz#D z^G#B+XMnno2+Y&UkN01YjO+wNpiP%+g6z_wF8kJ zm9f%2Gcvm}vKx4t%-PP52$!TT^)w(2N1Tq&`mZ3KFLa9i*ijkl*Qn!fh(~nTUZD-% zIE9@gi4^stUV*jqP2QFO<-VIRseo13+%57YLFQ%+J1oDwNTdybbpCD$zdgTW($lIq z$BIHY^q(@Cle;=QwE~hs+|U19zL^k4j^;YVCiQ)_V|=>nekP8(>ZxINH?Hz$PIu8c zYm{nPswgD?!CQe)Z5q36C>soWapR(OD&PUN{Q{9gu=l171pv17dWjMMC4tLQP5dL! zvFM%^k**L%bHhQ+T6xjB40<6A>~tcj^`zJa`FZPuz39N3L8;HEbkT^gQ@Q;aVAhQN z0>4%deRaE9rTCuN_6eJhP#im2vS;mYVW+=Fc<3-1O-sR4pWjD%SHCzf%6*a@`#81b zf_z0j{nBgF&A6d|(B84i1cuwSeravb(Grmg{Bx8g;(8ly(%)2bZ9wUzHIMJi!HRf zapF7Rf58W~=>IKAwWi$$d$vwrqBnl0qCpj<-m>50=$c^ANl>tqfL+)pm(}uV#%kAe zxvy0)|Ma?m(NSkXQLidki0yNE%(w2A=Qrwof?^*Jrg%%aEDLTTENz0ikOhnPPZHwK4l(NdK+!*$)#h1s3v4*=Fl+LP%lGCc-w22FU5b1H11i~BDAnDoi3@c&td_f%Sp(843z&oVo!!@_G{H{O}(O{w47$f=}JOTOc8n`=$hKWnwI zv8z`hSJtg$cP(llni;un&%3`TyiB40Rw%vGTF{WWwP1hw(sfcz6Jxr5t59O$*(B%j zC`Vx)Es-PcSm7GySIiB<{x|$@$Ymz`nOv}>`ajJvna_K7EVXrz-_0{zQrVw)Gi@o13X4Kj=e1bT4I~q&_^o4Pt1XoG(9A!P( z6eJ4KPE~&{hpl013wntWO@!1xg}vYGC|AR2-O|uy-UeyUN>;bf3BeK1$oa3l1Hk6^ zb1jUH$C(30zUf11Mgw7c2>0LedSe#55GhiF6t)BGsQT_q|2$1Qku~giOB_-htf;v9 zAytCSlLE@T9z!)pkmNplJD=s@Y3V z>A$Y>O6euV{HjLgu!Q{;|I2PmQSSpCJOFGT3?iDgEzeH)>ly~uHv6eQEYXWZU9Q*WBAcN~^ zd2AZs0gd`^REN3u?f(9SD6DmLg>_HB4%J2r=6WSSwTVNiBTw9OI6PwFIGMGg7&1|Z z6&0WiMC*{CPDZ15yfCAe9goO1pGjUBJ4f#$;{zEs)p*jGGzyes@g>J%35THV0qDoH zO0N<9H?xw}2VqN>?XBVBx*<^V&p3w<6W2!pcSj)G>FJ%?Yw`VVPEliav<#N69vUu~ z>ySflWzIb|p;dCUpq!*;uBU$Wd*yL^Nz}_j*P_;o z^pAbbj37trMRz>odZJ9tK%)i^7cE-jt^Fbhyncy!IFwgphBr$8E-0`ZBobx_Wr%Ay z+T~+KVK%%_q#+|yY$-OE?NMcl-u%Rwk@<0b`@zdk#Dt z!RCC($8ZXAaQ2*T4^+Qt72!^P@#Y zm=^u(RQ}MFDb0(~)lOZ3yC4ll#seldfTt|60euK;jRoa;TlBtTI%jid?$S2g#$kZ= zWQ$gP*LEvb(#ojWSYH;?AeQBO;9DvGKP~3o-XOWjT}O74|2edonR@Y~5dYAGHLt^A zQ~!AJ+_(x4*v^s)B_^&fo_9HX|F|3wN)K4SKsWsvid?T6+nm=zCjO1*Hg^KzoL;vS zs(a~PJ8J$<`iF8yALd~hc|+K&A#b2#WT8?1;!}!NGT(kM(YDhma+*`@8qG2xZ ztG%K7{sQD7q(yk#q^3v7r^rp-f-ck@-TThz;8^F#m$*AA1N#Htz5K!s&I#=_QXj81 zH_`JGq5fLgLr%Be-FzgEJ`NMJ#;SE~SWHtbGn{1N)4a;C*^OSejI|;x*vCF%o!+&SlU(#W-Le*8Pkl?35d({&_7+QTTt0ij;BE9SZLCh^} zg)U%YIhT8TN*Um=#9$^BwXzz<{2~cG6FSabE3$e1OV|aVctBS6(hulqN_stE-Pk9CQCS(Pj@jKe06grbdTDImLFgkh z`aLb9&FvF^qhYMe7FgH}{#48`*nxptjYV_#v2BtdCU#_3Nfti7G${-;f?=2X?u-6d}3BX$1!a3vQarsR}Z>Ef{1PMGHWy_ z&f!faHfRikImyl1LSAK${Xs5WSGPIZJ5T};jfTA-;YsVz3{eIO8vH|KX){wW${+gd zKiAslC@Z4|-$dBDS(#If@4H{?QU3`-V2&z%Ymv%b^lS+f^spl`(H<@q9S~L0h2ay zA|uSH!DodDxb~yUiFGi4v)kYxknfa_r-D1EPS{$>Xuw9v>0Pcj)GIMxtYvk77;1gD zPN@=w&=|;7;Fn=4$yZr<^r&vNJbhyd`Eggz*FoCo(EaZ_ zw~r)hm^I0TR~L{j&ctMb?316iU>~=7pFINh+c;=we&^v_R@H{xN7tCef37J<{gfAe z8xm|nO2@<`tk_Br0`0@)jJK=5B<>fJxYH$A(mmiYoNipLZuD$fqB>U|V$kr#2l)Bj z&HfjZE&K6>mnE{58ZrpfkvWD(eDb~=lhyyFWm#01;g`%^DO_dKoS+F^!LVl{3!Bg1 ze{E!62Q48SK1*KTRlBYg;@-dfRa5?W$y6zrfc~7?g8z5trnwoBpe01E{# zc5F!P;W)DqW=S#kq}m&^DTt0%gLMpK%2%ya*h_?9?&+tHifM!I}t&S76*OX!m(8Ru%!sA|PLB2nnn7NWD{Ga?cxI z;3J1l)i?+{we3&h9VSIaYUJ$a1@rS}qQ9g}1RTv+m2OiD_S%jxs?_jbO1$DWyJ$2< zKMr#G8H3|VYKX~P1osW<*|yC=1V&i7>LJ!a1}^n8yWClBt+7n^A#kj5C;dP`#G?j)0L90+Z2jX6qv_rLK%^Nu=` z`)@5YrnM3ZOK!FawCO`ElS2>}`O)a0J=YyCq38$+|5bl(tKyP%ORjQeLxpjo4w>k> z_7wMlXF4XvYQxRS>G9D*%=rAGy@TzQpa(wL%6*|`#SmyZ49>uJ7Q|zQq9190@;)5ar{zFSJXzvK;^nFy(hk)84jARr?$e^R_u zCbgq-faB{kEDhrBtkko0$k7LuVDNDQTUbk_q>v#Ee8VWi^W}$BoCYaz1Y3b`@0v;= zb#yQF)ozZAfK1SuK5*g8;8qkE-tc^+b}6?pE#0@r%R-acjzzaTeHOOher7+s{!1zP z`-ofS+0MJBF6ssnBzPqqVQa@~n*|t0bNycHt2PkuRqJ3-`w7Bbe4I*MS=~`^zLPzA zkbBVC|HvE3E=VC}X@j+6TQVFN=;f{pMUE*Yro`wI;2`m zkN)VSj=+ov50{jbm&nDEN?C-=L6nDeT7_dOq$Zu>tKtYnM5W-V}8)AIaO(=eVt{jK5~wm>X{| zCd{owpcVSZwx*p+kH;(zzh4S%ruy9_J9z)T{Fjn`;fC3d&YZ{&Z(#JPbL0B{=URo_ zpPY)SWFSEimTu67aND(YF+S<~dfxtjTLX^uwAR(}a~-i>L-){QQrvm$DBgo{7wmka zM|+ltk}0<%D~YjyLxW_xPIW0owaqw5uUus{H$EiuZ|~FJhvqI)!aL*$881~dn|G`i zuXG;qpE!A|?Yzq^G@vK!tC1)CC=s*s*(ya*8prK5KMxaay#J>+4q%ew!TY5Kv{NO~ zy<@mWn<|d)u~&YD-zZFRe%qHD8_Em<$(j;9V&)EQlU)UM%|*B6Vw9QoM8Q075^RrU z^tE95tBwx~?Z7PpOeTM6!QQ(L>_9r=@7Qqn{XpCVsd7FUwxfJYP|S(jYld!8TkL>k z*I9mnt3OfLirpY}uJie0<=#ld<%1ui&(3rBTm!%DrnWXH69OR-GF-2zfwN27<5l#6 z6E`>_-ji1Bs%ZK{5!m$J9FvP)x}L;}}B7pIJcKa*r9c ze+skR^&6Joq_X(KR%P>}79&WP# zgFU|L#UInK(y}fuTQP?drCDlSqjqo^5U_^GFD6(37{5T)2+Th9zp@IQS}PqnP#eKP zG2ApBzc{d=Ly+*^u27*bdnRELTw{|Y-n)Ng%>e9&gz63~c3a-RzvNiQArt>~b}lPo z6s2D+yKskq8>=Lp7rPuA+s5e2*BL31pEUmKG-i>6_y^C;72SY%!Qn%*7-l@ZCi+~J zI)NIyyS{ceG+poZV;^ZqOJ(=S#p%iotVpk+6tVU@UwXMUm#Q&{mo`&@5Wt}qoW#I4 z*7-bczj);a=tS#$4;&Fcqkeo`Y_7r%t;*iz856w@KS9pvxbJ`eCCM}_!9^LSxrAEw z36K?YQvZ}A{kV!aQYAU;ct}zYddzw-llm9h&CjH7C$hY*t?{esxxzu zMPAO>27&1Ss9)Gm zO6>vV1<@&yoFJyMFw3v`?{3E*12`#0rA{I@NuMAU9|W!49m452jE(Ss#tQtc#d3X| zIFlTf@6!O@P@xlh1hHstqbbv6$5sAj$&Qzu=lV{bw*x~TU(jL8)k*S02??FSrz@$hcA$m)vDZwN~N=G+cSxc zdsMr7c<1Lv_x03uMjZQ{)u2YlUjo$y;VU9=+4R`Qe)j93B2xs>6OJH80*?eK_t77H z=K|$+g^I;vq>5$L-V#sQf`Q+0${1m1TgBb9z|bm7Jv(e-+i+T~JXV3@ZDa}&r|gTYUYGLqRE z_RzokUe;7@cej4eTOaQW`T9jqlFhvj(!CT7mzk!JPp%p1Hx%ELk{hmZ4krO$3h3pK zo)Xq*;&e7$I~e24l@NQ1jF}`rgMV86s8HvRtkCZ;iREuR@=7`QVV-UG9p8J|Dh|Eh z_Mg>T05d9La4EC><2QEr^nz3*YGWRFz(*hzJe>(l(Es^<96QYg`;Xt&hF?BT(VoGG zPN87rf=wyZD+c_WgaU*xA5kI5#L-aR3ZWcK)%rIaK@{u$N;!$;oCrp$E@UFMLPQ`U zp(zC>maKR_ruPLGZi++ha#OHEx8s}v`*t`Io-dh^ajd+CB69oqqFJ41&&(B$qtD(^ zFxD%!@GD0#lDQNU)34P{3ySnw{lu?G+D!Y$Xw*e&^qUY|H!6z;iDU{S+W$hjSz?+# z^jz?k?NJcV?$__^6@f4p%CJw*4MCq{WXMp9I_SQ$-bCht_2J zh(3=0(kMx?qSr-h(58R(O-UA?43$siFI7EQ3_T4*X-4 zT-jrz-wjP^WX5E}XCGZAykM%{zZDLmr%d<@wuB6AS&)GZ^6lV24l)?LfTY4HS?OYd ze*S&c@Ux%OaHmGvhvWJlv_YUY{ceQkX(E$P1CP=4OwU0$M*I0ITr2@{?ha-1yb`1u zK}4g@szJshVJ>hT{I8*Ol5Al>&@H;%c5k}LJypZ5C4{mf74PqN6$YPd-im4Ur((`q zZRRS6g^bfrsiXd^8kkWMEVxiUYG#cu*XX)Tb{TMG5DdePjWgG2i*mAMJ~O*~FfGKR>A66109*6J%>rTV z@J-qLxaK`=4Ur|cm+tj!&xNAVa9^e?nk5!o2kI?9DuB@gCEVrj;yv4!Fmpku0#;%n zI+#8=y)!tB(*<~T(y!DJVk?2++IYCQz%U5zMVch2py<&t{7XZkZ15DOl^zT1%%1Wx z`2}KYiydK-p~jNIblASMQacnsUwN$WY0z-IGr)v~*tamky(xJHx)b37WfcDrSbinS zrbzIbzg}TRsv$PoB*r@t93M<+!}!$JXnJ;0Lr*BJ@9a)tzy0BO>Gq8GMT5=2!Oo`f z4RkQ~_i}V7^IWw4WgQkgA0?k1zFh+lK7TNF>7LzJh153a1uV|I{jo|-(s0QS7wm
6Y1P~N6Ca3FudV>ZAQge z{N>Xn>wl6kuaB$pqV~I~=>cv1R%j}mW-U*MUpDjcK9W9BS(ZTFFQPI%Ag~Z7rr+Qu zhyL?eT8|T#L@kzx`=6p5Ux3bYuZ{?J>Z;4>VR3oiiu0Nb#}N!cv7*a_X={(~jeApE z&`SnoxVr6Tjesk^`Pu8o4fDytsuTBQT=YYU;DEH5*f)fR#J1I^U!ZcgZX#q&j?m<{ zD~L2M_15Fo(PjhIX{E%!9BjWV$oyyR`f;|94CNtUIn=;juFB|xJA&DS!f{#tgMRMp z|Ee5e@{Du8!RZMehJ6X%mZFV^j0PCSE*3sah)rAj9YpxsepjE0mYE5te(7AJeb;ea ziANJP5LRr?UW)Fbph6*`hNS?IlPEBB_aa3TNjN|6M$v#zuA7dQ+#y@mteEfOS{R#tESoNOmcL|i+%ZyNU_V@BK0`v@)TtwuO<8nR{2~?v z%z76WF`#0|!DGZ4!ZMOn1LKaVx36+~B&1=6JUIERNR2(Oawk2IA?{xO3MY=6v+>~9 z=Sp4mv21EtMM(0=XUIA4aXl;ijW}~q?Nn|KeODUmAs%Bha;kl7R;AD<3AB@x=jiMRh)mFx(j$9AZbA z4{X`8Xcd)U4PGDU7U?_lW;PoQ^ZF*C?KMyI;DVK#6%ka8nC$OSn|=7!J(rhx;!XqP3F~R@rEicGDi4QeiD?% zi{3?VO;{lH_nO5!A1)hA#*pZ7<~K@H!AUQ{h%V-ssutR^q#TG22nHXa13wMf7->KA zI5jhTXAF*4MwOgwR*Q1-HRr8k2#4?KZ~Sz(CnC7qw|qOm1Vw&ePImGksLLeVUmoIb zN)|ICK)3MhQ%Rs|3F+v3S$!CF-UM1wiui;C+t+7T-pBpy`vW=e(B58AU}X7A!|UTw z@#@w8b!{bYeU(k)4XJP0p=Y8IOVmF1#aVBAI_+LwCiv`r%$y?N{dtVPxyu?4#=XiNZ{`7k;#owW_orEQ6=p+DWDBJU<5XY#lzAb3 z*^x6Q#hDv~Y^;kD%pIQ!dJm^&P)H#*Kaw^$Su;XooQfs_F6m{kcY3ZOnO1Oe(Qt(^ zlP}KMNw0VnS0fefX}I{bxJ_M>irx)QTU|EQF{X07%|#>>1EE~TTmVxaV4+9cC|cp0 zX9eXt2>6;{08sNwq~6*OOoczqS{{734RbrrEP$E@k;3PWUG6qh%*4S_f3e)=`DAm} zdZ*{&(%{EOnxtDCpW}R`Si1t4AOe$-;Q^xOH8%IVI32;I$?$DysU#>>D7k~2r&?Aq}eFJRB=>n|Cz4kI_l*XOiohro-=fvGc6b7M5HM||+T zvHOC@#KdCI3hXoXt9|yRLjCHO>@N>Qr_+b%{$Sk^PkaN>C*(L!ePQ&xQvkQcnfU7R z514nE^c>sB`I2JSdW~(ftyBQKt?u^)b30yi5sfc)ygtDU$~U3K1^@qoZB+ zGlRzG=ISq=G30oC-W{ruz$67!5lTRyYB?H`+X7-X9R5E%`E+YkFl!~Bp_T`;iVW4B z#7?F|v&l!!`LL=d0319giZe$JT@b4Dvrmg-y~)3JNnxFMAW%87%2&u85+~F zwOc;X|NExdi^cP&!AK6p2}KNu4xlM~#i9C$s!WbZDLgMg&|B;7ZtFr9>B6b{akr^6 zX3+HA7H0IH4Jn?59J2;FHw{As;a9kB31c|Uv1}IOt~PQE`LDZgPzh(!MA#Lce~E%m zf4RBgm3!>a0vNLKV!5XWs_kjzOixcQ3pl?eHugy^$^r5m4cKB!oOmq!Mnve9R%bo9 z-fdG;?XOGmV?m#vG8wNJ6(6QFamac<0Nh#Ym6Yw!-rIe-d(wVH$kh8?2Qs$`H&P;E zo@L<`?=m4hHt6>8`q=F^tFkoQ(n8)>;48^J_24hhF;AXFp||VBId9Au-ju0P-#X}p z52-tCF7asB1z>SN&vqY`t1Tn*tS`d=Fo~qEa&s_IFpX9Fi_@~pRs?K7N-n}cRk)nj z?kWtp#F-rbtF zK;#zz{o>d1*PTwtboSLACUv}pt?@wqO&w;5C|dF+ z976Wh02s&I8#;I}IGOr@38RnL>kG|Q^feA%T_PKkwb@BY4ZZC%5^dKUJYEo;?N2x} zXq=%!Wlu23APi0vE<5EaFCn+*w>X3(%u}Iu(+e9qtD$_eAy*@~zc)LCMxqjfT*FxL z(|vQzG7vjs0^OBATPCWC_jRIO`G$3J!IOXF-a86u23zlxa_s?Tw0o9vSyo_jN?RtC z6N<>vq7_M224&VS`nA=`QqCozr&a}$z zp$`>8H6aR1O^BC{6fJ%NUoqn`u|)=zo+4|o!GPCCQ@$U7Fj9#m@JTmlQ6GTb1TaD~ z#lot+-o8r@U6YgO?|?al*VS&TabrVw8EB5?>#cQQ+{GGt&HnYT&#s}6h1Veidp^lN zJUN@Y+^W7fhW{~s#w{L)DZ%i~mByPK{shv0mD+Gkp1L6dVun2ox=PB$JiNr>AV(q2 z9^3A*B!m>@C}is&+WeJN-^sdS#^&UzEr`RRZ5!*70?03Jx#q25ca{&hE}pn630z_N z36ceCN{-Qa%;9{Qk}ACqk+*P4zQ8WiS{wSKE9C0DU!?TeHr zq@-(8q}Gikg6&Eh^#;f|;_cmJYbUy}_!vXnGw-*j;*kgbSk-1vFsf@xm}$tL4WA7(cyKfF`nacPQKy)Yu8pkE!{3e0DUAmO%U zCZdkdJzlB#>BXp%fRBW{&!5-Kj@MO%zl@`Wk3y}`y)9G^=O`PWNyEI%Gk3`hZ7AAdQtwxyu$$Uin_`B+SJsLOU=OMd7#u68-T#)}*?TC^J`g%t=1 zG&m-V+)Qe1b(v`UtjY4ZzcU7e94=xzVS)%Cl=a1rtqmT==-GU_+!W|g8;MFZ0Xp{q zIvp{j-@m3E9UXN$w_T+M>bHwHe*=_IeM#9#;iVTvHKq7fNh?$T85amSGXE)*_6srN ztHB-38)2nM{CPTwGs;qseqq_<_UnsN@2wezSpWA{xa^C+K0I%FxSp+}-2XsKWa4{E zW^mcs^>8s31ylsB5)5sb=EF{J<}kQ|-dF*oHD2D|@}(wW zkO0Ab~WX?*Fb!$j@Oqb{5nzz^wrDw zdZmF}=M_gBuL~US33&kkX)pGwxA`ye-$BK*@GQK(n~YzVSS?;b$I5edc9x_PqA+C-t_ZJG{$f_Y0hW<)6TL`d z!h^H-cq?<2mK|!i1fzE`g!LmLf#ShR^|0Bc*joVY{GG!HkJesS$;#eu&tq>b*-jAa0PZS57i+(W zu;%mvvg0B=RW;!*g%&f7DLG&zLW7A}SN^wp8Hhy?uDSO?`lBA9e4N)(QNt{Sb$00joK{;}p zn}WGm^zgC6tW4={`P2tCEz!&-vxm~RqNzy(=hGyT0!(v+MI~!GFh&7LP4L4 zHb{U{=Qlj0f4zN1;t>m{`B2n?D6(X=!-9t%+lefMdqz~zV%CZZGrPlYE8)iV!&f!> zaTCTg8U0L!jv=|rgqF)zy|45P)Ull9D*bey@3ZFl6aLK096GV&<~26l`c{H0+^7oO zj_aF~ZNW19kp_nNZIveA<`C>M;p{1nUqcoQWhH<2*Ut;LBg5$-*llzLH0=QjK){s1 z!}cF#ZymsQ@&j`ZXI>lVnifaLPTBMIXnw8senz%lrRM>%CJzs;{bxX8%Y@zA_RJO_ z<1L;oK?F^sx*#K0XDyD|w_6=-dc`)?^;+Imt|*z#8I#H5A5bhN`kl)yWfZ=UP}MS>5$Ae0lmA=)k}|N4Em`5_u3dzvS%qShDo@2M!qvjCLHN6 z7iu0ag}64Ob35ZBWb)kw@ggG*^4d2^DpbEtj;F@MxNLmjXT+s%hTd$+lIL_sINdloi#KxQ&@}dq*MEoto&F$b?L7wjnq)$j zxKAUQ0@t3NE6S1v7k(KfZ3Z|A`V3~!D)p+|zfdPxg3yUItD9jiqPDlB&mg`^vgZ%3$93SQ;*0FF zTJ+c)1)XQU#h|x&&D9^}lGS6Dd&HdAPUtjYhw!|)bwleVvTeRyqNFWVN#T4Nwi~jV zf;>5Y{L?1?MK;Y+cA7q}WUriRmT;Bp^f<82&wV8-h?834?Iqp+VohK=NZ{TC#p-d) zui+|PzibH(F95QlY7qE{#=$u*%9{RmjYVDq*|98SV>Nm@tEeU4-Wr=zzgd~D-13Ct zezCX)>i8~@_^oZdE-0e$4Mx`h>P1EcHoH~ARv}NLa&_o&_X8-m?6|%xOfk_Mjj(@E z#5`a^_ri;Z{m8SuR^#;lacRiN;lk-1{eLZ-)t+O^%bGK50FUf2v)j`nGP9P&0?b^S zZX1)*sJ#NflL^P${kiM&fwSy1(qzKUkBlZZ&y$cGc^VS?SKNJe!~GGv^Ic(h_dlXT z;YrR!py33t9C<6MmhGHl4e8xCQDol9T zpzgLh{hPE!S2sf|D_N?hP)^%Te@06TsEJmOg9(Y}lRMdRgv4aZ)4s=G&mDV}V1o(C zZ5x7#5UCFmANE>g#fsxtxa#q!jFqRF=o2kxth(=DpA`5a2#H0_Buy@T3)u7R3{Nnt zwq=Mc`um+6FGSBhRAbIBKl<&5OzSMa59m>-W6k?IPviBN~|pP|5D?y=(T%Q zS@ugOu?&Zz*eCwdL!k4d|3lPS2UYd`Umq0_kj_gBUb;gGDWzMwJEXh2B?T{1(jZ;Z z-6h@KAYCHe&&JR9ncob5GUMPmXYY5c^;&7e>pfA^s(fy11Y`wBy+cFXFP2aChBi3` z&{5Den}0*gY^>X~>x|zu4&}-ltOgMv)lnVFU4t`QL{EI6r-y75N8Mh+t2R>0?`T**PF-m`lq)_cdSS3 z55$F1g7>3_`n=cQ!th&K7a>*JAMB_sko#1i*poNQdTD-FUDwU^xT5oZNmhOR=eaM@ zWXijum-PbH)rwjAAS^tVdiM3+>bePNOXZ+|K}2>0GU;l>VEq*t8+U9fYHH5Zy@P|U z9)bJg;G^PLrq^FX3ahh5uVJ)1j`bNVyVWFx)wfup0$06qYv=Pe7sfj9?=8^}1$d%b zt`B?9;D==hD*hVHqN{T>?i}E^R|9?1;eA5)++GrjlFf(EIOd{`=szZSqq~-X(MV~tcL2kz1Ee%FA*+# z=3w99fry?)x)hJF@AsmpuCyPPFYL7H7uKV2aNP?NlKfh8;w$r`DI6t0=qn{yz8a9% zNme(wMy&3<%#YJf*24|sd132J9tDbwVzUTSf*_dRhNVLQ+Pt8lR?qU<&|AL!PdfW(DWjGXE(^C=o$tvP zEYZ6Lv#|=6xpXMs7E10g{Y+ifcD`c;_VG{HB6eiZXeeuwY@oe=4D3`TIT2-Ou-ID< zvPrH{i3WE}&ilifsq-s2Nsrw0Ff;_VtU}Hx4!^`&U^tigSfiBH~;x8~q1Y2`>jP3z`*=~&928WV#b)u{tOUxXrqw;wi z6Auh=ozmkP%!KdJ@TmY6ELVt`7qLE*R}EBDNo> zF_EC}r6E?6+ztnxDV5`vx{Z=t6#6)}sch!c&c|c;wFfZ1H`7Ud6I7S#P*;ZaQ5+H4@TySKi5-~`)M7@dPCa$~X$lkVmuy^m`@lz`7VI51 zGKd9FFv83s~bn!z zF^&n9OlnN57~r+`5Hyrw-t-3n;Ct4sUSfXlKNIYEyH3{A!+%~@u=UUFdsgbxlyxyp z<%Ji1$TWeEe1^YLG$xc})lO(F4#R@Xo3H5l zbeO~InUM^Te@v~JstXq1&O3X{{JtZI+_XC8F%)DgaECD#+bVpYXVRXKo~iU{QHq(N zWj!+9Ku4#>K&N%x5D`M0RWBmVKd@jdT6SA%3SEf{xP$&3|E2RE7XQiFX?mg2;*|@(9Ni_U zaYWVsc;Ebln}lso(4K7n^drfdYKifpl{&hx(RnXYt3hy{%-k7cENqG zxMay;trKa%zMrwV5)8UrfF3?lx8=kRXL{J$sfn$4+}kLGwK|o-9bPp5uUfZ!VvAaw zNMaF3?7rD~uctUxDb}yI4Sn>IGbeH4Cd8ZNn1l1X*yqBN^}_E;xnlW82Nrz!EgG@WHJK6)CB7D*qPqUjq{L03h}=+ZD2qQ9QaK= zV*eiYQ(?KNtAteR21=taha@X!MPOV`P8D@pb1Zb`t6eSVmyFAfxWf>2D7}9mKV49i z8U7T|E1_rbw04Vhh|p?en8vH$f!8$ z^EKV1Yrhd?=pD6ujej>%*3_^nP`8v8zCxxr(c`J%#*VwDUOAd60ix|J=?7cbyNF~RPAZ9lI(|Ljc z@U}rSn6<48+ITy}{y3eRZpL$2u=`BEldDocV8m8(E&r}5lP0b=Z4eZIq%DD?U%z5T zL_}P&0d+w&6?-A~?KMdhMQLmdccCH=QARxSuT+7jS>I|Pf$Z6%lIjz~*p3}}@uE+Z zP!Z<D?dtcyKFeb?(epa*}+bya@&IV}I0O{_0ES9d8aC1?qXD zM4{=fJD%EU4OcoTJ6Xga-+#jIbte|0S5L~N3(*TR&+w4n$U?GVr-O!*HVs~9BTtUG zPOfMP@X0uIb!DzR^oCuO<}Suev#zt8p}i;v?-Q_he{k` zB?_s!NnUKc2Y)~x{89WXfGzt!4QVaO;iJL@zvWWoS9t@OKvm}N-@ktpUg*}^X6zn; zC7IZNT_DsA3w{*s%W#fuKQ*aniIHVUrnO`j(f34#0{oNq@-qdlDJ*rzEc9R}Wb+M& z%)h6DIbL&KspYpFaHm~Dz+CD}8-YBJfMNdX+gww#dY@;7k%zb$Lta?IcI3+1*J~p3 z59NVri|>4i&`}Llbvy0InGh5WBIvM;lGqM_G`EmBOjYY&i@2{2g1;skT`{6qbIlVt zp;L_umR%Y;9f@7n9A_F3LuJa{`Ch+O2>9xG#;VgC4bmB*?46p?eRJ6IwxgyC7gq>D zmSyg6$;A)DwAQ)PC|?X(;e|6X+cb2qr~Z!qXHJ5HL%?4sB5bAiIRFeA@_@Gvhwf(^ zl>J*#DGHW~=gE4f=muwAWY*@S9}b&|#;z*hd>es(@fBj0Y}{6FMS0fMv}{Kmm%h?B z1iJp#&IGT%JY}E&3l!2uPj{;KddDb5_M>yanOw&v=>a(8=nJusyRNqy)QMkySUwo@ zMc*H7O>m+fR{fSOmwiyPk$IM(xy)R0CqU7?Lq?7=cVL0_RMa?{GPSDM-E#n;GK--^rcf?7QO>~}j@_jkq{%V*WP z4U`av=%Ylp+jY8B%i=9=hl`Bm#n_(?#(%CEf)raSd>zEv_QtCI%4s~s70JfHp5aTQ z{>|Cucl{itXRr|x^Rj^HeA=iHB&(N&O$0TD-i^T|TumJREA1}J6lZcd2Q9nG*_BbZ zzU`|5$?d3o-~e|!8(;um2rFC=jCJ)83-<7Rx&&9 zS&{#q&iTZj6kWg z>9lI6f!j|Vu{-oXgYT{N`%3;S;0^&<1VNi~{6or*@F}LO)hEw#hcx6gC8+528M{WN ziIN>^Ow1~qLORdHE}U(&!tAZ5@fD_;2q#FZ7-pw@|29q2 zBASKg9dj17zJRs1GK_!ko~P?FPls9n=(in3?Hw7ab~Ou4orr?dp-qjKE-R(@`3JM;Y-GewH54X?}Dr0V)%!;vWOA!Apb zO1?iG}hq|rQiWFS}Wo5gS)+fVOxX90wd7S#>AIFA+?c6;L&3~Z$XH6AEq3KoS zlH6v11mL*no1-is8N{pb36ME{si)dGpowQd*4{A({m3JEcUPE0s zlgl7IRfWVZ|1mZ@xZJdOzw09&TVa=+qKc)~q4w`Dv{)T7@e%3NYtq-@pK*wZ!?HLn zt=U%y%RLGSts0{veS^r4k@e3O-uBoo*;K=7uPh^^XB#fVBG zSt#^lRpdI5us^-9Q_bF{SC@LX?3c4uJ$)Hu+C+=nkVXS`x|?_bP9+Vv7zc%Ac~2ys zc0ccJ++wn%f-lY4uUXGmcbTt?hn->@p3O&!L!L`t&Dc0D?tAcbd^A72f3|D~F1O`9 zU0_K|_|B@tHdw3Q4$kNS7cTk#6p??s9e|_&>9B5#^z{7PJ@rUgRa^P&;&l|S zg7R)NrU208TW)>2m;-`mp`HWY^BF@Lr3kkDnX&-MF)%N}0({fy+d=f>EbM+|%I$tj z$;{0T7T3FUFQD1v>>F2_&W!J16`qe~&E>B&_Ez5ub3 ziDpN?a8U!GhFZ2qio;Yc$7z~xQxF9VMB6LZcE!+ZBjN7J1{fC?*1Y{*HeNU68`>`y z=&ciesQ6E&%&v~MUG#sAUmzK9%bu}@sie_0B>FT+j@4w54WeX;W7$p`PvH$?4_~?n zneO~8WIajA^-R(wFmuD?enGkOb4QV+wOeXOW-k6v$sB$@*;&uR$8UaT ztf~!L@^+JMz(D|`=Cq#}nlElFf3H*eTr?SsF7T^PL#7l4j?3y}l}a46p%EJU3I)ig z^9=6_VW(v@_)F1t`rQxfTAYWVEySpTUspwakAceVan7J~R-meHZEd|?=XG zq&&757S7yUOLxT{)60d&&7O$jeVRpPbvp>@V7?n;M#?SqI(YoWh2c4~M~U<7vBzV# zqA=pP@YlyX@I>kg6|?fMJ_Ojw1gB9UdlaSzLiBji#k4}`>5{~;9ju+s+Qg7O{r2@Q>e6ZO28`!&F8ERw24miqG5Z9mG7@71X$t(LaNJT?U z_|=-A$VK6qxM_nW7smQkanS>|CtX<(nP3v1<|Oa8eBLZ+2X4GBv(fbn={ z*x}xRuz5dS0hAnA_>+aaWG(9{l3UoYvO|LUh{Fz;x(34+);ZNe2{`> zLs+W#*7=4;J95^9?!SwvnwUZz$JA5Ng4#5mWe&CX#~>n*ecD8{ZI%$JkKRx}jDvO& zZs78p)=m?&sp32;<=pvD;V+EEoIb*x%&-7Ap6T8G2gq4MBfb)$6|*c%pWs>Wi(>Th z3cPljY>c;`#fKt#2A^9{8a$n(+)*V0w-}5?y^hRH0wQ}t7dJ;JxrV2W|KkQ3dZV9Iep;4yX0h&Heu{7M^s*xakQU%ZM!&wQ_ubhsYXo}E zPEcfaJ78mDUmm)&golPA>CQc>CKS&uas}?p#Ex#p;+q2NELsCswFlRdsL2DV?O9}YTdeEpE5vYKPJ9T(0gI<2d=mFvu~Q*jX-lXqZv5qW4C`u9;@Zq$}VsGLJj!plI}( zx&FN+lw~v$Ikb}sEx;;C-Zm?wnYZqCPkA{}{0MpjjQ8e*FyP;*J=7EMJ{KedFy_|m zcWaLtczPEqyG1|#+kHQNt;W}Wsd?qu)1kPbwjM1l{&6Z298{QJF_i;Ye@~Dt^RsdO zJAE{tQRm`ABixg0av!lA=6)>K1M*eulz}l4D-~%@9A>8t%kVziH(zp6QjcugO}pJB z+?hkdPG>12-qJ~+UsgmeT}yHIfZ6@zqPYfRV!hC)(zoq%k z#%oWrkje4kMBsrPX!E(}FMgl6dH#M)2Hduff~5lw1Ox=ze#RQh+d=N0&-|wu!FLTO zL+|W12NEM&F7{^wRGW5{QJ2NQ6&LK{vziOc{#6V@HV_1qEI+k6rf|aS??$8cA86rd ziNzeZDD`0V>N(zq^(!fUaVrQ{ z=K(Z2HMOezh=$_%?bR$tT!qXRx+mLK6!Ikuev)s|<>xFKxOkGf4RWwmZKMe4LEetO`E8*(9U>9@Ptsd`?rz#CnA!An2@c6e8%RO3 zNbp+w9W{ji+iLs?@6*o$?MpGxo;hBdY|iK3+?O;jxNBvo8M&S(v~X@Q-u31(q)m%C z>m4`9Jw+El;eFu!)2I5BbMd!n>h<_A&v)zYT!pPAY|)hX9~Wc6z(ZUn1#tr8zE#Jh zrdtElw993BqQ3W&}%t6vBnZ5(!WSbk5S604ug8gzfbVvKklZ*5_O3P!xF8TwgYs6 zcG|W}Wg(0}%6ui{mOn3Bd|!)wvE-eep8kB~x%IC0H%!XYYVU79^P}aUKC&gei(=_^ zlhe@3YS7+&h*=a zArxTN71x`t!p9`_SyqvcNdC%=4yhLfGl;x$Nx*6SWJ2y{z!6y^;9zCJ9u1HsgJj>4 zrfFHZd+di6#O+xYM$?A9IM?iTwSi0@9*77pUI%Dm83N0}fhif-kzFZST+~?SQd7Lf zGat6~r(i{)-U0eAwlVAvKRRF@Hq!4Wgs$KGJ3xd-%7~_BOrB%Zf005rLkucXO^+!* zwf^;RYw>Z;)--lGr>b`nSMjkQDN49U)gXT& zLC*R_WsF0J@xhT=-1N&?dKn*vqn*_ok~;cK4rqjUaEqsbPRrMRvuF_Yu7VTQGy z2mYw(`%I_Z?bC%Rh3ACvKWe<2`9X(`ECE7fM4>M6{a>P9296qhwJM65R08f7m-VN! z$v1Z&pw-~@xWf@`c+!C(e*QFrkF|6wf(O*TuOt%BJ-`g>X-a;8Bu3zC&@oT1 z0A(XMK>(YB84nNd581;pS;^*EJAO09-Q8XFxaVaD@Ebhbw7gCldcc1*_Qo0hsZoa@K=bRh>|vj~hgtCkIP-;gY=dG&24uxh0pU zL1!md8fFT*_>`Pd6G;z?dG15f>Ks0+01>H#+=G!+3m>gyJH!d?uy?y0Y;o)OHXxhs zfrCW9(I#0}&Q=`r1hH_e`_re0_a?p(gT@M>F&iE5 z`#JQh?~_GnHe1_%+1et^jeaXtpT2%8iROWjjC!k?0p{p@`e1qHxt|CbbzhoK%1 zovg_-I^_$lx{!aUqR8<#8eJ2T%^UfFl#3v%CM(a*)>b@%9FI+8Al+s<*M*(v@^(QI+MsS(RA=Z{?2HfuHUX(jTRoH>B z(*k5I@7lngv=V`7pS6&%`BzNThuH^LrM!V7*yyj%Cw)L#H$M5ruI`hggVGj328mY2 znuMrfPf@NG;^e#T!?-~C4m~a}S$c6P(Vg@lAI!7t;}6mxk{ zAsT2NU(OnPu2>AO-6~kGC#blY()VW?XH>-fRm@?yW=K!+PtN{P%M@N7W+bnth%)Jf zrfyw&Ib|B%R={j+JT-{5wgEd#I*QF699uj7Sx&B|QMGDZ7qX<_{N+2rwO(GFt}y}) zTL8smyp&5{epkdt;7X!@rE4yyoyaaVh?E7qB{qi0TPlvffN2@jJt9xP+Q?eBe!0r>~K4o2dkisDUl9M;d)S7U9sW=8H5$vsjmlAbCVYS+s;LfZ z9zU^qqpEGf7{Tw>xg0pk)>WwMzc$I7?>^*g`A16ksm_CYe>~t1dsC{q8Ol{A~^N3t0CnpnrX+c(xfX<$sDa2GQX^-Vc6qeM@+xN_I2 zIrc;!j-ud%Ly(Flt16ndePw|y@pQkOOTFDj#h$WgQxXKDwFv6lexV*Jt!Bh6r_Ove zpMiB;Z1C_A=S6UF*Xn^N2Xq}I+T1$Yqq=)|?(itMJp_(|g+Ol|F%X&uj}sEB4Vr-; zF3OFc7O(t6?`>Cp>pwzUBG*H~goj9wkAv_t#fv=$?8DhN7=XV#Q1Z5xXZ>}DMAZgu z8|ZMs&q0p+ZJ+!1S5y)1+_CyAd1SL@-b?Sn48^yQxrU$9^KS@p2V$%HZCx66^8_PO z)@<@gEZ>{g&rCg=btEKMZa1KNzjGdxTB}s+EQZmj`^A+CW=qe0;}0I{Mk-*1Q@&@j z9Q>H428p%(TNDAXb<3?Ho=l(lzb)B+zTUmEk@)rE- z100LTte@7WGA9%{h{%HL%%Li9gYqkDymoIt0*+6~lbNKFg z2TkthxN%|BZ;}X(BrGV+$L@^DNu_38y!J6->01>nj?aRJ^tVmu@~?E5zKL*dRbAP1 zP>2lUsMHy^o6(y(GPpPtq0^#-QK$nzXlmDaRy~uI1@=dIbj`wD=p?kJ(&u|epOvGXo<;(a>?%PvOx@dn# zUWWA%Q;YL1z5vYA9?h5%p-TKmhp|YR#jCNnbKt=vhJ-$seU#9E3+oSd21{STFsv4n*rKt9aP8S*$N@T6f;d8 zoR5<2M-ShQGgP8|e)-@}8k>!?aJ3E^jkcdUD1!s!U3^{h{qjeY)z$FUL<0{V z-NYO-2*SWAe8*pSFQGuAC8;#kq5eS&Ye|aFxcS!Z-Mhw8A_ju<3ojS!=)> znjwrxo|utWb94ctA)jLYOZf~$DH;XJj`x9x4xP%H7Xo}~AL>VR^vh@OqW^`c4O~VS zB=qgM{#_tsN)pfHBrG~G{6P&r#QkMZqm#zf=tA&^l|A_=DL@2rW4zauZUdNLdy$8h zEhxf1X@o%$r!X+7KOQgIkui>g#lXW6=obEGy?ih>KBPxyC^^2&rsnLbG%Y@YaA@zd z0DMV9$>9!z!Iw>eme%w^#`gpSe?}T)8a+*F%H!k9_W`-rJ-ZHey5{h6M;+Xu zq{=HSFCoDCeFQHq9Shw28MD}8nOHDcVx4m%n6m;9ze7Pt3L9msQvLDJs5qo(KP^v= z!g&TU3)^sNUV&-&XJa4B$n>q`HiDnpX+sx<6g=FYLe8z@W&U6KkjXuRWouOVw&>Mg z=}#mIe9-mcvRnQtxU9l0{?r0fneXIks^5X0jF^v)?=drCZfpvi6Yr5S;onzAIE1U; zcDa1%U_sfgPlO^X^)Rv6M;KX|ha;l$n8Jz0~j}_P-F_IkvIQ&7D}exRp|p5{WyqrODpH3hu2n6Hn~q}? zziUV20b2D6#4(CPir>dlqEJm#zs$mG8~(DIy#8Bj2w%N2!WwQ^I>&Zn2nu@=BP!<6 z0dU-3291)itZ+kDTg7o+^C?Ms7Q#YkYVB3Aq;{}OR9=d2+|8EW7$TpeiDAmqvi_Uu zg&g>a8z8QEv4bjvsH#iD*`mY^B z#S=URZS-z?bgc@AbOK3g%BN3@Zj6@-0_B-+!efj%%&8-WdNoA>;Eka()8>rm^EHs% zwbk7r)0&}N@I$&Y?hZ)O79=T>#Q%H|;jB^r>gZ;z4bhh3BvnkauT9(IiSBP8%33bd zL0&X}Ai@7t0>|>^wPE^j6tbAia3-Zv><@fmc4KudoqJWAq4oX;ox7BiP0g;G@0oB} z9l;x{DgWx*U8E^xs{j5-yjJcWGS4%_u{tcr6q}Iv4eTBJHPZu+xA#rfsCNGf2$sr0 ztku}ifCwva;u~+HrevjCd=z3cs?*Ra;x%)=NbLJS9{{bBBd(Hz7&|@05p_DyVFf50 z&q5JcdbN0}ykaO7@fgFizqb+feUsIj!Ff;r+41+82o$RZ?o}hM zAL1dzuFiCk7U$=JxQqVFI6OYiRA!z@| z7U(GpaEDPo%Y3zyM+f3K4JtW>GygjX=KcGYXMzO{%(uMq zWaY*+=pw3ZIf7UpD3d4ORFkuRiG+~gijsI$-yFTTKezD%+eXe*d%B3Ht*2L5-JeW+ z%UIF*PMdE}EgMlVsmZF4miSe4KF(u_E9ypNd(1i*we{WINOCNS8E2dv_+tpJ~gonMo;nh(^slAP@0};?v;B6$U_GSj{Y&{0c;1Kq)ya^teS)~KPVhZw~ z$=UPB>qH69bYLkCXxdxR#x7>@RpT1j_A0SaH5f5~p{tMBJDH#9d>0aI)Y&1q$T64` z!IrQgRg_a@FK+%^fxd|9D+EJ+u|HEba3(#_xAp)8X(u1-VHvI@XU(p4VEI-xq6M5p zZji|v6GOsQJ3aS~)@+=(ui3h&`qOQcDa>z}b%gnlO@Y8uk#T`4oTmr43(%svG^c`9 zaR4O36s6(CYY^0HU|sB6B(rl2v}0WPAVDP|u*FJJI2Kdh7+C7#N*#veC%6FS;`-X= zsj@*xkg?eE#(yQIW~?=x#L@HI4kqgjUd|3~=k~mKqSgv-6-o-3h#fBbN^g|oTSwoa zNXWCLE7=uQAKcn&b2z3T`F*(NTjQ0MdsVqX4_tdK5T+2#YdRTaf+gDI&7>IZd@)Nm zPe{OKd#!c%-oTwna9%6MRR&U}Ve?vO2xK$_oinu*Qx$}sPrFvyNnC@dyq8i#&6mkk z5hnJBJ%rt2U52{lmT^S_0?H3T8tw6L7((ceBce$2hRhgW2^y|K5oCZE zMS=i*4hjO+y$Lz(EkXIx7||q=Y1E!E(}S*nznbR#-SH0u;WQyZv5}P@L!Tf>n+@-L z`e=-F{PU@DG;uBwahTX~K$$tYV!^hDIKq$b=mR6JrjwHVsJ$o!`{aYTk>etMLr@xx zRjS1(hc7{n>#+Fp0|sT#kKkG@}o*Huw~G=^UNSK1&#YQ~5zf`k`Diz_2jK0b6EF%Ml zHY6d!0wV&;bMp_+uh=yIPS-JX| zf2qB23Bl%DKkf$0B4WNB%N{3&h}} z<|$B4PZNb_3I;J~utpN8SF)*BCM(dvL@5V-*BrioCo-#q4LXjRtAArvG?{smoF@g@ zNY45}L<8t9DIGt#JXD|v%3m?$jr#+~3a;8T#|jvf!{dq;ToTOERSx=KO{cVFgKlgH zc`#1-%80r2Ci|8EiU^gygvehwj{5m48W8rX{z!P;kd0rG5|wdPT2(A`tiklu?tgyG z;^I^b@_hPO9gvO*fX!I*(ZzFq_!3ng*?vZ2O=O=W=5O%2XN6W*PNIYjjNs2deLWAq ziZ!^RCXQS7eKMMM+i6+e*sh+lK#zui!tXzsn5v^9aH`8XC|7weMb6nLvCy?kwVRf0 zdTYv4q{RQ7ayHAO;0Hq#(al-xynLbk&ZZR>MCSMoTFO3;PpRmcww zl*cS4#Udmq*RfNahq}pqV?u@_pXAY>K&m)7;QM1u8Oj*{=|dWEHg9kkYh0I z&BEOaKEj|_9F2hC=kc?Zr`d7c+9K@{>cLCjELg6_Qz(VH-R-Y4?i_R268o=4XA2QNbiO4EYci;i@KL!w}f4hS)TU z;hwqab7Mdb%_0|8>MDa=Ws!``@we5Tj;e_tw5-@35#x`_4jKIc{qC8;a|R%XN*N|0EDZQ0|_bV1wG z@nzWotzpoI_w=KpRlUeJH3(YhC$9B!hKBh-c>#>#Pr3aPP(f=Ty~u{Sipeuh&F2aJ zEH<{z@CX`}4G%U;;usbVVj&E-KRwg1X&FwjtsZA&lKQogeA;_=jUy3eOywK`?H=?x z${nV2J+MKUqSWWV6-K<^H}Y9Hd!1OLJpaM1In!Lae7Hw?wEVmQ>Xmx|T5&{ySO19@ zLm0creD2(MJm?rh|zf$^Dsd>G05}!UnCj?RDQ&Eu9vvUXDHA!@P1;Ym+)Z*QYs5 zQ<|{`=v8-~kM2#HkfZR*;^I*6E&NtG^}b4KZ5)=U#C|Kws8@&{Tw4ipxW~Wia7?Dd zN~{A%xmhaAn_bA2aqgY}y|w;u`#tJ&+>I-azdHLz!eTC5X-D@|+w;gGz-mBRrM=G_ zPFnY+B&8r{vW*cDQkH{5>YT$(h1$3;b*jAGh1b;j3+#7}{ZNTkeh}~6jYSzjhbFw~ ze7{h-f0H2SivmnHDhBZ^=9KBW4nY;H@mC@junXr-bApY(Ylhkk8g~d^jUE>4whZ%S zf4u){%S3^-xh*qi14ofjxd2A@gzbCY79gi`>SoPr`QokYEM24J(RZN4TF3!uNH4J@ znS$lb(!ebC-A_L6C;z6CWsH|gCnuM?hWH;D%txm8j2woZpef?KiKrKgg=)x>GU7%j zx#PLBQgggb`ITubJZ8#$Hi2Z_Dc_OFL;!H3>UYU`ICnW(1vek>XIK6(@UtZ3r^Qm3 zEBid5v8)*2H561UW7;c5h97$LLMdYC$YI4!ZSCO(v8tBm(RLuLe`pW8d~oJxp6e#35C$N#j_*nR=O>xQch{EqJ{PZu?5h zRn)(Qo&UB*3?uMOvO{um|7xdYb^fyK_clAvx8WdY684zOg=j!DZW11nFlwFmebAm zo?9MM?WSx)tUQ)Y3!gUcKv;%k0Sa<^;OJ~IuvLGiiuQbB@#HRe54raAqhSYwuAZ7y z)zL~rtSoN$+wdBdLp+K2;djzto_C_SX62OyZIaS=v=p{+tq2x3NKTBmeLxp-9dEd? zijnz5^kW9WDJgG1esmRfn#?|6iOmg?sM={AmHu~lM$_+Jj%W{Os!ixYX2h{K02_Hv z**}j&i$0U(gx8hU=3YCFk3K?%vwXYT^Z9`}lT;KBuGj(pr((ytt6LL=JX69_SJFxh z#|$kEof2^|W#}vDOPI)X_ITfg7!F7dea?rOU0-?UF5y_SM)NGa6-R54q2VWS^7~n@ z09MuUeuYmZ!hCMtxb*6Km?GT}s%whc`xQ8#F=*4%3QDqe{(!^Co{Zu~7towiYs!I^ z-8H}1^=>Woi_dK4Qs#$n12(rLR}{eO06~M)CKU;C>dONwL9G$fp4sV zehH>R6~U938@n7lR}mtHgv`Qskk7{{@LAv#UxJw1 zTtI~=iU2}{7p`dyEGz~7@QMPaKpmTni*(i4BYP!XktkZju3nz4WJxqhMh(heuY==J2TLJXDbdOiCY387flt z))+4^+#ncihu6=StY-|Nl!MN4x1CVOT~CmvSP}rWs3Xc!SwL8?K+a1-M?(hzPiLOz zUxp+zWA}G$bbHUNDT~Cx!wUupRE&uaOKmhTQbipp_ZzWK??$QKV@ygjZInej%TEuG zpX5_e6a=O`JAHI$foCV-W=ToYo~NiWO3l2n{p3M%?1p^n7aPl4OEqK$*&kE_rX0;` z;o#S-g)Pu}x!gyFZSyl7tVLkPnZM|^v>mSIVZy2JEsCIuK!TwSB)TDiPNgJq@ zLP6%bUeno`?QIuXF?sy6oGmDEt@VI?{SG(5XY}e%S55)M+ut%HX$a7i9~dQf90Otu zEvVL2AXW>dc0{40NDeQHA7nvuVGNn-SH@i6T8(Yi`63?p+Qu%RW1AS5t25=DOk^SM~4JnS4xw#)MCw$FE0kJ|;P zAjHCZ6j56aCMlbZJ8izyPBpf`=z;XUoP9I?0gln1PxI`(GIKk9!#}S>j*v1q3n=hl zm@j(~>BmH`+&RBtt7dXG7hpY}5CAc&_yI!Kn%pC}^y zEf%%k>v6f`f!5%+m3lHk>cV9b<4oh)l|^j$w6342ZP+{w`|&QTmKo-p@=)uEwF2Uu zCwlJAd-TsJ@i&GoR`o(24aWjVRr8pIce8*e)9_n7S6Wt+Oq2d1MtW$mo|wpNp|qLw zi`qoPAD$YTwx4buoWH^;dUek2rfHYq$>&ra2||dOgx6;u9^WzH=@WGH)b6^g{a~7c zy+Z_a;{MFN-ps0g_RpUAK;em#+tZzu|CsP9c`5acIRgs8+Bt;V>rI^ zqhr--$VCtPJW8M(7mes*oxZW4fOZ9|X=^urFL5LLihZS=BvjB6eX;$pjRq{LJ(HG& zbs?X{nqo7V$GbZQO_C}HF@$@7@cp+|b(Iwy7k7O2*yBtbzHHF+lwJ39Jbf|uMGAw& zviKnuW~Cxc#-nz6c_%H%87T{8>g~AtKI?!21DXvEuq z7~@!JTjBO8?C-q*58x%?e(apdrDf9*a1Wh$8<5uHCrhR%{EzxE)q81r(w>(EJ7s)a zFfC#)-ISW4g!do*IDhqVmRY7or=)z4?)bV+c)3_{UN8cvcx<2jFW5S>@Twhsc>o!UR>2dc%-6uN6n$!|$P?zE!yGgx?ym#?Vg8(4cBP1s z9X)|IBj2Ce z^iahbl~`yVse-JgA07Mc{?e1vdIk~QUSVB$u}_+cq>Y%wt-tL_Ux=-hEH}jAN9?=! zb{HZF3uzkaHK*+FM*#}l%2gstxrj|b3BVAKs1XZ=eq0YF!q{u&i3l=Hj{!jnk}5*g zGoBKSq9C_)%AU}jHt1hr9^&Lr5#bCg{s<$*c=?e+e*&$0;iCWGRE5&JpLpTZ%H__r z!vw1S>Ghu9yCZmD$yvUsDc{^*;KE#o5S@!%VpB)df0xnJA7GI3F)4438F$ch@yuu> z35DvyAqH{PcIC)7prWDga@pm0UsbW|bL83Uy)L@e#z4$k{dm_o80Yk&v)vSA6g4m_ zQX^%-{j|{PIiYS$o0c1v{GdOJzF?_pUGu)7-?@Ak=y;D^_VOzhKXONd@5IY;QP=13 z&3bR?)_gZ^c6%S6`nG>~uiJgmp{?U-X}RenuNE{^qbWCrCd{kd_(voK%s^i=7zc?x z-(b=qf)#)vi3z`~2fg#KJ2>RmVjm6ndR9gU%4o@YZY=Ve)v(YQNBK}zVO)X?UuZa5 zw-N|t(;GJ)p}wa0Vmzw?gv~BZ%x3j|{!{L~JxKVGoh+kUO(@sSxzq(KK_2cPBOy3s z_ckFLpu!PeyB;^|=z^gfuSw9i^Fx$SaosJ|39L~`tN$JuZsD$&R9-(IG17p&Zo9hNOlvoisFS}>~E&1T8*W}s>V z&PsZJ`1e6ERgIr}#50DAE7-$aEofM$#-OTMec|X7`tQ#u`Q2`S&~mmT_O`EX8rjh4 z18HeOaALWs-MOh^x#?@V8>3j7J_x&_0N-F!If>1);4lM$go5fdOKrho+g|`F6uhH^ z&DMR*OJEpHkY4kLK^H2`23OvhE~%g=DfZb2>9g3{3@7A7L`&HiFx?Hgsz&C@8v(k| z&r)8DcmH-m6us3K-4LWt+JO(mxt?A-ih*^XFa+EtkbZSksYEOVH`E<}G%r3KH3LBa zL?n0foAIl1n{FM2fQgu5Sv<9egA%0#G_4!mS%;}~?)$eteFcq=cf1mnlroT=;3 z7?~A^Fjka51z7#fb+C>)-!Jn_OS&)4CXV|NWjD{!N*$GVx#`jYaslj2TY_C$-b9-I zXeLX3R-fKj9^*81Yx=W`_xXB9l@}QaUaUD<@SmCeW@BBL&h7UCIFT0@J0STPOizT0 zt{LehY+_k}eF_i{w{jb!f(Q^g((bID>ejvUAAT5Q^WF?PGj!c4>W7{BbM$L`rIH-a7N8K!t|s=3<=B;ad59Qfq^bT9Hc-hc zfLUdtoXSVYrpU!k+9&NW#9E=!DrxPYCum?YVo5JKPH(A*r~<|ltSkwkneWB1o)3JR zyiW+@dnOOes+Ua3V7{!+q%2rJ;%WAZnU_7beX_xw$hu;uF}OFD7Y~HJ230(A{M}X2 zv6!H$nXD0yfeRv_~`S%}OVT^K2xwO3DTcT0DDCc%kX)9b}3HjVo=G%{E0rceBh*{+W zth_5lVagRCoRPNreQZeo9Tw6#9D|}^(j6~wz_Tcd>fTooj1o&5T zY^NJ7FWpdshpAp08oZZ`BQTo1|CA1uKrAdK+lHxm@#NC62Tt8=IoB~5hu2P059^?5R#E>K=qBf}ubiGfym6SV1 zuuj`9Vf5c-LZyDZU^LXFYeNt-&SjzIpnTo z;NQ-8i?pvh)8v;R9o{G^qlI$QO9=3qHVrGZ=W!xGwP7YM_x9dG`~2d00$VOgVo{)+ z_gm|$Mn#=_c9EW&+Y-AiubOt*-E%Pg-*C>J_jIg#{yCNJozv-sI_LG}_)y8!8x2xT zGXW@~!Oe$9b20epv^ySd+p#bIA5UKy7G?K+O?OES2nYz$-GU(99n#%M4xNHDLrSMG zbazUZbV_%Jlytwh{(sN=jSIdobI#dkowe6q>ufH1MkYDL_~V=lsKr=_0bx>>!CZxr z57{M%0+akqpRnA%(12ugPcF&#IwDg%j|WGDW-x)zR|!_IPs8Dn2gz)$`G z&S~4G(|I_}i&>~Ygk5d-(%41AWOlGfM78l>{N<&%j+$3%5?~He>VD<+nRuHUJ|;t7 zq@bz!8FLKC$BvX5D>I^Lyz?m}6$nqYJL39YXKoBJ9#^j0ITlw(HEp{hDhKqI*ofuL z=pPK|+`cRPtCxYudtEXh*Tt-4zXep!QD81YOd!e9A^t5nURV;)gkgPh6~Ip&))jse zBdBrQ0tRv5&}uL#ly^Mnvbrg7FW${7x0lb7?%VL)90&%V!K#pJ{$>Ze&{ zq~CH=x~xXLN1w%&`$sb-wX|yE(y?UY-9DzXf?yZOadc-E*{1N{thbwy?c+TV zJOB_b!xz^|PoS5}iPVz4rfLKG)p>am0-59};DuylgMavw5~L@}ZWy$2$#eZ~Bco@6 zUzX-{P^JFOlI&OlHIhtCvJB0jJkfD@u#ZATEm}RsuSNsynT82~lY%kxiXIRuLh}L0Rtlyew#7;|ZB)g52Z>lyYkdUF z_+!8!&4^Ph%T!DsR#UnyuYJU%MX4OF+FXK$Fc!% zL?y(p`R@@zc;)fDM?^lbqNLcvHgc(~KQ}5qc{RB;1X#W_#Q`1*pGQj7>FVW4%8wcM zNc#d$3rKCQGN`#(B(PyVu=^`z*doi}hm^F7YZL=6y3W^7vZa<;X`f?6iG~| zeR?Qp(iu1J&BdRKC-cVyaK98HDwODOhoaT(SZL|3u*UfTYyX+UTKLDxvjRO@NQCT^ z6kiB3W{~<3aaNE0xqQdH#)jPT#{Q_z&_aK9SUCXTaU`WeT^+HQSma(0=3b*Vm2)-% zmG0)0Q0nQ!mEPU}N!m)IP9mF5*6Dt%mR3fp!+6w#;!Wgt<9hpLU>~qRuBk_n9Q@2- zv+st@hpqp3hD`63%<1Y-K>DGipY#hh+B#CZmi(9_!^uu6Uiama!Uu93m;*}9P28lB0fWTvQpz~t%SMZ4q7OK zXoNq!UKy3=H`rL>CFy?jL5vT^#K!psz;Xgw*(J|x-LZ{JRn1#3=$qEhZLB4qhoG{f zVu>KpfA?1PJ?`b}ivZUMo5J~p*Imj#IAyXw#Ek*jI*xw)F~N04z3eb9IwdqZN+4u$KzbGVf6$yFTbIc zQ(={%{ZOH#ULf6~7y0D}^66un(BqIUQtYVbgOMj-s)HM`vbk`} zK=fFwIA)I^bc<9z{3H1f6r(?q;od!LJbQz%3hI^pmV6EsOdph!ILotiiFgq656x5U zetr}Ca2;QuOWnYt-Yq|X#)wfJ3t0_=Xh~Pdi814;P?M5Jqwl4&9(Zham)I@2(L*(- zWx25nX?Dd3X$}P>fbf$(52b-c>_9d&Ew3F7w%PUsm5{?H4&qpI@wy}{VENr>UtvFR z{%HpEtUzQ=0RJpbuUi4$W{2Sb?!W7*<@FfsS9E)edXJXGLTq3h4m0#fO|plQMV{Ps zF)6)$Ug600-}fgWcn*o^c=5TKU&NCVy&XyZp^;w=Oo$nYQh@7qK>DsJY$P!)N}$Zl zWRvm8Y>TpW?{FoDrE%E=joO|@MjEABQHC0}2}}Km zB2Q$eVqy+N&uf#idUstWi?n71oz)liby>zc5!b4Bf;NGcuf6{8#kJ{M=i$FZhAFkOwtkyVZ;QtFI1sJRmyhH)FZ>)6Gu0x zw6Cv*Nyo25b1cEUAx;Pl2I@N*b*Ut*Os$>|?ia)LqKaTssf#b|_x?V#nO!P=PngI>kuusLf}!SB6PIzwUkEnh(sCtl)?9h9a0auVRtDh zG;$aJD8Pqhs`AWth zVHm<5qW{!Imr53tFuCY531IV1lzwsVSWr(^4xK?$BQl<^F&);NKNZtf?j)#UVfyPT zolHN%D{8aw9O2dW$l|X~8Yw>kO*N3AINKA|w7u(_nVaetELyNlbY2XKUTUv1O^uGx z8CLom9Q26>P(FG!R#9stO1O7plUI|!eeWeI!g6YFkdgjWMTN`rBEW93(iMUVeRCI9 zrNEe%wjrT%Xg~uw$EAG(WZ#Ty7_OPa61Qlu6+$kRc{HF)on2E%WT#Yc8v=L02uJML@Zm8Frs94zcM zvQOUVFg7x_p0cF>h%NBU`3`^*C0_FJoWJj}&&dC+8_wf!%-H6R|0UV-%Lo@n&wPUL zT}u_c#|&Efj+qKHfpz?Q1#@A|{;oW4-{jC9#>y9isZ8|ps5I@<(hXz38m3?22s3$HG=P7|^LJOP_0+rYy9+h7Lyl^3EkOa{qlUCGmrlNt2sDE1=Ic z8aG1t>O?RY1`*eiR8sHKazH_rl9#zW{O|!78Tm#ni34k1*67P?1-U}ndiXbT6lR2j zZ(NrMcr!<5@Aw0t8_+=3@+TD@eH2k{CoVD^LzlzN61M&@TX=v0q&uz9LePRIkx-%V zpJ0XW!ae%kR{{IwUmuROK(4VsfB#R^O;i-05(x27?MXH;Pxf!>Vqx>|sw-qVd{A`O z??CMJxcHADm z&5S2891d+yEOytLDuv`$G2|36g(s;=z#geyeep!zGZ*lle1rXWSUNua&6(!TDDH7d zFB^^;jz%VS3TB_WG#dapLVX6kaLifs9amU|^Hox-JAdYehHQD<1&CZqepTaZ)D2H`Eu~z~h%J$LUlAp9k zVjxtn?1wW**BKisNSaYoxyb)RVBJBwYp*doJ;OaZP !$^4Qo2@^eU(#fDE0sGzZ zSEnCUwC_z&Z>Q#=e?Y}w-eZJ>N~m)3ddXCNDZNfY*8HzW^TdVxf;tz7WmVi zy*vtUruy%4&W;nID`)$Wel}O5E7xPa3v83teWya{jfoA4rQUmxvvW2p1@Mwe{Az^Q z19wrNpIZx)Z*9+!8%Lud5b-4jXI!U%3SEi#)xwOnedIW=2(n}HxoHBZHhhp`7I#ej zH4rw!EYso8*iKm=IW(p8x4tS~r>hRiXFe}?NS=>e91~}=+{iV`fD(21mML*1xuZ5x zpj#up3_fKF9NNuy2q$QM)QoM(46{a%AiWBEg2 z_c)AyJ-`;lC(&+Ar zGpb+&&`tLT2sm;jHaHwYwfCR=DM$R{d^ zn_c#)2jRC^{p(!&ZE?9)|8gE?X$iJpPUi3Ts+8f;7{q*DHGXLa+73%vEXY5O z-S5xa-Z*Hodd{U!-?q6I^0pJ{HtUDmyTQQZ2e*!Hz?0;@f^YVDy6H6qT!tsnd*_%N zru=}LnlkXOrW1I_EROw_#X5ajHoZLoJeaEDsBBO$B*vPLgPkjgaz@FJ=Xj2!XB1CE znRHGfjX|+H_nZqgTnyfV!^}4eQTX5Krut=`b{|UR#u&K+OYhR|PB*fwo&?Q9g33Pf z@hG~JiMP~HFvt~<0*&*C5k0wFb6_4YAO#ZNmBR+k1jFooa^~xZ?-6%EU|sx$ zEMf8!eUtuEB>H|KZyR&F1 z+RPNXb2jKo^Qww)z+nS3eA)lk;JEILe)zt}BE?K7h_APEB`LKWtFP4#T|z(e-$ zV|MZz+u7b5y}r@PvJRDJ2jSP1crQYC3*tRI*AXNF}{)225n8hYRM5 z&bRLDco9Hay)i7wQuNt4RcYB*U3aZq^RVaM`3zsGfK2+@i4xKRNNzwJ6>m|frp!Zo zyZ1Ho)&I~MyNJg=^Szb!r|!j%m>pjNq`-n>%jsqQ{#UhX!eT^&{0SHqU6I9aLx|j*v4Y}Vu5}9 zEBA<*{UNTbj*%D5Np8LVSy;8kuGl%}1`3>fp zW31pLWv}gn@uacxIV9qEWJi-}BxOuAYOL(&y|h=E)Yj;(WRgI+B@l7(u8(?MT{$S% zz~ULv1@^pE0kYCI)*bP^k*PotrD4HlL4wp}97q_wW*EKOm@;){)jq6cyXWP57EW#p zPZS}ptr)nb%Cm^7)=yotZ*XBepK|JC0CO|luP=bTl!kyed@`RVkQ{!N`=KqY{-c}q zFDc6re8H8mEaN9%!kT?_x9jh`Ew0GRK&QTeQ{cWEbX?DRb70-xW(=t}YB$gx2HZZD zNfbx-f@-XoNjpVbf(mKX_=LU%?DDh&(jnlhdjFdm6R%{Rtr=wPMMXjb9QDqh->)qB1?b`D3?0@w=Q^++2eVUFOG|eT%ENiHbviO$40a%fc1Ig7kdnMRprErIB(hM1`?1z_8a@b=# zoMaS$F@I&r{mHjq~ea?->;Q2!UwY{bWSuTG4cnbWkpI1gF^VEzZ1FUe4jy8L;#%Nq*bFL zZK7(e?6l3<>6LM-qg({s3z_Uc+e>dum|+z&^!d_1`Ka$GQ}2nehp3|6Kc_&#bdCdc zxa5a@Q|1(w1)7(qp6fpkhj=7#B3W}u7w7hVv87dQ4`X|x08~D1RKe{j z?zzbnSTfptI)pJ1Lg~X=b@XM9dhA)^?sZ@U;U%(ZuIhOD%^4FyCHcyY06fN~(_4-c z;p#vsrSi>NJtT0cC%!KJ3GgNG1+#~&0O{oUWrm$xJ<`b``fWMUDIk-ycZwtCXFrQI z%+N_X2ivo(If@dov4%>j;?udA#fj6EN{mhK1GVrD#@h? zuIPW$p!S&zZM}9ym)-EQ<2!%~QgQsZ{M|DaNb?*LkS_@U5cXh)pnC+AWuVCT`%_(Cr_u1Pc{ z=ZIJD{nfM-9>5n&=zPb!(f6r9gR7!xUWfYeYzqx-6Y{suw1;px^M4Ew#ePV*A&`K^ z+m{>c16$C(LB-&F#8ry;U8Cc`a~~{aM0ljep4bPC^;Awa>D(NM^u(vy)kV8Ihx! z4C{V1eb`rME)UbP@{A}*6vaaoc25#)p&q_L+}hfZ38Rw8&+=NXE+ak@H7K=vN4KQB z-JmokthxfHVr4~QESEgz^}7PXT42%9$kX)tsuwUUK3z!fxs>f;mhHGORS>Z^$M$Uj zos+!-8dCn+=&KCy01i-gEP&2OE-&OFG*?+)KC4(Fk(dP(ZSsS5ncZX(T1%XvGs0sq z59_(o3oX>Fj;Eab*VW;Q9DOu*2DyGIO$i(Z1(8LG%9_H(nKKW(D>e0WUzyVx>9Uhu zEdvg5k;%zSk&&*VqFvon%aPtM>tLV9pSvBO(&T}l+XQWP@N8;N(Xt6j8e+<-);7>M z#3oxzt!Aq3DN?{#+@y_5!G^K0c*eao<3t`FPGirSs|KL!|rD7=zyfv$f9--o@<>uezl=9-1U# z;I^diCPbk_P>6mD`$Z78=Te5tCZcZPd5RwO>ZR-v)t z2xa1SJDGX?yZyTaR0M_h_p(GNE=iXAcX!=z35Dt2ZXI&$Or0+5tc*qiSl-;!l{c3H z^b#iXzwr8NuU$4eKaQwkC^T6*m4ES$VcpvQj6@uI;?{yH&${Qh7EVB#J={q#03bTJ z?~EnuQ|Ek=EnJ@}jv{*57V|fz&Jk4O#yt52fc-L3bL-hkjDg4J;ze-eiF*kY51b&B z*7M5Drb0YKXeKowVj$j^mYqIczVz>EM=b7hzU6&kC;q*6_XYHB0OQC&Dv4Y^a7;TC zI0@vL?P217_uG8K^K#5b<6C$CUEjOeHO+)E=@UOkYIz566O@RBPHNuAED14{lrmbI zm`&WLK6VW(^1idaTCUOUppf>jXu`jj>@HxFxVt2dH)x`ybq3k3-!IZJx6#o&t)klg zaugbO^il2h>h}*-ftjzB8#w)8j_H5<+FH-sv+cVRF!1)EIZbK{N2LC$1&fInXZB^U zvFG-2uDfE$^{Z7)ZqV5Dm&&s_x)s&x;k}ysdH`EhtL=roFp#*b?xemHwB zOlMPE4>Z%1fvB8pCF~*r#9T85m%8PDA6(iy_vKgXTp37mTpJ|F&>w{^yJj?jlbmWl z3jhyb&?(l|x-!PxiQ)$TLrZlfYedyyM|x-T7wa@WXE(AK#r!x{9)Bc77PIrtK>{=B z3~?NBn4h=<9!j83^3+xS6oJn{5k>DbR`!U$6urw4&e`lVLID24Hj8J!5WXa*$w@P3 zAv}S(ewJF_xw83B#!WjRg9TOG@8xNxq#GD$!+XDaEq4$ytT4x?zv}BB88|7m5^l~B zIMAaUY^1);=CwH^xm4M{sFA5jXZRE|>d#uvcVt#izwgi@M2r8V&91*O0j#jb_Vv}B z1$jBE;P|3vWoDp?@GEj&WYM+7Cq`MhH$gr7Zhbc0U)gBdqKsy^UZYD&V0C-D6Ld9S zIVh1Q#u?N`w@G~g}?THHAJO(?X*w-`ZF5N_1_+!+HG5q3aBW zliJBVERg@_dU?^G`VX4f4R@?KkuC&A`&4j&TbZz!2_q*Wy?zyH(V?yIE40CwKC_LO zVD(E97g(!DDcknt>K>)Jx;DGQmfI?Qb^me`o!LX9^<7}ct$QwM~P zXra`0;nKwLlC5unC2!bH(6%yrIKUn29m`ZC6aR|)`u1*pMERIy2*$CWf-@x7o~oce zWt!n5#&qvSEl|pDIi@hD0+#Z<9Jo8j)+-sA;2k#{Ngp1dAlVR{>BDhDAhvC~7jN1& z#o$l>g8c`F^$i*4I^e~?$7i}9RXV@)ri;eZNw1YR-1eH<={SqJVkNy7_|5NQK$KSy z=sy3{!zNEERJ&_Sc2E{QO|HN7ca=BwMDgLQ2h4^Qv)1Wz)yO0j@NQp(ssbxth6Pt2 zyi50ws>xfkDsa#;({}mzf9d?#KT}z7l64mdom39?PXAf&Y$J(_cAaJdts)4;f>x7+ zPFnT$uK5}f7jGxA9o^gZjTa`KRODU`MJ@k%ANBR29Q&smA!PAA1TE8eWp0`k7lNi5 z;ytLC=1wawvqr(cC=TCc#bM#=BTB-?{!Uu%r4GU!&|@_bI0-AzWi{FxAo*l$-=&=` z=q1{}724*DtYWXLLZru;Z*+Z>k6d2q>J~Ve>5>JA!NdNm^6e&|cS09Eravt&*j!Af z>1QUQ6ow_iYLC{OU>7weolKUWTyk*SDFw<*E%j$ffalVn$HZ+F^KCH@)avlt z*pNJnzlt6oFjyx3I>MiaN$J#Jv`$N#6wB<=KB2%XFX&=}IIzc=)KLrbt@lA+%}_5G zx0h=lobc9ijy;)BJSv^KGTq}+o#ZYTjQk2%tV$z@$Y#EbP^M6q5lg02!TL-6pBd3v zq8mU1j}kaPIFBkR5a$-AB~V=^xlvbhu{!K9wxRTFMBsl@IGi**$}Byf60_#~{+{DT zcvGG^nf2qoDp3UvBpOq9pwcDN_|Ij?gtbYx#_RI1mkUE!s|=fFc`nr#AMXn=xap;1 zd~D0KX#he{PS4!o_2QDn5mwuq)!d+rhZ)A;hI6Y4=dR$Ecsm&~4`r6&el z*H71Yxg@1WMmg)BWWCPs_l~PiP=J$M{ciupemSg-0+%P)b@n}Qpo;;Vsi^R<6>E!v zMTGq`_9h-(91H3^-K~t9fQwL#_q~wtA8p~YQ+z-`nr^_rA9{!+-&3Y~n>ao3si2_p z3DhTe+3ZzqMN?1~;ClQjQi7ML>}6;oN_9z)e23o^lxQ9;F8Z~Fl0+jRKAp}zHc36{ z&Vo26_D6Fx75il$H?WYM&p8O9vX%usaWoErF@7zOq)di|kk=*2*b}6>EGcdQgP*%P z->Q|8Ww!j{QV`^*KWzS4N&M(Wg!m;+{pZ}Duf1#vd9@N5`h&(^^r5Lcq`T9eX6RnJ z_sc%-V^Yn}ui6QmCE%5^^>6b3&RAv!emWV8q9b{?JN>M8`mgE=nDS;2+r?U}@JV`y+}+0|3J|CyZxelp{4#qYj(TzSKL8aS@Yy`aGBk zILjJPD7sKxmaimJA^+65krLitKdZ8JR>;dkCPk4%!~#0YA1Oe-heeRfmQG`?-%pAT zE~FCH2P^L(W32D}(>F9BhxjV8UfPZ=9xDT^AFQ6*P5e~;*roq{L&FQ4S_2bbz~_zL z6f^V#1?xS1Df`W^7#3f<|0<=goM_I~dMOddV_fKq91szdv4s6ce!7gYhf9wBh(;T2 zk{PS|JHKRbvzg77i%%b19Y(w7WvVf_74F3YZ!t?YJOCPsE` zLOAZHVhmsELyjzKH@^~N+1Y*MGRbY!9at7^!`OxQKeIC0W~ zIb2%lR_8NfEPIdx3$G-o|Ke+2;-o@i=b0WH0dStwCP;vu zVY|K`et%l1f6dMtI5}{{vQmxTNWHViJFaFRUC;o4Qg|ZK<1`L3u zbgSOHaBWX=X^@^X{abe&MQHgU?{n0acJM0~*Vt%$M^CGZ=v{sae0XbY6SCEt09N`Q zYq9CdInZ%Zg6D4VEf-5=z@f@b>C)_Ndy+W?`}hm|r#z!h+VW@n+w%4QyyGDk-x zYF*9Amp3{NTbIP{z@uArD%)+p;h+KgFc7S?&9=yt>vrXm4kE5w&BhkC_l0E>=pG6J zn07)Dp4_Y}@ zlz>Jdm}=%Wsor~_R;PqGiU;emiucQo>9b=#W<5?9U}hDLnm)C77VyN ze`X;2*!-P2v0H`l+-gCl?y)sfx$eggGQ^eMuiu87ZhCR;g*jrDveJ66vB$SgOe6WY z+9K2%d8B#Nx&am)yN1yVSBBmlhsHpkwWHZY=! zH7&=Vp*?0yqZYIp@Qq^3bqW?;5))5re40Du?-9qnTlHc zrp!U*64bXPVE1F9ynqTE)$pKDx8l*v%haTMvu{ofk>ic4DN84dp4u=$qH9Q4(2q~& zM@Q8sTb6r#E+ng3s;$_VQ0l2VQ8k673(CYgVT<~?JlX5t3}~6m3Tmb(VVi zX4M(B{IRk}M14UU|31XANbtTS43~`tW3`sZXcju;Y;$j+4};nBg?b@IOZ%%IjG=msEQ_~mO8#QSYJASCP!lB3)3BA!u0m;jU_W>zLWN{guX#XAszaM z%!d3Q%;gO|;bG1!`Y@I6XWltWm`=ZfjOMY&PE?f&K+NX-c>%AE=)3w|@nM7f!oAnt z_D6iT$=3$E7>FxhHZSgWxeq?SijmJ(x$JBMJ5xs1XG8-8M{Js-G+}j}0fzcn26M_! zf(yP@G}6q`?~GKYd<3GOT=tr+aKtBo!|$RwFd~Z;X^Xfq3=0FawC?d3?l(&c6?etK zX6Ri?f`i+b;_j;tR)5d96>5K3A4+$^rBGDBYf78F-BUZ8WCD9J9gzqV+nXF~IKVh1 zt4=yf$TwtbAN43@=Xpiq@t1e9labOZ!xnA?30S{-bK=LTqgf{lMbd$$KYhL)Hx8AX zWF2uK3=_E)cDwE&Hd9gp&Y-8vHCX#*3B4k*q*&)VJuWK0vGV1YuTO9}74V@d3jpt` zEc%xAN^mPe@c9lr*>W0_73<`qYO}vRZ#{1Z<`gx2Ma7<7!I_b{1tK|f(5qJqvdMM1 z{3yeANR);K!93ve8@dZa%t59r^-PF=mMrrC_0otn!6)Tpay=*%GjP9e(D3;5plv!?dpBISAt zwns)7vAn8dpI9;nkHSKq2&yDB9EPw5F>2uBQh)zR;qchv(jko0jQIG~OKQC?YY|56 zmjjH2rgMt+pm7;v(9;vU)I+Ow0im7V7cynS!4?9Kp$y6rS!qjG+nY~s#Gx1%g~`q- z24in?9U(VC6L027!`qhzbrc8Q7EUQNM?`38F|LOn0BDcYmFA?ulm@S?RG&HWNP?-N za1u|gs*x2=W7QznC~zNtYJmzUHC0LAYZIprm0JMuO1sAiIzcnele_rcBHAS7(6b~Z ztXKLExD`^#%8bL4xAXbxEuF-;cF#u+#IS1aV1@@pTG9ym&EH?0a8{0pB?YYcT#)!( zjM{SV5bqyNvI`ipq73bTR>5*`z#f9=3UkK9GFH*r>Gc zdGk2@LCav+oW=C9H}sAXcer$WI7&It83Lj?g0r4KW?bn*G=`D+zE91axT+d_rLLLR+!|MX#g1+RL=(x9NNlG(P+XgxgDb=lYDRc-0!x>xHYCSFYTwI-8} zg>m_pZx`jLA&fEt_{pB(8fOkd`kha-Kq7$k7=JRwm%^uvcAoxCwYj|)4V}bNkm*=Kgc?jrd#K)d->u~)T;2%hqGXl;K3a^K8O+3@k?>Zg^X1v$DbT?K{?A%7 zCOG?+VeIh+Ui#&?F4M5C8y(Qy)0)XKQl~(eaSd6(ENst}W;>*)_bi-TvO`hh_CJ+^ zYt?>pu9in5WFIxhZQIYZLSL&$r*HAc6$XzVYji%ecARfzZQOw2MP7i*jv{AG1*pgfqd`^QD;z|&srY6DRV(~Oma32fpwlhRD8YL$a&G&o>AqCyeawd{U z6uFKA(Y_^ewh)C^$01e;JJ^Eu=QM$)xhNyg3+$h{2JdB>+Z=AL% zI-h-UyS!FA|1$0JdxpBo`RiiA5%RMC^qh_nR`#5zoO1KWp%&LF0yjs>9amjKoV1$r zf?H_bBKu2z>?_JqAa385s6fXi1&&=v-<@<);* zp)IIxdtaE^m%+2qBh0oTL!3VH{$3IL&}*Zcfg;izsot-MoSYM@x96kXKdzpoZ;bkt z9Wm#f;VvVtnEX~O+4}^BjAlY>O%{DO%N_2`$wj5R#u{kRFZM(@{K%G9+btiK0W|vb zZCHVSvSKH~V}Azi#KY?qK*wl};ctA^&NtPp)$QWY*xirf2Mahdl9uBa+xyb)es1}K zO#8`)$f4EvL!md-s!eZP?P?yatrUrwz+Y~?g}+cdkT01{0Z%DYyJs`a-F`L%Rgk?c z|gCKX#vZ`FU9!kyyKD zS%Nzc(**dH%@?RL40MNvT?2cHnBa-XtFlraCrq!10PH772^WCPf*A9`h`Ov^4W zMD$oSqiR(3TlX~gc4MCBl8JFSOl&J6%!fylD)3amGKAK#zw zw+A)5?B(gP&NO*MyZq|tt%AmVwPuXYJIDx-D%A9qd07Rp#Ul~$gnZ>tiq-JZvVfXL z{x4@fdrE^){WVo*#FK%L*)*jSC;?;#t3SSlTX(hN%$i~4V^$RWEs2vHA|<4x6BP-U zQHLvIfhwJ?*WRh|2EFyk0^t3%4+UG1FLhr!yiPfAosKMzSyxCZ9>$`K62O09z{3%# zBqASi2rK1IQJHgkMrX?W!f9_p5N-5NK1N4RjfR|tDXxH{?6^=SoL0Y6DV_=R zORlo_R%cG(;v?dGX8Nat#pOa4b8pg|&_DS0KRlPB+gmz!#;7Kf*R?ANJ@Vz}(f%#^ zR5kyKe$%^5=5=@BJJWrMwuFWiHXhZ{*H_tpZtCNdrs?=2S;$v#B6WJUF)dYC9QYIL z6U^x76+SA)psOf0t)>dwxtGFNWb3gk2&5W_*yL*GtL%zefEel4VUtEh7UH>WL zx^qz7XmVaq4VJGSx7W?=L*W)cxi68|Ma z(&MGI{NF?&Ek$F#*GO5AIsQ|_3_K%&gDauu9KhK{r@Tlc{4j*EdL3z-)UoDS8Bu(2 z$XB4u#*i}5>OJD6nwsBJ1h478b92-V-U1xQ4z;kZwND?g9~Izu+bf9H9^0=ZBgK;q zHV60#Vp5xSIgXw$o&++?uMeoj_X>e7{MT)^!;tr(lZ0x(g@O1GdE4K?vi_6I@~nq- zd_#lPnK0Y&h|OkC`8N>+7AiJ-EXckipJ`7EB0$Yo%04#`$~zj(&$~(cd#xh?pyW4* zk_R9SUjN4)*b4bSsAOa*iLnwIANHZ$DAzvM-hE)`g(AtftpmN&@MaoGZi#8U;m8KQ zDb8U#OI`a!H}jzyCj3MhICgxZ9|?OIl(;Gsx_OPCY}*+lIorHC-l*|kUj_w5D*;x1 z5RqMsh~Dqgq!GOo-1Kz`T3{0u7-br)1t?}R=sVW}RwEZ9p78K-!7*dT&! z#|*g;WXi(;Im87rG$2CvHybR_A+4&KHTX2UBmYVy?N6ru=+^#kl0SXBj8XNJm^ErZ zi+w^s|APXK-TJ&5LrVSIcr6UEA00On{Rb#h8kE{bg|wI|Z(_ z92m|WBU8w)?c?rt~15`O~qLdimP!9**+MHO)RnUIU;)cO0`Q(A6#5 z1ClQREsc?aYu{GYsZ)Go-HN`1%fzM+H>xZM(0DVdZO8e;f;as9(NHnC#w|4hEGW+y z9T=U;6b}#iS|@vcT8IyVlo;PWDMX-9rlqy%`i)wrJQCQS0v`kaPXMTAoc8YduoU~_ z_+I0((6Nv%qkV*wE^eefK@&YGH>SUa3WU>fRZEA=j+p1rwz~9Bj4tC%)Xju(&P=&fZ`etURzxFCvNm7IKwRf6MH`Z(5Zi!{_1Ry-= z@vAK{O4&OCl4eH)nh)bFG``0^7?mXNjrYeQHSI-1ztRK??;E}tCp`rL;_ophn*L1!g_PK=n2h>6ahm(ptFT!--H4}d^(|zoC zA{|s#iT;F&x%WUpVkgOD1E)1ktYrgzYw&(92i1%C-hmxj`&s{H@T;%%s~9 zGyqQI#&a@uh4T?jA>!*evb|e=rAc#no57I9Y2X} zsmI1YZzlu=!rPT<6wN`ztN-NqFF!7g8DD;4c|cvg(=ENNRAOC!^gY?+R1ko?&p=*^ zz!@xVtyCMb^Xw<^3=*4tI`$S`G|+|>e`us|to!V;+#6_r^kfbiQJc)nu2aLOm6fTa zd&hTk^Bfl;5W^}CUHzSBaa})Q>{8NgJX4?t5PVto@bJE~51lfyUX4qt_<4EB@PxpC zg**f^avI2A6v?ptA7g_e1<+kYZ4a++=lwr4Bm#lvYQpmudQ2@EH4c-Qai&(pGD#Hl zgqvd#!o*+Abvyx66f<#P6p<3Kgh9-Ptz0$HQ~&U|is4s&5$mtvPTnA>PY(fQuA@sZ zjZ3ikrGzKZfJ;amb&J;o`j>+|b25hygPKW~JGiV289?ozg8IepC$g~l>uuN(?_nj$9d+f>Ab9O$T96-j-ME_iD$0@ps zgzH+L#IVRDS>JawTk=jL7(A#Rxg3Xdoz+LwT`pvNWMhz)5vG)usXQvHPgsG#CL5rA zWCA_W`=I*MzL5JJ5zVpj{5E*xr^8X@rm{L$qbUzzR2iR|Kxb1(X}N-# zll^%h3G)u0dI;A{1Boavt@2TEx;HvAEfRl(!%{i_-Z}o&Ll@H$4!v`KEZQ(gDVQy5 ziY;RT_<6$YR2BMZmd4I!JHnq4lDsUeTNcB)OXurj?md*Pc|%~`FC@C8 zRmY%l@0YXuOV94(FA}&}eM(z(o7=lmHdN123!Ri>q2p>hCdxGIeO{S`OJiMG)M6tc zM3Hol3d>%L$+9wt?FD_Qh*wrmh!+Z`vAS8^C=vuHtx*9;!xZuonb42(_qJX8WH%*0 zwT>bh3HoxSzt4N-2jJ(mn}+H^Lb~YUR(z>P;T!ccZQ6obTL-pPtD`c8O#KShhH5e3@)aKCTzB9WoF+N!`wr)?Iz5kO5$Cs6Bh_%Zh0Eqj=K z`TW~h)GuH%bEUu^A_z9wN!{Ohfe-+dz_Igr+szwzGtpOH|@vKED$(+4bg3UInX4NG`t{zi9-B;G@Wx)r~TKq zYcePIZK}yOCQr6)8VAIjTJ>*hU469oxzByH8yRT%~K^>Sp=^`;mizO#e~xHuNzIA>HTXZhg|w;3!drCMFIkFL)ahBZIwuGDv!YV{uaeRYN0{&3ot-r9`tl65Qrqu=5>)s1`a z(h4Y>6D2A-kbi{TJZO{&hKmHD7ag{LXo`OS(-hUOe>1E{yLul-mDXP){l$n*Np~_{d)}S@`YUc~&_ic696bx-0}C?e*lPOBjeaWv_J9XSH;Q)fCfv5uKK(19N~lE6{wt5n-9&+9Uz46gnL-nv+=4PAaTK zS`4|G6l!TDJ<&v*-coI{m@;X-4cx_;h~_cJe*MgSl8}GR%0y^%1h}D&Qd_!vu4qkI zYtYuaBRF<{%|FE*E55!T5&xAWtG7jX9k?Kk(IDcS zWCI2L4?FF5k6NhUX(T0xn=@P6L*Tt1>3T#T7R$2JnXG#4<$62r7;C=2=E<@b`Fip0 zkNNAAA<6E}1nT9Sq39$@%@}>syYU@8@8vw6p|$5p<8?|2URKt5V%M0ve4@xup?ybr z-qYPgn7(^uz<`yqCmm1}fG5g-XA85WnWg7&%yyK6e)j0`$h0dOS?i%@C;p!5NCrJc z4+t+Wn5Sk<_|ah504bpHJ#2!n1gS`Z)ewGirEjQl$XyC>Q)1pW0*T~@-=*_5kED5b z@eOIC?Y%#Ve~wjZA~W3^0Z(j<>I4bj)C+%b)qt=|S99poVG?JpQdMulc4AN}BWn;*!lm?HpDN=CZtlKZH$UZa4 z2?#F^UyqKKu>MlWyhp>6BePdYnXV#szpHaQDU)Gq44ek3O$+hmk1 z3(SL=DG^*ywWq1ItZzSj0Ms+m9|UzRm;8=LhcqV>roL*cKj^}!F+gu8KYx=e%>Y8L zT;s>$+df;UDO|gePvK0738^P8Jbee;=`OZ0~dp;4gG2c-QF-jlLbr#S40@-Yc(%lQ@DP8 zCals7w>0Jkb&2tghf5^Z)i@0Tc)jTOVNAC{y{`{<$6yTl=?;)>#6jNPsXypdLFE|+ zE6A1E|FT_YH}DkTa42^)JOW-6f&ZU$>I3q@=?!1cJu<*)=O$hDc_99z${g zwmvOB% z^i4*Px#XJ@P|6C??9dw}E()PGXlD--UdpU9$00M+IZTQ-K+M?;UYK~ZCX^j~h5(Y{NXt7wddPo=oEcTdR-2TQQQmG8}(}*!Kh~#B} zV0~V4Whs%ndZN;zFT&sb)O!~G#(gadrJeP2Dg`Hv2BjN><_qOD6A|-!{*M) zn_xAA_(c7zH>Qx#tseEEGIX2MKRoo13c2`((|_`Lx!ppP!|WlmZ5tIYdsEb7RQET1 zD-NiehVtaWfS`kx*8UV{F_3D$>z5Vm-*QT_4mW~O#drFT^4_;a_tBN+q(phv@*&tn zU=!??#2f9GaKSU$zkqLIgC$27dbD z`dcsk1IAKTY)cqIS!^#CS;2{-e)tt8q{fE6;=5Xbf_ynHJJ9P>2FKv=)3onwVFt3nKtl3Zpm}seU^~)*3wkjDh$}+BzV>nRa26|<>v_(}yg=&}B z|8#><@^H9LJ9wI?srErml<&tZX13Tf2Nf#%slbc8F3-KWH3(HCYi`3kZWKz081p#F zVT-m2er*UPI**kq*x^#(y6BaB4$@vzAgexenNgdS3G)XTfsWvTA?*?w>>v?p;=ZGT zsj-`43M_e9TE8V|#=#g^7+mpa810Rgeofp}-r3#%b4_JU%k~tjjY0V)Z_8CdX}Rou zla%r{K=4zTU3Ku~7v=%bukGO3^DZA8z|gcAkl_uS>J9&h#R zp%*8U)^;&KwM6g}YJ#+v?Kp%!@w)6Fuo#9(PRX$-f0FGPB%KKbUT8ibHU+b@Oe6ok zOytl-Ta^FMR#g;-44KD(&3z6%Fr4GejSDaOQM6qvV21Ii7|XinBI~g6WHjlq?zUC9 zG8ZAl0`Mzb{5PbA4^RG>;w+r>!JS|xs&=+so9d)H%tBXwZH1doUz3- zlNGl2^AmbcXz>ow$j$So8j(hncDFiw=Z{X`e%S)0!C$IQ4l92Bk(c={8nGu7@(yM| zqo(UooSs8o0|#}w5eK*JD-SU4!OOfGr7+p+$<1-{VUM?=o;Zqgp)kLS^!8P&>}{RO zFWa=K&$0s>VO3FW7SDD4zHXnKb#5<>qkA3lqtCM)j-ClDsQsJ{cK zq3WRb2A;z^yKdw{_DL>rtU6oz z`RyojhM72c+9)0^ECDePaAUxt{Rf@t=N!M*MDBWltAKY6YJ)d5j}XRQ$^lq*)~ch(jX!gkPruD=E7`aK#(_NBPfl=5_jJMB;C0rK_Z=4!?C zk#;=0(IIWB9GV(duEIU?ihb*yu=E5{n@_K6%}%VoUxRJhZE&Q`eLIT{5kbd3370^= zyWSa6<;<~G6%@SaIS2x7?(d$cmtg%1p7xk&{#KL%8B+Pg%=JFn2{7W-XEdU?x?GKU zvL6rjl58{1$`aklBFKUpFrN!i)O#1}(TcCIRFdGWJIGl#bg1cR^6N#ng?@LT0w&wL zL~E4UzMXgrR;S-=0P36u4;CsX&^5XE(|e_JlWp7C+lmeGro8MrWT^ak&3j|v(TJt& ztP$O}MDoTzUVKTI+MuKA1&Fvw1E`LyE2;QzddD=sa7J|Qi=^%&*!nJ?_=q#YCuobV z73N=DFtMG0Pyo+v<;8MAelmXZ^HWbJ+zEoNA`Ap0#vF%DLb9o&4TGN^Vzc%(>BZ@n?$rpx zVwQf=P26J+X(hk)tIN%uHuJtl^%!w`RY_%Y@TB~?r>XPe9W?bBSYEc?^AsewnVER~ zxhxm%h_HZ8uaV5u{(`PHA|0X}#wk(084l3^1fLsN_f zus;yqBAS;L@*?5T%T>XK*#crR)LH^GLsLLzuws3%B7!lbBZ`EYDy%dGzdr{8e%{*t zX?zt_1+oAPWSM{N+8FlZ^q&AERT_pby&^(z0SQm~g0{*7kuV-tFR$NI4v|R=Yot?S z#+lYJ2XF50H=$rWm{2y-8YVz}j}T1SY-vlYm8MihnFpCDcW^NX!Q0N~x%?yZE`+EV zLf!g;5D!Yfsr6lL`yHNN_2u;P^B{+f)(ik8%8eS)rOn+k{GcKvwi3lK&0FAK$1Cav z)E~$ioukl_!z+dH5qT~c?jw&@bc>;HQI%yMk=qvjxCu0d+=>S=SP3C;vMn!5^%xaMPAjbJ*{nuJjTjW}Ro{jrE6 zNq)1MqDlt0qAGZ48Usfru9Yy|s!#3={S@TV91jN83bwRz;PFq}glu(hc&< zzS~5mjn@DzibF+Og1iM)fdGnlj) zG5UZaek_d#?l}G#JRk_U55*C3g|2xT61!qPA`Bnqhz9oq+|YerwGJ=om#G2L&Sj#BiT?%Pe1fu3@&;{uIe zyE{x<7iOkp?WZ!|Ib0TTijjjh_ISx0K#>>cLN1#vuxqbE1~?;p-Y`iUugQ@#+%PD2 zZP;)?>~?uZVEL~g+gh&GhCqzmZr+HtJRx_Mj3KU`mk_coHl~g8@0%{1d8^;9-Y()0SK}<_%rnXJTUZEW89PSnxVB4nYfJChSDS?Ha6N+7IL}`FskLG zE*c4rTkoP`SBgv4yH=k5DSf#3C&>P%P#>TK8Em#Tz4GzcJFE**S}NxkVjCSpfoO0i za`)~m{g$K`Bn_u)!RBiT>kM=%_1pJQTS%p1FwGdMIAK_2YB9b_q6yUxByR#JY&0=- zQ+Z&L*&KBuD*!O?jTuK#m83ePSxJB&fo(%EhPUnS~EL7zVjf;#nq;%I)_JA}e692H(uImD;h&*5n@@oW8gx z;0~YNz3CQvC-d|ESAS=`Cfu$pX20>+xOdr77j=9C!51Lzl|TjLeJeU|CWcp1`6?*+ zd@x`VmS?M|h56ZqOwss{Y(@D5_{^6PG{@Gm-gl8!jYr27m(RLP#267_wm)t@1y8@h zFCJIs!)es6FU+#64>XA!o#Cz}>$JJIse5e%5R$#xbJ@cAakw6yvZwxc!Mlle=Ip$% zd*VIt*|!3X`i*!Z1|+BD`ckx-EN#t#9IaGXbll;`Q1*X=g8dY9zsFdK?xKf^;8hH9 zLL4C0c87*K1_>jarzch;P3KYD2N*{Ij0y!1F}#rS9xM%+7$pspv0{A8^_Iy?WhJ9% z+?fQGjaa3*Pfc8#$?q2dvXU|k_CY#p20T`B>>fX6rWSz(0phu*g~}V~+{z5& zS3jnp*H_fji)c5N8(e-@<(>i~IPRjn6!8oMW~LjlQ|X^I@aV?8oD$axEJ>m zZow|Ew6N@N9P8wb(YIoJ*m)QpYGy0HYeAaemSI!2is zN|cCeVAnKlA4+IY+EtjeWkmzuX+rsq{$Gp_ff2?<|1=<{?_g?wB84re&@D=<3BE(E zZdlHX)bSf4Zonv5jf9$hF*2Xim0}rQtZx%p8yttGEqwHo>$GC)4LvsT_a+Yao~$`i zr{~Rm>^RQKuX66XmDm`!jz0q?z??)d5&OR(k_pA6V;mqA2@Yc-;bm$))O-GXCI(5m zL}}p}A(H42If-HNxSJwLov^i({E+9UZsH5`4QM^9XbJGeqaqU@I*=i5`-NOS^b^Nt# zB~%=L38a#cyBn1vqcrks5%g9KNy1X`A1gX?KyG(l>=*d$s;(2;4jPeE90h3W7eLXS zDT$Ulvs9zCBu+L{F&HxM4;Ygt@|pPCw1sl{-rXIFVx@%&69Ud7a(yRdh}bvfANy!9{twd|~;En~=a zY39?^+L_yhaj+hgwZiQ=IQhHq;GbNL15EvPf7JJ|V9A3i|?TqQs8s&o-&AhW@rIy-6iOW~MOE zD-u&Pa{<7N^CwG^&tPc~)uPDl4ejxRg1<-xvaD8DVH35yBFARJL--$wblLdD8pFZ_ z?_?!3w6T8*Wx?ZYTex0e1bc?b1)Uu8sA=Yq#wNYiNDbpFStRP#Dyj-cZhHa z1bT1?rSPwzOW?>o`hfPEf7H!iFW`vEp}p7iBZ$7np?*#b>S#3pn)H6BFJU+ZVsz3C zSU^r6nKKWm%YjJNh{{cz^BsX%L0kY<4js%4(IAneR3aqUxcJlJy)1eBqP+`QG_cLA zT8MAcT;bBjQ4tb_Q@+>eYbR-$$mv0jrS7#_U&V#44>$6xf7~FbtTsVZE`s7+LEL)| zXOLlMUo19<4vaS;&N(KA$Oq~w&WN_tpX@j>IjH?`QAEIRz17IvUw<@QkhL{ zI3l=gyB#YVvg%7u5M4KlHlY@iz1Xcr+n>D}eyb}h$+W)|p6+k3G_8mCBW|xId}dg~ zCI)g%%oJw9y354wL{WXT(Fbgphcxrj*lFGl~C% zp-QJP2u+r;e}TCPiZV@MYAaKgk{(5F^SXUt9<4Gj7i#;Li|=@SFmL2R(v7^AF7sqi z!oB(P^Exp%r;4v`J1j5i&0o@zS>|atA>#nlK$*PnsHV{sLZpnnG(l z(X~^S*#O3Yw$q-+McS*BP+wkrGt-l%n_(t6HSM|P2-y>E;7r&Y#Vj6woDBiDk=?(T z?fYwby$xMY60{Y@HB>0yZsSsBr^N>YN)8NYvmwK_|2jDXMUQ#9V|(o;h-PI;M_aO0 z<;((>MB|azI!fTRpB5JeZ*rSv7{kk85&j0(XKkmrix^@-RznF^j5cJ)9FVL%72Sy? zlGPWAqU&J?)`3q8)P0Iu9s4O=)I&u~CKyp3css0!Nq5q8s5015MCJm8jFsc<*7-5i z)$7p)LByp2HRp`T$V2vj-O!SwDeR`r@qRw%9fp^|Qq4r6geL*H|I+-2C=)Na5g3?&*s!LmJ3!z(7J*3fJIqGlY^lc`N*7n+T9{wgB8bhC$*^ z`)|rM^p6yx7v}JO887l)D{rF%E6geGGJh3I1{mDl$olnhomTg@{l`3WO|h?Qr}ez^ z--u8hQQP+`)zcamZ#=Fa-xavS8$IoVSO8LtXIeydF zZW#2}bV(yMIZ)nO=2oXRf)OHmhXEtBG+k?TSS?Yh1Q470&zv_2e4K|GAp>4B&YJSN zK77$8mds5?&6OaXJTBfxHL2!zRH*lxt}ok65bS*H!5wXBKY2UfmU%j#DxN~iTsNwS zlUF1qbVhc9D|RNkUX#AP91$c1l%1qL;p>YU^}3M0z4?p3yu!qKt!Y)?Kj{VWvia`n zb;3-)zr5@-FL$`+JU?tiw8(8No7XK%*1Z-^d*lgmef?F=yRbfjoTrKbx!qseXI^$N zaTwzZLs0h4D;}&c$R*{r4r?#@bOyj5_FkjrJC#=Se=IGZxn9=??5PAz{$iS`J~dwT z(cFP!p0oAD=kpqEbJPZs(?7|vp6Fa&PI9jg!OF%xoE3oFz|1dhIguMUW&%2-b zUh|MB6zVi7Ez=DDPzuc#Hv*Rbr$$NEWp&!HiYNB5N^=CGf`sb`+YoVFd0D;<{o9IS z_~!Al#s*qslMI#6C60s5c3$&7cL`E8UDYH`L86ukU|c-3$X`jR4qL_`V^R>dY$$l? zc#dSbY)X+NnZS9x*&<_ITpx?8>sI?4=>9>3sUvRSDiCph@kV__buz~oEY1L`V_K2x z`7NdOOxRlo6>4^DJp@;?fcE@W5U4K!y=AN`=)BEB3k|+Z`NZ&ws4z+wq1GejuCNL+ zy|Hyx!zH>rPzQ(%U{|lO2I>H&|Lh>RY&YaZ` zc&!dkx!^r+9s+(R1nGR=>ZVZs??kx_$#4`Z39)A`)3ZaiAd%TiI!@~7HqD|0Sbn&A zXy|R$nBJev)VU+}9T554#Rr@hcguveA3xdcrZ^)$#UXrYd#`$(nV4&)qQE}WL~L#sD1NEnE=R=#=go13$!>|6!r(V z@?3!K5soPW5%HspokCo4ET9}_7Owv1co;MCk0WiqT|X<_RZK)>vEX(raz4P&yS^eN z$7Tk)%>`TymT*5y0PM9q8p$3zKSCF1Kwtyh=yE`)Bs*aS%tgN)gz&=M_gilcGgcoA zef;1ws`Q14lJ+vY+y%tKDjmjtD333N_=ZUp9BF@;@hQD-(AX=TWRuQFliO7L%Ve8x z^}(-FeCM4!5g+c`r2M8Ovv}zd2IPU~QN25@>kwY6$2>J_xIx zJ=f^Rym!0ZFfKkCoM@BUy-#k=J7pOA>r3}ntF6BspJ~)(So)3D=Nx4@BG`a#Oqk62 z4dH`-DSul2Rjg!~FuG6QI5_WxPuPQTuu*MY8yhKf;upeUKv5m-u>~XC%c$F~%u*O1 zBKPuV&e;N=kmj4)_}^^^(R@;)^e->^9gI>Hau%`9u%Gx#i?Vmu9 z+>B%f_;c_!=;BTdFls6Cj3Gg~WPlsAcz9RsIj=hZKwZ2z8?=-inp4D*I)NIiFHIYd zg&hOb$Ie2|hj3+eQR#S1S)7vuQA63Xy^IjC%%l}yieg;t@a#M^vpYV(1mLKP3#OM( zFh+n*S_lVoh~X6S790>yUQqB;`xHYKwC0Hl@B)|sRO+u*AE!$71I8gRVOF@%mQ()rcbJtH~8%<2AN~VWI1c6P3F)&AR+tWqIbX=Wqr% z{&3bSa)SSrn$Co|q4KyhU4EER0Cl}qS&2`TZRF9mo?X02KcAyjUKC_-k>O^hX~IHp z?%BL_8MNJ6o<$c>-nN=*mK>Ngd^^Rpu27D>+4@mtpvDm-W4dEzP$fZ>O!9vwUdUbURE{N z9{fF_G5*$L>=AHN?OcZ+%YAJ!bc!YN-LqRFaJStB8S2x9Re(1dYu&2`{TiYl}# zt#NeQKjr@P{a_sYgNZa=x&N^+@n$oi6L}|cG5svkhOybt z;V9P_4zu__WQemq`e|A2;J+)LAsfZ7y5VnJ62j`~ah<7+-!u<6KlL1DK9o`}9L9ge zh86vM&LC)?lSnOlYSkVy`R{D`7@N4~@GmD^3to=%AdicdG&&{5i!82)W<YIt8p$$5|u0zRh7{Lul5nK7X*0cz9aE zj2zGVa}z=2c0cI-gXIbo?Bd@uU@-8|BL0ZS3{J!<_+rO1K3u49kdHl|4EwMlQOJqQ!MiJaV<2b?YkYu zD9#5Beby=yWca?sf&U$hKQ5=Jb&ahCzN4(D;I5-rM$&@;go75XBAb1+ZZcPOcDVxB zr?VcUPk3MbxmC=d>O%+?wfn$ktPp_-KUOE@mU^`GOtf??#N5KNCgNc&!q33~Kpt-34~;w6Q9<~Z|DWSD69!K7l|&re6rgcIPbZbpkC0&0 zRvzBBl|i`xB~vMSyJA_0>VG}n4(l8U(hW6d24$}UCys;RJCqK<^lhctOseAAabMyG~Gbb_Cqa z8UgoFq(<1V0WjZ(e`Bd@MN`J>R(QwyBL5j^sugDWADwBb5NO`oMR;@C`J8tR^NdL& z8W=f{`+>#ir%c)7iI1$mvnj?&WL6SmMHK<)v_xt?y7k!E_Mt)wn3QSG$IdIIoI?&oo_w#vN;*A1C z4&l}AQA^K^N+qZ~Rmd$yYP5(i(0ymFWp0muD&#N_6>}Q13@8^)o3yitl35H=7Vry6 zA+1-3Gh~?Sa-i~D{y7uWaYwm0za39jY)!t?lRKT3@2W72^2hmzH+R;KCfxdT0Z>Fj zNosP5GromqawniI<>?}ux5l&57Pvb92>xG>?NSgZDD*u29nZr(zk##WkxM5tu|K!0 z2roorsJpp-OWzXpdu=!+XZP?y5Ak#ytg;GVss%qnhmW@l6;3kn(iF^~ywb_iD{uN`vYG#jwG%f!u^DXN?}g^oa; z7=>F4g)er{X!`ew?2GlhPCa{}zM3oOqaYV<=tUO|96Fl6#K3w7X`q3NDSrezz%(T_ zVepF_b~*~|TJeK+d#nmFJy!eoD@<*s*dJ}-)LZzi28IBLD|Ig;Z_}mI+z?>r9qr+@ z<}$lHh~`j{5|hIcgJ!E!V~B@7abM?SA98DEjybol7X}$sn`Oe0>mbK&MtMdUm`lm(4QC=sPWS)99rP zsC8QKZLy-U+08m;Jg~?19bQS4%rAQ5M%6DsHJ^!j+380&q`e&NXfXq@Ym?P0bj%JN z=qzs?lCu{6h#@?^Dnt4y$ zppHa1{0^~0y$;qNsMH$U2Bc*;0-mhYM%_kKJdyfivAlu1PlE8a;pTMZjOMi+>a4#< z#fxjLn&k5aP#^M&)UHlD*6=ATQ#40^FO=8Oe)$FtqJtOf5Emj)OrV2@7i$9dZM z^0X54FpDY_um_QQv!%4C&O52j`=#;G=?UgP;DN4 zhjPU-oTNZ#)J&A=e6GBU2`KGx_?tFzAHk2X*{0Ld>_}gptW7$0GhEeUW?W}`RmbXq z7rcu!`tY7l8AF|FJ^-IhN!tS9um&6*KL2z^yln|*NvYvTTE8>Me>=smTtNgIC3$cy z*PoLU4R*rwDD^6LICe7Qy3_y)W4fxb9VdqoiQ1y?XJxUi8(wxr>@^#vGeuqRB=#>i z2aOr_e6IwkFDn}i+hO5S7eT^){M=VXN(RLtQIZlH0?T|9iNfxt__Hvn_ICly z+rgl_sN)Z{^iQ>C;oHZ@LxO`fKViRvms$Odlb@T?5u^BENI&i-sXOgFOVSSH`kAa5 zV7i&6_K12kG5wnQ5M$|=h3`!Nw9Wh`m+ zqZ#QJsUG4R*K8Eme~n2?Z}mb6E$IE_nbH(M6{-Q><&cY!d$Ojwzs5D$Eq9?WSn`ud ztp4qc|DS;$i@>azl+H6a+FzI1+EwXKmu+dKvsC{%B2MR-@Nnv*j{e2Qtyg)ep>W`p zBJZEJSj-|#)?x|pIf)PU=5}F=ly%yhChhFJtJ3M~==Hh~zK>n@JOt(eFg!`+ z-CpWuC(9n!?*y40*!OrnpKOHN4lgGuJ+Gwj1I-gdvW;F@*iZxEJVt4#qU_KI^Aa-;uFypiu;08Z&;_}OdYe_XB!Ca)VIy}mp#)5b!3RnLg9XbaBy zS=KP1FqY@TRj@x;+h{m_?O-Fey%*asPdUGHSVJl?)%yiQ1-xn`9RogmjbjHDsx~mi ziOv=XoGWfqs(~t~id_zOgw6zz z5g)FBakl`euUnfzm7B9-D_3AwPy5w`e=XSdg`Nc&ZXCVF92jahk4_aZKat^nk)Ykv z{i10{e9S`QPMhzKX^p;K)2!O9#B!1~fdIhnwuJd}O#p+4j;1r&2K|5DX2_aX3yiPV zLiO&IaH1kBTVk5KvVyy?i_~QnjYsz>5$P$Q2CNgF7hw%X%ZkIcUBCUhPbpWVwd`G= zPOAQCES?O$?OpWmaq$Fs;hm_C{-{3(1nK3m&ppL@u=t|iB_;IsgUmFFz}aPj2-eqH z$BGZtLo1awUiFX)HQslcyg`<3t0KAI+wOSmK}Z~^YDGFfMG{s<@6J`hV*VXwBe;g> z5wEz^twH9g28)r(D^s_s(QIE{Gyils0^v4BDQ&nUFEBp>%aO{8}mAd#zYPL@F3K7Iosqh;3RO0L&nWpoVv{!wxhLbgHd?JuyAc-l}$6 zc|Y*32>dNIhBsDr3nq%ve{c5O)j$qB>mm5EY--(se9!FvCccZYDNZE^=1wq0eu|iv z;Kz>amtoX^2#@w-f{BJvA*q6fAQ=Q349qjB^Z-#B81|UcR>BP=5vd3gQ`?AAyWqu~6OGy;|xM@aJJL!v&^xDYz7zXNsg zEBisBXEg8U11`;|8Q=T~o|hSbk{xz71Hd}e1}1&Q6|~{%(}A3&-r~yAG^4XK8((-~ zi+Wu$)PQt-oEDqQ)#Zx-X9P1e&qeBj{W!tuQMPkov7RvT_F1~6;^hg@!m-&7%_YV7 zg;jR)LU^@5-HXfUaivT*!Qz;U2(S>nD0}kRw@qpn<$wN{5;8Mm=D3Z|$w}s{ya8NP z=FnlHAATlbnD{a5niEWKUn3<1TtS706j9W{V=Dd)*j$bL1hbhS^|_L|;+7Y)EGSOrkSIBV^ScaHr*tdI2w6@&=lOUT1)SK*3x=a$?%M1aS1g>w#mnIt zo`v@ALo--f{%DyNJ&Wx!ay1cdJ-ezSoRW_8Lp^^F;kJu9x*%}q(7YYXZg}aO=bawq zG*W3&^8`>R^Ugsmbt^)a@|2nv+A0?9l`F4qeRUN(DbYNY`YxRfuX~MjVYIrxV};7G zd*x9%(-UsP{EceYEJOor7t}Rgj<{7BnN&UT+xKgEbZ@rzw+nUvVWuX&!UT5Cxtldz zN`hd{^S-^~{DOi)P6;s>FxXDsyM>W_>=;LsS=MRS+2@+tqz9ndp#$y%UvpSkXWo%h zZ^6OP5+3HI`VDLxeVWJ!u~w05|bL)>H!vABQ8SU3xG#1^1)l|g)#iSpc~RmRw@zWvP6ph5o#0q{m#P|U7)OhkHFWwfMmG;BXSU$DfqsFYcO^(xuF)YAFGjrr{ z+7+$gWeY2;pmOI7wE5;MqyuIJrWRR%5#8_|*z%vcktWg1BwKeV-tr5~#-Dy^>!J>o z$o+Ac-?{(9xm{KUe@&n02$v)$9-cBq{+aXT1Uh_{_UWL#C{F0 z5D|8L?FttxXBIT8dfIp&=%@k*(#Gk91u-8>@d`&cq+m>8qq~jdqcAJbaVQ71-h*Aj z7bUXx{cVBENSA^ikQH8=COIS&qZDY2in!}BOD&YA!cLzjW>wYyxQObJoNA06`Qp>` zL7J)!2)F^uZyIWW)(c)3auNM}GxL9>_e?o41X0(2zd*4eKpSDU(oFJ|)aqPBpLrhh zm{Sn|XVEHq%=)#=W$JO%voJfY7T5MhKJInSt?s>57Snc}s_uTWVt>EUNu%A#!DaB+ zVezzav0|_5?3xN2Sk7I%2vmIo454E6=X$gSnhq}dQ=)Y87BG3enj1z!Z5}4KYyXjE zE~7+*js93Ln3KQ-oM`^CVi%ZatsBlo(mMF_wLN;aexBwV;yY@Nw}!&DqNjB^Z9*RGQh+Q@`8_(iziE*ou#X)n`@ zTLltO3oJXbQ|zmGbhf3o1FQOLif)IxU0JAPIuNV^r+&kxz8d04=lr8h?-m%E02Hzd zcQiCV-}7h#i3cU7c_Pr?0>L=Qm@;GcgKg)hP6qfZTx-`ykquHIa+c{|3tQ@)c6TI7 zLsB@hsTKrWiu(l?MR1r`)=JAa$+lyq?pypmFj&Sg-ggFlQc4YBHhTm%8=kBV+?Qcp{s z&AA#xerfKeech3a-pwoh-s|II+mThO2Q(R&A1+A@X=e)7M6 z<}@C_0^pKCUp)^k(nVF5e8LK9^s28>B&D`YU-1yx)Be@jHd2(VjWTXLU*PJg{xAL4 zsok0@u|b7WJ8zWib3*){XmI(?cO{v^Zx84IUFB1cxrm!u{d+nm`@=;eRt`Sz!txth zR=D5E^>%HuQUme5^}GQqz&^Urr#Fc);P0w@|09iPSGV@3{-?BE6hwDT{GSI*ZdXN# zm^fZ@V0MCeT3cfV$GrO@FR)RY;JHE;J9p|*GBkeJn9K&0V6TRXNYN}L&a#fD zs$*z>QY#gEx0#(`8O#Y}EiQ%su(k`uaT22rD8i0%3fVFTAdt6CXTr9)uz0?j2)PXe zzJ{>IX0ehww*Pz4ed$f?6AwDM@dFx&ni!5-S4}S!0XqdMF7_g!M36tG?Vuo9J~HYU zG?WqIv`@evRS>I|t5$W^XH`aE93UDxI^-4tv)R%j!Bs<4OfSA#OcON*h+Rj|gJ2Q!|I{CIx`FqP!)&%<>gK%ifJt)W*4FeuNw) zM`uLePyjC9amqYAm`GHh96r*Lfs@3qUti!v151w6QMnh&Nt{5=RLcl{vYpB9R9Q0p zGWl@}*w30h=4Y>4SAEQ#H$uQ5i97Bxb9Cw?ZehmJ7WG}a?Ya87Yf^CFo^x@u`Aht< zC4^yaq%Ph+uRi4sv5RU&LQCGYP#tH8(23UG0ZGxQ>Z9ckw8Z2!5t>DVc2X>B$Q`nt zV(qT-+4|csY7&eRY)?rvh^i1}%dh}DaZ#S~9Gc$(mds(Ph$Dw#l!sBJ&E|wbLlgP- z8zq<-niI>F>==u7d*+|8kp_OV*#Uf7%)wp5|HsoiN7waz-`}y#8{4++Mok;rwr#Vq zlO}1}WW&uEEjpCt%mzRIavNSel~qWt!>*?{zeUOmXLL3gq@%Af|O zen8TZ?qr}*+F4`yDEcg=WaFtwE2#nJxA7y{{pjB~NT3pU7#JyYfE`(w6&v|iPkCUG z*>za;h6aJRed`s`3dZnV)OGp(BYX!yTf`jo#EmJR4A2YgqSq~+{&OSEHUZ?jWjxG3 zI#>j#qQXgnRSNpc5QqQe`)lDud9n)pt2*AM4$e`3JvAr z`}zrh%25Dwc8d&n)i3P{ikP$r;zOT0nqb}sTPXh?fVr+WYzyzvQ~4#IO(w^f@L5X* zj$BXh|C{(1LO#Ty`a|cx&%Npxa1x?t5_l`Yu-fN_cTtN|V#TD5xNvbaNHhL5vp^Rg zmmgs_rvuq_@Wbw}eC!z5q4s~%*x^=bUnYD~nf)9bOzVZUwpv_ygXAMH0iE$^<({KC zSA=fePC(fo!dEtI2`6MS+_UUhHo!4BaG#eIB44jI{5!{s{y-M`--WG-wJC!YC<{Q$; zvb3sI7Bw*Z%>WW0tn>uYw?~HpBoKy0#iatoR}+8E-rvc5W5I8FF2n=UXA=)3W5f`#90|&lv_k+Y(9p@xEtakH_c+odVYQ?>^1E1|^AZm9$RH2Kc`e z%tPREPB^(~J5#>^u0IO1PN{i1rPWu^U%m){+)fGqi!lU9>S@H$l@w=xYNPl@g(9_= z7bOM0(YC6Wwr;~d444b5@sv0DeA=8|0Z*tvUfeO_A-=Y0n*1d<%_} z!9r0h{_!ns^n`r z{n*Xm0>Fqeo=bf)0y$0+UC7cEvQGW+#XzCMiT&udA3*WBxsFX$+tX%TiiX@ZFPj@l zxxpq^=?3)L8yK+6ML;~A(<)alfW4@HvN^AP6#~}W@Sz;&C7vP^RQru>?>u;I3NMU0 z1E|$pL+hdChEadLui5~yiX0ly_{D$z?QMcWaxFY$HOqpNPSE@e)Z-aphg;rV02$kS z$hvsiIA7s^cKi6tW=8wPQ-Sm&vEg_fbr%sS;QjDmZ@th3^?()di=LUd(GiGiZbyq-xH3kxFs;kFzECSH!ylz!La?B@5WZn!mC_>CA#g3a zC=sgGOUn#-K(6!F9z=+s6OD`asc`61FRjU}xQtdEacFLL`!eq2X9v|@sSvh_5p1?O z>|ko2=SXUoJum+AZ+(8~{JT% z%WC+9_SOBnb7bV5k1FdWrh#$JrwZN#=0~Wxx>ieO&Oo?b;#aGjoC((--={bgbM!~I zHvgzq?q<2j{6pS2tjGHxY6lb7rY21|jytXyVm-r>GZlYR4mH)~&J$I(&F+H!xVOO- z7CDl;UWK@f8L2i9xu5y)iM5#t@Y`i<&{7Gx%vke6q06;=KoQ#~#k5N;>!X zHNG6NKM%jW*UQVXxP4pur4<2iStCysVD-X3+OS(IV)Jf4@}BLnZt-O%r$h)-jqs&F zhtsp;h2dRnjqRLpCP^?j1Xfd8GuEWTfsP%Vg_W-SRobQ$dP3U-BoaOax7K3d(&pOhXiQt0rv+I6;~N|@RFqLkfZ}>c#l1=p{j`pHo`bB#-W)YL=M|R z-C1)CCf&Z6fqt3TqtGSN8Y7LPx0O~J04R&lz`ye~ejD5oZ@LUd$&dUoNGag`8{H)4%lL2735Ixlhh1VZsPVQT{g{Cd~SN)j=hyO?`m>Y%chnjM zx$~WwWu^V(rz)si`k%&x+%2U(u+5)sFSrU~kQ#+X_l%c=&UPt-!SR ztqCm#0(hHB69Pmrdde)Dmxr9cpq)Z}3Ta{!Q<@=+#{*+zwj(1fyRc1=0E<@;%t1u* zsS_8~N-`X*Pdw#84yEtjO`!)c@VY*P$P=z#V^b>n8p8(wTFvIJVTeUK_cTAZ=KeE{ z2RIJ8odQv>kmyL1s=$(`UdLcXkzpsYEn)Xj0V$XKIKZJzQTKl-zVS|13;zJa{HK#I zT<0k=B+XVsI$om=Zjn78H28U34ESutQU&ISnyOlPIfq#uZ8^CBAkgsO)Lxl7WYopr zz*Fn??)|ck>QtcS$p`uOuUl~6m)h7yw{TZX4)pQsQdr?JnH(@ zVI9!td&XeISjDPhED2Vu5$6tt$9;UrJvqHQPWm68#n$704o~o3Ipc;qVdpHbb$E6z zc&-hYG4?$fNH_#*7%|>#zvyGcs~B9dR1#IOlc;g7v|1z5CdF^#6&(D>nO~0LeEhr~ z^WgqGgjGl{T^R?k7Ko*OGFFb_pv|%Sk=ksKP@hy()+c|=X9py6HRDJbw^;J7P5A@i zCqVZUND9}`6+q7d1GH|J$=f5qbU`cH?gO}jHYl0E^K}s$aEaGJc^B@>4*UfNC>)Ox zlcGn_));Mtln5)#0C7W=uI1P~Ab4E9PedIEL(I7U$Ws9l^cGV)Sj^gi5#x<6nvOYB z>GqCqL?_h^T2wlr%ssLsAmWFZSeXyAIF;XAd~SCf%fn(Oj4}bxt(V^v#DUrflypHE zl_eU&BAILqfXmUzT#ueQOqt1wo{;%%_lt=7 z?z}9HPe%@TOIDnpKDwJFW+;9A^T#;{vLABJxLlhI53JH+$)liFNzS3OQUg#{j}R`H zbavM7`-@*# zgvTKOQWFR*zLQ7CvimZ{z)kjk*Am-?8Jou|b53DfCzKk4 z$^Xlq6DdX2NQoo$`cz#;sP-2DExL(QeD4<$R~}k7s|DIyi4^BWbV^Aq_|MR25${3h zhgODgr`e2Vlp;2@zH_~9#MQ(*O)l9SBM%4DYlk5augN#Q2>MG!aI426M;NuOZ+x&8 zXS!0Wgeou_e=jM?t*<#~5Zi))Gz-?&g)CkvAdi%hYKnc{R)x~<9;rzlUQ{aBC>+*BTLI#*2e)NJkrCe{+dWnS#imt%#~0PK=DvI zQTePr9My{C%pJezZvvu@&$;y=ut>YsbmHSP6_B`R_-`?T#nE|RXSas8|Fothb!k}u zSxYY0t`dUgh28T2d<9^AsT$TV8>J7ejrf^l^^E8n60s2C&0OZ#Ec0wK`*gZQsH9z6 zi0jj^0tRZll8L!tb4ipW_Xj#O2Arzpq9@Q5HeW0N*cxTg9sCfmrhqJL8rBvU+*B&kxnSOk?*yKf&e#=;)D#9d0PFr@ zXEcko%7MOcBWsn85EMy%Bz~|&@YQiq69O2-6#TvU&1lS8Y*aYk?RwenEfHzW`PHMH zEkm^cYJ;8sEHQ>vOw-AnDk65mSZNiC8h2^G#|yC4*@6YnV!8;-o27hgKe$4@vJ~3_ zvkrF`+nZPS0oD^B)rdcK30`{r;>b<*%eKj0y6j>sP3=?3x^qLN^MTQ_(m(5W%ThF* z9pM(DDRzJmOcZ&ZEo4sKOAAIQyp;2KT2UwG$B+EXUB%XPZj1n)C;N8ZScvg)zM66Q zcITWEjndP)XTNjiWB=#;^=f}u)_qY{egT$EkuI|M^(7!dF$B^_*SwztPbuf<<(T9n z)ZF`7@nbeGe7%wU71Z_Ur#WFe8f;JASG&tdpC_kBgTqvHz!-p5%k^nRmSw^e`qMd@ zCg%Ik~-zB&q}zioyPI9lG^{U zdhAiau<}BCJ@hK%xsG^m#Cw z^+e_N7Gn9V4J<0wg^ft}UNt$1rr$D&(V<>5X}}+~rja^Z7+Wv4@9JvPw(Cx9YXF|e zX|MDfDTcO;+ZO!Ms|rn6x!hpuIN*858#JyvL?18FoS}ss`MYZy_XOxKvY`*aT%1NU zBt9pvej|5c9Vg4Cj$TBHUR3x)HcOUNE*2%(Q#|D6GTzGzsVPTG{|5tP5;@$wB4y*X z=G6&UA~>;zVf8ymno0Bq>|}5pxmPt$3S^Nq5~!TE--u6+&KR59JY|Qlx8+tmobkek zAx&w{3X!Nv!SvCM0GrYzksC=XUwzW>i#FzTDv>jwUCpzUgQ5q_@}`<%>?>Mgqq#kn z9w3bUykc(R(+{Fi$xPRBMs-T`zk{1L?dYvuxN8fvZ_|(Qo$2DFQa|YMaNCteS?Uw5V_I-;EYq+2L2RKiZ zOW+T8RBAC}da!YMRF(DJ3*2n)59Hu&j*%v1E%ea<%`)7Vspmu1znXu{ZUB3U$)Pfl zof0q)dIgO2sPBGA34#S10P5`F)j&}I0~jIgSiwKLw{v*a3Z?f3W;GnSp%ewrL**U- z<5K%-7kz}-k(bdCj)x7IZMSs-nErHoBdED@ga-wX4#=gn_U{i|#e07v0Ti&OQ44OS22_UL@=wUd!6UQbygqm8OQ zG602O#EYVY8DU-hyY>PNk|T9`UkvcVrkgox1yzRO^GB-}N;N1ZT56FFdC{$QU}FlQ z>k6r?Dy_2CrLh!RX0&(<1_9~;M{B-_()~FnW3~{E3NOH3Mmhcs*uwx{eUfM>EQD=< zpLf^IK%rl4n{Gv{)yy$TP*joAsDH|Bi4xV&{wqP_P`#OlAu zoVT|}2yO2h>EBmFjp8GR z!;Pms#6+lq+V7o!AQokk%K{MoP>HOEaMTyyOMLu9ngqCb70sQE|K@H~X{p#y0S&LL z_UG*UWSp#1)Y!*qW|ps0%d<|0VNyBG&4D!e)d>>;o5!1qy$6-J!ILO1pj93fsC{ar zB7fNEE}D-EbrXl{|1|?he(%P3PCED_c_nJjh(&8>^_&IRs5#yc>HW=o zlvD+-(Kl7(B<-vzJM}%vay0KYDlB9%m1EfaENb`>-`B<>;FSlEPEuUkWGL>}rqIo_ zI!a@~3#nkU@cs*lI%72zA7B3D7{b zj(+iH`!p9OD!+dyMY#>ir%PYgSgKbp2&1h!am2jhgu7r7MfgL{j!_WOC;fc|fD4r9 zX5mOh*ZuWF8=b(dg~K`qplDekyl@eLUGZT-YZ~uslo5{dY(TBBxpm4M&P#FH9fZ!H zCY94UwHjutSVe`-evAP!Bq2T=$S5TB{u>59APg%Ww-n zx9?s^B6pdL@VI z^0~t97-@_acL$!X#|Hqx`hX|s#T^%R>kafND{);Fn9UsbFQI)83#?WGtl`68zS_9; zOE!I{(D|q0%8$$g))yUGF_hfm%NeA)kV~4xA-api?x4T0%m^sk8(_uRN)@0ragC5I zkoxJ6HBLTlBu#>b+9ZHns?U__&b4NNqj*V1cocg0C@3;cw`Y_?K7Eupt3kk2bdq2w zjDpSblS{wycpyN&0`g1&b2T~~z@{Bck?IHJ)^}AG-aX53V42)AfRXc~ji86#$`5hs z0iyZ@D7YY%&+h3+%i)aBM zuP03pZlfaQM{xX!RzSeUrH|xQgpi*-?#Xn0yvzlMi-!=JURoJ|p-GPyqI|>9`{x~@%{`b8mDS0cF9t{t8_5*Um8Gn7 zr0hrVE&^ax1x?YZ07>>!IBN=$5#QII#6>Q^rKCd8Y)0#bi$blyw9aVX9Kcjc@fA+V zQ=mC3f)5Q|7bHK^50YRnB*o(!E)B;73zXCxGBa@kXc@prLcp0v)hs+HH2f_TL5;eA z7M;+$XG`(>jUWc4bk8k#uLH$@yBc7Yo}v^H^L;;64aSM(M-EzSom*;@nJF>H;A=e6 zUXa@q9s+wA4glj>XVj&3-A8@-IZsyjN=M@Nsbh*p1is@cRVM&9rsq1Z`Eh^O6YM?a zm`Q`_2nkUhDd4e=*H{Jf{BgD6dPw_Xb(!mB>0Oa5o5Ah|kX&v#tary+4s;dGv};AD z-!2>70A|C)#U=jXQLXrbpraNq4!5z@{X5=*w%5CfhbFq%rvdwNsW*hKzY4m@;~t~%eJY&#G}45RISQ`9=KCnBYxMz>T|ZfK~DG@lO&aoa4W=R1+buxz2`hm5NmB+4crnrA#?huuG^W1Gj+z35=-jD3^%u>#fb( zGlkcg|J}j**r?FIzFsF&w#siF4O3{EW&UXi8r=1smEmo0ku0_!5O7}?D3~VXMoxw& zlFkh+%=NXn^(j4tCBxNUa6}jOz>#+7F51!-GRQsSIUR0}3FtT%CQSzH*8%69Y9a>V zutc+$nJiKlXX{q_tZf~CFDlMu)ry(l=TOC49d(U)mG6G{ z!HHs!fWzsw{Cr5Ja$WMw|ymnJPCw$gIG}OmAZG&t4 zPHi4~V1)yp&zo@;294P|9>*MpNZv0=ikj#3+H8a2vhICv)L&M+7ol|UNpWKAnKysd z(>Bm5Xa!k;4967U9U#;gTBF$!?>~R%{1zuY%OCV@08ih45KY>LBCm0`>!+EdDLmQY zW7mx01~9!YO|Nfpq>Z0cEvqsv0l=mOl~gDtMDT!+B!`!F4;MK2f#GUle^eO;c{!9t zjRG9GCgu2Nqy^-!Nx^=3fHhUvFtwb~^X-4HZBCRJJ%2yROVNIk1C`H@_S@}L;&NuG zJ7-m5W1j&DH9FepEg*9XA&zChUP_kJkxMAe^LP;vnd>cQ3AE7Bof0W>!s|MK+bAxNtY z8pw>~*<-HKK_bfE(u{tUG1GlV60>)Y0KquASGz^1(D+j-IZ=Xuc8mRV%8mZ!9f;FM z$mz=ju=2g_!YQ>cr-b~(;+9i4&+uu4l_;i|(08}7JdXk>V`c45& zGE?BJ1+vC#%!ZYnJ$Q0brDKn)rZ+)l?MC)6g- z`E!KB7K_MhXO&f6oG=$BP7H*?R8OIVp@QSHJ4bMI2^bU7*ZD*Py*1a;8^j^JtyL$$ zwyslW$yg#*{s%CpWA?HLdEin%73DSCbe0u;Z&yy&=Ts2nYz&4~uIjPe{+;R)erDXjuPM_0dDPj4t~fXJO)#qy)3>)$LsGe6KWzv17u~t`O42X zX|fV@0=5GxS;&DHoF=-xpr<#?(Ec*LeC*a(Vqx<{gf21uZ%f{LxO~yxHkY9aX(rV} zOj9E+|H>@gO;N&$M^5~Pxo_idZs_a zY_tfdQIYQO2+q!L35CRn{QyayGOe~U8qv72{}rb1ZH2+$;dH5A&9RKg6T1FYQo5nN zef80^Dt*`pOE)1VCgwNmt5x4Uj{M$ZgLiKYV~&2-i?;brl>FzF{qnAKO89n<^C7cz zy>L@@t=r|36Gr`)E!^$u_A}>JHKw2NUOP%EM@>xUu}l`y>xn8q2v^hF>eTES}l(z^V;VgNv7*V?p<4T{jK$qBv2XZ85oA6uc9)1^j4gXg9B+S*#6?sk(5#}oBmZVzA1 zHFq^yuh#hPGCcg2$(cy%*iF;9$bWy#S6hEws(Hm%$`gz#l1bPKf+gx1aJO06;U z_4RehyuEdM8J&1RN=r}AUilP!k%#;KB(mWka^GJv&vOeAtHuK`iMUo1G8*8}6t&}F zt`F7Lb)~7af-9p#NTT}^Wm9qhu#n?yHP+houj|Xxbsz4vhfya%AR?|<&kPAH(>SCo z37La|Pta*-oqK5#Qw>f1CE&+45=aS1u!dV;wJRETVfZWwEU%|LJ7Hx8`@s_!DK>o5 zc=i8(!IpDe)B4#WWp^ndx&WVZj8Y`tOY5?}kh{aGEi>j*{|Uyxv97p0v8smbtxo6P z^+=8QQKti>&z6%x7ND=GkvUlxKC>@|B?hCWVG3x2b{O{ZEHpw-5Ih@)D!gj(pc;&x zELHvu&>cFiL*Qc#I07$iU@n{PDUWs8N3fvm(*ivJ%xol~bUwefh?2W^d`f2Kt#p~Y zb9oyfpja3Lh9(s}vK?(QuwLCxU)GenS8^v~OR^45-S4Waup?9iUOEC|fz&3CwRS}T zW-+vVK>^nXX*7WZPr>+op>r=!;Jk=u@xP1#4qo0apvZcvzcDqheAzW_^SQTQ@!HSz z++{G(+I8pP=Z{YCJ282v7kREPzg>TSyEk!isxuP0zP@$?5)VR121MSrMT|W?J+B4E z`Sf3pG`7bD&If>J@4i$ix6k1H)}Vb=F!&;D|7}agaakF~!EclF)|ZOPV)78^wx{s- zePLXp{H1u)&*|%ehdkVuR;`sZ@Vy+P&&cfh-lO|O@Z~zYx~HNBB(0fx@vt~63K7b; zYWXMi>R^Q*XAWxG*e@JNi-qaT79}-Sc7Vz{d7EUbgb`^^`m*+s4N&zh`nTfhbyg7g zfjkt6CQ1bc1~`J+Gp4qo+y8ai(B7uxwr1VQottb1FRQ0RlibP9+~NHAf1b}a?(VYS zvgk01KF$o6cQfKlz6v-Q~WamLFD#>!tXb-)=6*<4_(ShucFF#Y&3u{S{Qcmt0|@)iLSzAlDSsBc)&=)xQF zv5$f*JC~8N>7)h|RqNn8wEZtxCV?>hcxmqrzt)aOT1Qrn1ncxu`q`k{c!kaGLu7n) zip%l|U{m%P%7vFE=)5{^zpxDXJ^N{Yr5aOUp7hJ3LGC36VZLQF!Rfv&L~J8;r90T3Ff5G{GG>+ z9eRZlau|1|=>iPr0?Pf@3qLWoJ({@@0j_9f8HE*ntk0vB?FOr$$P~xRxFKA zRV|oNej_L7dg?$e5tLWo?cuW6VZU+Eac_r_IIr^?7kZ=MXR6|)6?Kh?HC+si`BcmO z0Q;G6TWEU%^XA(2h^H}s+|NPAx$Cj^thp&nHMX1^<;ah2{5c9wqdg;5N0BDu24_3) z;}{qRI=DfmtmNZo84z5gPS#8kVs<8~K{$Z~{QsTdAJDyzY$&8~GW)L_@xPE)F?j}> za+^p9C)XXG>)qx5$PVgGkOD=3)%O(C@O)maU-lVH|DmtMBXHJQ&mlnmtJ&tn8pN{kX&1h5nLJCT_|w$>gK3(Mn9}(>iHdF)@rcP&&#U&*MH}5Bzhf+(;4g_1 z)!2SQFzyKgI{NnClGaeVX;35Yj^pNc8M_UDiRQTsr%D!3>|v!&fcMtLb`KU5VnMhw z6XEoL_xk`D{?1gT$EV|(;W(Z(%XSnKqyXRss(ZUyDtt?~oH7T{iVfa&4a&QG)}Plb z4h1#;0RJv>UvQr!-YwhWN3>W1)LmQPYZ)c9wBpkEo zzj8xYrkd@GMJ_?!*5LMd=1lkRT)1_?3W}~(wxnZxR>?Yv5`)H*IMD+gHYyX|dVc0>lV?*Q)5L6BF zi0C(w7G{^b>?l7bWx>4jmlCRza?A;0j?AS$=8-Qy?S8J$c3v%6t}fnwUK`OjfA^t= z+;yuFd)Y?*b>R2VU)4yF4ekFR@w+(y^(u2ZE*`@z&Dcqp~O zQ}7MQixKbLd`*~9jvdv>hJYwjlABn;cjevbgOsw&a$EG6{qd_w0Jf4apwk)TcTsn= z5STw-7#x@P`IvM}Z`i7j3_W!r+8cYft&ssvy=S&Vx+}ju71ok~=tL;4Rd6}8Ls~+o2x^Ewq`{V>5Ui#df z^j_!P3(C07HXYg+JZBZ%!u8n=twoiKiUDtz}x ztsM11P+=5pgX8N#*B95{nsTh#d$;qk>P!M8j?wppR!xj6zTWmkh&J5lW%vN>$c6>?3eO(UblK?hm0xEDidXtn(PMFbZsVB~Jc>qG@_yJ35__I)(ea-o{hu zv#(*=9}+Lq14Hi91ktNYs^8Vz|7)y3Z3-=mNn%13vKs#jRuM^vu*a;v;h^%PK?t+1 zTX`!WdrlR8*1C|X8cbDt33$(cZW|#KLD6-?z6j?beaseFZ(&AlflELL@Oil0o0?*& ziKIfxtbAyWK%v8-I~){HKrn16FYigk)#>JFdG_BAR$(yLMF5oFHg(Gq5h*3BhBj6^ z!I`*`enHj|lez9SPR_P?$CUtU0Kh=%cfBDYXyE`+a@*}>6XRsS72^BH{Wxd)$F$Xo z|MRKZ`l|2sSp1w>>?Smer`W6qaDKj1>AubBI8;47mt@;JpJ;kaEAptl`Yqcv8`;^7 zO|}71ZW0rIuzNT*Pr0)VO5i0bp>^EI2VqyZZX>LJsx)Vepn}+BPCwwF@#?f$!JZz3 z(dI;O<(z!8oL<-X7xnY8TN{pr){Bp~hR{V|-05WrdWKB_-LK~XS2W`zZTI>f zZUith8r@KyclAMod&n$VWZ_&VgXkmc#QrO-iK4rg22FBu4#N@=N9*#DgiLCKHw_aD zx9b-AR&&~)1u zPn_&sr{?Vpn}Pi^-NbY{V86cR>o<4xoLP_Ie`V+b;RURbyBGk1;2rh?PS4M@w(tY) z=WB7jy<)@1BF~Ex)lbj8uq0T_I?v1XdAE$iw@9d{CdS6b*XO>%2@(+~eERvM+GaOH z9>#RJ%O5#DQa0T+cq%hdQqBGgFBYkq4SLgM*>d0$U|f~tYuEr91R7ToQNEr+zDPuh zuDBF7aI%_p?e3-1ZNvhhiqD=q1h;+F@)ue^6pCUgTcfGahHLZy-Z(+*W^^4?p<<*E zSLXJ{XQcFa>hE4DOPw?&q~(tyX0EiwUUTLj3jh|F$c)@i=RiXNhU@FIlL$Syu7x-`t5V&A#7Osy* zFM|O*kGosQgb>(aVuY?*-A%km|ELFv(=xj}0IDQuLUZKrWv1#RLKR`2Kjj7_SA|gb zC_tjRkhAX4$;(_5H{d`X$>j5RKFrkE>uq(TLKQrUTc}Fxx2)b61x!(oUC}4GS&dMU z({>K&{g%qjL90dMY3cZ`t4eNJ{%ai9pP}dDYXTysfE4Yz&hI=&P(U=+!*+tktKY?j zn8xuuvw@C&`_a?;V*9zH%+W8uje8ICspRSB#WfGQWz9BKF*Gzfh$$$kx_b@ZS&hN) z=+g-3!EgiwTKY25XmZ)}PUe$ewH7`CTyA^!GD_oenR4dr9DjClo?Y~OdgV%dE!gQe zTCW8qm9p+jCX9xw(T^=?w|iCkYYzrot+7+3m@+J7&PVamDCOZoA>anZBO8bQt*pg5 zaw2KbiMVU!A;mlm=_EIW`aY~_J(K^yw5_CWw@$~bXjpdJ3LB$X;5O}Uv$h#XfZS^` zoE@ch9envrxm^L31h&*Ce6ot$-+QeyxlHKFxj_aWM8&MeG6GMFvFFyd%%2e%Swcbv zW!?zOR!Xt+8~Q%aTm94uoIXQ1z_cE2ex5_rmRI<$eW zeb#@bS;uJRx)fw*7uo%YwV%f0LVfW#k-nnaLGqHYifT2ZEz`B5&%o-vCs5Gjwt%+@ zRn&9vbwUS~YzR|SP-Qhlh@IZ(^r`P0KbAiBX%ttaaf}x5`QM8e`;+X7$b6wQd{(mA zzwled8_lmWDBG^Hu>ML^XDjcWz>RwSVxye+X}b|4ym2O}OHqmz>c(Az8Kx*!<2;kYLOZM5^GUN@FP6fgQZz<0#0u_sD+*^F~f{j%08}=^TbGTO1*6BD$b- z(O}l1&{A|rn8PGva_y#|Z2r*Rooa*CLn)}x$L?kEZaGf52Uk9nMgolpe zKTUZg=IJddR#=O?x7u5B8VpO#Nt9m}Dd#-ACzcx2abK%xfRCi(t~8+DFr;?fM2AkY z*}$&niTPZH4aWp0(1k>&MQ@!1sh_o+9;>ib7>IbLucxj3t?PD+fEqJa+nO^+_FZ<6!-#(=mxuZ8x1TD- z%TaYHeDO!Gd^@0!rkjb5jsB72)$;}!$sMf!*0xHg8RtdFWC%(A+QY*`LWMdYytJI& z{bWIfef92ixnS3C>gLh+;OOXAL-pI+TX1*Gu+mNn@OF{^eyQ(D@ z<$Q|3W|ZvFcyq~T42;h}^_hq?KF3p$gy>*Zl9ZI>ob}qd%A}d4VAV#oCxWbQN_Y1h z4IjCNt=;zNc6T=emi5w4?W|#-9Fhii6BVM~B0K-Fwm(qEp04FjSzj3p{Dh#Oxs`25 z{~d89O+FJsEWWSMcFpDP4y48*4b^$TOpT9E-ByJ62>0>+dKHuPVow?7L~k_H;fNaO z_Os#4*nOMzef{EN4)Jqe>mEc=?sm|m7mS+ib>;*8FM4~z{=s-YMk7y>MV;rb2=k7O!~D>_|2RJ%TX`FZQx+u+Pi zOP>&-V9^-nc)97~w6eB}Z2-AM;os3E^PcW)kM_IC{64x$LJnzoIufRIe3*+23dcRH zKo)|)eJQ|}3Y_sYu8_n0tPmd^JyA~_fQn-QA5&FiiYO#$46A{!^fQ+UQT|%uoTL;O zDVy~V5(G6D3>fAO&}>Cak*eB*j^rF&af|q<{!-$Uq!b6qnu;kOyRrY5oyDWq7z)Gl z=f*|WG8KsAq%wPe7>KG~&bmZfN}SoHHO_LwU;sWYfSMuHZYTm5Q*{6?iY)VO$;NCm zP8jj<&*k|M`*UUB%gi=dpqD4KQLG_W@j9EZ*PKQjOgET)JMx0hd34OWU31?-eOGXe z(-*5($l-kk!G9~lT`1bQ1IPh%r#-hD+rmGl19dlT(x-aLZeM4XDvfKXp4PSOmdQ*E z>qFo4XJ_XNrETRLq^k5w{|ZTC>rCkoZuhlXtvoyKo*M$2RRc7p$6WtqaGAloU6s)w ztq*e|t;>GxC4p46N^DPe5`tVp7Th<_D3U_x%1}B zaGFfqVMKR3X8zk*exg#s`;#I^OP|J_f2Tq9g%L?ZRa%75D1UKt z$fDlwNZkg~jAa}D!iadiq*&%g?YQ*Deo=f`M*B_s?!olP^((=dEh$i05)dl>Ri-;Mt@&tDJr6fotr}|oCJ$En2e~& zZNo*$n1_*rqnyG!AyhPemW2?INtXR_d++AJ82PQn9k2vTVE5#_I5v8*g1gb{(#=ld z-x-bNn2(+#k!cpJ+I8)H3pVRSXUs=8(frsm|2?{9RB);ZBc8W#m+I}~pPp$nf@aDv zex^f=qzNP^G+Q zC2Sgr3$0)F_FylI4CKXI>#)2hF{;Zq`B`yq~%OSIscm2l3B<|yt@_Qs>f#Wz57;r`Wjj9hRw2Ist_IX z`861ko@Hk%hUQH}EokN!HfBINVl0ke1BZEv-e4ZtGwec0f-+8(9G>aCFIP3|(LH3v z{Ul3`*Lx8)M3I!((U?vZ_E$^0Jl!Cb)XCu?$RgM?LZ6iuAK5ue|toI@+RUKCr<8`r3~=_wksnsv=(S z+OPsVI_iDQZtkCeaO6Ub zzaa>;8s(1k9rYEI(Q!F05Y&%4pX;A6mIh=i{Z38>AedIKyN`a20e!?R^ie(}%%?q? zieZyXI1I5(O$z?Qzvj0%?c3{Jvxf7U42&A4+(C^$P!Hzme`b4kuJcVMtsT~}WavCT zPsexQocNQl*7JmD@Zbm3q}s@>m*q2rf~~#HvFYB0X#Vk==-lb|Lw$Chf zqVyCPS^kBvjSvs7jpc^K5Qe>1bZY!kly)H`gvq%3yDto&;2Nld4P6L6YNk1?sviqE&5l zjd(lpKqu@l_W-)plBVDzoal-!gJgf^4FXoDUUZsl#rV%{<&!8~U0qWY<^hcX8j5`J zmxVUBiefiAMt(2Tp5znnji0v<^L`Uc+R}ryv|wbeiZ8u92p1bMn)Lk{8@|sSXLy>H_-h#Xe+3b}wMc~_s8y_)sxyvz zd={hZ)s0 zmgePY9(kXjFe~@DBZH*=I7&yWp79ScDe9&FM8&{h8G7XXQ-rz9t=50C;|l!W7DCah(5}F~+?Pk(7w2tbNCLm$nV)_1dXGV=IgJUiA}uW^}o`TQ#eBw^`l?DAo^$7gL6qbWP-k>oIzAJwsbCW{qF7~WKXGZSY12u&>4$f z&}i)9&@{0Jq2r=i(@+FOe3^aMnf*pVM4-VN#>2QrVEftMrg#S{y3GHNr>hRDYHRv* zr%0ESbax{iQqrB$DcudyB_S!@U6O~8?rsj<-Oaas@4erC&Yy<|SZmLknP1FOJ#$?0 z3VFRlz1tFbxykf#9h7f{&-AD!A+VRrW-DbmEE~tV{WbdtrhU0cjysr-t5~jZs~fIj zp$m2dYJ;rXMNh^uO{1A&Dxc0C=3ktqcMU_)Kt8H=uzP^8F!$O>5wWe<0lok7nW$Ue zS8m=QA`mxV=^V-#@m>z_Y-R9v5{GKiH==lYrTmgRLyd+*g7 zfgL)H19m%Wzf02}FO*NO_I-H_2l)t*CNt`odHUvhXM;9BKEHrwn{un@7!F}%#$L;u zxu{J=E+A`PTYNTX0vS)@hID@?QwF?h+3si0s=H{aLTJw9y+v*s(fJMVO;V=zv~N)5L(E=-=~Ljg;=>IzGVfRF`$a>PWu~gnzPz{yUAs4$eyyO3N)vQN z=T`!S+|U!g7r4LQzH2Zs2{9Qrc-^&~%MO;G?8Yr_$2~er?YC*nheztyZZkM;%;(k~ zS5-O?Y%~P%DHYUD@m;Ff$QZoGu(hUrTi@>J;8@zVBGsXeL982|;ON|gX5tY84eg7? zK3)7_kA8R|!IVcwiFzmRRHKO!M(nEDW&8HLCoDf&W=UWNdbtf;R^U6J>^V>rxcCzY zvIo7mPBVtQDLZ$&Z^uiK6L8{+Qw-fLp1mNZyiKjJR`$DU&U{W%{AN)C2Jf9%Rr&U1Phau06L)nTE!+akm^H6dX4)py<6 zpiT(<`lN#-s3ykzq5YeEkna`*Nhjo^o31PzH-W7Pxy^cFR4v$LQiYWyt3Xs$i6R50T*7f0+$Xy8ut`F4=HcF zJ>PJqcUNDfhN>Owinq5NDDSnWnsC(@8PMWzRJKd5+Q(YQrqF@(GhStqq)dLv1b}x4 z_8!AJNUyIC<9>El9e;I!M{^bF_pPn1gz!X$4&CtU>p|#1`PKgiT-A1o^m>*3ma46B zk*Xl{V5)M32`Tb1Z`0mQCvto+cvZ_w*zeW6z` zb&;TN^Ary)V>%*ke69Zjh_Z`$xH42CJrD^>cFRXsg%h>vB&xL|%T%%_`O}MmDb|0@ zQ8b2#msjJI1q;IG_)U0)P_&{zNh_H%N_D)73#W}0rvMd2PT?1_FbFA7GYKm#ihFD)H$7vjVH{ty%tq|q97CzMshx*rsEASg< zFxHrTzuzhHhfGX7lKAt;BZ}Y8L)~|AjBwbJPc6~Qq2uXl?%*}KYtY`1DNL4uwf){q zX}1LhZIfce&xfJGih0?*ov~~^A(kcO_ZSuL@sj9N@fiE9vn6oGhS$%7u0chQPsCjW zv7z4w+WO=^V8m~Y@f|UUlPAt1oV6S=JwJipnD}E0Eq`B6$syado_8aYB{hHfAoGst z_j+L9GJpq7MW{)>-BkH)fZkrt{(ynFHP3LAT=e+weXwuLNUVC>`O2v&kHx7c1PartC5rYDxFXvw$IoX#py?2fZ6t{MByuSZQJ*wyJ!&zC<0rh$CCblc9bJ zY5k(c5s^;L`MnS-R0L{ZRs86NRuosNyfZHE^{%i??f>^a3S;q?h0gL1OJ#$zAGC3kK!)<0a&w4Cq#bwysoHaMahKO4A2_7kk1d}Ng58vHJ$dp(EIOW9KJO74;C}} zEOydBFlLE-ghq)@1)X-hMNr1@&{*PewVf7Xe6e)GmOLS$P|te9&B!t6R#Ai12dh55 zOx^e)Vyil@8Y>w&kBx97Gt;lW)s}BmLnA@kUYUKxK-ous?A2J|_f3!q>a^%w?C+`c z1oGO?i4vVHw2&b%cujpJVNE||(z7F5{mR!R=abH3ia}Dm;V2gQCC%Re*VEIx2V}jP z4$Bg_dcgq!kUbtut;cLDF7tX=e%##LTYj&5esq;b335!d7F2$FnQohe;QP>xYeH_j zKfsTuIxI^GUB(B>7KnSY;bUjNy&5=dhk$$Qthtx8)lcXmWko(f4ZI==11$r#MA9+n zg1ytwi#nHmPqo~gHrOASS`?vOvNv8}Sxgtamk1l9KNo&$aq}Wpf8i&oD&OOz6KWd< zgRRw_TS*h6zY;LZp3Yjv8N3?@MQbmGU|QxqW`k(l8}+fx(UDqx)Jk$A6-! zW5mQq^KQK-Uc;69lBhd;O_dbb zT@J%BNN)C~6rjndiHMmkH}u9DiP;*@GM>isY|ROzP60&V~Cc%Qv(szn(V(@}qbc_`;p23GCZ?%J%s9SZ%Y&*5l%RsFK}X z<$FVKv(|fJ1I=hYsGw*E*(k`H_Kx*8=%Dxxx zy_vX9mi_9mvF962`1XMJOU-~5tJp|Wl}3a`;Pnj(3v@suls?Dn^)4Z5Kk6q!y~~1C zEEBdG%q)jBwe=_&ED+*S>Cx2|3X;GYk{`oHpa zg+ncnSlzw7yI3VwhNjrax%{$w#YW1&l8>3#&xLS!D5;Rz#W-7oeSE0>1}ne>VaxJ3 zI>}x4&iBDwxGO8t*XsAmnYR(TT^rT+6a%&DZ&mL*?!!L?i!BCZIDaN;dTy=PnFqEW z;DKJ<5PmiL9~}$X)x*hdd!jKHK_5eb+yxi7qKV#y0T)5t0?-+tk9Ao?cAN+wcBbLhb=wIG^Kkl7@bGS!D}So%y(=lM_2Y z5QVL_y5WxCB852gpmP5zDCoUzv3Q*1Ks|f9JZmGyVdR@W$QH)!$#IQBX^XkmR9+6O zH5Z2pm{S*jG!wmD7EZ5h3~9sY)c0X6PhCY>%rVT1I5sK4otx=9(*Zfn#CKY-lEIil zzMs=&oWZ=wE8_JZ^;#*(r-iUtO8iqOD1!ho`77$Q5TYgRIp)NqiE@f=%F33x5w+i= z7GU`P_iQ&xBH7ObsqcCkx2t&`zo*jKU^bdy;wxI}EY_NC=q^6kn@gaYc!vCLdf;+! z&(9=jX*xx`Lz4G3aw@cc>cyZ9l^(QE!Jqv+pI*H;l8w)F_nTsi=Zf*MtDn1rEI>)A zSF`OJf|zJZ*y2bFuSVevb^QKGGafBi7edZ@cW7H%`G zqw;w`%99LGc2a!SZWo%ldQtd3v}_3w3gWYSR!t{mDJYvk*|xOJF9Sh0AZlxSPPD&B zw>5)Z=`J2JjDK?-o4be4fzzHu`ZzT?c~do&Af`Oeadppm6X>NP|I0ogBD+{Hi8Wen zaiKDrtQ!|11R$FBg3{0g%8fhFn;=jclm{-e|3uOE*ufUKT`&Q@b$jc&@@<%rXFE=; z-1faZKlpJ+*zv@G^x96d-VhSXUciAh_bR0mJQJ1NJ3LWqK^u5N90v`T;u`G#F6P6^ za%^M!oy2s;Lrky)q=@=QVH^ZiA!XzTDu(RE;OX0=-os|b7XIx zmifuoNeJ<_WV((mbUG9Bt=+}b{a&kC!U@5D9?s_4>0Ry#t+}GUF&?}K8Dd)&7pNftFtXLm zIX*we)I5Xl8#@|FwXu#=JGT;3>(-efzXA+ItpAL#?(SMo<5Tx;%p=}rIe*r5du+tn z3L5wvqFhB!vX$%cI9`OS-#D3>@O?l6=!KL6@?!Xq#)Y03*6up)$cWGg6`H>7$ga3= zMgP8Cvc^QvtUAXz~lHdNzYJpo~~3Z?@2BL|?ko3rUucn`|>=O~YmS zbd=COQRB_2jms>SUxZ#e-b_NA!0=%Y00@@|d+fo@1P1O`tj`0beZUAebdtBhq&*5PzCI;8^?r7IvFYFVfaeI>aSw< zZxM#FB%GV6jd})a%@SyEQ2mPprNtDQ49pxc9%PckV4y&K3mINDqX&3N=HuWQf&i?3 z=}n64?u8m^MJ5#l6yNn}X;LM)>%m%x)J->eQ&H=xVa@7BKp^K zP(-aIpCvLEjxHWuH-0{1tK8Tur22eAi$#b6rk+P-DOfB1dVmXfgWkUfawiO|U!aNs zA{Ghj1r5hX?b7}`IQ3H9|0?77=Hw<-{fpN!sfEeouQjsMJ9J^8Vg#X~(bScIbmRaD zxM+as^4&U*L|5goZ%((p{jnOb=(zf~Mte_d-y6ZN z>UXcJ7L)Dm%_WzKM+0K-zDug2#HR8~V;8(K``h~+;R#(7e9Zrngnl~TPaj2~h70R& z7YV2t>Z0g@i*NM1qV%t@m9CQbh2FtMax5owsAqWE&Z-db#l=HKb1-6r9xaG`t|u$2th)kX zV?vZHJ%QXsdOzfXijCtlO(u7-cLqX-IB$j52ZnGC%+!1-jDvZWP!o;Sol-t;nn&W< zg$mTS7-f=!LT(}7k9w$aJ)*gd(kgqVjYEx)#TlPcLv?rEV!1ty&0Q4BQO^GI1W{$M zJ8S%JD3CYFr*!K3F1s+RdY6T)xJq^tgh~Z(G^%=`q^@#De=(Y|5H^j?ToO>8X+)z$ z6KMN*M5oTQfDBP~$BITE#M6i#!~WYISKGzjJ|>CR{|l{jPY?pEnENy);>vxK(qhfd zJ&}Tp>ecg^g^J_rLEint898>*XhS~fg7NdJszz8t@^wvdXjUZ(mp!B2?r;?y&+~_; zfXM`;Jh%YNQT#uyKhDKnlxiWgukJ8nq$h{*!?%%dy zQF^Vg+B$`OtP0{P@H$gin95>L57Bp<^W4G{EJl+mFp7i#uMfuVAJ&nob{$60U*w92Zr#Kq zk|WzvB535@?m1i>)nqTi_hE#D@!0`x1AOw3NMHz)a8gBex0^;tusqY1iN4=S)4-30 zv%O{}`|s=tEo~;^)Pu@1!w!>eBf_iDG;)6Sm4OO`+(LDH!lP+IU#)D>P<$ZUiJ0~@ z)S-j*dh%3tb~}V0It4cmI0*H07Au0Dw2p`DbI&@p_C2=N_641Vn4XspcHooy_X3de zAkJ5r(TpG1w$2K^>4Sf?!@bU2J@!)YEwdxQl>?2n?n~VAa221^=&G~aBU=^!bV$-X zWRcj59gTqz$CCkb^nB@Ne`j$wO($KR__n)(3`_fwCA(C*A*5cWr=u)(RncM z#oa3NiGL|%1UW@~wR+MN?W;djHt2k-a}jT;;wg1-M~g0S3O~jR4`jcDrzq_y zH(?k4UnIH?5O8O|v1_t@nhaY^&K2v8sa3C#$Gy^xko_wW?qQiz-ewbAyl<=#HaFFiZ*F0c-?H)!#(^Ok^`tf~$5y;(` z$~})GZ>@+u6ef+y%4Gm^1@!(rFPHod-2qoDKcu%#8~Af93A}v~C*A_e%e;l~Hyk$9 z;tSeYGn(I`5-j=28$h1MM0lgG+{cNSO0uMhIqn3^b|hWWQ@V!A)Bd(%GB$*=xd0HR z>;_{5Vh3g248C)X%7;Mst(EWcq=eL(rebj;ZT)!ry~->=Sq6fUbM16e98L#55ihEU zHErOBZetu(fV7CDwfHCV5%lbl+}HnVVBlIatC&UGN)5xAl731*USHw$D@fW*xn1Av zR>DK|5al8dO9sysA(BxBznhM~TT{J#`$T#}0hs8-<`99C7|*ts$ywL^T`2SY2PpJc z+(94poSQcxRklo0+Kgb(`n(hOzqao{<^BA83wgU~9&dG5fdQO1 z_yVt=4_L>LfM}5TCmOCFllAVmgh?72qO?OLAR(Lc(BC|bA>0HS@QDQ(5u|Ey<$~kZ zuZE?6qVVu_ouy#Lz#x@=psVdnS!+?{UYWzZoqxXb_T2M+nB|S^i3ju26COQNdw}ty|+0_&sGl8mBHpvd4i*mZH?^uiCYEqyJ6(>yN8n# zngoQdQARBKugz)7oG38`tUSp;{p#r4_nbP56Rc?D@SlXns{cT#R~7ACH4kTlxG2?D zCVQGlrN+m6qoG_kuAZQr<&cP30DV+Iq3l-XaIM2DHn{5L7vh`S5N&7ntExk`vSB@J z>xSQ>a=j1Rau?&b9%j^eFPK*oI+jCvS($~^Dpv#OZ&!EDrAnr#2cHl8NqmOF0vI2` zY9~!?OGtT-^DW%A@fUaeQ1@N4m^LevCX>$`9hW7adJeAePa?a>0yZ#Tthd>ptnOY? z@gGh$+RroS%>aHB;}m4y(12HEcxU(!;Q1nmJwdv)`Cz%Kbcf8$o-850)?;50{=Jy2 zg72iPakt7=^L?D>u0k-nnp*E%Kqel3T6qis${f=^Za9o=cdjUef$tF;!(sTr*p>$6 zh#l&z)%Um@aHHNB{WNdh*KY#Ac07zyG0=Z7`t> zaUUYoP<@FAj?uI&ow{xO@hZD&iLci4Xlvr`x#iGXZNVxJ-H7(_;y#qjhI9%fE&Fc} zs9Nizbh;<~^qEE2z@dMBwQ>1vC=vul7pF+GYv3uOuWnH@Qgv@@sKFYS8m%@@>D{pq zA%~2LhQtq&%P}Jv-|;FS8-B#{-B@N_@jZ-{wd1yu0Y~U1Y4DsntXNv{W#@iPtP;M5 zoB+obQu$cCPW2z%nvPYdCkJ$pyb!-N`QaNN8>oE^nGA8dp$E|TR-wfRfc-K#LIdDp zyiOhPY)luKb-&iDqvd;7*iz&u&kdLP!MiWi$!cfoP95K{CEd^!MpLIYAO1EKnnpjq z3s_inyu-qr{4wWsU&O-k#fPPO&PaJcXn>KJirap<4cR1bQ6wjK00Cx2&=cX5UFxD&cj zpC8853}GeLIOTKAN;tXBy8G;moFIIPUwPTh0de|EcLwZP-~-vioD0n)arE3?d-i-P zS-Bj{Wyb&gzoejwj`9;HZ3tTu@&g9Mk~XJveThYcC8x)8CX!&w=wZhIF{!?Q!e#%D zL5O8H*@YUp?n=RTjdm#*^AB`=Bd)vn1np#oslC@$Yfa=skEI7e+)uKU$mj zI$s&gOdagJ`y+<%`h){>+72xberC|_xK|FgYpyYrT1GwJ5jImVvpognK8n7pMPW!a zdG!kMBAG(3*kwnWCRD>aIry?sriUe@vf?f8y!p}{o_uYmGBh(#0=Nq@zL~f=fzyms zjW|ef-EBKpH>t(N)md49{|29bE95EzhVRI;_K= zpR0I0_s$j$g;auum5e^y=3w?VMaoTtw}&PSv7r6m=akMJSBw@<*={*6V&)W{FU%OP z!#5T$AoSc9A9GCtKr5G`h3sFcWpt)}^)4tbJ&XSo^@GaJJVrVSRNicT9&=Gv6?TJm z(`sk&>`q!cC>2~J+|xQf=36yCP<7<_)D4uS5N!jE*W%l(|Eq_@?$75dd)gJt%N|Rm zfUUrI_hZci8~RsIP@Z%_Ej4B>1KHerXAT71aJcn5dJG7_V9{r;s2Q~^>_H>sdJGi| zIE@;pwtIZpZ~S(SU?jc=zEDBjU;fP!)@BW#kFz!0qSUZ=>&fHQYaCO2k21b}`MG33 z`vsqi*Gni0ul0beNTaf(f!=u%a1L| zIr^I}Hy&4Cx!PQM-C9H3ar42J=T5A`{k&$df9!X6u`kD0Gv=y9=)@{$eRn~JA$VpY z+UC(B3-=z#@Y*X&ZIf4wJlevXBDptr-;J;8cvR%}MutG?A#i2_zK8aG4D;%LtMv_4 zN~xxS`SA*i;p_CNIY%&2jjb+c662W*+Od`)r-V0HL?i&C6OrE2;imPr2mfhYgi`5+ zc`?~VqQ*^eWNzVlK=gfmW=aT6F>w9J)3_A?9iT%8m?wL1c7r$Kt*EBFY zj$Q+*p9Gmf2kyjANX@~`t;mWGhE9e+{Y=Nl@O?E2VC-cjWqLG4_PsBoA@S;q1!84= z#;s{1zDO1tWTrjEuV*xas1NA#3x}#wv;lDHX^gZ>IqWlz=>;u8Wt$B^lGPHf_l}dh z8WcsB{sSGMLgxY6cFTVKXXxkq$JWv;kWi8Y><@h854|HAn?xi;A<1qyy*9cQ#5H$}X$v{+YF z>$-EXB6XG^E!BM3@LdC4@y`*91zwwz+{pBksc20BRjX2p-TqQ7`F*=foen(AOBu}- ztgeJLgy)DS!e$r6cMUWctzI0_HTic;q5p)>2qG-WSH9G3HZ zC!0hEjKaMgbc51qgfM}Fh3f0`Pq%~eJ%?T|E%T4{LBS)+_^tDNtL?1oVBEz(-7%>< zU)Osz^%9oS131d0i`b<_O+e_N3K)mTSVTpwwYP%sr2(gl& zh4@n{vEA;G_+aa>hazQt5r~#tdLlMe}zlT$Y^xuQe0O0S- zG^+a2IIXMSUY|@x(>OJo?1*CoE(bi(Z9Tt>`{%P`pN!DC@fM`XF`^I?SZ_PXF)pkM z>+|2Xagk7~0+gre@*Fx^cqz#^z7L(<(}_aHeGHck8v+_Z4Un1fL^snl*3XxLTU}x^ zjd*@01}H-ykk)>?jLm*Q;d#A3enUrvEXqa`cyV5Qcu^D#Tu|%?$%zz3gmAx_bo74J zVYSeH2(sN-TRf?D`mBu#44gagySrH5^0ir_BO~~U;=db%Ee{RHbtHVs?hGhZOOKB? zkL(1qw-zVNU7*i5V-YA3HCtGs3y|ev>m>acXX~eIHEooPe*E29g8yx8kwCjE7Srn` zs{8e#M*sM2DgRcPho-9fho)PR!~GD9Sy$#kW5 zS?n9ZtdV93Io3(DXtXoczQuUZzsHURB&eF-4_!E6CF&=M-91eQW6o}*KNz85n@|Pn9XH?5-?}k7i=tDGoDJ(cC2%1Da>(Jlt5eZWo0TCAtMzah zkNaND!grR+_p(D0A2NItp%|pWcZgv zF6=Y|zd6+p#iF>-S57AlXaH7hY=R`@hC&yzuxzZXi|Om6NQd|@?%848qYJ5Jbe`qnQFuVOTx6rb1oCF@a=)WwF&QCD(SMeAq6Vr{IWQq1Eo~OUwo(K<7!&<;`A084ghA zlzgI#@?3O?rk{seWMTW82>DOmM4h%Iux&6=lZze#skPk{WFiCstH{3*@<8 z*OuorEqiaEvR5@I2nZA2G>k?97E8w#<67L2%%p%^3+W;`?$cfkKyyugw$2TxPE_3t z9tUj~t1V7Z3^zY_F5!P-T%LF`WBS(C+d92x4xmNP_iafQw-&Q9TJJ279w*-2=J0L< z!xA$JEj2+tDC4#SpXgMc>K50M{kQtJomG!Yt0AoP8B_k%>lPEVU8@d!_A>0NFdkfqAgj5XvY)`j$HvJ8gp?MTI zqN3LNmUhe8~Z_|9_7a z&qGRsTF^)$AYLqskk$;!HHFT%Wuz1BqD}tg{Bza1ya7o{O*{lGy9vNIv`=5Umm{q@9{qXCcBsD)@`Qdxero_Zm}bIPDjcYLzg)hd9DdeYTSb4U zu?GPojf^jTeYp?5E{ME4{yk^6cIp+ia|8Z5Z;z$ z&?|oPxv68OmHv1m_E^p)E8ejCjRFSvXH7I#-AU)rk4IjWb@gVpwN&JLav^?nJj5_a z#R_Zs7}oRVuWw`f@R-QI{ivYRX26N7$qTJ$Gl6`GmB08A;j%1c%@t$Jz8q+Qs92W( z!-Vu`mA!^?zu*-1pDtd5iKiPWudj4bArB)OW6=+A!^h!L5|n^<{=BmjsO(L-E7A^8 zX0EM^JyJ7r9t`Bb8IdtL@!T2^l`DTdgD}OvKcotB-=o%MVM}X2J(7YF?vY5uYG{IX z+J*2K9|Zh!3m1{;s44v4E|)Qz58TvZhf#JOisJNZ(RT%1*w=#bf1~zeuaNd)#PonM zUzZv>;n%brJ&Y~TMVnp`J8-i@m)1gZ-28}?KHjxrblQSe0~CD<5Z%_!q-csaeD-43 zfnM_dR55R%dHLDp>a*l};c}q+{4%xMVW-*4Lm6t6!p{7A{;n&}c12|6Rg*9BAB#!h(>dDSNB8*Sm*DI5iRuH0|JYe4rH_|ddDKl&Oz%wdp z&S*sH8igl(Ygeu~4qO!(U*a%Yx|Fyh>zVeFx;n-#K`jA|1hKbtma1Io$@p*Mp<3s1 zq;9j^I65T&(B>|d9Hza_h*3Dh>QVHdiyNyYN*&WB~c`%f|}zN=^}uV4r^=89gAri^HhLEMk9n-F>8^Y!U(9gV|uA< z7HIMs7VqVH0jg`&OMFcL3V1)sjbcv?$*na1*%hLTEK)KR+OOu~(i3chX`vEiFh44_ zZc|J?%n`8)+S)r|fSN6Y=liB;TGF32n|$6|p^n7^T1uUI4i>=wW|%TKQ94aMQnwVC zI!h945lsIBm6D*`)}4Jj<(ITK%0H-<#pC^CtZ%R!b9?<-&xcyZH|^}%&f*lNgIQw+ zebjdzAxZt6Ny*nPf0dH&VwB@!LpoaHwth}2k(YBVQDP9~9ezC_{t)ubdpGtLJnHqH(u*V)0M zo2d2-S_=2OM@RrgV4KoL7>-H`FLV`NyS3mKa?`mFIz=JVX{VD0?->}xRKraivuYKj|1-)fK%aeB&{Y0i1!G^%gc&?k-UFKxj^TYK zspR2SiYhkFC_e9=vCZQ+^1^E(Va-j8pV4`^Mmghp+m(Oo856(E@Yn3D`!_R`O^V-8 zZ$b9hp%VS!6*?2IlUEZ>Ex5++#p^5N@k#4muZGjo@!vXPaoN25;R`ug&76q3=4K8u@QRG_wuh=gwxdJ&5ue~G@$}8Bu$61B3=mU*? zV*)%KWRRjFr~7ry3??U;qj8_r@!mtZ9}VdPZ?1(|QdI$m82Pj%OW zvFOH4l+QLIkz7Uh4g45|dzQiau0^$-?YHfgk&cwTW!RGK z*94hc7IKetO;yQ8YSeRTcKD@cew{nX_A|+^At})yFnyCi`v+Rgc;f#B^C*Mx9n$kF zX{_R!;YGO_IYViT-vCa5y-7@{M1hUw40sWlmZ+{-0I)4%#HT(S<~l9)09uIIq#BM~ ze{v&VjfGhkhQpZs&@YLWs3o6o%y-p;@yA26<)-&mWAcpS& z!#Ud90L6d*w4$)>0XQ45>3E`h4Q)_;G@mV_^2rm3afMch){mbZ{8gM8(WFq-U*g#I zK(nQwuTY;~^^@1B)@b5td>-`Ha^$a~K-+e5WZ?FdW;8{Q?cyzMTzoRH&8nz3R;LqP z*ZWj@kfEr<14Rxe-*LO^F&5mTcn<*qP%ogWs|OBeH*GKPqHp_4;TWdv+EW_CCwJAg z0m?yQ<0U@THaVX{lmRh(!HpH4MDq9V$A%tsu0HB{66FsE#zXP&uD%Q^IRr%QC+(k z_%r@K7NtjrhoTx98tq}9OpEV5GYJ_F+Ve5{q<5qIGB**jt6Ul56unJ|B67(xnTVe= zexB-Lx$y<-o)Z9xsB^vp?)f6NlOh(Py}k3G$ox&GyaM$A8ZF?`Km0HsN8Iii_163O z%Llwb>7VW&?0-YL_Yk6-y-tKsoYQtzy<$iTFgYwCn%w{Ks+}L#IL+*~cP2mlLZim2Y|+YSm0vckgTWo;NJf{6YE*%x%D& zg_rv~a^+|@`;pORg^vgGxV(5>r51o0iC1+Aa57WH1LL5_LM1}{nTh(MpwWYw*QLgz zT<>4TUd8~UM@}mUH6i3MP>T8F4`GT6A6ICJC_;e5DyDN^hV98J_+4j)>(*gaxbunM zVn%rnUr||MTwn)|oAxv^1aeDvoD1Fje?hBk!ZJ;=K!c(dE0U=A=63Nt_{2q-t;g;w zN9)t@;LC~n#E|v-MPI%_o6eGEnI8Ue0>KnD{sj!6Kl*o8MUy(;Jd(2+cQ`2j^J8T=f+&@tp@;DxugNc~l zcqmLQaIqvIJ`MLjw6`>*$d3?u84l877dp>_gAv-rls#_p%@7qr^ioXRlgu=TUf&F% zk@CzX`ArwSe>c$Y_M0o}b|2=#1!Dl? ztGXEA>9}N}Qo;CrZDS6LFM6?9+|lNdoSbEX-^Ws;=dq!Yy}B)sY9@f$3IBVV%T@}+ z_02e{raDRs1sw!${b)4#l*q2_soi)czx-D3kNL7SoMLdlfU)L#Nkb_UL}|%$xeinL z*jKrPmaD+g8}=vSh1kGuxo9oAvWeKpHxw4R^l{B(V}(QX)63Z#U}p{s7<~kXjPBb$ z$5{0ySy^8^UmHtUbI<9WYH~b!HvASf@8vqR#FzIvz0_Lrz&x-uQ*wqh4J{7b=l37iHk}KxYolTc}gD_f@5M%ainn`ZR#bx?+;+hCU6`Z19w#^f;%%}SO6MI z^pAmF!6NYLsnw-Vf(gp;#*z*lZbv&EY{M_+t_4TO1nwvy8BU{r2@dVC{kwYc8nDm1 zm0#0KZg*V`XJmCwEX3&%!jK^A8;UFIgPF{@_q&I4cX_k|CWyf%X2!o=eo@I^(r+Uj2_UG-+$z`TNJWDqj@=zpw$ zNl=Z~jH3jetv4Fyn|v>4sgd;gyMG~`j6Pr>8)ow+H29G|%kQhxL-^%5OaxR`TJm71 z#O%zya{+0BTz75(){nOoMdb-TKcQVBN6IB!hF}_}BnBeHTt8Q8PqTUoB2-bjX?5)c zs^Gj&&Ua0D_UhE4M%Ij#z?7%+^vK(ujF|5Q4~2D_N?oOk@(ZoP5slJ2hjBnIW))5z zk1~3Q!t4InQ~1f?L|AgxBy&0w<1b*XIYk(tSosm7*))Lktt@MmI{Mwt< z_hw6X-OKj2N-h0y!i@p>m#NibKp1@W3A!6ujd%2x38oZDKvrJzr>N-ew*}~ZUL)cA zY(J~b*8xyMFMm`URzTVRJ$Fk<&hlam(P7ir#Is?y2^rSMEMx^IlcAUJLI8#OSE5thbAGK z|COZZmJycH1+ZVXQgT8dwA0n5b8vwd??@&&dimjt&rB}cFKkiMSWL2Gjj?j)H%;9S znPabREkh?oHCqaw3R}^MaocAdmH?>v1I)~v>+$_yv<0y{T#nxg%=3MJOtjQe9ddiv z7&E{8UHFs9db~WAUlj{Nl+atPBV@==pXhl1VK}7|;%o)gw~Bg{s`i)#wa88jNo*12 z&V`b{?rvV>lA!u0vO5R5YeNT9%S+~&%fv#xzy^@wKdO4-8{7RYms(hws8my zW8w(#s;{WEv@Q0F<%y1!F=+2lZ}&R2I!@n#BNu&6cs9K547X0*)rJSryn6lB7y<9N9@Vi}Fqy%>i+uT^%m}m2c8M^Y5;F6I zE@99{y621=E$4^Ic=C00?i%AkNHwXibKvrko7F=@F;l5!=WXVcxZ(2Xjk}(2@4)sD zboCK3SmLOFbUM>@e2*#nxo0n^@$8!+sGSHkDvhd7GAE=PB8omLS*5bOIECJOE*&dC zxoo&Hf5}CIKYP;4#Sx-Di}4_U4O?=ac5#zSVi_0@B(5s=nHU2z-lXI4sP!VL>w`_MTI2d|2tbO5RXQ#jdK%5i3jiKrtVdJ+PhMJQoD5x5Q!tqcP_Q>juyhrKinqTe_Cv-S$E~c6aDt^T7Vq))#Bs?gWpwE z_&eP_X$NjNcN-=Ii<=poyfSuB&#uZ{WkbHb|6Xy{%5Q7p4(AB0B+V;cV5(QQyDoYZ z6VQ>LlKiN)4GXS}>4vNW3<0z6uxJ5R_d6C-Gs&B;>5J)C<%({_%-|oHX3un^ri7kB zihEEP3BrUpnHFN%ej!qOMVb%n&{%f{eh;lkr+QO_J$Zz#DWp~M4`Pw9*efoBMmCCq zu-6>0RycSkwoJAiv$N1Jk9(ym9NL>({wh^=+xH!h}EZUb0LdtvuiLPdKd%mG-4i16||CSK$T= z=JNekVz>4M6RR~55izOsn}l$MdRMoE*}c39!wYwp%n}^$s*fYts0}H0!L!NN2cIqF zJgMpOjAU8^TFhH!AE0c7jHKIJW?Gq}hmJSnOFD?kcAAfDfWpoxh)sf8eq>tZRkYI=sNutk27((+(@EWalB za{8)$+Vm~QRV}j(l$Lz0t}jI|zdTu(3s_cd`DI(-v#xR)!{3Cj81sGucs?f073T*) zi~oOYePvYCTl@CVEg_9Gh|-OKgp`D!#LyDbLy1T?(kUPyt#o&H2na}bcXv1ZH|Lz^ zJ?FzaOVG7sEoSy_?|a{IMa1xhJPj@`RDPJ-C;VEK7eVtZYRmB*_dWWAqn7hSdNr9o z?B~wOEr3fH9VGlN;dVsWJ!WX+iTH42#*1sUaDDdVTWBl|+R3jQfG-ZwOvtnC+!=iz zb^6W{zyS5frO~@WTsr$(_t@#WmermI{Kn1ATs%#(v6wO1?XE%AyZ(qi?XSFHj;3d< z^|grXuU*Q$2*f#BCMMLocK`qUR<(}TMm}Pb65>Nw*fG0)eE9Cc>Z%zqYaMLz(a2e< zG$8esq-Vk(iicw_*epQkaNeaDF6*jLncgo`C`{ZnijttyH&7=WG|}IrW>YKg(1Zyg zzPTWx?%jEPv7N%#5cX+ofqHm&ujvk1uaDoC4=5Zo_j^2g;*dzYY^H)W9XZ!gT_Eg{ zh#ry)vnS;{pDmR%n{m=L)8hvEJN|&@NlIC*H}WxF%ITgewWCE@2$Z6l7Z>}4$+qia zX{&`_S7$TKV3nn&PmyM~(!{*Kx?brI&K&*0!J|T4+iAjM+hMFPj#uTWZ)EV&6K(me z-mM4M7l>?_SX@*S^JIh=U!&D~4;5&+*c)8}mIJrHYaw$&Ks|kg>fuc@yHwPfJL}70 zK`(&n2TGYV3kC_!f88nYef;ZB>aVu)2(qS2jWELa*NA7Y=MKXh7Pj(=>>Uk<-xT)O z5d^^_!UJ`!9NrLCe>K?lu7vNP6dI}%^@dWg+iJAk3p?$a5~27tcfHR7T^{*TbM~*= zn>U)p$uM*h@z&q_9Qe;6ot#fo1V=Y-xO|MhBj0x>Dz-^0uo*eF8|jokFwWBRU|os7OUwut zSmMBe?Dm9|3GXjuPF-Jge^<;u$4a2nf2=9z+;I47c@HI^0q0$1YtCVA(rf^wWA)-~ zg0d2K^{}J2nofxjq2P>b!N;W%`?A~$zb!(VAEPHc zs;JAm6{N)SSs3^BSEmM(G`8(QV@;WQ%f`zWs%Z^{xDn@nK^tRwh1MC9-e$IYkoic_ zKPMw3p8_I+x<@&}*Y{w|I1la?YWcf7IuA{m)>H(w4`Xw|J$*~ZT>+A_SfPCu7>h#w z{dRWbDk5O?$h`AN%}L;WZe3S6;86!`ex#2wjR*7EWHMqYn%$j#AJ84@#|oiJJA(aF zamRJO^X9L)HB>px8!~Fx{509m)Tx{Su`Y;JE`AeEj$sw%KPo9V=@f=9qAKWdAV~Ll zYQp;ZwBTKxb12cs2x6kU^C`lsv*`v|s1!l^NB+C48*le(Evh)5`$bH}~v1QIUbjG`BTd^R|z@?8XRVIGTafVPAZ;Da#m$m3+c`U=u~q zH`OikTg>q*IkiT*3rxlwM@362`wqiD9>(C;oAIMyCm|(3dbQZIVJU}y?Xj^tWrBlfM$?0wpX@3^!)?6r1SfvT4=EdSw{4Ugs-CM zv*(XKygEF~WyE>Q-HZVB1*$lm2%}0!GecEX#~Sm5P99r(!W#7DAae^!=af8 zdJmy0nw4tq5D26+(UL(oA6x@gnw7uB^iK3e6!?X$9Gha#L~wb89}s{v!@T>XErM+K zug@OmjK0kf6CLJ!=dZ&C6Blt3@$vlH$rRiz3kEqxW3+~7$Ev%bxAV>+o5iN~s$OT6 z?1o*J7=$SvJxckBvr8ABx?E`BNUr;UJ+BF|e$!>RW)L%b8jmNmES{KXi$;@IZ z>7yOF))^hg3*)<1{J)DhC(Ot2$tut5m3#D3h(>8<3{`n_dA@1IsLAixCb$*PWT&E! z6xL=Fh4Gi|gjLKOevd1I#AzIN`$=MqH5p@Z5;e*>)Gk)(`n=b@)NeoB@%P8t$I!>u zZO$Nw{h4(uzTSL)(D2x!?vmK$lK;`josfyCy56=unpTw@F$IT?3{XB=lNR%MJ%JS> z;AUaxkgHxsV+NaYq15+Pq{$`!Ynhaj)vL%++z+ZedGE|rhA&kZWju55m6;!|MpyFR zA!>vKN?n{jc%A_#(Ul8*_gec=&U3emV}wsW9+6R#oYG{Ag2sR4>teU{XG0{{DfLFw z2bWdMEnQ647Hq+!{&a}WTJRfYX9n!a9fc9xevi#C891d)N;`|0JwJ*{asT-7JpG5z z(w7x6^|*j~%VpMOT};8v)Au&a7?S3ttbf-EpT347O4rDxyQegCdkv#8g^Z;LsJ=+c-v}Ioz8u{w-*cERqbh0id8!MOI#<)hrXA};OM<8 z#s2l62h*GAb1zNEW669TyO+#Yn&3)w&%3H0Fa`hc&?j@2XTr)PO|p^Zq`EBGs&31B z6ukB<2xQl&_ShX90x`MH{Ko>c7eiXH`ulfJwU&Q&(EEtm{`Oz{TC`vxYP=b4x zPKnVzbR_d=J$aD3Ba+1D=F@86KQk*?9C*|V9=b^1@t^qg*Wo)QKtJEAZeMCK+EY%5 zty9(FwIy}_NOrV27YUVF;cp%Bp?Aar!{s|?#wu`4Z@FB1PrHw4Uk`h(plfFc#SbwEW|{P0Tj95)^x#WORZTAIGkowA@pU#^svSBde_{&MiNQqRT+cRN==FE zk0+gZ!j!eO8E|E@7EkixenA8Eg80u*CCp$vT!;l(?k@CbS6t?g1@`FYq`xZ+65tRvD!BN zV^gy+oJY}*{s6(z!U&^Z;lj8;=^hahl6a|bQm+q}UZMzTCb(eN>BM{)77g*_SNGSl zdFd_vqU^51{Aa#KpfCj7zxXgU>y}yja~YwtoH#p$8|k0j=TGuDNz6O5)WCUH!{p&| zhxRJ0pIxl?cP%Uvh3g%wqUEA9Cnj{rZObleo=2mFlmfv7{=kQZBj@Ko>vuse$WfY1%9npC0-4GWT&4PoP+$E?kG8j4@bA1usXW&z zjgQGpl-Pez5x@KT#)w@Y#ydtaLLpB&9YZ9#-vUFwsPXBOn)Ju7SvGy%mZ+@)xK(E3 zqN8PQ@ET@&@BM|>-(_wlvIa8Hib_|Sl&f?1aLbG3NtKNj-JXn`>sgd6I&5vs9kuOY zqW*PblO2yj;YmtDO6a6Nm=7Q)-f#tUE4=hN*1pYab-Gd~vGcEou^atr)WcCeLXz8* zLa4kE4j_iabhGYfTnnkexjJ_Jhj|ZGN`$ss@f~73^8E4JS5B))=`jVO&U>xiSA3z_ zQ|C{(hNmXkMjNfFf$zl1nIY$7_jbh#)=%3nOzo8T*q!%j-7&*aUmkqN?n-a|dCh*X4|!%C*IU z>}qCG^e*c<&~D4^fMC+h_xGI#J1S%&X<6qQt?8|wN4@68xPrFNSuy3I3UUzhPtfIJ z{#~U)LsM$}LU9_hE=_|VKdinAOf|sEG#;0R44>X)(o#m`{R_aJ_VWCr;`}lM-dZP* zJ-#Rc!C93)@=B030wVT^@80IBy7Kr1mhJ_0`WlPabtjuA<#XoFs8tikgI7PAC@(zj zv4MqRu8wu5i$WWK+sW=rXAE3Tp3|NbH7U$+J09Natt^GdzE4hCFgl#?)xATc@wl@* z3qS7nKdUK%f2R8}b0{1i-IP?!qlTiz`9*4EY?baMUhJ4cZ&C@!|f?h^<+jiFc89^W+B(d@=Mue6o6)#WtDyysb8M`7! zdFtWWVSId7Tm40)8k@+VGZI=3PmC|7YXbK2N1mb`p2~Mjd*cq3XtZBL54SP zqT&Fn_qfjjc*KSYbe}nEHL{bu=p}DjOz=>{Aw=@bOwkUTgEpAfoES`g`w=YgR>Xo6 zunL;)c)aD-iTe*G44R$Rsmp&*y5+f0H&qrcST#^S=XN^}Hf=aDK%KoKx^O=?U-+gB zd=zqC@N!YR=5_k10U&-<|Esd;uYD?fj=dJed>+a5KxT#0X?e2Zb*rH8l((f|dTo;q z&frMv!!{*Qzbzp|q|SdJ*WHN}8=LP)7HvC%sgE@Xe8E$0^THgV5buaUXupO4ic(D(0!qOwuTs=04({Mc#@ObTLc^HcKcm%A z6`&|f{gsQ{+h6puIc(Bx;aB6)(cRh9L?$RT%C-yI4Hl%J>RFUbuPGR)fAng3uGlab z^oS(?0=uqwJ3-`O_pu-Reu_D3&sMD0vT|Z+S*b>Hw~b|bH$@-CXUJ(+weHE)k9c>xA2?k*@5~M|Qn}1tA*m1jtP({H zxu0kE-5o};4eu;e38^JcqkrTj^>;O!?y+aDZmXEo1^L$ktY3n1csWF(#n{p}~Ii!!pZ!f@(6knQ=-+gE?^Lp$8y62#0(14OE^KEjj! z-8|Tz(Fx9P*^{;4u)=cHv>c1v;9mW`Od}gx8v5mf{l`XMiqK{jeBD+*_c*4l)-_O+ zcCu*BFH>KH`oe2CrZ(hOvsVU9E+D;mZZ4meRh?E>wqPr z+?h~t)fa90$41W(UM*KNOPiI%?+wrCRVR-1drUY&ctTzR2L$O>sns0{o&I&4?Le;RaSh+lZ# z&#GXtLjk~a_qoH%I7?Dv2i?{2v|@9CmsVC5%b&q);W@jeq};ZY{-#a!2F>fS$&tqJD6{_~r<`wZ>LhVA=piuMW{%mMvdR0w${(~(4edDCh zx{lIL!M6a@Cl8O=XO*%Bx5$dz3-)nI&$M24LqeUK>#jvL^4$|s0$E6^(Nmvvd?;3L z9!;)EDnSGMGxP=QH!}nn*M}9@n`h2Lfa%D$ZeIbT9_FavzX^OY66)O1qJ$4G*Z%4Ab8=h8!EAhDk zk~$CSw*FNpnb)vF!iDY1H(U0P_sAB&a-6w9%l(jFZn)F^RQ%*g72bOj$}f#y)>AKc zt&uxA-t?MRvk*{BoP{TaC$|y4+L=Rx95fu1FP6_T6nfoE2_Rb4kpQJwA*S z4u3gT4!+rH?}f5J*EkiFK{u0l;npA&h5KL);o-7u*BNRCl;#uU0sdm`#}O+`wkv#%o8wy~V^ zy1bkuF{44h;?i=m~oYlUU!;GI9=H+U|B=v?%nkUX(Z>)rwzsYdA`vwaJx3TnngAfx>rRJGWJ#%Gtq^$Rzdjp zO~=hyRV`ngqJH_*_#?q0{?e9Jt2{WnJeHk2X#Gu}JpsnLrd*!zT?n?wttD|ha!3ez zNSM<_Z)m{F(9@v6fXtHcn;qeq+Zo>Fug^*e2Dmxqlp6zLWL}ZG7H~7i)5_o|;iTq( zu6nN`*Yc>OJf>1)*>+#ur_X&HF3U&faTd~TU<^^cRyU%I?RxdXDTGvLZ8XI0Bm{%q`AFkyq|FI)z^iF<>j0s; zU993n`Gg0O6XasAiOlkRKD2~3tgX=czEqEMb-oIYvijrF{@S63>TfM%i$|51)TR1k zckaqjL@!NPo?x6hvqkzKH?SoX09D>CqB-}T5`&Agw;$-M`r{%xuEtN7wVUq5iT4FP zRL+HIXv#Fxqdm2bd!|>Bhzc)F;ehdi#>Hfof~Yw&Dg^b)@DHrOQtrw( z=^-*kxDEbLD$7mLZ}L(9N+9)jsYRO1EErRY;eRrW%OXFV?ociRGz}h6hvcZ;z7^4)WPmJYJBxIjM2 za!6U-sYk5Cgg0-#$H%lltdb(YDA8#cjL#2#Nb(zFAUab^cST+(!UGi}Bf(NGGM|UJNPc`l`Aeb3X!2H6MTlrty>O z%N{M6Nwh}O14NI-x+^n?@X9~KZxz~k#A}DCs1$#SLQE}H zIbJYRN5Q!^TG$OrSv=NZD^wXw_>gD{2JyOMxv6<%;d!G*yt2N7H-{5g20THfUW2Kv zOwpM|{+c13IR?x%S9&`)XKaIKXva|DVcRuvjr&qA1XKK~xp+&N`!q^8h7@g^BkhS= zozBeqO}lc}&E*4;J1WlIBx2$FTVf&cdk$V_?5^yL{tC3f7gvvxwLT7q?cX9#X@%!r zO@wqRg1q)AQ`pt5W{aisjqt*Za;L17E;nE3UmAg*#VMVnn9_s60=c>= zGOr|CZF&UW>tcfxgA(v;x6#F8W-bY32%B#Taq>Xj{_u(@e22QRr!qKQ0ETV8{c8KT zPH!h;PU7#96cC^EW}k01&YmU!jI59IJ`+QmS}PT*Q6`IXyOAI$DF+<(~+3tmYm4`-V6cka#KAc^zMY#n94+`8RI0Y>GeQ4j2;KN~1l*MsHh*h7^p znMAs~+mcqoX5)`e3ic$=1I=+951Meg5WmS6rLB^syjrPE*$!7568RmZHFTZqj@e*- zHCR(eDs4EbET3 z8jjm0&hnbzSPI^qYlM0E^9l$CNZGU#h8v+b8y85i*;CQGXBxxe_bA#8T<-Q^Od z1vejst)`uib4H=YA>f_Nw`b|-0oqJoj+D%P48M`PYEG*9c}#BYm;G*S!eK5hvoj&h zOq9{+rv7>1v`X)>`Q^~Jz1{GaUHf@~zbOEoIUv&uI3K_x+lR@Q{~Z6UStVyw_{TI3 ze}vo|&hkd>O}qX(>Q@)uI0d%oOu@3?P9TP|_9jTF;si<9w3&o=#!Jqs^5PD9dSg@Y zb`HH%W!|@LJCv?|bxWLM(5*ZWMUsf5AW=eFD|n+R9eUj6QbVh~Hpf|qB2P=~D4 z)w=sE%3g`bYheD~=PX?Joy{bK%6`x1q$^z9>F&Am@H%FA_4U)rea_qF4K6lD;^6H$ z;D8bo>fRzDG4ibOo1Ay&j7L}BZ>+quj=_mfb2k}Oe7RfRtG3G zRz`BQd`g+}h0u|3)oLDWza{_jCFV?XP6{&NVUIEAHt^==q;Whqe*Sl2C64fI$K_Yj z-EIP0T%K=h#n{( z9x9_`Mo{@dVTXxr-#X7A4+`|3f}%rlf! z%AE**uD@1+c#>MS_Vsv#jSRVAj3sHEE%=L|a0rC_PAROYy0ywReTn&ws$>BDIyIsF74&P1n*n-wma&V`F{~qG}kc zyq9NkFW4uxGFSJ8jSP}LuNz(nzLH{Zi4P4h5Xy(vLOtnT?e4_A5alA#W43ZFCZz0y zLWy}$LyS4$`x{rpxh>q{BqShAAd8WI@EtvTZ5^M_3@ddDAihUTpd@6eeoJxR;6*2X z(drv5X*()*>_MTumy!>O3~``nVxzcR)PMq=Ifc0@6e3E_p6uitBMd>>i><(5T#O?= zLU4;U{&?F_diM-?apAnnPbx&h_u?m~-WjDd`o~Spv=-HOOUTwl-*)XpGre!t zsMQD5ZjU2`jN|%a7S!8SWNE=F@sQ9MKgm3N;YH~M3|$Bi1|B*qs2!FlyyS2tY)ieI zx;t-}v?2YFsb`#v{0`6RNaEX=mL?-*= zC@FvD)o^eXcTuSaW}k?vMN!th9-a_R{PpqW7suR_)^`I8)TCbragWpJ^WWTTeEFwU z8~ACp;y3Q9LdC8Mv7L7;8^RmJ4d84>K>F^>fOf-qbQD~zte0XIeEe_@P@*O+XwB9F zfE%8i5Lj`fHcJA0Bq9qQ62#*AHYq@go4dV3jh!3uW`$u5na4x;;HanL++)Xp{tJoF zGJHs~4cv|Uk2K4hDQk35ssPLJ8NWW;d2Wsx(l9EgbvI%aEvzamA))4sSYw3fM@l+c zYNM_Nx;Lo62P|MY@yVluvJ^PTuZ-AMhu--J&D#2fy|sPNJs}Y4+(~n(yU%$&aCgU5 za{BiCyJlGCq~Mwn$%Kgv>AA=jTg`r;iQ5aurma|ciD9ybK7jJTa?xG~iAXheo47&k zIR^C)Gg3Mkv8PdS7lN-rYh-r>J6M6ajmU3An9>t5+f4K^WaY4|IrYGlLk5lxDctq` zGjqbI>Z)o?m6|o?yoejy%*8L`nX4Vu9SXUG__q*sp*)iHo$+wrBwV!)DbSqs`x^^J zJE@DF1;y(6h7KL3LW66fc@-h#YV>!@H^4NA3sf0mJ*!gC=iJ6mk9Q3126Aw8xG_V- zex!d25bvpM+i>C}fC@AQwHYX&1d=UYRN97&)(7pai-bE$y*e-vNvxK^Lj1{7Av#y- z^r`lG55c&%^|$=J#L6wvH|D1{t&v10S&{dJ^I`i_z9F}t_cyZ@Mh?j?PmuSVkWh`83VX=-sw)eh7_~7y0DD0O zU~K*DSSsc|vFPk#*1=4ckNs-JHpB&2@$>>6Z2WfDYwP~SZo#p)Hw8HvDZ;*VKa5U9 zqS0AG|AfW<$cVy;M3mouql5MemXb2=HYN4yy56r{xM_n?XO5oYQ(#XIKEm! z!d|p1!^AROkv{dwV3+aT)-T`@PFbc+R5R$XzyHN%;QpG}<@DFblch%hZ>CL71dNV( z@MT2Nibr4mJ-=0Ci7sG=y(0mW=iWT1oO5%WXcAd?!l=<$E`0+LV+e2|)6IiqOrF+| zfWrWOs-e=7Uo|}EqEjR|Y5!V#lRVx}9Wy|ZfsfmEq=Y{Dm4oYj6%N4OLb$iDB~Sr9 zJ1UR+I@xw9u$imhkSRIYnei*Hno5@9DLE&0!k*)!pMWwJ!{(7{zx{q#A)f&M9M9S>zj|pfIQV zgp>u07Fke^RxB?GIaj4SY?nN*nsF9R@%;@w z=BAK1yuj>aI$^rXjM;mj)e_7QmTO${WeshcdBqUwox&DI)x0S0i7$>~$w|Jbol?|{ z44nuzxf4tY-%@mr%^%JUmn;XFe|@pC;XQp!$(7b@O@GZgxR08f3vWKoaU>}*%5jLB z7!W|(a@0TPH}0U|C&?3K;-s_(3yBvqzSg8l@>Kb3O#Nw?*hlgdmHO%3s^B)3?P2us z*mu$dEiqw|_azXZxDUh;zzF~Eg!ke5dn2Y0O|<>$9}#Spz^PMmcgW{-MpvPVg01RN zmRNvJHv5$69~I(W6MTUpqE65UAqlbd&c^9Gx!N}7+2$LdF|y`~*jvvv2jx@LI*yu|f@+>M8idH;#5L&>)Q z^D{yk62n!L#|mRG4VQ*S`3r7Fq}H#3MBmYaxA2-HuFsZ;D1}OEFaJ^8dI-)heF&tO z^6+DTfY@B%?Kdqy+MZ9@NU-LgC{QOY6d)Z_c-)o`Y$k}77lCclxqR?`fl zaq|?Y07Y+D&saEqpAb>?I>iEClb7>l6()o7`Q-SFo_0A%PYkyA@0X{J`0lSYAkAY< zLLova)gyyO4v8MFXI`Wp-bC&W)*s+NVW@hpa3^T`NI>|QBEN&SHtK$J9~17eqTRzM zgng6~aUy-x&M7wskLQO@G}+{ojqP`Tz^95frgsG;nrQH0IM2;gOk1r zLzsa)*CW;Oqmm*du2GfaeTUlG>{!ha7oK8_7i5eTwf(z$MAOiMx?0b)FmK1}>5}F9 z_g_x(ogfgNDIX!qOA*YODvG$K8T6O887^mUewGbWGyjZ(hZ!za8V zm1vr#oQC|L&RmL5tL{Hrklzs{O92JG4SpDjrpT$4-nISkv8-TK+WtaK?fI_1e-bIc zBtm|4bJ~EE3F%t*3Oif#^6Xd)Z-8_8JlMi$FmQ7ee`s3AJ4Qh?k}kWZOqu#=p8%Z) z@uzEe(+@{~8mdR@=dO)Hk z(STbXh#Qw|4$5!5AKjioKXpB?lNLI}^jqKiazPg6H8!Gj0HHq@!3Q!7V)L-;Wogzq zGEHR+!yNAXB%OLbdylgO)61H|T5M+SV+N4PUB#c(~1POxbq*ur;#e zOXhcRKt*q&>x7NmS(?IpDy%0fpr+yTJs&gPQXJ$tgnww+0p*g&d!`X0rb;CfxyNbS z!*Um^HHQlh#9Dtt*I4C0Q@n@xJsLbJ8&Clb?6aQ?TtGa_LQvP96lJO_R_kqsY=T0G z=HXbN(R5tr0kP*=9O04zRImb{7)rJxqm9IdvecV04Ypm_my98v%$xha29^88 zZw}YxtSAMSUW8CMpjY0XgcI}cy7p`nXz?O|c^_oClkIa4C8OU5l803&0ibF{gxafQ zJIAHdh8E>e6TVgoz+NY$e@7q*JtQ8>DQlgzb>UjrHc zC!6R&<30XN)oSK-L>vd%p@9M;r8n@_ zEVrlpHp*ai9!XGD^rm12$Dn1BLOF#@%@~09*K+QY|Hrk#9pq*}#6cf*!ABIuBYisM z5ce(^JxzyC@u2mWI};JHos!VGLk%P;iogQ2fCYHoW;AD$whKPi3rjntl>0S`^w)eHo1-&UZ_%O%9Hygeeg`KEvPZf|ffAQS4lRPw2oxtGi@+ZqQnR)}! z$6vV3UMQ-GMxEzHl1mF|Pw!Y`6_XtAOGX>niAx7f-*YJ7Jx zl|tpb`}WOSHpr8pIvXy9LYSL`MEhR>ncezo&+Q%5l4d~zAkmg$BNU9O=-{$F<7KHT zPLWLGULYct*FO%>HdVP0dnZ6B_It7l6$)j@d@R;{kZ5p&D2M7*hMnS1*|4s6P4>^w z7bFYZ?*JWz1s0H?6l((yfUAjcZkKj(10tA-%L!diur?>_{W~UGB5d>Ic=+GW~&5A z<4rU0p*ZnW$8vG z(a#Kq=>ZH>(IE)b8yQOsO{@ze7#5E#&!QctbA1_jZHN||)BwLPY#&$w_isFwM=2r3 z30F%ltl`&s|LtX4m#1ROXWm=}-k?wVEs39A2^B$!3t|*kYhkUW0J5UV(X9D&Wi4Y} zv_`hd_&eGZ|72uxzAaa}h5sZ+oRd&N7OZ3O*TnEOWk|vJEe05WV;qh3O0%d3{XEx& zXBpGxETAJ%Q!B{a+8=07k+>KWQRUd$sz>r@(K?6?RO>T=RT|U8!~Qx1RBs!FRX!!) zMC~%2Aj0FF)!)IFtGv91BaTY(w*9Fn6DYc=jmlEAl#K%~mVEO~=LrSUS4%sQJz8s> z)?xsp_~#XYn}Uss+~Y6h3laM{6&m>F@B!ms%QDeeMo$Yna8V52Zi zyw2aBQ7WY$OJpK5DggT>hDLfsUkWc9H{)g7fgKAx9g^l*R`TRlswBoAY=6*JAdxfS zUcB#9SDcml--iRucA|oU=HIAa-xw=@I&{<*`&m(8zsb+p3%ojqz2br#Ckb2jDl`kv zmw%ddjMB}5!Gym~u%%$n2vs))f{t@dUc36I>sBlEZ@E!|jk^@%r%E8kj+UoaaXn(_ zV3i{sB5du8Ouv7kQn7{1b+$IlVLy|DlST^^cC8;!FHjZ+6EN#8URTydx`Cs@mjbcx z>x+x*!0WVKMhP|S^nwJ-0{?(azK4b{>95+|Hlsb30?v4_H**jTHT>3;BV>$3ZrA?G zFN@4^eRjy2-ir=%qsohZ$xL}iupBKTX@8|bu79&0Z2ifY_TSVxlN0cX$`2}47!#fz zUpGW2r=kIxR2A;G90$~)J>sLh3m#y*1|va=$ep!MYt|}g(}`YV;iHf-U4DNuLlOm5 zc;XLSUTO!!8spud+XLxDI#rN;B&mk6$T_*|4os%$6myxP&M|vAymC`a18aVahp*jz zVI;5D`&ISdEt?t%avD^>B}ol?3W+pO6fjWgtm*{@K$7k7aGhq(77}T9+4eK8G%~QTu#? zMb(5|8P}TeCJT#RK_GGp_Wh}s450ihVfTfW2L7Qp=`@rl=y%v9A`&iPe1xzqJ#?|| zCx(jp^VRT4TPlCh(ia>O!v+5)m(tQ_9U>5-s-Ju`U3i5~_i!&@^X|uFlK+dipf&AT zuMU7U1m)>$kK<1?^~yD+ruBJ35|vqZpaq(0#HX5iBUZ-qf7C1<6G%Z#nEH5wG+)kD zVEWdQSn%XhX=7NaJ?~5D3v@H(VTY9~Fw9$*zayS5s=tg@R`!Yt3DjRqpvLyFZ%9xmEYM32gpgL;L^)bMG-wC z5TlBcCH9lFb^S^F!A%b5t>KT*BIyt|?GRn*fzQZa6Ed540{qpX|KLSHmG}GFa58DG zb2wxahX^4p>H&7j&JIhXZ=ewL;%qPyP_!$Xxni{Rkk=Z*z$(VAuD~N^QL`D_kvmf< zWY;W^y_OKod-0yOkyQ}5brlo6bkN%4_+xTvSFY1y(M#04@cIsWQA7v9%+Pe{4Dj7K zoV)omW7A-hjK!Pu*Hk6@?#)rybsX9>@k@Vwtbn5XW%`*q_o~I)S4}=YBf6Swn>@Rd z>doTt@e;cICFwngTN>$cO0j=_tgJQVjFYI%cFuXGkOl7v=@a-&(P-O;UY79h>DUwiSMbH(5E`{HtCkgdi^DjFK^v1ZlgTb+0<6tKAd&Ir-&HEb+P=n98;F%btNrW`BJZ_UOwX-bi2Cj|AT&KydnJW z-tNP9)7)IO>g+)%?6rW8#%K_`LF<7jECDUX+a-HfBcsv6k)xr7g?x!vchx0GT-ttbL1%wM|= zO>iEzJ{8Bolk(55AL5q=vZIT$BYOI0FfeKjp#5+E-4i3(U}cggEgedwts2g%6pK3* zL5wkHj+xAUbWonv$0h!1r@Y%Q9XZ{V_Q_ldpK9sd+MvXz zAN9CXl&RlBjXWS{l56{8WHECBL)N67BoH8K|cNVYIxnHBgQA7Ck z*ns|K@%#*7VyUqz^!VRMiOVCv6^(P8RZ%*V^G6m~|7mzEnf`KT%$%d9rY+UJtp`>f z3VscLcFH~tf6FU`tvW$5Dw#rn7#1x4&^^aN?ka~u>=^d0*ipNJ*rdiz<(5=Q(zB9+ zK&p&o$Gi>Ps1g$P52Pp+l&sq&T)JVSzDTTRL6~r&@(dhjS6m?Bl)4M$}6m7bj>Rq$t%b{+1uWmvqHn|N{7s7D+Q~7Z;-w$ z<2{E%erxtq(mf6un*9f@?d%TL>NO6nV}}YxVy9ga(@i?hEKD*zJ8fZwbcM|7YG^G$cQi9%e4 zAcrwG7+&;gbn`%7e>0m>0K!)~wA@@VQ%}Fcfozcwy?s1UMhkHffb73{Ui}>M@+5-~ z$|Lok)1CwLM&+QSO`{7jbZ{jbCuj{kVtONc_4a_Y5>E%E?BE0(jA!ieOz6sQt<+df zWV0*gt|u`{!+r0jRQ@|44U0ON8c?eb@G}` z(@>JPINU)qs7gtGXy*mD%6zVRRcm(d*__lTuL5V#BpMGb(lkDIks8&N*>lX6oIZQP z;B69mr>T-p@$)_sRswZx+WsbGA%p!L`0CJ3XtF$%2t^+Nr6`q@|301pz>jr-S_xsV znK_!l`ktcUhy|z~#lb#^#E#E=6FI+cXz_4^RVWHU7B(`0H@=BFK#H{ z9NXz&kULp=@QL{t@X9PLnoCM~72u*P=1lyqa5}|;5+We3z@6d-l$Ia#4a`o44C*Txokfu_#x>s7a7ZF1Y$}IcGkBLz(;r+x zc7F@v(ahCHB4NY(3TA6ecg zXBi(2XT=p~;|2Y&oD=?vPicIH{3DmN(uz`wGYKoGyYvplSq5UQJ>_LxZ>fv?pADB; zY6_@=C?Gj`UsEK$r4iWAL`|Is*Wx;fo|GY20z%!cDqp!R^NU-@DYQdUU!7nQC~&S!-H(|5j!DYZ@(3WT_8ZDKh!sOt$zjkC>F6hAnrohYEM_q}=`*6=F-dmjosS z{6_OSa>M_*3=~y)LzZSf4{J0aq}lH|1kDylM(w8eunhmX%XR=71(Qy9Q;+IbHHYd{ zMn?mZ>^JSd^smNj`#GaIiW_idLI zaHOJIF;O)8-{%D|T^K+;+Uexyu0^|9RmB_f=(F*)l>+Rr^C|}%Dex_gJxhzw4B;4e zD)~+)zqbqmki#}l$)MJdAcuRNmm&_KqFATW5tdDN2utJ--n}jXN(!RH&?26RZ~v^)1Yp=Vt@$96+BIC7az1(T2qB(emvhPg6aIb(D6$&xO$(<=h6;d@-c=e7}cE- z@3XV*r)h@v2Jd#}ftbiwzm*|dXIwSD3Hi<}&pPmj_yg|fB%Df@If0a|K?L280_Yds zJ5hpg4x9mxC%1P)X6A}KQ!vqyKs(YB7mK>X8+N(KQV~`5CF2K^@%O#LIpsniPjTEh z7XTA-W#xCT_PDZW-Zt*YYIdIjhd6DI#qQkoe}`+S&-<8+wq6#3v)_RKE1t0)?+*+Z z<7I}skP+baRHhdd&*XsKR<|<&5^6LrUwOgQS6vqP=uuAea&#~6ptPFl_|%Ne`cK#G zTW5|rL+OJPJR^6Z0Na>7bo|UiCkqI@XeB4D6N;eVL})o8OM}QNS4-n)wf+0oe4Glr z;8-msp^#k)>oa?g%>Nk$fh&i*ca(`8hRNG1UcfUN(+Aos5h>$RriVCFh;}Ke7z^SEFbq7-a8|wyDa6;kJ(lV+# zKfIw;r;>@DKIQ!sP^3DOjc(>V%etq`)N=-8jnl46!=bAL8su_!XLY09HJWy4A!|@U zZuAgF+0#i6zG=<65|PX;^OVWXAIa0YpkrlKax`PN#8d4!sUXrn5tbY<^9uwfr&b^w zY2td>quY@dE}ZM)!A;tZM5OJ>=DLWnv9XbTxUm!5xvYNw$3T5{xAO~G>8NC|cv_1o z{_gR)B=YEeKKD}W$5W>~%kcl{pM&c?6GyVkPu$<{srB)-mvp+j0Zg=_P(ee!*}C=< zql$8#n@)Ihc0y0-V;z?1?iw-m(dgpTuCMt~N8+h1o_;{j^^~u(J8N`zFBrx|W!zS{ zrn+aZ{&FG3eN%u}Al>fQw<#@~hjc&GVxzXQK#To^#o6|NR^Fk=8)iTxRnxx6*I7-?DsYOjDZJ z=-N?IXj-z=U7XIIGcu+C`dhPB*t$%Y+b5TvW5#wLrhOps3EcgSZ(J7n zqnFRe?cEeCU4+2hWmKz1Jeu}Oh3Gfy@Y+L)4?2R`Rw~f;IFsZ+^P+~z1$&Jc4u?JM zeDxCe-rioMbIWPqnojBQa<6W`QS(s+>=K0fuRhI_dDj?XX-vNGT~Hor{zP1q2kNyFsKuDakuO&+nYG&wZYI*FSFD zvex?Em~+fA#(du^dSU9Z73sa0(%(+jp8Z-#bi2#;j{stJcsjPf+hS;hYFWOQ8hoop z$;g>sov=un?oQ6U$xla2iRPN68np;*qY8KJ66)op$X>^E&f6o`aW4qzu|VhRu5%uo z??|2SRP3Xg26^SSx9jgRb&}C(1yx#kYBF`-L8BF(?$5_!W6ik{s~MH<3Q)Tu-Mjfo z-FKR(?oThOxPL6Bsbx2BRrS}cs6RHN zGAWEPwOh*``+e`eCO>%h;GM+pA6|-ziqCI8j(;y1b}inftGk=a`_P_*jO@6s+qMiZ zYe>N_X@>=92MH(##n+r9~tngMmXi;=~x)5G0XX&3GC zZwfq12>C(=99G8jFTK4Tzk5aQ=p4+4-ITl1#*fSurptwNs5I2!mH;o{#h0LVZ zL{Ys~B=x@<2%%Euj~?gh#%uXEh$65!uU{l%!VUUv_dYwzZ9G2Ubwa<1yNVGBS~%9k z!rESOL0RIruBd|8Ch_1Gcn>@ozC+-YA}r&ge8vp2K6*^m=sY>22(rGG-;+-iEp zoAlb%s{TGAXCYacd79i$d=pblcwz){`T%3_Mbn0 zgx4~2bOQmk@$z0v&~?PoX6%>`h@RRxiqPU~lHp$W`9X|vfg%E{_1urXzDAP!+SD{P z?UZYy8TEg07vZ1ynVc;AfIN#BqOY73FpZDWn-?X@tyEB6^yH1|II4z&8og6ft{Xz< zHJVD-D2CQve0CqPR5Wla}XuT2IFL*19OSE5T8OSkjbaK@Tb@-z(ehv#E zlMI>vIFeXEkg4VDJsWcAeYTWG)2bx~;Wpjm67!0C<5G92J>93s7iZ(DD?5^X4b8bC zVl^#9bQ##Pl2pB3NCw_5P|W_eP_@5EeM40 z=Kj#{E$;?)xL z&r!+vzRaRaB>V8XpJKtA>_l|xqll18le^ui6-!}x?L$`{;iA8eHI#~lgV-?)Lr9`y z4TJQzJUBA!MORl5J2sZ}G`Iv%h~NU|3l+bY$pLYh&F`yKK6we=^dU$Q z@!M^i=Az$QjnD}ac*O*5Z%l-LhTh#Xr{g`8C>&UMotU_)PAQkf8^@j|?4upmm>2Os z!?FzrjA!1;JS}~lxi?MKoi>>0IyK`hWaGuDu7_D)z`1HW`^~^agMn`ogo!9ocPy#6 zZRc@oI?mo3@#d^nEIU(kM>#=g=td?dM8eWc>V2Nz;3if}CDbLi!bxFy)C1VFOKW zF?^mnGYo_-#xFbby};?wrmiJ_9P^Yn|2!?iruBD z&MWo2Ll|B6cSoS`+$gSKRZnnIM95FFGY?`=9>YHh{@vYM8rjbjPzYU`jdmm)jypf$t_RwgNCY#e6o?T1Ce1oKP>bJn=l8r&4k0Th%M z$f$3&T4Qx}VTNRoe19Br4_obvWYMbIwD9c+sj2rFb*Bz+$j8GYAIYkI#mkqTe^cl)IFdob^WTnL!ysI z#rK@jwx$JDZ#{Om!e)Zko;u_GX9qD^`{dU|RJXG*I&hd<{`2E%etv$d$oYwh*5*iw z0h*V%gi)udvEd+QM7zUw4i~n7*wV*ic(#HL7s6Gno5%{E=i*@vKJqHG;C|lsbH;?_ z!_eU!!L>(balbETEFL{hmp<1YHLO{#8NfDBBX?1y=F|N%U%Tc)&$3$oY;+}d7sgtN z0HJD5y7(vIRt-EQk{dNUmN{RoWT|-2GxPHD9?8k=-~j;%E+x<8w!V(-BD z`2YD7(`$X1((mg;B?fZ?Wrq}gU4dLlV{m)2SK7&Af7vU3qJ&VayTVS#e`%05|jM#4UPdowwc?H!>8B zxGDO;+c8!PTfBBCXm6idz;(CQ;2*%71bu$tqNlq$`Bl5d`bI14o8mwb_t6D?USs5F zKRcPbm06o^P^3Qe!&|HfZm+tbxYfD0yYGRq;9;-vJ}p3f?PUA`uD>>o8w2+i9-;>r z{GE~>{@IV_y)@PPy*)jy<23)+w1IhO35%EGo0-HJ8|PTa7nzHAw_iL!rr2B{^9F`& z3pywH`i#{eUO0b&<~oPLR8nk3H*O|TMEj{Prj@LxI(eLvx|ynFoSC#>5oZ@v;D3lf zW?Xces&h+VFEMD+-)X!ppWHn6DVV*RKLrnxFw0)}zXKlp`Gw0*PHiJ>pUHkOHIn91 zBW`B#IBcmekG7%~@B!A{P9)4rV98kB6E&{C?%7b=ffLBQ5>VNin`orN^U+C8eD0`@ zmB8fT)gJwc;?~q+mT*UYPkLM_qeEzeYO($KJsq{AR-pb+^-yLdC(ZW_J3culT3=sZ z{$9jCzeTiR9;fWt^0z%TFMdxtcb0ILjo|U22R`id=#OMc`WU~3FG}3If@Rr|Sn^vj z?M-7D)Q2P3ZpC?-zkl>NT@Ly^%Wk0N>Ka@Q-@m>34fBemyK8#u91=YL&OkBXp-1xa zRcy5U&X=AI7b;b3L7~g0(|C5YHna|x9sK7NEq(^P`s%jEVV4%&J+ZYU(O7}gy{BDf zl0FWEN4S-MSr1t)Rv^jXe)6`$42#1ZJ}wf7Qy8i_YvBZqwaS05wkBhUA8)@7_kNS&-nv5V}LzG^W%VZAr0fy&Rt!nOcEy(YTS4!F0fSV5kef z2VeipL9=1Qa{k?$4U{Ss*y4doe!t9`7#Lo_OlLfy562>Wwe$3|L|x;x(CjR8h;07I zi8CYwot>TT^RI53u4T(51_d> zK16%>?p;V&n7F(=UTA2j>GAalDK`Cj@|~TXvkf>w=07h?c`>o~UT8(vpuAL7O?_;C z37vrYgRkMBrD$6Ot~2B9OVfdFRMBFes>s-R+ucUGV(6l!7W8Y>D4rGLlMr5b-{soS z$;3O}93!<*^UIn^PMYJAsB*@oa;=w4}NFp==U6I;35^6Ayt4Eu7+$Q# zh+Mx~)vJ>EB7-^QQ(U>IVeU&z%1Ew=_8ps1C{p6YH_s@JH-prtJdzxDsV0l4)^T`x z4LGNQ(ObxR(|{BD#e-0~&+n37(X6l_47y4g1WX>@M73RYot~;HNqZ!9*vdc-0}szo zQ;IX)&6}75ISL8v#99k{H*WIDKf;M5R`y?b89VzwKZb;~szDtR%ly58PT>$bmgyoc zi)V%8TU{X3?puCnTv@Fv0Rw%8+$i@pws&@okPO=s-^rdRedpjvVn4$N?GkH1Q$_)91dpyzJ9ug9%Y$vFu ziWb{9V{)eJizSs-b0`XX1IkC(4886Y6$gDfF6Qw%p!DPO(7sq6ph8W| zuFb++=ea3sSt+U=>MUx0FzbVTF!yWjl)d{T{E37t(r|zoS7kGi0VL>)O|1XyIYOm{ ztbq$WJTEo_&&eYmQj&j|B??#DKIzM8*W^-Up982#F_Cv;v?D?N^5AgoG{ zoO^A=!vh@!N~kCmIDWe%@Jk25KLb1cuaCL8q6g2<(zve{1$2BPuse5->4l)9>u@-p6bEIL<#IweovF62oA~#0P~u=c5+ozG5ivCj0RtXxyA#b7m4566kDZ%tsU`Y$P2*WNly{Fke($== z9{e_kCo|&r>$AwJPW|#|WLcs!cGpVRFQupM)W^lf=RsA#j_<-+en!h-@++oY%s+k` z|C|rPXoI%T7`50vZSCXPrSl8#^64aZJuPJ|pWQOCS6_1q5*KzKGDv#KSI%ZnMtI?K zThO$o)6HbC%63oSX39!hoZgG{KlR2=Ecuio2tBEnlfkj`&sWc@&^PGs;^LH*Z;)qu zL`4c8Y-zKaTD5=!!U8?g2ViUL7L)x6K?=RqZmMJd2p?SQiy_D1WAY zlwKjHFCU< z?Vf}PwN``~o&x@oo*ZF#w@Gf57oHF-6J#rUw zFjW2Eg#9r2s z@-PbqdVXg~4(zUUSoYwXsNw<{Qdi^LdA}-e@y`lL;CtNZPY z@1Jx8{y8j!9~Ck$&@=cD|Kz54r+lO7x5lg-yX^5|7_R%GZfVMWzuk@rf-L10SKEy~ zt7L5c1|P41mHLSpYFjWI?CiI+CpE)~$(c8NeM6Y|cA8NCTnQmxoVd8AH%j`@ZpG{> z6kQ96#G0QUT+z8?^5~^5PS6t<6Uv;kODkB!ZrPvqN8GOjIc$X%2wP!nvAmSBIMsMs zTZSn*wFJadI%oSUrV58MEP8r;DnWMw%KNsT%S<{H_4FcMzQk}|A0=$?ItXepyySeq z)Xc)l3TI<`u20pG1qKFwU)!@7F1*fB`;)%Hc1nB5#DOhennaRH*qdCyZS(KDsH(pF z^5qdDBjbC$I@g~=1qrLm6L_4YU@o{bI(b5Zbt{Y;$zQPsS?1|i#{;5J<8BWVR`Ba(uwzeE+hYR>r4;(Q_ zNl8N@A|!zha9H_}Ko5k$kV$myVWT({{Vx-Ij`!zEn$B90L4k5RvoEBgg1f?QhGsd% zjfS3qLC7}ABrtY%dGx!wnpz+vl^X&AlrTE+y}nS4|Ln`e9w{4mh&@K7s0gz4+g zJyDm+jiaOYx%zkF1PbzYP5}R~nC)T3KM)Y0H$8SqO=eo=u$!VARuq<+Kp*7v~yrAz!WnKK@kRD;!p& zQ$6k@$j?u)&>rz=cV!?tIeC3~I+_6nZnVaMf!BKUc?9KsWMpI;MbthF|VmAZDe!<5l7(~LBGSL1OxjY zU#|yGtUB}SI(_3oB<;Qu1Cf%*q?nihs0As)$nHp0rkwY2TtWwmKNvW<47-^|8d_K^ zUz6_R!zyTp)nMb6l$FK!B$9wIwxIy+*0 z`t|J#o@c|OKDs3%CZ9tH-G96@|Bf({Riq| z-8Bvi+nu-5a{J>2w!}}UD94f2{J`nQEQo1hYHD$xHWGPlLP6Lt`L)>j=*bi3W4;r% z#}XvjPi{>#=hC6=iR=<$&@toidGw$A{Jz%h9xc{FG2XW(p*n^`mDi?q={1!~Ubg6? zoso^f86#Z^qBs#o~-RKgut_5x@f_kEq}T3c=MAqt&izJn5_o#Kat@nD=V|zs&n5l zo^T8;BQec?Zg#FO5?zu8g;_xu5A+kVPrWUTOD@$Z~=&b&~9IV|)3<2dOuqQ~d58awaP z-`{VqJeROX#hNbtt=R&C1y#^p%6Zt!X1qx|pNSP_;mw1_tkvrcw6!UI^rl6zmeecn z2qP2Li25h~o<62@+&>o?Dm?SqXH!(ab(5c)g6_tJ(qdb`BktMxjw)A6Zc)!#{!{0j z^8hob6dsH<_?+a{Qt+u5im1iL8dg0xjnI0SPIq~dJ2txb7tPU1^C$|1snuE_mIJrg^lAs;TKTI@=Vt=NjYn2V zcSaW$797t0EF&5lme$n)&hv6vo2qf{YESl^{O9eKIA&7>N- zM!#>?>6b`DYUrzcrjf+*Bp8pn_4$R1_Os0wsw0OquV2AJQbB{~o)}0d(eK__5(nkx z<+Xf$cMoAym~Gu=8hvWO=VQ}o7!?^Q1?E93Rp`)dBT`HXX#fQfUwJua|z-(YL|M^vZMcV;2)U1r&@FCdn zAt`d2gNB^%UDk$cwp%YF-!qEU!Ljf=6zY1mpL)yEZCYRAAVd%RJJY-AaJ}~5f0r#s znbcdJBcIZ`H)0S)>wEaH&jHC$xr8ARabhWXdHo_AA4sQUE@CFqJ?ee+DBZB=SN6!C zDq&U5CoVKr7%gY)cPIZ8wOU*X7ch{Q+1i@*d^vo;^D|a|z_4k5bGKx!%2UYj?s$;o zlub;?BW9#cP1ha9e&^f$nJ>drURw=(p1VwV)ch|YX{Nt_56ASfJq)|X&NdO7kYIAS zJ;%hsvG1198Tj+3#n3nl8yiGz21O+$Bdr9;R51U@@90$9N&=gLM=KnTL+sGF)lNuU7EANaubxuZxQdxqxfoh}t{K%nll_ugZDDNtRB3 z8j1DwJ(frdbw4War1g(H=#V))JY0y{+5Uvz?f*_g&xO?Ya1NV=MFMdXnI zMJ)dKVcg=6S@Y*d5~O7;_nwKJvjgC2pc(Tb(jd+Z_|K~*JL4=!5*63;+~VT)(J~VyP0gRX|4N&N`~8@W^p|>~ z$cQgWNT)r%U!xT_y{xR9CEVUFdro70n)!UdVjbT>dM)4~r@D~M`ju$o(UF`&rW^pmppVMGIHDUNw@d$ZX@e$;7U`V|3xh?qad*;0gFVt(kk%H z8=~%7G6Qb}qts0OWljMzb~SptLnLZQ^o$k!J^rj@ExPij3e&nS|LjgE{bs{~{#e;~g=GNXZ2HzVzjs>z;q_{rqkXg>n5LO5eu;Lio&o61 z(Xguw^QblaEk%ILZPFpQdwEb3nF_$~YJw?N0Q|77QoICcsXfeN*^dD(p%@=7+l>Hx z;n#r4{Yl;c)J}z(BEGl3vk^Sf3RWT;=;r4{FAOuWD+8P zJ8Z3W;SQMYD-_(9lJ4786;j@N8g4Z(%ZmlPR?t-WVTJc2UR~n2S*mb~sG6Eh;VjzQnVrY3W^9@&_LB&hb}c zd}Os1>(v>L6zjz=UFN7kgHLfdx)^WZ`v+4)*8$Ut^2zNJm@Y#YEWCp`b1fhkA-MUM zTh0za5v-TN^noh&EBaCi^9pqezWK35<+cTlIjOy@=h9%}8yd7OR*a;T1QQbp32Dr& zk=35;Ev)(^D4t2y{n5B(7GigYCsTa&uJZ7R>NhShuXM9w1ly7J)Hszevyv%#51*}l zpR!y`kyA>2V~Th5zJf`%w}qxiJyCm#u>3lo$M_EUV>#XeBE#N01d3`KCtmmwSdSEV z>h}2AKwws0osQit-Za|lSNY~!U^?--f7w9$)~xj_)YhBT-XhkXb|R44=oJtOESmUE z!|t2)$KM)#j*V9b^YE(e#w+sVmLdVE(us)7nENmu7dPx{uTM8nN=iyEP zLdkmtIP83ChC6rg?Hd1NTTcbk`u^O$?27i5*M{O~f8&`J2M0$xz@+(K5O!CS9yr}X zf(_u^x+`Jm{myw?^}q2rYG%>LJlB3(_ij$r?aZ8?ji3rg)^-3kkDk7vex0rCeY!Vd zW)M#!=&q;~*98P_ccW?3>Hb6t)?R z6mz1;@%p_s@KADyCsVOTL;=9@$GmL1rmIG_1X$Ab=l2_0a5KWR$1-)oP|uyF6UT5` z5&bH}ed$yqB+?CMEQ`-66NL>7-{%MB^t1at5JjW{LSFJYDF#bk7$L>}w6sKiMK|T~ z!{<6JU+lrvv3$vY!E(9bs^C%icv-n@USv&TtN!zig%_7z9QkXLdI%voH;?n<1~4AI z*1Qwmc|6Dyr>8?W?aD6Z_?KnOr(fE!5S%HXemiP^>(w#v-occ8{FuEPQcxR2-jq#- zOXz^YIdtxWeUy*&@LSnW$`M_sh>SdK%6_X#UX`0rL`QKPBnh|`TjTcX*fo%*@VhwH zMzt80=G88-Bx`GGG9~>|A;6F{sGWv-0L8fn)fQ6GB^*baz`sRslNmHClvCTDFGPvV zL)0i^tF|6fR&rrm^J+;j@Lh52(qD7nwi)Lp*FB;A3c_|cIae!6S3@I*=@2Yy3POPa z*!bvZ+7%W?#M$=PGj71@$82u{%rM+r9g1JlvHgfyJ?R*h-!TipK)pyi(4-?$E8c~l zS}KBK$(hzS@~RCWycqWT&xW7u;A_}6{&_m~3kHhHw!0T4AwjZ#CFuEwrewA6zw>ML z9Z_Tg_wleUz9zUse?x!Q>%$|3nmW5yA@ieZb^(z^ajcpg33XjO>Yte@N>^AiE^+3JscQJUl$& zmxhaUSX1u~))IA~%(_+AuVaS6ev_)Q_L-u-&S{7S$;eDg*y9)D*~xE(;0Y%-tc0Kz zOwmN+%KG}r6=9^NvesJByv}9(vhb)EBsBZU&RtDb^}^S3lw(bPe!$p_FF9~iM0_Kw zrDC0aHjo`*{Ra>wUUg+-8dAB1<|kHJ4q$v^Z3Y-R7#D-uTL z?2$m}(XLdcnA7EJv}@-pKjSzlS`V~q=1UZHa$hc2P#l}IBpp|4h+HepSQPYB{-#QR zNHiHws^(T|H2Z9alzGxL=*9|CSM7CZRT*y5EC20g!UouJLk9v*={)l*Yp4K*`W|fE#LyMun*~wsg zlsRw#$AJZ7iHInx32Q5wq}Ka-6|S>lr$y=26wppgO%0D0WKB{cY3zm7ljXR!iWT2A zPAZM|$5>9Y+juJO3{a-hC}c*rrdu*UWo%C(Bx9xL8C&N>qv1fzdEXC==y64E{8E>d zSo8xiE`go()c6Y8-Me=Y&ZXNCKmZ_uOyyoCawNm>@bJVh!N$BHB&4@<=5w?g&8`!5 z-#p5J4NKkDw)k5u5JSNeItERb@6;0z+MX~D7?^wj(^`o2w%=$Ztq4Z}meeMpBw-S- z&6}d~)QrYyAO`GzEy{E|nwm0t?*2?a)I6hL0CE;7eMo5w%Di^k$jY3S<7;O9v7CwJH7v|>Xtay5MlQl|J z)~63jX^=3kGMOrTfuyp;q^ct_Oa@y6_%8EV5U`hasGE)|ApVhPce1C zFJkj3Gg@p==~kbmj**H{teW^MCJBtQCdZHve^po4D(eS;y^2nYs;h0I#F9ihuse+H z|7=vxn07=8$%mbH zB7Tk5f2t;IovxoP!WtfdGF~eem7g!$7o`bat8Kv6ox@rREBaAsX0Jk+toib_H%!~f z{lY@Fg=-dG(>+>l?!;eUKE%urOKTE)9vv+TGRR8aQ^s3-_^Fu6oEl_%(tO{>TyTb; z{eVk9Rn5xJCNHBC(B5Xjm0oqJy2DX4d~Wj9U__3<-z%IiKb(U4rUC7Giw*StA)3dS zl9JL3sGGWmdF-Yqi+BsGXR7VeMou$kjeLX}sA;7msmk6pQp{>zkph}Ij=e7bYu3J| zgYzj=xs1ogLl)fpDZKqjCecnv(RNEN(Nt^Lg4-Rmbt?I$wGDD$yI-WYoZrkZE|!v) zk5q_kBB|W{XXf^AoZu^5NH?Jv<8MoE}pM$C3!$WsdGqX9w4Bkd&5Dpmo z22>7Ep>RFzNnTNp6NFS~NKI}7mTJiCT)rpnKrUQ_RB{Wc(K0gVRaI4IzeF==R$7tL zc&&3)02Tu7?PZ~7t`K0EZb*X&ni{JW*sS@q#|#Mlaz@cl~rX6HP-G2rkIdj)jTn0&;0ARGErPaw70wRWu9@1dKZpKH&iGT z>}{=yyv_M=Ut)YKX>V^=El_DX_|+quh+Ug^Azwa%;YQSYyZlj#eDL6)YW27U09)%n zz<=lOM)(Kp?O8)1t#h37;R9S#)B39|cg$MK*SGOo&79^H4#dy!uRsqRK+dtdfO=s` zTITHQJ%_@B-;0`5tox@>siC$XLvY5ue7OvicOV?^qw*a0JcWc0XD?o%;`?soH62MP znut1pn2q9{sC;H#p0ani<0|MFKI*v;aeo`O5IUdRDRp4rRLeoi_M(N=#{bC`NWr^4 zR=)EyGs+lz72j*$I=x8IZ=HFgzF!UGohil^@sCeqZO9K@oZZDZ{L#F zO*j;Ca}3Wl(+GLK2a1Q|U}1T5+a7Au`J(FSR#++6N+iG;ggGp<&p|wBm%Bgp5>{oi z1@}B;eWYd=K0k2+_FQwH7Ir1%sD$?<09%W4m=4V~-x7dQ~63mu$0W3(KQ2DvzX3B*HMNpD_qJoUgiod1BJD*;o*+LMrlYXEz+yH$Iga&mb;gpiZV%c>U>S zyI4y;gA%}$Bs)sur&kB#JUBGu;ldV4xD1T{_LkrI1WFK)DClBJaaDgB2i(gtY@_2FAS2YM)*p94*ZR_C^b zMW=SJs@P&u5tKA8vo4ZJm|zs{hhc=k3uz72$7j67?{{);P7?hp!ext3Nl8@eo!2n| z^DJAT0qEg}UtXUtU2KHruI`^teI~k0{CLGn!Fn{mrv2IS!e9KP%*L zZ6MnME^4vnHGy!$=eqvZOix#rYTA9_YQnLn*VUquvheG#F1m8f>z5<65 zU~Kx%cb4%U(!=!X1MV09c4b%X`Ij3W`mkN zL$M_)2wIO-)w|ZF*7iKBCrXPGm0MOUT0@)KFF}e&I^cke6ZtaSaDH}d0lg31J`D{) z!z1{!nmCxCzqNlz&<}-LfBXr%HM`;g@!!-k3f9PQV4p6$Mt=dvsK1aN=_dqwCHRJT zkRgCe&1zffRQGutgqi_>AJ}Ih0cZ*^9H;Y7#rlJ3uhAwy5r|R@6Mn#|B2*4lRj&il z5mjIU=&cBi2bAj9%>~#Jnx%#pg05Vr*Et7nWfVj4LS$U~XHWj4bn#$%W@eebM#wAr z&|fK30VPLC{jbmgT3WPbDAu_w`xz^&$A}=Ey414&EtRdrZr~VkqjPaBALWC?0LPy7 z>XI#wvN9V<&})&;5)=3?*RQ5(G%bF-iVtT76bGsFCx!2C-H06a63cYhV&@^pRI!Hx zG_NCs^m=KrvXYHm;&n1W7s*vJ>CkEM(u8XpS*Xax>L?c=EL(tgCfV59;HhZz-5*z7 z;M1RkZ(y$eYelaMILu=p zYo_}bun9|?gGSy^#fk8&bOQ<$&0YB^s-|hL7&SgYONcbGb))S&a^I#I|?GOPp8a3}Y$oV+~Q11jTVf z!^DjqHcI?GHPazRxyLhnNLvgh;#rn(m5`S1j^9v2*|*gy2f8GYjGypG@m;&P_PbZ4 z1BgT>o%;|Bzb5iLcA%Wr7xz-L<5Tw!gVhK6p#3+Vky+?CZjGcC_}<{<*1Z7iRLxuv zrJ|~;soS~el!D-cYaJmF4&Bn0jbr7ZfYkivWQb3=Gr! zT1itCn}PdW;3%-B0JRXF_lB@A4M>-AiQFv+4uWn`!!eW@pdz5d{5^jE7_&)3V5`4G zZo)#p1sbXO%JzeY+t$;%F*2u(7-FibianHt17ln9i9=grFVrtXUBzA-$q5p`wy%)(j@k-4Em)8Ru*UjZ{E`#HDN{+1BD9m*jZ>G6a4Cig_4DA4iJdQ8^nniX z9C}t-zL3HQX=zK291bBlR@zKlLli3Ol>TO>4w;{2ZY7BQ8KQSdO$1!B-U+MV;}1Z$QU9nHOBq3kTs`Z4m`?Cby-CvWAxwnn|Rh9j(O9fntkiv~>?|5}% z=dPlTDdX#SW2qQ!=0R|}Ug*TJ&~35&m6|z|amn8~YG=q!O{}3cwD37HzWmBsWp5xwYWwl`_jf#puwGPisYnDOriB5d=*oWQ z_5sWfC^N5-Ad{OX)Zl^#N+!uVMc`jy0S}36W4~aR{oLl)1hWs-c(t9KRuA+9BRQ{X z0T}NLy7YlDECS4j`54!~(ldN0&7~Bv!m;X6_81mPp2H{e7R$Tv1#ej zf&ao)2R33QI-ZOPcEV_{!X`eXp;PA==mr6s|10S;&Jjfhk=+oocCAO`+}j(d>5yNg z^Z`x9Y4SPZK!kvM28d&$wb#cj)9kTwj2-{{|E1+`^od_jKxsS=M?5>P3@QpFF+1h7A57j;9a{Zc$yT*KdpkPCecaVQW#|edmAs zdwzV#r3w37{jHir3)3v~bS(`WV!LIWs^2pN5`*rTI=SqlN5sYGS|9p;rtoRz-^D~*Sy_3cpis@Gp{8a8ifQP??g)8aQBfPDQc~Km!8X{9-}tRJE%=R~ z*oMAB{IOraKTVF$cy=8y3aEwgskcsm&>WhaOx2CjFM$KxGAC_=k#*Ei`Z1F(n_)Oj zZ*6tex(d;o=#?chqw_7>J08z*)NKs4N3ypEoYN0d{}{tl#~LW;F}XTCduEXX1%N2@KRdh<=|7**frb?&xYU2`HLMp>H5D%c0`-irt zd+TE=!{87t9c$O83*8ckP*GAMgnp}MW3@mY@lU2MFz$ZH&dyLs6Gpj!$3v;Y&c=ov z&;pCj2nZ2%6OM&1b5N+e-cTK*T)_D7yG95k89gwW{U~1sv@x$v366_$>yJjyYi|6d zB;IEZjHz=*L}G=vKX<-OH$R^xTRcopPch;_XC;x0*@e;K!P9AIdN(xW)iw6s#|4;x zmA;l2d>MO-v*^KlU9!%n{N4+l%o}u{iDo27b`M>FrhYD!S@y@+268Y*(=IZwI}>(I zTJa{v#)w(Nz&RRyeOSj%QZ>N9szk4Dc!|tDgUR@B#ztabVQ4H5>wT*t1IsrmMK48~`}u6FT~t$;85fVuONG z*JVfzuX>pe2cP)Xlh^D`;8=3aNvPVN3#Oe17fbxo=%}VH++yfjy`+hw0OfNfTkgBm z)JOof{R{humZNpvJPV*#91NNnK7OZr8d`ChUK>LQo}kB-y+!;wl|v3EEtNx!*T(t^ z79G1>K5zcWV0IbfDm_{6H6rjXT_5LL@ zR*R4dUi<3~HN8+>Mh0Fc>xwj@o-bPlmO~1$Np<_3pWdhO{COj|B?S?G;LdNb$AE!? z$BG1nLg~`{%}n2U!8wtX*P4PPEQTmSV->;;D70NPi^ymBaL52VNdT;2|NCaQp1egX zk8z|!SV;Jqrfa}ZFLHXfL3vqNU^DGHVT0;Q*+lG-yq>!jW52*i!3p(w&H)h`pZzQv zsHrz~;LQYd9XoHjRxkgZdTojb?h+dlJW8ud<;uQAQ)ccpD}FDYT%jlj&!dk`Z^>OI zZXtVCD&P+<^QE(oE<9464X4lS?qUh+Q4zD#-{`p#qx7+&?D>+-H*sK* zGaAZQ;Y#aDpjDEXFP0gfC- zq7AvLrhz6(K7TED1lzDR+TYzXr;5au_5-^&N7MnB0a{G&YQ^8T8GregYUw;WnDH|K zZWS>On5~(AOTz$GKr(#LliRMkHggQJZcELhzO+}A`- zcZoUbx5adw`y|~VI+pnyyAA>}v%VclzrQ&ZW}fDA4G?}a(1)f`BD>$kQL|A(3ms9? z0D{=N;Y%TU!8R2AT`UhlYn{!@No@u0mt(>Y9Dx=yjSbz)StDyU`MwSCoJeKCHhJOE zK)k-|m>HPQ%FXngow-vzeq2xJxG^((EdTQeoEpK1X$BO!7ASxt!4x!B^h;e=Hyi+d zIyfVcZ)p})2_y~_*A?9+4#_WtBcuYrRPu#I!1q_@?V9;eR%_wzYh+{#pr^IHe;8mI zcM}9cJ13t)hr*W$2$uJ*Qq2sdheErU749#;h;`+4(J_!)h^PGIQfB{EYe!pL@ z=j-{rp4W9fC5uzzw?FDSezh(^JJxG%c6-(onCK#wwY>LwB*0EJua2QZhd2niRiiZ0 zoH4Wy+K#qF4-K9DL2FPQE#>9#%xR(?6HruA`b^plN0)Q>>;`op?pr|9s~9lm$MKv_ z(tfzh5Y{=GMc+o;Zz9lvW+8v*(A8FP645{^l!{EsGQ=4%&;LSOzW%_01F-=8;vrr` zC+dj#2ySu-h_XhG9dlol?}{!5*qvk@$*~Mz<8F0zb-ORG=_7VKD2-+Vph6Gz1gJvF zgZ8iM@iQks1^xAxvaU!u6A-V*U~Q2*5SADa7)T%;v_+RDY6XDZ235z0Go4vKemFio zp0}Z|DMQ1Nw68?aY?KDiM4VPrQ$v`&$P)?CFsAns6C~^B z1QDR*I(D1rwq;m_3&yK3zE_D_Y@kW;eMu3WPQ7*G&VqLjua3RB?!E9u&vSagojV_X zX}roXx+TPq(mTEPz3HY+LuOoE0w0zuyslh(9@@yctUICXpBuI*`*GTRzBxm?$!x16 zAKGCRU$elu=MT!q5gWn3PA&1RyMBV>KDB9N%Ff`aAMcH{G4H!99K!9R3;XtDuMJ;2 zV5|G}^vPdj1v&_EK+$mdh+f6fbWe5l^@Wo?0{a*29NO$fr?lY7**8L2EhfXIx99nQ zEjbSK-Cw7dgO0Ua(TI_P-p*z4v0`Il6sku| zT52f|ccgA)KE@BnEIh0tgbG^y$P`wU9iSe8La)_8hk=oE;lyn1iAJ*$=$t<`Ja1Fm z$(_bXOVTVX-t1~yqO<@HpVQ-_+9Sf`CS+L1W6t!I*{^4BJ2!lUh`5~v44P{m>|1&c z=$(IYDW&XiwmG~jV76qgdme4J!DO$QKQl%rc8fdC04rn$Q}DXJD;X)H?yK+BKlbXD_3aYr*?eO;ukcz&VK}Uso7*`? z8qg^PErF%XsNC@I)m{rnh3erk=$ zEq5GfYyISmuJCP9i}mP^7YmEA-XSJ+IJjS;05z)-)7vvQJv<1Gbq6##4pS?gFPQFN z3uN299%_RkRDuyImAZ13UHGA1wQMo)c@bDj!0EgII7h0r|0++^i?@+`Cb;r8!Q!W&?-G zjph?6i`0D{X`k?{+j%T*n|lF!R;x2Bdd8)~A1*CxcTuQ98|Er_nHwYbxHwBavMm7j zy5($z&^WF?6);LxaSWyGP;XeD( z6h%_-sAmT8wr+bg5!#0arzCR1Um7PzW=2_oWFc* z#{6})*G9>S0lKr7z^Qmdm%FjnFFUsqY2ez#{XM!Kfv=C#)AwY(fhX2M8>{bESD8tXI>FQoZUzfDw!wub^P^+%imW@Te(=ap)mhl+<2my^G z`U${)jK%K(a1DW24_FOh_xpQ4I*fDIm*j+CZ;>XAe?S2J=FLG6u94hXGfk9NHy(LO(Jnpfxs#e2ED$cWzL!afZh;?Mjs(I67&Z$<2Bhu0pRF?^ z3ue*rNa_(tOAjxWr@o_Y3r^AiKs({{Hu=+?g{!Fvoiv7y%8y=A3^`@hKL+ceG8SP8 z%dik%#H0EQ4TL9T7W_Y6EA&6woxOOLfg9NBEUbAi3R`m%S8VyRkNnCTum80hlR zIc`3r8ea5>i>tgTB*f+1YUz>}@hgB^nwtlU#IYf`u5VL zB<3)@J_YlN+OL;PUjLFJ|N7(0^=EFUZd^aND=Sgmz2L`bRRgx8`T{cx-VYyC)+|Uf z+snKv<)JH;$|e^#nG!G2QUFU+zty12cZbofzJc zW3dbP`4_hCa@u|G>8{)BrI#;%uR~RxqhpO#Td{X4R>3;O-+yRgtE1G1L`$4hYTWeu zOEXQy#dAXq*K%&z$)Xq`L?6-C-{Q7%`Qt3~f!CgyX8WhL55%gPX2J(IFm+09T`%}x zulzOs1L6@$ZMxL`K_vlkHm-V4>Q3-&K5$GiY_!>2)5Sn%q)crrU60OYxp%D`M+%d} zq9?|;8=7f1LqC0gz#D5LRe2Ib@Pi974;DyMY()La&vrj~(m#4VUX5XK_sApXdy0yd zWHQ4)U%W?SVlR%n@|}CquqZY4ee||q_JDxlLt`!LH(AKlsh>Dhrym>@Tg@AJz~gg= zr-QWE?%c<3UtJXD;yU!869RPc4fcGa8b1D14XKrK5=-0*9A#;xCF8wEm9|}Dw#~e} z4@B>hvO^EVzRzpo^3zp%LZ9~`Ie3KUG>96n?-p8q~v2AAg+JEVT z)vk%$c__#A1Kazw*`srjOzmw7X`2=av{hXgwtJbu3!kN$gll1gFQ$?NsuVQ=C> z8!R6=9MhxD4nECFpbqsiUvTW>=l^2Eyh=Uq;{BR8MQK;43%`vFb-$(gJ_vltL8n+z z@rY(5^13R_Y1^m2PF{cez^VLCwL_{^n^s+TDQ~tFSkGB;jRT6DWllbSB! znZrSO^JcGoDq~Wh-?gInk(cEU|KMZO)7Zx4WMW#dlDfjX_7uMAm@aEr@Ii+|xGJyX z5AMTNPYMTusTusAcyC(_ObhfHA}}z8c|Y<{x)j-SQz^FA_JDjtJa1KT-UDuNaaY3| zihs~$2L#NxAH1QaXdg5)MdrM#agZ@0|9mkb(yZvB+jmUOgYB4dP)K;ugOM;%Cn-K& zT^(~)J4a3XV+moSsRxo>rfb9Z;q`wRFxS2+Q~yrZL~qZTuv{%@5f$8(W6I= z^6(rMrkk0ak>Fc4Cs&&GY-<;PL_%GzXUheDKZ>PQYx9A)8w!;#Z}zWWY;kVGh9$W? ziWfDu=wu}^_w56<`?~teuM+g$MspJMZx`1H`S>YpAsx|wzP@;jFzu;4Wl=sfNijBw zVa$9=y{_QPeS^_`6&Lpn+6zGD(eEC<W9eSH)Xc1lDu1JA z@dCeq9kD4o?2ki&(=;A5(gkrWG_piEBO`(S^_mEA;yR3WT9CiV_${?vERXm?Wj?*x zeKjbIzo)Kh>xnIzb=?o&oiTnebJ(MBmGtC3_gu%qq2U7C1X=SZfB1#p{4(Xxb!h*m z$*y%z0};Y4@Lgk*>>*O8y<(1106R91XQPpTEK_wSf8r|C#TEh@i>`(u3Z37D_^o% z4{IrScTL?@e$n`>e;}@|DcPLbu*kyVMR!f6Mv}++!>hP0gSN&F8eGe{|Ixs_*8JvU zm*gbbjqi5B7wB=uWC~SFz{l$d_tl@|X8fq8iXCI~rBZ z>%%3+@`S}^zt7y{eR26~h7BXDmNavipUdw%FV#B7LtpUpRr77d{W;oh%CO~ z(DoJ3)2oMlyUVgS`M^z`U@HH8>ST+|b}4>kf&C1jRsUVlieH30whFzND!)CtK zk)Eq3b>+=T{fi>Z-6QJJo=;>YSvT<=vwQj^bg3N_>i0O=?F=*UiGqzq4;#y>CiGio zj4twy@(*_2^GDZp6_@Q_%tfi~h1*8TuwkP%asS*lyBGPlJlElmo{WTU+jwR)^%~}SE zG=Zufr|_8LvUZqhtXiYYk#!FpHa)#qJ^8{){^FR;{{3z)b5Ei*+N?(_WnMRq>}2M+ zd2?^_(jP`gG2EgfHX754|Ml`&XS*miG_;F-s`}(Or|U~wf~q+;@UghTzu_3?^Z48Hi*}q5o;+eIoMTs z&*Omg(;upjl4-ABJ4}f(GI0gvO;R%Mu3sO~zR%MQKG{ly1@N!C9dEz>vIA3ZgwLul z|DdoU#kx9mqqoi13}tS-IZyY(=#GM6oW=%oYOV4-`bPrSN%sLOWep*hX7GK*ghHyn`z)G3JLJmpLL5r~>})C$GpYJ9q?L--rHrhijjc#-!}6h~8ZPRHbb; z9kiZuMNAj^PsmsNB(QURd}79&&JFIKEyA1%ZsV$aiCQZ@imkfcm|)Jbj3vl}iDC5; z4w>Wb+oP7eQ0C?{*VX0Q+-`Ku_oXNcpHaPCk4wRk$?IiVNeNx7i zhSztMw)JV~^-NBhi@ujxd#&HCv=l!uEBldOP)}HvUD8vpF;h`d<^S^8`OEF=o*y;Y zd1x!O$C8gN-uZha!_}+mAKtWf-=QU3Zdw_rq{N@FvzzLjQ0=s&EC{`Wb)!v$mFQs%~c^ z7t6O6>bCD&ya0An3onl(*TnNS7`IK%P^k}x^{UKoE)03e%$%4UZz;1R-$Hmh=qh(d zazX-bXiFx^CGqqKu!};CGFFAZ#4)}89^eYMeLO?rG6bTzg`iyuD}zhkF* zQ}Qf(AHQJFH>o|7Y8N2$5p@<2s1iyzPM`ZAU399Ux;4eT;Aq|fdbOj(B=BFaB7Nn* za(W{45*gQj`{u;dD5_t-+c#DtUw)x2vz)oBMNCf!O7fRH=!)U%`&u_lD!JW#NNB@ zxFfxGCg*bnC04=&to!%h+jLLd$vW@vv{%Yy#Mq>OUDDx|_)TlkasgX@W08Z#ZC5(> z#fH|yP`G}q@q`@nvRChf>BZdTC%5nWXXc`)_>i-}aB|xi7uSOQ`_-2zCxj`OTKdq@ z;>;hvShtvO@5U{{KHn^@9_@XYTy!m|PLUOV^v4cneQ=9q~D#D!EcuTw0>u`182ylNA;Pe#@$;DV7;~ z&!#c5B(Cj$RU)}1;gfS!NZ`$-c~||UU;Hb5QQJoPo6u;}1FInY90*q5rJ5f2(cj9t z#LIWBpC9kIh3I?HTE;d`&V?sh-=Dlb`OdD~j_ZM({80&4>zz+d$k%D4rXq#Nq|F@T zs?k@9bzGf5eduxMH8W~LC;bzn(vqa8 zndGzE91BZ-S~DU1C8_#g*{HAIGCol~y`Ja}dNrLDY3_~xd@>I+sZ{Ez(6?$|Y=0UHuk*+J3mAIbhtBH!|?H;MK zqq@ppd+e@yc&KuRr+n<-oahf!Mf){q=b3{FWw-}?6~Ao#cbq8t05mOdUM|;9hISA* z1{zFjXi(_r=yYHUK(vC5kMr}{&^kQ;*2?odWr(99kwYEP?BmP6dT_h=sDaPhz*YAT zF>q|%>R1$m;cKm;QhK=u?kHoeiF!)Y|Fq%79_B5nyuD+QH;2wFx~&Y~w!3i|M5%%& zB2+~*E*JaP_*?|uRbj~b793-x%)Y=)yQXUnkqmW(6gnBMP+*(Uh&f9BRDa&<*RNBa z)|iWC558h0UQ3N$#RL_CLZ13O7YeRF=oj;xC!C|vCHDtN8H0}A`5rFhbD`kmZ-U#=jl_iLx|er= z75+bFD1`kA%;$)uAAV5nAc6hdM|ynFp)L7eHAc=AA$sOCXiChXh@2q}DSc zS9;t|%C-~zBLXL)pY;*lkS$Rj{ksXGhHlngXJ=pVX%1OA&}1@!kybF(u{eS0A2X&m~g5dD?1 z(k=X1QZoJ^f)s;ugQXwR%mOM+(X%2yMtlhF+*w{=X#1=Z(6Kk(VGB`<%3*a~D>{ix zzXbing{@4SS#`CwMsOU-?$4#!VgKAK12gm*y8bZQ`h-RtIGIxEdWn_J=--v0llL8c z)2Y~I5_rV_M@`wdc*(!jl)o->Vha(YW46+L@zZbFq^G|Zr#V4^0r6Kc93FNUy`bnG zjLXesAx%)(*>O|dksBbl5YG)LUxW#@*~_V27*q**t+3Xj&IvS+B;OrBT36(=G8D|B zXN8%W8_)uM{r2rEI9^;rH&=(9puejnT1YuV=D5uEo{1$C6u%heZ)Yw)gr1z(2N4;; zNm_=UkWvVH5Fy9n3B!f;X61R}NC0kk0DctEZTpZ;G1ZWK+Szn8W*g6fw8%7Y4}Ko7 z#?qT@evFGp8$cd6T(fuU?@!I}>*1smLlM&SNOKa>OMd~q_`59I6M0kU&k;oe_GhU} zyQeSIDGboMFQ7n&VvG(yF+-CAe{y)1!RH1+rV(LOvfN;1C1TqqP2}kDiHUR+(jg<= zUND|M`x>ryvxUT8+_)MoW=2?q$f5(y)*n~XE#ms!XcfCObCukjG*n$d4Tc`8!5c2@ z--*i&-PhO%`ts@M)4gxX%dgKcZ{M@$-fvhaW*wPCL4qGII?G15va}U$n>K9%-!-E+ zB|Zb>_zl1Kb%Hd0ety!@gdRVk?KI~?;;JG&^P?us2|=>MDp;XtsIy`R7C~b!*iUQF zpgSvIKu~D#9@rrdR)RRYuAiG+5+}Uc;2INeeH{C^6)eLk5MbR}g-L9|YXxN1KQBsV z;>!&*0Wt)wGW1BGF$aHCzmK5bD>rVxnFvlZt09bA#BvWQIxF86S%Bz$3rcjdUl*qw zP)veK=o8k#tweA;SV^Y`4OaKsQ?ScPvF}hSm2>34+o{)p0B};SsJ7b?andOv2r}#P zTiCjZhueRJ5MB{UE*bLd=_1kKyw{yDkT)O;XQGYwFDX$xdFoUQ+QTAul-V;j38G=+0}W~i_6dUDKHSA>tm5z!g7x+F zpYbe9&@dt#e~@-yVZUK!YRvbg(f2>w1^D@iON=o-C_Hc!L8e8*4D-BdXmTO5sqXWa zy7-4bClLk`pAc9)l$Ms_JwbjvfKUDo)oVLZ8kDiICGyRAvvHgK0|4bh`D(v&d0Qvn($um{seKxE7 zdnU$f`uS4D`!8seITof&cRNb$5EiaV5O?YQu+@s;LbiD|SbSCYBvdo|^4*3N)fh_= z&+N-@@|h?r2OjaDlpqfrM7qMXa^=d%(bJ&#I*+-GNI3WE+{+{$49%zDX0Rp%rg|MI z1)v!DVF_e;7(}Y@fCOzQ$jh5z@hmr254U1tDX3?8Q?E)&{Lr#pZ)Is25yhYyrCNZM z5P+MP$BYj)#CGcBNk76}8;1<&Lwd&>G5gvw^yw=)AQkqH@+iPw@B>&wdDys@|Pq79}v(X_&+i1s~Vhv^kpynO)fjY_l!DEpEQUzPJr z--ik5XZn%cGroa#+^`w_!mD$W4bMyP2?Wl_@$ekTAAY;16zkl#@2)bpJ+|p*WGIYT z&7gefB5g7((97(@dWbwTV4mNPcgjb0v_DA6bj%HD#?`rrDz6d=Yi(ETQ^?3tFfHqUvOikXCOKh74lGDv9~QmxX@xD7Ptsh6(Ne_$iGH)Y$$_RdHO z303xq6PpfQRs`UY+!OV4m1T0XgCSni9b4wc$$wT&Jx9oOo6(K*V_8Z%E_lgzp&fop z2u@HL@SY!~R)QE61Gc+LNJlyGiXs^c>{ix;`PzF%Lr>2ibepy4t&wxNY-R+foD_1x zCAg$LnYQg`T<+l{I)_V!?Q_V}_2879CPGdVVo4)VLf9K{bt;2qR}B^z?sFRjbuMf_ zo@)f7C1_O~a%PZ2?7(3_+@7dorTRZmHJ*(=?o0o9@@ImA;P@Aff8Dk?#MUYBj?%#j$$r%TVPPW}voLYV`P13QSo9QN2 zh$sXI#UEYMyyh=mT^*qZ*yjh3AxF(>S_?1&En1jtHA>OCyFK|p>LZRuph^Tf59?-(Y#8&7IPx1pSQzjtojb}0CM!sc zT>35uy9w_{VHFZcERAk8fH~vZ4t9+Jn6t$G#q2l;xS+6HA;wRll_RA0OIS%r1>~`y zG`pWCOMic{2>P~*X1n1o4zlb4G;&cHjmhI+TG0OgiRqWyIfW2b8Y&MnDB8?Q0lv!hDSwnGyQ& zDTCb_+S8KGfb)lcfl{nI z4!uxNW^wqy!c}o}925um@+~pyEDt+)@Sxp?^OCJRc<`?Q!pLVn{jyY}{%KrB`WaHf zke9;BUwN1&dhtdYx+$OxQPXW&-;%3`O&6{$r)3PKPTFNBVt56f?VBb6Fg9U#8CIyfUO8pm+n!)J6SB;O{w zV@SX|@QpZ%sr)luFo-kT8c%Kj1ew_wg!iD%(yUoaQ_~2^)A;Pvz-FxggPgNml#j&A z78D&zT`#0Xrbyh@OxYvkxebd_4w@E834;IRB0W;8L6~~$n3%XcdQsizq?*vl!sIB6 z-+HnMY90~KNyo-qh#dHvw82~@vS~tPMb*ZJeRM@>TQqYle13_#kPrx`A)2Q=+&c!k z3pp*8c^hT*0g)h#oy>l)m0zK}B)W-vGYFA{9ZTdaDkpA?kRR5isK?b9ld(OJ1YZjS zU2qiSuX!gyR7yIp20&G{tKPry0SdkCA)QvpS+b!KLvZvxReARlhG4!-F)m)mz+l>V z3N@4Kw+FsN5mb?jc*~0OZ7*mYk(pZpyUL|R$cMk@;U|p9X97>Ov=nndF@(X}0u2irBB#xCvwtl=1$IU)_ zAi{BS`n0*zgy=7H3iIuZo6s;xd^JH6vehAMoxc96T`ht4?b^Od5`Yt5|CeiLEw>u0IJ zCE-@)jT<*g5sPxH$B3zKA7Z*hT=N*AOR`1SyR4F6OCIrpoNFB}vCl3V&I^NBzc>4a zKVDiZB@_JoZCKvCKiP0LZlI=3d#JXd+kR(*0z=_hBS2;9r{N7VYBTSXD9 zcrj^R%u65)e4{goML$lTY>* zJXGz`1%!cw%gi`d5ss>a$eABLd??wX zlu&2#HexrNjSSmgx+gttUs+4_?o~#qVCXgD)R;>=6Y-25)y(u`#S>e>G^b$0)1MsY zbGtDpD=TLABm?2XN#mRl)Y4+mm?kI7LvB1?p##4#Dfv>V^cs;>Uxnn?tz%`S{cwGo z53?Zu$Gk8(&Z`EkyW6e)^1%!kUNQlv<`O%*n8;20EnU=b<_TT#nLUv*l%eHO% zGN<93;nsSJWBNx8W=CK@k8?f!`X@^MS2ANQ@Z# zVq$W#0y;NprfqA~$RJw|0xQ$8jfn(GY8)b>zyX>n0*sv$ljlB2ti-4I%?bt}PQm|w zy?^8JKN6Vpu(nrik!6EV{*PQ6ue3D<6S@3xaUdyk_{X$9N3uyg_TfBUh7`oIu?smk zNp(fw!j}~c%aO~-q?u8>Ed{CYB2*e2fKI(RK1>$?8%y&|4DK3K-~8yQXVLO(%5xD`RQo|yZF}GCC<#|aMq67MAq#-vt$p4T1{0G7Wl^hH z#b4h7NO(4DbPJ+_^#oG<^hR!j{u`)zzT{ky>t7I|-I?Y5xnw!vZl{rHmtkR#)T@3i z9Nu+AYDh4?>$h+7>N_(^4_)T<7nk2p>)4HBqXq`5XU{?>c>)A-M%!k)NmJXgj419# z27u34@L`ElDBG(Mzlp^W4*L=WU3=JiC5LqW36Hj$LLTd5R;HtFcKr5k0ha8%3kwdZ z#-ZB?gCfQYQBL)zMFOcsszC=CXEp#P5oq8@D}YBeN)Z+dF@^9uZ9Lu%+vOIwuE;be zME&i=DwR}ixXqG?p;fX4?VpDxVP!OCs2MJzTd=p_3G6#bYBt^ z?4{g2mk#F)b$W!LbY=?`a-r2%LQA}_VDxb~d`}3z;P&^VG``vDpb_h31Q2#~Otlvv%BESO$Smj$k|J3RXvpu= z4B#Zpp!dufU=9)Pki<$2qjm>VBm1Txvi=Cqtqffhy&H%-Ho@mH*pFCncMxha#8SuE zg#m_k6iR&#Nr~CjmY=zxEP234R(rI~;~eo|9U5Q>QW~66lc9O+FCJxC;rsJOkV$Q6 zRjY}iHtH+Jz9|&76}PZG-No{hNL7v3f?w@Bx-jUNU*Gx@9v5D7=Z`hDA;ebZszgfh zH8tcaJQncgfRB+L`Fd+p^iBH33kb+Li@f8_V}&fN0a=08aSz8yO*5K*l%jg5if63V2h zn1G-6M)Au5`iuP(a)hbvBYt1-TnL#OlNE$rjQGjem*6PX>mI{f z{@Cnmx@Vyi)Po-px}ok^bAGa$2c_o{kcUfA(b;4k2l$9O;u6B_XPEOW-)q~6peGo% z04ouE<6=(Hre~*B0aXLiU3ATm0i5M5kGC)y(AN!%1#6i!vWUfcg#&3|&fJq#KY|OaCZLgGfYx&`mXpZNsyz^T`-Gq0T=C+^8MB8XWuz zLBW@R1NEK|JfPyc*52lABy1_5=pjfLG@06|@m9_U?o%U+AKm8lye-AC!tq(p4?74))?`B3gaj zF)V-&t)nE96?zWZeHve1B$R{SvqJzN!MC*tN5j^iak^5O9K@r`~%L)AuvcU|9$c$Vbpm?DLd-E#_B0WJ|s@p}X}2A8~aO8>bq zU#kS;zrf%b<4 zu@#?2-Av&7&Qw4{#QkGIZ{$O;=hHgv?k>rF{8)*MB{p-(LvmI#G=TH=%n_#?%x0*P zI=vqX2?+hs(Im4Mui%s~=jV+CoC}yZrLk%=pCNu^L(nbAm6o(>QPwgH5?PdueqZS&POY!G7!(#dz- z;k6i3tjUX!`}YZm;EXwlB09GK$9_kscB}hJ*%aQi#-Z z^O9rY)CRYLG?|7x*-%)d>g1Ps*&$6;2LtGAl-)Ydc*w6o-uA&(2!+VCtbL zDW~$G0a)rElU_ZJq$3rPyJ}B&iCOsZD+I-;Z)6oFnmVC5oUO9ms*=k_9Y*lE=jW_{ zb@r>-j9`*#-Pk&8OlEjTEvx?-uT^8KKjPRcK_$SikE72Q8HF+WD3B0em$`)-KrSV* zarf_|Kl>MLQJ!b_?oFnz0z(r$;BzRw<_cU>*`S*UOU%P^M)Z1+9YjEV>`2Y@MCgam zz%!#kqtRtIg-o;Jd3boZKtDrH)ntImfiNppLxvYw4V|Q76B5=*dGR%%=_qy_e?@Km z2(dD8X}%)=j9|fKxA(Yghnzu%c7NgFR{1R=Pq_ZahpIYk!E0y|>Lx)Hi-9fq z{ietSDnpi0n#V{VIVLkxOYI)IhvEZPXfTcB-&no4V?I9D8jCQe0Ldp}bu`fPiu-_z z5fLneIZFYcjp@%tU`^`Q-tNqh$O)<9G~aC64kJ(y-aJHIXD+%Y`n zd#g+PC!h$Fhg2TaUot2UB(fg6w4*_V{-cmSbmLvbPX273DjA7F2B3u30qpv|4`P${ zv=+$WR&Cl@@@W)V$Stp`sw$#fL9lM=-;#4`^SQ$Z52oZDFSc4pfgOS@O#_RSV99#a z@kkku4bWL_A+S#L=9&g#ui5*os=S^H)0%KLJ7=jv6C2S1j6OC#{&nZga70To6^DPu zN%4(qcjGgjC99Y(Kzz4|g5z(?yfr=Uf@f3KQO4db{+&D5lT(=F*A=;Fb9X>JUkd2x zegm!b%rFW92u>xF;Gc5u!nbQ%_r1fw-in*axJqJ&`5n(H*Ln;s%qCq%dEFma-QrwUMe675$9AQuM?U$R-h)FP9jM~u z;5-Vvi8M(U%C8foVL~x!J41V@rN)Xbe;F?8sDXjC?r9O`@1#;;oF>)RyyUr=pwHqp zEOWFIb7xt0_O;|Z>ulezR)R;^=iJT`i$6CboYt*Vb*vS1x4Q(GPnZSYQ+$O zy7jJt+`FW&!%Bk~b2t0B@A9P@(&+hD753b1M!kE9d_HWj8;Q}#PKq1ki#aSnSwfHT z>knr1qnM=})gXKV%Csn|3` z<_ZDu+jto1rgCyI5O?s!qP4H=&v6J#1rWK3BakR73xro&S&gN(HAOl+Oy4!5C` zjk)B+?4-HDD3&jQTTNOdDE{oHU+@7<@6jMJ{wqPDeu^#-dU7&FC8-dyJ*HerojfJ$AF8`uNbFoHRT;pP)p zAv$lA9+-R%I?@v2eNR{g_#jVVz>#T-7J>-u8+~m;HtkZ%oJRN07^pwd5?gy>9~0gK zVT~ZETuLEbEwwq9{+6rAJvZY?mJ;ys`P|G}AkpIU9TA)%%sWpmL*92v*LLR}(sa+W z8H4%_>n-296+x*QjT_P-bS^sp{DgoED68i4K;($u5mi4F)PMSe@ogPKeIT$2z07_r z<^4FOiNk>j%5mpKw_(>z?2o>`+qd=s>;sAU;89S|e&~>c76tA}-6YIKC-g3Ct@mHg z69atGWGA)^f<}8l2{S+j<=nhBZvJQ?DJ*%p{ifR-^}ufg_UwaBu0H=FEN#N=`BdZs zk57Qe0v+PiK?m1g2ePFhw7^$V`?*A$>bL4uHVCX#hQNb?7(9hPYWRvrgTF$g*R zLJI0t5?qk#YHDeH21e;Dpr&$XXQ^?gG=%`n-_gC$^VXerXz-f0&udOHEMOtWLysG& zCa}xbLI!EAn}sBna8BUN3?D2-d@!_c?BHsdMYWmL!(x7Mp~$o%qre9 z2Hhj>r2992d`y1ZRxt?>l_+{qFo6-eSY1OS^!oLMKp(LnKI6Bp5%?f(@xG+r9sdhU zkq!Arit>>Y*y{wlLyuYktMA&cb`F4qQ**Gf{fLv%X(FPiQ}$ObHJ?zm8T-r!lojq| z_6gF2Y697pfns7usGUve%dy9ui(>$q7vp0{uL)SF?(`D(%TTNGJ91?*RR`74X@(6) z{`|8T^*w>la;*0dzNgoW80mxB&wV2!@Q5+F*X#rjX~{BpW7+{3@iGYRk(5o`iRb6Z zK0m(XJPfJmFJg|%!a3BNHo>}>n~3LZ3JoeS-|+V0m?%)!NPmO4K>{wzX_-ZMF80}I zX#Q*#xg>Gk#r5#43;?E|cw53Ys$oVN%1&qOb7Zs(K#0==XmA_aNy7A zy2+nAmv3Ewj0t5S$?~il)98STq_bWKym~dYQNjRW{ylAE9LXK&w8BR7{ntS}DdPJ` z$bMKn{@6p!s{;&C_Y=Yi0LhQvbx`cQf(g^Sk(K+iMr${(XB#&Z^iUI0P_)6kJ9}nY zVdOs#=MY(&52Cq{ZOmiT!XdsOdYx&445N3L=GZ2zF_+-Fq zausSf=d7##{zU}zBh)MyN%%M8pxH&3DCkuZZ)w<7$iS@YK8D-&yJWkA@bn#h7t(8+ zcRTHijg8#_#2UcP5&Qk+064dx`AVLcJ@AZe+qNx2E76<7wb?UovHS}>fdKTD!Mc5G z#sOQS)uc};ex~KyjagnZ5oV-@R{(5uKucXRJuz$#c#A;6eu06SwMuYO17$XV7`i~% zyC#c<>m=66IB#BedftCPwAQfhDMg0zl=sD5ENY^s#>J=Z@4i;T1*&?3olS8zNdp zIsvXt+U0r@22m8YCyLz3m>BNr2;S45A_&sTTCirG32GzQLD_u(MiFn()g_waQ>RSO z0|H5?O`VYEEj2kw@P^l|$*AYH&eY?OPpi1U53j(7c6e==n6z|F_EPMbi zBX_|d1!*Z37@qN_a_ZBkCBUvP;t}E3C?q$K=ZE&cI-{T_ClAk3+__?Ot&y7rBGZSP z=r(lTQ4#J3of)4rUseUzK~@(6;5KNiS%Q{eD4}^%Iv?SW;tP9YKiTfS_)ZdrZpVm0 zMhZ}+2q~u(peo=YlQ4|QfbRft_|`z12wa=&Qov1SZXp&3qwZt>rp9!rD2K0n(i|zu_!eS$l#kn4} zua9YI%`3`*9K-zlK?9ALaS(GFQl3-Gh8nD1Mps>(zSL2>=iC;~U@MgS65hQ2CinNq z|KpP>YTANU=!(NP6_Fw@1WqHSE!p;jV}kQ(re)6x?p>$;dI8#tOq&<7A<(!A^{2jc zb{fNNi*UMdME0Jk!PA*1X};yun*8TEjFPO#(91l*C^$;}lpJVQvsgljOPa zl!mfTlBokS=9oob820_28A%~SRU4h9VLJ_3K^{qy&amlw=rV|c`kqcmc) ziN1c_o6IUBHKBbKug=6Ckz8Um4Tl5*WX1HA{bNAp`HA6-kI7xNw-Ha*kX9MG&`S_| zTe>qX7c1>n+1Ih#N6IV6%4@08?j+W+Y;I1=RieKTz28eJ6w#f`N-SFS5BfX?dw2+f zoJR~GNngp!IgI5A@hw2a%{Y?615O3vhAcP(%M-N(JbFoNL9YEtW%U-X!VS|S5iEJg z9*r?9WcxlR%a8LnWX<&Mq#2)%ro1jZsRtMTz4lgQ15@8b@?Yy#o`>LzW2I_`Gd^@~q6`kBA{ z-g+zIVehbN7oRNhs>WQr+s|oS4_^uVbK(}F)GFU8<$L0*u@o}|G3%w{ zr-hAI!G`IHh-KL@IZOoxhSr8LSc9%8`3Ykh(VFVKDp=!Cid>xC=MeioRkjAU1}Gos z{vCuEMSe5o?|}-oSl%wTolx8x&BAqW5gI3E2}b`2WyvCW4_Kc+FCBigDr3Oj5p=^7 zF%W9IqMBoNh}?;lv+gQ?z(8X)SjYFP$NOn+|F{5QwuUazQTro`wak}i_elI+_vBBX zrz5lm%o(dnYsq!8`Z3UcqPh_2O1O})ex`D16#XHByuGn+tyH;&_L z^O=FF2Jh!l3=?b1x_7^vj^LHFH>j{D8(iW)8{Ft`rg}w>_UbGfbEGJ!G_6aOoIByM|1)p!<<|$gn$Eq&H*_ZbG8=qEP_1;*P!B!?lujcxnFud>- z4y&|I1W|!D37le}a-|DuYipYV58xjOTt*19;IV?y4{Z!t%`;OlRM*dBA9%|?T=#c8 z)e@2ASz*Z5aF#r+PeK3Lp0^24?yQ#9E&VBdTiaH4FD9Yq8ch4>V_0(ax)V%SGRes02_DmDfYUbRP}bY$S~YE8PW|gaO({7Z~l_4 zZ0L~qNo^=@X1vC9{izfpGE#$ykF$l;xfGlcZZH4+Vx)9zu+TTX2fli zjBiDwml*UgWxTPs*+Q1U_jU zntHy)JwJzY*}_1j*c$P^#Nke>mnU$N`gYWkCqEPoIG5PJ7a8I?17R&ENf;fm6W{PeV<}WapS5y#78IT`{yApb%-j(BeWVCa^h*n&f z(u|nW%!J-Y+V*L?2>0`Xh3pFZ&Ys;c1Qo zuMy|LE3|JSGb`=;ChVaJ5Z#~McKM&{=AdW2hVT5~0z|HxLfV>|u5~;sgh)9HP8cDg z7;Lgd6Ln7+d54;Cxq^1M%y5$^U=;D*s3Z7 zHTZ-770x_whJ4q4&MPfphMY zWCl|p)?gQixuHS>Fq}q@BrQ*j?2nGBn2>GE!1Y)0V62>3nf?F-ONl0jCM%=wi zJ>1TlznV?*Xl6b-v4p-6hcrLODFWS;zwOc^BCP+{cALXU&tuM;71c_R+}ODMzn49f zP0-L>OWXrxh`x=EZ9972$y573C8Kss>zwC|IDLC3pV`|tj^55?VpaS0=XpM~C0L`O zZ21*L@;cK;3V7d-`|9h*W2|8*XOgRDj3B`e)P#aLY$DAJ)3-< z0X8YWrJ=6gd!`}B;k53zZ$IsxE`RQLs-M+A*OWK>@hNq9?MKyxm-j1NcxWB7EL(Fy zxc|p17g)D*BsPE0V=|zc)IB+v$dr+NX{BYNR1JOl{?awIbQzY57tqtZ7i~AEyLf+r zVln5kWm^XZLe@--a4pZTUiWcw;;)mhy7H@Xx(sB5cNT|x)bvzVP2G}h)@t`@%IC54 zb6Vnarc0V9ZE>>DF|E?d-tU)&f;fXgH1_>K+>)x98!}0UF z7AR5AxwDiM;C0N2xfapl&VTJF(`@uA=Zkw-cP~1RnvX0Aj>ywPxuEm|M;hawvKr1i zsz0XKXRk8X9(+!|~x0gESnkoK#WrmY#Eqm9G=gvPoOq%CWI-me5tW&5b3QKpt z9hoB+R5j4{>t-Y+<$S%Ht{n+5k_)-Gp_vyz3ImL(urLLzZ`O1p{a_&`d2NGkF4W!& z9CT3pvWsriYzM&*C$Cf3FnD0}&u98Jm=XdfdQ&$`JV)j;IW>AisYxum?(B^LI;HyDwOeJtuCpCw_-0s zlvd2&I!flV<}-OhO!O9V$bT)U+1c6or-3m%ff2b>2IvEEBXAMr&Nw$Q)R*O!8Gs}F zF(;?f_$S}Eev}}!Fvz>slw!Qkrx2&ZLrkf;T8l|bI-dfa0G^JZV{Ge`2!)a+aK-mu zGa(rmK>_y|m1Fr7z?$J&U`GbVk@VY?PM$lFF>*Y<(t|S$AcP(@B_*Y(3O>PMqXQXO z6=9?3GdxBz9xIgeDWack?B*ZMLk7>WaGv-b?Ck1_gE@ChExPl!F)b#U{|A&?k07&{ zsRceBMFmXgGj|1`o$af!4ud@n6uBk3PinQIBv${t3C%ia;v=(_ivrM?J_vL|5w3s` zUI_zrjvnP7^qZ62{WK*-Bv|sZpI(d59&bz;DFxs8{i~jar6zc~79A-3f&e#``7;R+Ks^=Xz|yOLG;M)j zt0P!eX6Y(6=Qmo?qWnIfwuy<4|F-ma2h=$Ma3gjMka^qv)?W2cs!-JkQlMCDZKhXX zL2rVpIutuPK|2}6-)Eh|b8e3sFiO*|1*Gsz1Eo2$#$y#KcY%T)4Xo9SC2LQgn z$>HH)0sx>jk!+KOz$Nwcx(kpjO`(Yh8*@M-oh@&qC_>X=c<~`a+*uUC@p<6ex zt2R(g_ewT0`*}~}f8IZ9U9^2nFhAA4 zXgQA}F!Nn^hijr|MU?`X=|M~wH#DwZ*431=yuAx zAN@xtT1+PhLH7gTCsW5#K_l9aciy?; z)+r2}%h&a)Ahr5aPGn817NuV zli}I0-GCX*(GZX+lyIwJ@SCggIMEFEfQ+YMJol{_<jOWjW8kzVZM6(m!w8|Hs{M${Jhp>n?sQGr_|o!ogDb?~)GPAev7~h`X`iUZ*0I z9zgm|WL=?=eG{q_O0D2UwO>E`;R+6FI3YR^>1i3-eJrSX^?R!-D}%6cBr(2z6UNk= zu$_Iqb>Tw_W!gyhi6(zWfyB?lhC(?6FozLX(|H&IcYB=ZfY#zFtOm3v8_|{h3}V4LMwoLH8wKAeT^+)EmO#z7k61R)EzH0;I z-wuw$v!*t23S~L>-|J1R7Y^RR*y!O6u(0(5@2%_*Po!pN1d5&msLo?izY>q#5`-J^_(1TF*!lzw6e*H4j6r`0q$gtQ%YA731nvqDlAHjMIaBVyBs&l%5g(2;_} z6woY*GKW1-t$)7EpyCIVcyz2<7O*9(Id7{D_m&1f1}}srETp6ps~Uv)WjW zrsx8JYjGj4zVRedrXAZ;J5ycxG`^7ep=`sc%|qhvH{5UZ3?D1ZfkpT^y+#FtJ>Cl$ zj$L6r;|C$l{UTQ!8yy!Gt??s^9(L910Wv3zMlGN?JO3Rvj$UFBHD6c8=Ahj4K@I@4 zhghm$3+(6T#k>6g>U{=!Y{ zK>d9c>d-O>NtkT`8T=J3M_gq)Kn@OqF-91=LUS`jCmX9b2Ij;IULm2Nh=_=BoNJ8G zI|T#CEFoS7SnLo`J;iJp+olLKf44%i(a)c(i{X$cf>c@aK++{gsT!1w7~~oVw%{(Z z8%Q1s*Bn8TC}l$ngB&SYZ)z#!!zQyw&R?DvE&jFP_B_B{BaS8fGeESQ?V+MAGxpuQ z0m)AQIWN$Tm;fe{Rj!n z3PL)|K*B7(1_~3}?bPol>yF@qGhsg9A=U&0BQlWH9=$m2oVQ>;Fo6Lsn2bRR%$W3h zs23lS$sHpWUlK?DavIuuTM@%DOQ$}Z1U#FHESIeEojv3OxfT7Yrzo{4SkyaVLqB;~ z4%&VH=d&Zpgn3Q;{Q->Pu716p4LMK;B4%QpXE5`Q7->NkdcYj{o7632_TFc*r+|Tx!A8hHt?%`d4$olL^O?ka+1`}m&rhGd zEq9$obCMBtI&X3rim|~KBv)dfv-u~EBJDipS~*S9y|nNrXWW~*x$)a8T;(W8nEzhR zDM4fc349_Vm_^Nxq90@?+C{v^!PDnJ0P9)d-CcM01iI1Rz+`fh zL8=qDFX?oolh&(?Z^1241P`Q~h5>ygUbDl|D?G{gr-X#55)I0QhYY`xF3JU)cx2dv z;m@bJ3NaAH6{yc=m*-Q*0ZR~sGE>qPNFuPNEYcjxd{YQD(nxwPNYr(OuTZ2J&Q_si zas?)akKOIQV{- z*c78Z7<_P*qy*%FksD!xeX!%?>uaR;&}+wOLe$D)h3C=i4Lacf%yH8Qsv~V$?!B>O zRKD*Ekw4ZkEP$G&FAc{x?L5|31Qb{n2mqZDX5F$`;fnfU`2hi!GOuKhHB0M$Lw23ruyQ#xET5iwcujd;6C?JV!VN8(m}eEL)4aoGpRC6 z+r32%uUUyP^t`3Fzw+^5RpWxAOWo?~>z8i)9hRRuGmx|(u?VA$MPg+#Lli33b5H^# zv~6gs?7j~jEb~-W@hgy3)*Ks@%EggJMxWSxr3a8p*pNwdbGZnIRTD#MJw7?K z@gQ@Cyf)M@;IEbwz751ab8X(PV}lf@>())}d-KDeo+sh6jAQWPerG*wi%mWb(P> zcF6KBVEs{)A~b7A>mdRhm>~(<4lnQPQ7nC8Y#CAtWo9H0$AaMD18e;qCtx%*+-k?@4*a)_Us5H(>do}Fwiu< zKobE9t!N}+_0(pI=RjURQ9s9_eV$05pcmE^mkoFOhy-tcu2ZXgy3y2$1!Sy@b)b_z zLD=_&flw2r)hDq-M!i`3o!C4p&3#O!5%1#pc&412G37(uk+=|N(ipsbVcYpbop_u;S zNIFR>y>3_09z4{q(hZlI40UssAYj7^rZU7vMnD8o^Lg<-?gveYk*}(O0`RtEh`HO zzq$K4Ykw!4U|R$<#2nCnaJ8IiPLc&xMh=u=>M zGch9_KWi0Z+MThl3}sdm$XGTQ3UO~Wz|-8yN*mil(v?6GFqLsz-^iBgLMmLUd|JRY zF`RunSW@|xVQ{BRsQ$zNYyC2^V^Svh%@A#nRb(CS;G&Nggd>#aPrHq9NJYLaC$q(#Vokwk#mTMG#6E^ zrrF0+R9@(m-eEy1L}Z2K=_2hA9h~KAM7UH>r3Lo7c9o|Nl~t5BxSZgtCj_0tyAT|i z3SOzvwvcqnL!p1prn_nqSL?gs&jhegGBC%Vi?nT&UG0t>byzk`VQ4k!$0>@ugPBa6 zQB-&Q<2j~(I}{&p9sp5%Hp_Ove^WER&p-X-n&y76x#)?3XDITN{pB(F?14Pwf&c1< oU)W#ox&NJixQ74tHOw~-4j;B?&cfyOU2+s%X3loXnz1 cpp_cost + assert cpp_ordering_bad[0] == cpp_ordering[-1] + assert len(cpp_ordering_bad) == len(cpp_ordering) + + +@pytest.mark.parametrize("num_subgoals", [1, 2, 8, 10, 15]) +def test_subgoal_ordering_contains_all(num_subgoals): + subgoals, distances = _get_random_subgoal_data(8616, num_subgoals) + for s in subgoals: + s.prob_feasible = 1 + + cost, ordering = lsp.core.get_lowest_cost_ordering( + subgoals, distances) + + assert len(ordering) == num_subgoals diff --git a/modules/lsp/tests/test_lsp_evaluate.py b/modules/lsp/tests/test_lsp_evaluate.py new file mode 100644 index 0000000..96d1056 --- /dev/null +++ b/modules/lsp/tests/test_lsp_evaluate.py @@ -0,0 +1,145 @@ +import environments +import lsp +import numpy as np +import pytest + + +def _get_env_and_args(): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 1037 + args.map_type = 'maze' + args.step_size = 1.8 + args.num_primitives = 16 + args.field_of_view_deg = 360 + args.base_resolution = 1.0 + args.inflation_radius_m = 2.5 + args.laser_max_range_m = 120 + args.num_range = 32 + args.num_bearing = 128 + args.network_file = None + + # Create the map + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + return known_map, map_data, pose, goal, args + + +def run_planning_loop(known_map, map_data, pose, goal, args, unity_path, + planner, num_steps=None, do_plan_with_naive=False, do_yield_planner=False): + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(unity_path) as unity_bridge: + unity_bridge.make_world(world) + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge, + robot, + args, + verbose=True) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + + if do_yield_planner: + yield planner + + if planner is not None and not do_plan_with_naive: + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if num_steps is not None and counter >= num_steps: + break + + +def test_lsp_plan_loop_base_no_subgoals(do_debug_plot, unity_path): + """Confirm that planning with "no subgoals" does not crash.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + planner = lsp.planners.DijkstraPlanner(goal=goal, args=args) + run_planning_loop(known_map, map_data, pose, goal, args, unity_path, + planner, num_steps=20, do_plan_with_naive=True) + + +def test_lsp_plan_loop_base_dijkstra(do_debug_plot, unity_path): + """Confirm that planning with the Dijkstra planner does not crash.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + planner = lsp.planners.DijkstraPlanner(goal=goal, args=args) + run_planning_loop(known_map, map_data, pose, goal, args, unity_path, + planner, num_steps=20, do_plan_with_naive=False) + + +def test_lsp_plan_loop_known_sets_subgoal_nn_inputs(do_debug_plot, unity_path): + """Confirm that planning with the Dijkstra planner succeeds.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + planner = lsp.planners.KnownSubgoalPlanner(goal=goal, known_map=known_map, + args=args, verbose=True, + do_compute_weightings=True) + for planner in run_planning_loop(known_map, map_data, pose, goal, args, + unity_path, planner, num_steps=20, + do_plan_with_naive=True, + do_yield_planner=True): + + assert planner.subgoals + assert all(subgoal.props_set for subgoal in planner.subgoals) + assert all(hasattr(subgoal, 'nn_input_data') for subgoal in planner.subgoals) + + are_new_subgoals = any([subgoal.just_set for subgoal in planner.subgoals]) + are_old_subgoals = any([not subgoal.just_set for subgoal in planner.subgoals]) + + if are_new_subgoals and not are_old_subgoals: + # If there are only new subgoals, confirm that the images are the same + total_pixel_values = [subgoal.nn_input_data['image'].sum() + for subgoal in planner.subgoals] + assert np.std(total_pixel_values) == pytest.approx(0) + elif are_new_subgoals and are_old_subgoals: + # If there are both new and old subgoals, confirm that the images are different + total_pixel_values = [subgoal.nn_input_data['image'].sum() + for subgoal in planner.subgoals] + assert np.std(total_pixel_values) > 0 + for subgoal in planner.subgoals: + assert (subgoal.positive_weighting > 1 or subgoal.negative_weighting > 1) + break + + assert len(planner.subgoals) > 0 + + +def test_lsp_plan_loop_datum_correct_properties(do_debug_plot, unity_path): + """Show that we can get datum for the new subgoals.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + planner = lsp.planners.KnownSubgoalPlanner(goal=goal, known_map=known_map, + args=args, verbose=True, + do_compute_weightings=True) + for planner in run_planning_loop(known_map, map_data, pose, goal, args, + unity_path, planner, num_steps=20, + do_plan_with_naive=True, + do_yield_planner=True): + subgoal_training_data = planner.get_subgoal_training_data() + assert all('image' in datum.keys() for datum in subgoal_training_data) + assert all('goal_loc_x' in datum.keys() for datum in subgoal_training_data) + assert all('goal_loc_y' in datum.keys() for datum in subgoal_training_data) + assert all('subgoal_loc_x' in datum.keys() for datum in subgoal_training_data) + assert all('subgoal_loc_y' in datum.keys() for datum in subgoal_training_data) + assert all('is_feasible' in datum.keys() for datum in subgoal_training_data) diff --git a/modules/lsp/tests/test_lsp_utils.py b/modules/lsp/tests/test_lsp_utils.py new file mode 100644 index 0000000..e6fbe73 --- /dev/null +++ b/modules/lsp/tests/test_lsp_utils.py @@ -0,0 +1,43 @@ +import numpy as np +import random +import common +import lsp + + +def test_lsp_utils_get_oriented_input(): + """Test that the process by which we compute the input to the neural network +obeys a few properties.""" + random.seed(1234) + + num_bearing = 512 + + class Subgoal(object): + def get_centroid(self): + return self.centroid + + # If the goal is at the centroid, the vectors should have special values + # at the center of the image + do_not_match_count = 0 + num_poses = 100 + for _ in range(num_poses): + subgoal = Subgoal() + subgoal.centroid = [10 * random.random(), 10 * random.random()] + rpose = common.Pose(-5 * random.random(), -5 * random.random()) + gpose = common.Pose(subgoal.get_centroid()[0], + subgoal.get_centroid()[1]) + + gvx_r, _ = lsp.utils.learning_vision.get_rel_goal_loc_vecs( + rpose, gpose, num_bearing) + gvx_s, _ = lsp.utils.learning_vision.get_rel_goal_loc_vecs( + rpose, gpose, num_bearing, subgoal) + + cent_r = np.argmax(gvx_r) + cent_s = np.argmax(gvx_s) + + assert cent_s - num_bearing // 2 == 0 + + if not cent_r == cent_s: + do_not_match_count += 1 + assert abs(cent_r - num_bearing // 2) > 0 + + assert do_not_match_count >= 0.9 * num_poses diff --git a/modules/lsp_accel/CMakeLists.txt b/modules/lsp_accel/CMakeLists.txt new file mode 100644 index 0000000..0db0070 --- /dev/null +++ b/modules/lsp_accel/CMakeLists.txt @@ -0,0 +1,34 @@ +cmake_minimum_required(VERSION 2.8.12) +project(lsp_accel) + +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_BUILD_TYPE "Release") + +# Download pybind11 +find_package(Git QUIET) +if(GIT_FOUND AND NOT EXISTS "${PROJECT_SOURCE_DIR}/pybind11") +# Update submodules as needed + option(GIT_CLONE "Clone during build" ON) + if(GIT_CLONE) + message(STATUS "Clone update") + execute_process(COMMAND ${GIT_EXECUTABLE} clone --branch v2.2.0 https://github.com/pybind/pybind11.git + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + RESULT_VARIABLE GIT_CLONE_RESULT) + if(NOT GIT_CLONE_RESULT EQUAL "0") + message(FATAL_ERROR "git clone failed with ${GIT_CLONE_RESULT}.") + endif() + endif() +endif() + +# Why do I need this? pybind11? +link_directories(/usr/local/lib) + +# Make the library that pybind will link against +include_directories(src) + +# Include Eigen +include_directories(/usr/include/eigen3) + +# Build the python library +add_subdirectory(pybind11) +pybind11_add_module(lsp_accel NO_EXTRAS src/main.cpp) diff --git a/modules/lsp_accel/README.org b/modules/lsp_accel/README.org new file mode 100644 index 0000000..993202c --- /dev/null +++ b/modules/lsp_accel/README.org @@ -0,0 +1,3 @@ +* LSP: Learning over Subgoals Planning (C++ Code) + +C++ code called by the =lsp= module. See the [[../lsp][Learning over Subgoals Planning module]] for a full README. diff --git a/modules/lsp_accel/setup.cfg b/modules/lsp_accel/setup.cfg new file mode 100644 index 0000000..9af7e6f --- /dev/null +++ b/modules/lsp_accel/setup.cfg @@ -0,0 +1,2 @@ +[aliases] +test=pytest \ No newline at end of file diff --git a/modules/lsp_accel/setup.py b/modules/lsp_accel/setup.py new file mode 100644 index 0000000..f0240a8 --- /dev/null +++ b/modules/lsp_accel/setup.py @@ -0,0 +1,81 @@ +import os +import re +import sys +import platform +import subprocess + +from setuptools import setup, Extension +from setuptools.command.build_ext import build_ext +from distutils.version import LooseVersion + + +class CMakeExtension(Extension): + def __init__(self, name, sourcedir=''): + Extension.__init__(self, name, sources=[]) + self.sourcedir = os.path.abspath(sourcedir) + + +class CMakeBuild(build_ext): + def run(self): + try: + out = subprocess.check_output(['cmake', '--version']) + except OSError: + raise RuntimeError( + "CMake must be installed to build the following extensions: " + + ", ".join(e.name for e in self.extensions)) + + if platform.system() == "Windows": + cmake_version = LooseVersion( + re.search(r'version\s*([\d.]+)', out.decode()).group(1)) + if cmake_version < '3.1.0': + raise RuntimeError("CMake >= 3.1.0 is required on Windows") + + for ext in self.extensions: + self.build_extension(ext) + + def build_extension(self, ext): + extdir = os.path.abspath( + os.path.dirname(self.get_ext_fullpath(ext.name))) + cmake_args = [ + '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY=' + extdir, + '-DPYTHON_EXECUTABLE=' + sys.executable + ] + + cfg = 'Debug' if self.debug else 'Release' + build_args = ['--config', cfg] + + if platform.system() == "Windows": + cmake_args += [ + '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY_{}={}'.format( + cfg.upper(), extdir) + ] + if sys.maxsize > 2**32: + cmake_args += ['-A', 'x64'] + build_args += ['--', '/m'] + else: + cmake_args += ['-DCMAKE_BUILD_TYPE=' + cfg] + build_args += ['--', '-j8'] + + env = os.environ.copy() + env['CXXFLAGS'] = '{} -DVERSION_INFO=\\"{}\\"'.format( + env.get('CXXFLAGS', ''), self.distribution.get_version()) + if not os.path.exists(self.build_temp): + os.makedirs(self.build_temp) + subprocess.check_call(['cmake', ext.sourcedir] + cmake_args, + cwd=self.build_temp, + env=env) + subprocess.check_call(['cmake', '--build', '.'] + build_args, + cwd=self.build_temp) + + +setup( + name='lsp_accel', + version='0.1.0', + description='C++ accelerated functions for Subgoal Planning', + long_description='', + ext_modules=[CMakeExtension('lsp_accel')], + cmdclass=dict(build_ext=CMakeBuild), + zip_safe=False, + setup_requires=['pytest-runner'], + tests_require=['pytest'], +) diff --git a/modules/lsp_accel/src/main.cpp b/modules/lsp_accel/src/main.cpp new file mode 100644 index 0000000..21cbe14 --- /dev/null +++ b/modules/lsp_accel/src/main.cpp @@ -0,0 +1,46 @@ +#include +#include +#include +#include +#include +#include +#include +#include + + +namespace py = pybind11; + +PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr); +PYBIND11_MODULE(lsp_accel, m) { + m.doc() = R"pbdoc( + Pybind11 plugin for demonstrating C++ features + ----------------------- + + .. currentmodule:: pycpp_examples + + .. autosummary:: + :toctree: _generate + + )pbdoc"; + + py::class_>(m, "FrontierData") + .def(py::init(), + py::arg("prob_feasible"), + py::arg("delta_success_cost"), + py::arg("exploration_cost"), + py::arg("hash_id"), + py::arg("is_from_last_chosen") = 0) + .def("__hash__", &FrontierData::get_hash); + + m.def("get_lowest_cost_ordering", &get_lowest_cost_ordering); + m.def("get_lowest_cost_ordering_beginning_with", + &get_lowest_cost_ordering_beginning_with); + m.def("get_lowest_cost_ordering_not_beginning_with", + &get_lowest_cost_ordering_not_beginning_with); + +#ifdef VERSION_INFO + m.attr("__version__") = VERSION_INFO; +#else + m.attr("__version__") = "dev"; +#endif +} diff --git a/modules/lsp_accel/src/subgoal_planning.hpp b/modules/lsp_accel/src/subgoal_planning.hpp new file mode 100644 index 0000000..0c9a48c --- /dev/null +++ b/modules/lsp_accel/src/subgoal_planning.hpp @@ -0,0 +1,245 @@ +#include +#include +#include + + +struct FrontierData { + double prob_feasible; + double delta_success_cost; + double exploration_cost; + long hash_id; + bool is_from_last_chosen; + + FrontierData(double prob_feasible, + double delta_success_cost, + double exploration_cost, + long hash_id, + bool is_from_last_chosen) + : prob_feasible(prob_feasible), + delta_success_cost(delta_success_cost), + exploration_cost(exploration_cost), + hash_id(hash_id), + is_from_last_chosen(is_from_last_chosen) {} + + long get_hash() const { return hash_id; } +}; + + +typedef std::shared_ptr FrontierDataPtr; + + +struct FState { + std::vector frontier_id_list; + double cost; + double prob; + + FState(const FrontierDataPtr &new_frontier, + const std::map &robot_distances, + const std::map &goal_distances, + const std::map, double> &frontier_distances) { + // This is the first frontier, so the robot must accumulate a cost of getting to the frontier + // Known cost (travel to frontier) + double p = new_frontier->prob_feasible; + double sc = new_frontier->delta_success_cost + goal_distances.at(new_frontier->hash_id); + double ec = new_frontier->exploration_cost; + double kc = robot_distances.at(new_frontier->hash_id); + // if (new_frontier->is_from_last_chosen) { + // kc -= 10.0; + // } + + // Update the state properties + cost = kc + p * sc + (1 - p) * ec; + prob = 1 - p; + frontier_id_list.push_back(new_frontier->hash_id); + } + + FState(const FState &old_state, + const FrontierDataPtr &new_frontier, + const std::map &robot_distances, + const std::map &goal_distances, + const std::map, double> &frontier_distances) : + frontier_id_list(old_state.frontier_id_list), + cost(old_state.cost), + prob(old_state.prob) { + // Compute some intermediate properties + double p = new_frontier->prob_feasible; + double sc = new_frontier->delta_success_cost + goal_distances.at(new_frontier->hash_id); + double ec = new_frontier->exploration_cost; + + double kc = frontier_distances.at(std::pair( + new_frontier->hash_id, frontier_id_list.back())); + + cost += prob * (kc + p * sc + (1 - p) * ec); + prob *= (1 - p); + frontier_id_list.push_back(new_frontier->hash_id); + } + + bool operator<(const FState &other) { + return cost < other.cost; + } + +}; + + +FState get_lowest_cost_ordering_sub( + const FState &prev_state, + const std::vector &frontiers, + const std::map &robot_distances, + const std::map &goal_distances, + const std::map, double> &frontier_distances, + double *bound) { + if (frontiers.size() == 1) { + FState state(prev_state, + frontiers[0], + robot_distances, + goal_distances, + frontier_distances); + *bound = std::min(*bound, state.cost); + return state; + } + + if (prev_state.cost > *bound) { + return prev_state; + } + + // If the cost is sufficiently low, avoid exhaustive planning, since it will make only + // an insignificant cost difference at the expense of computation. However, we append + // the remaining frontiers to the policy so that the length of the policy is the same + // as the number of frontiers (and none are thrown away), important for some + // applications. + if (prev_state.prob < 1.0e-12) { + std::vector sub_frontiers; + std::copy(frontiers.begin() + 1, frontiers.end(), std::back_inserter(sub_frontiers)); + FState state = FState(prev_state, + frontiers[0], + robot_distances, + goal_distances, + frontier_distances); + return get_lowest_cost_ordering_sub( + state, + sub_frontiers, + robot_distances, + goal_distances, + frontier_distances, + bound); + } + + std::vector best_states; + for (auto f_it = frontiers.begin(); f_it != frontiers.end(); ++f_it) { + std::vector sub_frontiers; + std::copy(frontiers.begin(), f_it, std::back_inserter(sub_frontiers)); + std::copy(f_it + 1, frontiers.end(), std::back_inserter(sub_frontiers)); + + FState state = FState(prev_state, + *f_it, + robot_distances, + goal_distances, + frontier_distances); + best_states.push_back(get_lowest_cost_ordering_sub( + state, + sub_frontiers, + robot_distances, + goal_distances, + frontier_distances, + bound)); + } + return *(std::min_element(best_states.begin(), best_states.end())); +} + + +std::pair> get_lowest_cost_ordering( + const std::vector &frontiers, + const std::map &robot_distances, + const std::map &goal_distances, + const std::map, double> &frontier_distances) { + std::vector best_states; + double bound = 1.0e10; + for (auto f_it = frontiers.begin(); f_it != frontiers.end(); ++f_it) { + std::vector sub_frontiers; + std::copy(frontiers.begin(), f_it, std::back_inserter(sub_frontiers)); + std::copy(f_it + 1, frontiers.end(), std::back_inserter(sub_frontiers)); + + FState state = FState(*f_it, + robot_distances, + goal_distances, + frontier_distances); + if (sub_frontiers.size() == 0) { + best_states.push_back(state); + break; + } + + best_states.push_back(get_lowest_cost_ordering_sub( + state, + sub_frontiers, + robot_distances, + goal_distances, + frontier_distances, + &bound)); + } + auto sout = std::min_element(best_states.begin(), best_states.end()); + return std::make_pair(sout->cost, sout->frontier_id_list); +} + + +std::pair> get_lowest_cost_ordering_beginning_with( + const FrontierDataPtr &frontier_of_interest, + const std::vector &frontiers, + const std::map &robot_distances, + const std::map &goal_distances, + const std::map, double> &frontier_distances) { + std::vector best_states; + double bound = 1.0e10; + + FState state = FState(frontier_of_interest, + robot_distances, + goal_distances, + frontier_distances); + + FState sout = get_lowest_cost_ordering_sub( + state, + frontiers, + robot_distances, + goal_distances, + frontier_distances, + &bound); + return std::make_pair(sout.cost, sout.frontier_id_list); +} + + +std::pair> get_lowest_cost_ordering_not_beginning_with( + const FrontierDataPtr &frontier_to_avoid, + const std::vector &frontiers, + const std::map &robot_distances, + const std::map &goal_distances, + const std::map, double> &frontier_distances) { + std::vector best_states; + double bound = 1.0e10; + for (auto f_it = frontiers.begin(); f_it != frontiers.end(); ++f_it) { + if ((*f_it)->hash_id == frontier_to_avoid->hash_id) { + continue; + } + + std::vector sub_frontiers; + std::copy(frontiers.begin(), f_it, std::back_inserter(sub_frontiers)); + std::copy(f_it + 1, frontiers.end(), std::back_inserter(sub_frontiers)); + + FState state = FState(*f_it, + robot_distances, + goal_distances, + frontier_distances); + if (sub_frontiers.size() == 0) { + best_states.push_back(state); + break; + } + + best_states.push_back(get_lowest_cost_ordering_sub( + state, + sub_frontiers, + robot_distances, + goal_distances, + frontier_distances, + &bound)); + } + auto sout = std::min_element(best_states.begin(), best_states.end()); + return std::make_pair(sout->cost, sout->frontier_id_list); +} diff --git a/modules/lsp_gnn/Makefile.mk b/modules/lsp_gnn/Makefile.mk new file mode 100644 index 0000000..a317e31 --- /dev/null +++ b/modules/lsp_gnn/Makefile.mk @@ -0,0 +1,344 @@ +help:: + @echo "Learned Subgoal Planning using GNN(lsp-gnn):" + @echo " lsp-gnn-jshaped Runs the 'J-intersection' experiments." + @echo " lsp-gnn-parallel Runs the 'Parallel hallway' experiments." + @echo " lsp-gnn-floorplans Runs the 'University building floorplans' experiments." + @echo " lsp-gnn Runs the experiments in all 3 environments." + +LSP_WEIGHT ?= 1 +LOC_WEIGHT ?= 1 +LOSS ?= l1 +RPW ?= 1 +INPUT_TYPE ?= wall_class +LSP_GNN_CORE_ARGS ?= --unity_path /unity/$(UNITY_BASENAME).x86_64 \ + --save_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/ \ + --base_resolution 0.4 \ + --inflation_radius_m 0.75 \ + --field_of_view_deg 360 \ + --laser_max_range_m 12 \ + --pickle_directory data_pickles + +LSP_GNN_TRAINING_ARGS ?= $(LSP_GNN_CORE_ARGS) \ + --lsp_weight $(LSP_WEIGHT) \ + --loc_weight $(LOC_WEIGHT) \ + --loss $(LOSS) \ + --relative_positive_weight $(RPW) \ + --input_type $(INPUT_TYPE) + +#---=== J-Intersection Environment Experiments ===---# +LSP_GNN_JSHAPED_BASENAME ?= lsp_gnn/jshaped +LSP_GNN_JSHAPED_NUM_TRAINING_SEEDS ?= 200 +LSP_GNN_JSHAPED_NUM_TESTING_SEEDS ?= 50 +LSP_GNN_JSHAPED_NUM_EVAL_SEEDS ?= 100 + +lsp-gnn-jshaped-data-gen-seeds = \ + $(shell for ii in $$(seq 0000 $$((0000 + $(LSP_GNN_JSHAPED_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/data_completion_logs/data_training_$${ii}.txt"; done) \ + $(shell for ii in $$(seq 30000 $$((30000 + $(LSP_GNN_JSHAPED_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/data_completion_logs/data_testing_$${ii}.txt"; done) + +$(lsp-gnn-jshaped-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-gnn-jshaped-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-gnn-jshaped-data-gen-seeds): + @echo "Generating Data [$(LSP_GNN_JSHAPED_BASENAME) | seed: $(seed) | $(traintest)"] + @$(call xhost_activate) + @-rm -f $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/data_$(traintest)_$(seed).csv + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/pickles + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/data_completion_logs + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/error_logs + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.gen_data \ + $(LSP_GNN_CORE_ARGS) \ + --map_type jshaped \ + --current_seed $(seed) \ + --data_file_base_name data_$(traintest) \ + --save_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/ + +lsp-gnn-jshaped-autoencoder-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt +$(lsp-gnn-jshaped-autoencoder-train-file): $(lsp-gnn-jshaped-data-gen-seeds) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 28000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 7000 \ + --save_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/ + +lsp-gnn-jshaped-cnn-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt +$(lsp-gnn-jshaped-cnn-train-file): $(lsp-gnn-jshaped-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 16000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 4000 \ + --autoencoder_network_file /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_cnn_lsp \ + --save_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/ + +lsp-gnn-jshaped-marginal-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt +$(lsp-gnn-jshaped-marginal-train-file): $(lsp-gnn-jshaped-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 16000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 4000 \ + --autoencoder_network_file /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_marginal_lsp \ + --save_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/ + +lsp-gnn-jshaped-eval-seeds = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_GNN_JSHAPED_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/results/$(EXPERIMENT_NAME)/jshaped_learned_$${ii}.png"; done) +$(lsp-gnn-jshaped-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-gnn-jshaped-eval-seeds): $(lsp-gnn-jshaped-cnn-train-file) +$(lsp-gnn-jshaped-eval-seeds): $(lsp-gnn-jshaped-marginal-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_JSHAPED_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.evaluate_all \ + $(LSP_GNN_CORE_ARGS) \ + --input_type $(INPUT_TYPE) \ + --map_type jshaped \ + --current_seed $(seed) \ + --image_filename jshaped_learned_$(seed).png \ + --save_dir /data/$(LSP_GNN_JSHAPED_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/model.pt \ + --cnn_network_file /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt \ + --gcn_network_file /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt \ + --autoencoder_network_file /data/$(LSP_GNN_JSHAPED_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + +.PHONY: lsp-gnn-jshaped-results +lsp-gnn-jshaped-results: + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.plotting \ + --data_file /data/$(LSP_GNN_JSHAPED_BASENAME)/results/$(EXPERIMENT_NAME)/logfile.txt \ + --output_image_file /data/$(LSP_GNN_JSHAPED_BASENAME)/results/jshaped_results_$(EXPERIMENT_NAME).png \ + --base_resolution 0.4 + + +#---=== Parallel Hallway Environment Experiments ===---# +LSP_GNN_PH_BASENAME ?= lsp_gnn/parallel +LSP_GNN_PH_NUM_TRAINING_SEEDS ?= 1000 +LSP_GNN_PH_NUM_TESTING_SEEDS ?= 500 +LSP_GNN_PH_NUM_EVAL_SEEDS ?= 500 + +lsp-gnn-ph-data-gen-seeds = \ + $(shell for ii in $$(seq 0000 $$((0000 + $(LSP_GNN_PH_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/data_completion_logs/data_training_$${ii}.txt"; done) \ + $(shell for ii in $$(seq 30000 $$((30000 + $(LSP_GNN_PH_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/data_completion_logs/data_testing_$${ii}.txt"; done) + +$(lsp-gnn-ph-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-gnn-ph-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-gnn-ph-data-gen-seeds): + @echo "Generating Data [$(LSP_GNN_PH_BASENAME) | seed: $(seed) | $(traintest)"] + @$(call xhost_activate) + @-rm -f $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/data_$(traintest)_$(seed).csv + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/pickles + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/data_completion_logs + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/error_logs + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.gen_data \ + $(LSP_GNN_CORE_ARGS) \ + --map_type new_office \ + --current_seed $(seed) \ + --data_file_base_name data_$(traintest) \ + --save_dir /data/$(LSP_GNN_PH_BASENAME)/ + +lsp-gnn-ph-autoencoder-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt +$(lsp-gnn-ph-autoencoder-train-file): $(lsp-gnn-ph-data-gen-seeds) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 28000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 7000 \ + --save_dir /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_PH_BASENAME)/ + +lsp-gnn-ph-cnn-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt +$(lsp-gnn-ph-cnn-train-file): $(lsp-gnn-ph-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_cnn_lsp \ + --save_dir /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_PH_BASENAME)/ + +lsp-gnn-ph-marginal-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt +$(lsp-gnn-ph-marginal-train-file): $(lsp-gnn-ph-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_marginal_lsp \ + --save_dir /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_PH_BASENAME)/ + +lsp-gnn-ph-eval-seeds = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_GNN_PH_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/results/$(EXPERIMENT_NAME)/parallel_learned_$${ii}.png"; done) +$(lsp-gnn-ph-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-gnn-ph-eval-seeds): $(lsp-gnn-ph-cnn-train-file) +$(lsp-gnn-ph-eval-seeds): $(lsp-gnn-ph-marginal-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_PH_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.evaluate_all \ + $(LSP_GNN_CORE_ARGS) \ + --input_type $(INPUT_TYPE) \ + --map_type new_office \ + --current_seed $(seed) \ + --image_filename parallel_learned_$(seed).png \ + --save_dir /data/$(LSP_GNN_PH_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/model.pt \ + --cnn_network_file /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt \ + --gcn_network_file /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt \ + --autoencoder_network_file /data/$(LSP_GNN_PH_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + +.PHONY: lsp-gnn-ph-results +lsp-gnn-ph-results: + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.plotting \ + --data_file /data/$(LSP_GNN_PH_BASENAME)/results/$(EXPERIMENT_NAME)/logfile.txt \ + --output_image_file /data/$(LSP_GNN_PH_BASENAME)/results/parallel_results_$(EXPERIMENT_NAME).png \ + --base_resolution 0.4 + + +#---=== University Building Floorplans Experiments ===---# +LSP_GNN_FLOORPLANS_BASENAME ?= lsp_gnn/floorplans +LSP_GNN_FLOORPLANS_NUM_TRAINING_SEEDS ?= 1000 +LSP_GNN_FLOORPLANS_NUM_TESTING_SEEDS ?= 500 +LSP_GNN_FLOORPLANS_NUM_EVAL_SEEDS ?= 500 + +lsp-gnn-floorplans-data-gen-seeds = \ + $(shell for ii in $$(seq 0000 $$((0000 + $(LSP_GNN_FLOORPLANS_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/data_completion_logs/data_training_$${ii}.txt"; done) \ + $(shell for ii in $$(seq 30000 $$((30000 + $(LSP_GNN_FLOORPLANS_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/data_completion_logs/data_testing_$${ii}.txt"; done) + +$(lsp-gnn-floorplans-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-gnn-floorplans-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-gnn-floorplans-data-gen-seeds): + @echo "Generating Data [$(LSP_GNN_FLOORPLANS_BASENAME) | seed: $(seed) | $(traintest)"] + @$(call xhost_activate) + @-rm -f $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/data_$(traintest)_$(seed).csv + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/pickles + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/data_completion_logs + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/error_logs + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.gen_data \ + $(LSP_GNN_CORE_ARGS) \ + --map_type ploader \ + --base_resolution 0.1 \ + --current_seed $(seed) \ + --data_file_base_name data_$(traintest) \ + --save_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/ + +lsp-gnn-floorplans-autoencoder-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt +$(lsp-gnn-floorplans-autoencoder-train-file): $(lsp-gnn-floorplans-data-gen-seeds) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 28000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 7000 \ + --save_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/ + +lsp-gnn-floorplans-cnn-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt +$(lsp-gnn-floorplans-cnn-train-file): $(lsp-gnn-floorplans-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_cnn_lsp \ + --save_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/ + +lsp-gnn-floorplans-marginal-train-file = $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt +$(lsp-gnn-floorplans-marginal-train-file): $(lsp-gnn-floorplans-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.train \ + $(LSP_GNN_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_marginal_lsp \ + --save_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/ + +lsp-gnn-floorplans-eval-seeds = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_GNN_FLOORPLANS_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/results/$(EXPERIMENT_NAME)/floorplan_learned_$${ii}.png"; done) +$(lsp-gnn-floorplans-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-gnn-floorplans-eval-seeds): $(lsp-gnn-floorplans-cnn-train-file) +$(lsp-gnn-floorplans-eval-seeds): $(lsp-gnn-floorplans-marginal-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_GNN_FLOORPLANS_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.evaluate_all \ + $(LSP_GNN_CORE_ARGS) \ + --input_type $(INPUT_TYPE) \ + --map_type ploader \ + --base_resolution 0.1 \ + --current_seed $(seed) \ + --image_filename floorplan_learned_$(seed).png \ + --save_dir /data/$(LSP_GNN_FLOORPLANS_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/model.pt \ + --cnn_network_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt \ + --gcn_network_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt \ + --autoencoder_network_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + +.PHONY: lsp-gnn-floorplans-results +lsp-gnn-floorplans-results: + @$(DOCKER_PYTHON) -m lsp_gnn.scripts.plotting \ + --data_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/results/$(EXPERIMENT_NAME)/logfile.txt \ + --output_image_file /data/$(LSP_GNN_FLOORPLANS_BASENAME)/results/floorplans_results_$(EXPERIMENT_NAME).png \ + --base_resolution 0.1 + + +# ==== Helper Targets ==== +.PHONY: lsp-gnn-jshaped-data-gen lsp-gnn-jshaped-train lsp-gnn-jshaped-eval lsp-gnn-jshaped-results lsp-gnn-jshaped +lsp-gnn-jshaped-data-gen: $(lsp-gnn-jshaped-data-gen-seeds) +lsp-gnn-jshaped-train: DOCKER_ARGS ?= -it +lsp-gnn-jshaped-train: $(lsp-gnn-jshaped-cnn-train-file) +lsp-gnn-jshaped-train: $(lsp-gnn-jshaped-marginal-train-file) +lsp-gnn-jshaped-eval: $(lsp-gnn-jshaped-eval-seeds) +lsp-gnn-jshaped: lsp-gnn-jshaped-eval + $(MAKE) lsp-gnn-jshaped-results + +.PHONY: lsp-gnn-ph-data-gen lsp-gnn-ph-train lsp-gnn-ph-eval lsp-gnn-ph-results lsp-gnn-ph +lsp-gnn-ph-data-gen: $(lsp-gnn-ph-data-gen-seeds) +lsp-gnn-ph-train: DOCKER_ARGS ?= -it +lsp-gnn-ph-train: $(lsp-gnn-ph-cnn-train-file) +lsp-gnn-ph-train: $(lsp-gnn-ph-marginal-train-file) +lsp-gnn-ph-eval: $(lsp-gnn-ph-eval-seeds) +lsp-gnn-ph: lsp-gnn-ph-eval + $(MAKE) lsp-gnn-ph-results + +.PHONY: lsp-gnn-floorplans-data-gen lsp-gnn-floorplans-train lsp-gnn-floorplans-eval lsp-gnn-floorplans-results lsp-gnn-floorplans +lsp-gnn-floorplans-data-gen: $(lsp-gnn-floorplans-data-gen-seeds) +lsp-gnn-floorplans-train: DOCKER_ARGS ?= -it +lsp-gnn-floorplans-train: $(lsp-gnn-floorplans-cnn-train-file) +lsp-gnn-floorplans-train: $(lsp-gnn-floorplans-marginal-train-file) +lsp-gnn-floorplans-eval: $(lsp-gnn-floorplans-eval-seeds) +lsp-gnn-floorplans: lsp-gnn-floorplans-eval + $(MAKE) lsp-gnn-floorplans-results + +.PHONY: lsp-gnn +lsp-gnn: lsp-gnn-jshaped-eval lsp-gnn-ph-eval lsp-gnn-floorplans-eval + $(MAKE) lsp-gnn-jshaped-results + $(MAKE) lsp-gnn-ph-results + $(MAKE) lsp-gnn-floorplans-results diff --git a/modules/lsp_gnn/README.org b/modules/lsp_gnn/README.org new file mode 100644 index 0000000..76b3f89 --- /dev/null +++ b/modules/lsp_gnn/README.org @@ -0,0 +1,38 @@ +* LSP-GNN: Learning over Subgoals Planning using Graph Neural Network + +Algorithmic code pertaining to the LSP-GNN algorithm for learning-augmented, model-based planning using non-local information in partially-mapped environments. This module reproduces core algorithm and results presented in the following paper: + +Raihan Islam Arnob and Gregory J. Stein. "Improving Reliable Navigation under Uncertainty via Predictions Informed by Non-Local Information." International Conference on Intelligent Robots and Systems (IROS). 2023. *paper forthcoming*. + +#+begin_src bibtex +@inproceedings{arnob2023lspgnn, + title={Improving Reliable Navigation under Uncertainty via Predictions Informed by Non-Local Information}, + author={Arnob, Raihan Islam and Stein, Gregory J}, + booktitle={International Conference on Intelligent Robots and Systems (IROS)}, + year={2023}, +} +#+end_src + +Readers are referred to the paper for algorithmic details. + +** Usage +*** Reproducing Results + +Note: =make build= (see top-level README) must be successfully run before running the following commands. + +The =Makefile.mk= provides multiple targets for reproducing results. + +- =make lsp-gnn-jshaped= will generate results from our =J-Intersection= environment, in which the color of the non-local observation at the intersection indicates the correct route to the unseen goal. The target first generates training data (both with the known map and via optimistic planning through similar environments), then trains a graph neural network to predict subgoal properties (predictions about the goodness of actions that enter unseen space), then evaluates performance using the trained neural network. Upon completing evaluation, it generates statistics and a scatterplot comparing the results with and without the learned model. +- =make lsp-gnn-ph= will generate results in the =Parallel Hallway= environment: procedurally generated parallel hallway-like maps. The process is similar to the above. +- =make lsp-gnn-floorplans= * will generate results in the =University Building Floorplans= environment: real world university building floorplans. The process is similar to the above. +- =make lsp-gnn= * will generate results in all three environments. + +/* In order for the floorplans or combined target the extracted version of university_building_floorplans must exist inside /data/lsp_gnn/ + +All targets are run in single-threaded mode by default, however both data generation and evaluation can be run on multiple seeds in parallel. As such, running =make lsp-gnn-jshaped -j3= will run three concurrent instances. As data generation has a smaller VRAM footprint than does evaluation, it is often possible to run more concurrent instances specifically for data generation: + +#+begin_src bash +make build +make lsp-gnn-jshaped-data-gen -j6 +make lsp-gnn-jshaped -j3 +#+end_src diff --git a/modules/lsp_gnn/lsp_gnn/__init__.py b/modules/lsp_gnn/lsp_gnn/__init__.py new file mode 100644 index 0000000..ff03a4c --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/__init__.py @@ -0,0 +1,7 @@ +from . import learning # noqa +from . import utils # noqa +from . import planners # noqa +from . import scripts # noqa +from . import core # noqa +from . import plotting # noqa +from . import environments # noqa diff --git a/modules/lsp_gnn/lsp_gnn/core.py b/modules/lsp_gnn/lsp_gnn/core.py new file mode 100644 index 0000000..0b9830e --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/core.py @@ -0,0 +1,279 @@ +import lsp +import lsp_gnn +import numpy as np + + +IS_FROM_LAST_CHOSEN_REWARD = 1 * 10.0 # Fix me: See if it was really helping + + +class RolloutState(object): + """Used to conviently store the 'state' during recursive cost search. + """ + def __init__(self, subgoal_props, distances, frontier_idx, subgoals, old_state=None): + if old_state is None: + # create the history tuple + self.history = [1] * len(list(subgoal_props.keys())[0]) + else: + # update history in accordance with previous subgoal + self.history = old_state.history.copy() + self.history[old_state.frontier_list[-1]] = 0 + + nf = subgoal_props[tuple(self.history)][frontier_idx] + p = nf[0] # set the prob_feasible of the frontier in p + # Success cost + sc = nf[1] + distances['goal'][frontier_idx] + # Exploration cost + ec = nf[2] + + if old_state is not None: + self.frontier_list = old_state.frontier_list + [frontier_idx] + # Store the old frontier + of = old_state.frontier_list[-1] + # Known cost (travel between frontiers) + kc = distances['frontier'][frozenset([frontier_idx, of])] + self.cost = old_state.cost + old_state.prob * (kc + p * sc + + (1 - p) * ec) + self.prob = old_state.prob * (1 - p) + else: + # This is the first frontier, so the robot must accumulate a + # cost of getting to the frontier + self.frontier_list = [frontier_idx] + # Known cost (travel to frontier) + kc = distances['robot'][frontier_idx] + if subgoals[frontier_idx].is_from_last_chosen: + kc -= IS_FROM_LAST_CHOSEN_REWARD + self.cost = kc + p * sc + (1 - p) * ec + self.prob = (1 - p) + + def __lt__(self, other): + return self.cost < other.cost + + +def get_lowest_cost_ordering(subgoal_props, distances, subgoals): + """Recursively compute the lowest cost ordering of provided frontiers. + """ + def get_ordering_sub(frontiers, state=None): + """Sub-function defined for recursion. Property 'bound' is set for + branch-and-bound, which vastly speeds up computation in practice.""" + if len(frontiers) == 1: + s = RolloutState( + subgoal_props=subgoal_props, + distances=distances, + frontier_idx=frontiers[0], + subgoals=subgoals, + old_state=state) + get_ordering_sub.bound = min(s.cost, get_ordering_sub.bound) + return s + + if state is not None and state.cost > get_ordering_sub.bound: + return state + + try: + return min([ + get_ordering_sub( + [fn for fn in frontiers if fn != f], + RolloutState( + subgoal_props=subgoal_props, + distances=distances, + frontier_idx=f, + subgoals=subgoals, + old_state=state + ) + ) + for f in frontiers + ]) + except ValueError: + return None + + length_of_frontiers = len(list(subgoal_props.keys())[0]) + # print('length_of_frontiers: ', length_of_frontiers) + initial_history = tuple([1] * length_of_frontiers) + frontiers = list(range(length_of_frontiers)) + get_ordering_sub.bound = 1e10 + h = { + s: distances['goal'][s] + distances['robot'][s] + + subgoal_props[initial_history][s][0] * subgoal_props[initial_history][s][1] + + (1 - subgoal_props[initial_history][s][0]) * subgoal_props[initial_history][s][2] + for s in frontiers + } + frontiers.sort(reverse=False, key=lambda s: h[s]) + + best_state = get_ordering_sub(frontiers) + if best_state is None: + return None, None + else: + return best_state.cost, best_state.frontier_list + + +def get_new_conditional_data(subgoals, new_data, history): + """ This method creates data later to be used by planning + Takes input of + 1. The subgoals + 2. Data dictonary build only using the subgoal + 3. The history mapped from the history used in GCN + i.e., if in gcn history was [0, 0, 1] where the first value is for + a structural node and later two are for two subgoal nodes [s2, s1], + then the history passed to planning is [1, 0] for the subgoal + order [s1, s2] + """ + conditional_subgoal_props = np.array([[subgoal.prob_feasible, + subgoal.delta_success_cost, + subgoal.exploration_cost] # Nx3 + for subgoal in subgoals]) + new_data[tuple(history)] = conditional_subgoal_props + + +def convert_old_distance_to_new_distance(frontiers, old_distances): + subgoal_ind_dict = {subgoal: ii for ii, subgoal in enumerate(frontiers)} + new_distances = {} + new_distances['goal'] = { + subgoal_ind_dict[subgoal]: goal_dist + for subgoal, goal_dist in old_distances['goal'].items() + if subgoal in frontiers + } + new_distances['robot'] = { + subgoal_ind_dict[subgoal]: robot_dist + for subgoal, robot_dist in old_distances['robot'].items() + if subgoal in frontiers + } + if old_distances['frontier']: # In case there is only one frontier + new_distances['frontier'] = { + frozenset([subgoal_ind_dict[s] for s in old_key if s in frontiers]): subgoal_dist + for old_key, subgoal_dist in old_distances['frontier'].items()} + return new_distances + + +def get_top_n_frontiers(frontiers, goal_dist, robot_dist, n): + """This heuristic is for retrieving the 'best' N frontiers""" + + # This sorts the frontiers by (1) any frontiers that "derive their + # properties" from the last chosen frontier and (2) the probablity that the + # frontiers lead to the goal. + frontiers = [f for f in frontiers if f.prob_feasible > 0] + + h_prob = {s: s.prob_feasible for s in frontiers} + try: + h_dist = {s: goal_dist[s] + robot_dist[s] for s in frontiers} + except KeyError: + h_dist = {s: goal_dist[s.id] + robot_dist[s.id] for s in frontiers} + + fs_prob = sorted(list(frontiers), key=lambda s: h_prob[s], reverse=True) + fs_dist = sorted(list(frontiers), key=lambda s: h_dist[s], reverse=False) + + seen = set() + fs_collated = [] + + for front_d in fs_dist[:2]: + if front_d not in seen: + seen.add(front_d) + fs_collated.append(front_d) + + for front_p in fs_prob: + if front_p not in seen: + seen.add(front_p) + fs_collated.append(front_p) + + assert len(fs_collated) == len(seen) + assert len(fs_collated) == len(fs_prob) + assert len(fs_collated) == len(fs_dist) + + return fs_collated[0:n] + + +def get_best_expected_cost_and_frontier_list(grid, + robot_pose, + goal_pose, + frontiers, + vertex_points, + subgoal_nodes, + gcn_graph_input, + subgoal_property_net, + num_frontiers_max=0, + downsample_factor=1): + """Compute the best frontier using the LSP algorithm.""" + + initial_frontiers = [f for f in frontiers] # Change it to all frontiers + # Remove frontiers that are infeasible + frontiers = [f for f in frontiers if f.prob_feasible != 0] + + # Calculate the distance to the goal, if infeasible, remove frontier + goal_distances = lsp.core.get_goal_distances( + grid, goal_pose, frontiers=frontiers, + downsample_factor=downsample_factor + ) + frontiers = [f for f in frontiers if f.prob_feasible != 0] + + robot_distances = lsp.core.get_robot_distances( + grid, robot_pose, frontiers=frontiers, + downsample_factor=downsample_factor + ) + # Get the most n probable frontiers to limit computational load + if num_frontiers_max > 0 and num_frontiers_max < len(frontiers): + # print("Took top 8 frontiers") + top_frontiers = get_top_n_frontiers(frontiers, goal_distances, + robot_distances, num_frontiers_max) + frontiers = [f for f in frontiers if f in top_frontiers] + + # Calculate robot and frontier distances + frontier_distances = lsp.core.get_frontier_distances( + grid, frontiers=frontiers, downsample_factor=downsample_factor) + + # Make one last pass to eliminate infeasible frontiers + frontiers = [f for f in frontiers if f.prob_feasible != 0] + old_distances = { + 'frontier': frontier_distances, + 'robot': robot_distances, + 'goal': goal_distances, + } + distances = convert_old_distance_to_new_distance(frontiers, old_distances) + + # Fix the 'history' vector for the pruned subgoal before generating + # the rollout histories + # vertex_count = len(gcn_graph_input['is_subgoal']) + new_initial_history = gcn_graph_input['history'].copy() + subgoals = list(subgoal_nodes.values()) + subgoal_vertices = list(subgoal_nodes.keys()) + list_of_vertex_points = vertex_points.tolist() + for f in initial_frontiers: + if f not in frontiers: + lookup_vertex = list(subgoal_vertices[subgoals.index(f)]) + index = list_of_vertex_points.index(lookup_vertex) + new_initial_history[index] = 0 + + # Estimate properties of all subgoals for all history rollout histories + new_data = {} + # Need to calculate the histories first + all_history = lsp_gnn.utils. \ + generate_all_rollout_history(new_initial_history) + + for history in all_history: + gcn_graph_input['history'] = history + prob_feasible_dict, dsc, ec, _ = subgoal_property_net( + datum=gcn_graph_input, + vertex_points=vertex_points, + subgoals=frontiers) + + # Creating history for new data + history_for_new_data_key = [] + for subgoal in frontiers: + possible_node = lsp_gnn.utils. \ + get_subgoal_node(vertex_points, subgoal).tolist() + index = list_of_vertex_points.index(possible_node) + history_for_new_data_key.append( + gcn_graph_input['history'][index] + ) + subgoal.set_props( + prob_feasible=prob_feasible_dict[subgoal], + delta_success_cost=dsc[subgoal], + exploration_cost=ec[subgoal]) + lsp_gnn.core.get_new_conditional_data( + subgoals=frontiers, + new_data=new_data, + history=history_for_new_data_key + ) + + conditional_out = lsp_gnn.core.get_lowest_cost_ordering(new_data, distances, frontiers) + # return conditional_out + return (conditional_out[0], + [initial_frontiers.index(frontiers[co_ind]) + for co_ind in conditional_out[1]]) diff --git a/modules/lsp_gnn/lsp_gnn/environments/__init__.py b/modules/lsp_gnn/lsp_gnn/environments/__init__.py new file mode 100644 index 0000000..7bc3c0f --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/environments/__init__.py @@ -0,0 +1,4 @@ +from . import jshaped # noqa +from . import generate # noqa +from . import parallel_hallway # noqa +from . import modified_office # noqa diff --git a/modules/lsp_gnn/lsp_gnn/environments/generate.py b/modules/lsp_gnn/lsp_gnn/environments/generate.py new file mode 100644 index 0000000..81ce394 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/environments/generate.py @@ -0,0 +1,50 @@ +"""Primary functions for dispatching map generation.""" +from gridmap.utils import inflate_grid +from gridmap.planning import compute_cost_grid_from_position +import common +import lsp_gnn +import numpy as np +import random + + +def MapGenerator(args): + if args.map_type.lower() == 'jshaped': + return lsp_gnn.environments.jshaped.MapGenJshaped(args) + elif args.map_type.lower() == 'new_office': + return lsp_gnn.environments.parallel_hallway.MapGenParallel(args) + else: + raise ValueError('Map type "%s" not recognized' % args.map_type) + + +def map_and_poses(args, num_attempts=10, Pose=common.Pose): + seed = args.current_seed + random.seed(seed) + np.random.seed(seed) + """Helper function that generates a map and feasible start end poses""" + + # Generate a new map + map_generator = MapGenerator(args) + _, grid, map_data = map_generator.gen_map(random_seed=args.current_seed) + + # Initialize the sensor/robot variables + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_known_grid = inflate_grid(grid, inflation_radius=inflation_radius) + + # Get the poses (ensure they are connected) + for _ in range(num_attempts): + did_succeed, start, goal = map_generator.get_start_goal_poses() + if not did_succeed: + continue + + cost_grid, get_path = compute_cost_grid_from_position( + inflated_known_grid, [goal.x, goal.y]) + did_plan, _ = get_path([start.x, start.y], + do_sparsify=False, + do_flip=False) + if did_plan: + break + else: + raise RuntimeError("Could not find a pair of poses that " + "connect during start/goal pose generation.") + + return grid, map_data, start, goal diff --git a/modules/lsp_gnn/lsp_gnn/environments/jshaped.py b/modules/lsp_gnn/lsp_gnn/environments/jshaped.py new file mode 100644 index 0000000..884913e --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/environments/jshaped.py @@ -0,0 +1,191 @@ +import math +import numpy as np +import random + +from common import Pose +from environments import base_generator +from environments.utils import calc + + +def gen_map_jshaped_base(resolution=0.4, + random_seed=None): + def draw_horizontal(grid, x1, y1, x2, y2, width=10, value=1): + grid[x1:x1 + width, y1:y2] = value + + def draw_vertical(grid, x1, y1, x2, y2, width=10, value=1): + grid[x1:x2, y1:y1 + width] = value + + def goal_on_right_map(width=10): + grid = np.zeros((100, 110)) + draw_horizontal(grid, x1=80, y1=10, x2=width, y2=50) + draw_horizontal(grid, x1=80, y1=51, x2=width, y2=100) + draw_vertical(grid, x1=10, y1=10, x2=80, y2=width) + draw_vertical(grid, x1=10, y1=90, x2=80, y2=width) + draw_horizontal(grid, x1=10, y1=10, x2=width, y2=100) + draw_vertical(grid, x1=10, y1=50, x2=70, y2=width) + draw_vertical(grid, x1=30, y1=30, x2=60, y2=width) + draw_horizontal(grid, x1=60, y1=30, x2=width, y2=50) + return 1 - grid + + def goal_on_left_map(width=10): + grid = np.zeros((100, 110)) + draw_horizontal(grid, x1=80, y1=10, x2=width, y2=59) + draw_vertical(grid, x1=10, y1=10, x2=80, y2=width) + draw_horizontal(grid, x1=80, y1=60, x2=width, y2=100) + draw_vertical(grid, x1=10, y1=90, x2=80, y2=width) + draw_horizontal(grid, x1=10, y1=10, x2=width, y2=50) + draw_horizontal(grid, x1=10, y1=60, x2=width, y2=100) + draw_vertical(grid, x1=10, y1=50, x2=70, y2=width) + draw_vertical(grid, x1=30, y1=30, x2=60, y2=width) + draw_horizontal(grid, x1=60, y1=30, x2=width, y2=50) + return 1 - grid + + def apply_color_path_right(map, width=10, color=.5): + draw_horizontal(map, x1=80, y1=10, x2=width, y2=50, value=color) + draw_vertical(map, x1=10, y1=10, x2=80, y2=width, value=color) + draw_horizontal(map, x1=10, y1=10, x2=width, y2=55, value=color) + return map + + def apply_color_path_right2(map, width=10, color=.5): + draw_horizontal(map, x1=80, y1=51, x2=width, y2=100, value=color) + draw_vertical(map, x1=10, y1=90, x2=80, y2=width, value=color) + draw_horizontal(map, x1=10, y1=55, x2=width, y2=100, value=color) + return map + + def apply_color_path_left(map, width=10, color=.5): + draw_horizontal(map, x1=80, y1=60, x2=width, y2=100, value=color) + draw_vertical(map, x1=10, y1=90, x2=80, y2=width, value=color) + draw_horizontal(map, x1=10, y1=55, x2=width, y2=100, value=color) + return map + + def apply_color_path_left2(map, width=10, color=.5): + draw_horizontal(map, x1=80, y1=10, x2=width, y2=59, value=color) + draw_vertical(map, x1=10, y1=10, x2=80, y2=width, value=color) + draw_horizontal(map, x1=10, y1=10, x2=width, y2=55, value=color) + return map + + def apply_color_j(map, width=10, color=.5): + draw_vertical(map, x1=30, y1=30, x2=40, y2=width, value=color) + return map + + semantic_labels = { + 'wall': 1, + 'hallway': 2, + 'blue': 3, + 'red': 4, + } + # Initialize the random generator + random.seed(random_seed) + np.random.seed(random_seed) + rando = np.random.rand() + map_type = '' # l or r + goal_color = None # r or b + other_color = None # r or b + # print(f"Random seed: {random_seed} - rando: {rando}") + if rando > .5: + print("Left") + map_type = 'l' + grid = goal_on_left_map() + + else: + print("Right") + map_type = 'r' + grid = goal_on_right_map() + + rando = np.random.rand() + if rando > .5: + print("Goal looks blue") + goal_color = semantic_labels['blue'] + other_color = semantic_labels['red'] + else: + print("Goal looks red") + goal_color = semantic_labels['red'] + other_color = semantic_labels['blue'] + + if map_type == 'l': + semantic_grid = apply_color_path_left( + grid.copy(), color=other_color) + semantic_grid = apply_color_path_left2( + semantic_grid.copy(), color=goal_color) + elif map_type == 'r': + semantic_grid = apply_color_path_right( + grid.copy(), color=other_color) + semantic_grid = apply_color_path_right2( + semantic_grid.copy(), color=goal_color) + + semantic_grid = apply_color_j( + semantic_grid.copy(), color=goal_color) + semantic_grid[semantic_grid == 0] = semantic_labels['hallway'] + assert len(np.argwhere(semantic_grid == 0)) == 0 + + start = (34, 44) + # rando = np.random.rand() + # if rando > .5: + # print("Flipped the map horizontally") + # start = (74, 44) + # grid = np.flip(grid, 1) + # semantic_grid = np.flip(semantic_grid, 1) + + end = (54, 85) + + occ_grid = np.transpose(grid) + semantic_grid = np.transpose(semantic_grid) + + wall_class_index = { + 'hallway': semantic_labels['hallway'], + 'blue': semantic_labels['blue'], + 'red': semantic_labels['red'] + } + polys, walls = calc.split_semantic_grid_to_polys(occ_grid, + semantic_grid, + wall_class_index, + resolution, + do_compute_walls=True) + # start = (55, 15) # Shows fork view + return { + 'occ_grid': occ_grid, + 'semantic_grid': semantic_grid, + 'semantic_labels': semantic_labels, + "polygons": polys, + "walls": walls, + 'start': start, + 'end': end, + 'x_offset': 0.0, + 'y_offset': 0.0, + "wall_class": wall_class_index + } + + +class MapGenJshaped(base_generator.MapGenBase): + def gen_map(self, random_seed=None): + map_data = gen_map_jshaped_base( + random_seed=random_seed, + resolution=self.args.base_resolution) + map_data['resolution'] = self.args.base_resolution + + self.hr_grid = map_data['occ_grid'].copy() + self.grid = map_data['occ_grid'].copy() + self.tmp_start = map_data['start'] + self.tmp_goal = map_data['end'] + + return self.hr_grid, self.grid, map_data + + def get_start_goal_poses(self, min_separation=1, max_separation=1e10): + """Loop through the points in the grid and get a pair of poses, subject to a +certain condition. This is a more specific pose generation procedure because we +want to demonstrate the more specific features of this particular map. + + Returns: + did_succeed (Bool) + robot_pose (NamedTuple('PoseT', 'x y yaw')) + goal_pose (NamedTuple('PoseT', 'x y yaw')) + + """ + start = Pose(x=self.tmp_start[0], + y=self.tmp_start[1], + yaw=0) + goal = Pose(x=self.tmp_goal[0], + y=self.tmp_goal[1], + yaw=2 * math.pi * random.random()) + + return (True, start, goal) diff --git a/modules/lsp_gnn/lsp_gnn/environments/modified_office.py b/modules/lsp_gnn/lsp_gnn/environments/modified_office.py new file mode 100644 index 0000000..0f7fb07 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/environments/modified_office.py @@ -0,0 +1,847 @@ +import numpy as np +from scipy.ndimage import label +import scipy +from skimage.morphology import skeletonize +import sknw + +from environments import base_generator +from environments.utils import calc +from common import Pose +import gridmap + + +L_TMP = 100 +L_UNSET = -1 +L_BKD = 0 +L_CLUTTER = 1 +L_DOOR = 2 +L_HALL = 3 +L_ROOM = 4 +L_ROOM2 = 5 +L_UNK = 6 + +# default parameters +RESOLUTION = 0.5 # this value yields a reasonable scale of office environment in sim +INFLATION_RADIUS_M = RESOLUTION * 1.5 + +# the default parameters below have units in terms of grid cells +GRID_SIZE = (500, 300) +NUM_OF_HALLWAYS = 5 +BOUNDARY_THRESHOLD = 30 +MIN_SPACING_HALLWAYS = 30 +HALLWAY_WIDTH = 5 +ROOM_WIDTH = 20 +ROOM_LENGTH_RANGE = (25, 35) +ROOM_DOOR_SPACE = 1 +HALLWAY_ROOM_SPACE = 1 +DOOR_SIZE = 8 +MAX_TABLES_PER_ROOM = 2 +TABLE_SIZE_RANGE = (4, 8) +TABLE_WALL_BUFFER = 3 + +semantic_labels = { + 'background': L_BKD, + 'clutter': L_CLUTTER, + 'door': L_DOOR, + 'hallway': L_HALL, + 'room': L_ROOM, + 'room2': L_ROOM2, + 'other': L_UNK, +} + + +def generate_random_lines(num_of_lines=NUM_OF_HALLWAYS, + grid_size=GRID_SIZE, + spacing_between_lines=MIN_SPACING_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + max_iter=10000): + """Generate random horizontal and vertical lines in a grid. + + Args: + seed (int): Random seed + num_of_lines (integer): Number of lines + grid_size (tuple): Size of the grid + spacing_between_lines (int): Spacing between two parallel lines + boundary_threshold (int): Minimum spacing between lines and boundary of grid + max_iter (int): Maximum number of iterations to run + + Returns: + final_semantic_grid (2D array): Grid with horizontal and vertical lines + line_segments: list of line segments, each segment as ((start_x, start_y), (end_x, end_y)) + """ + + def _check_if_connected(semantic_grid, grid): + # 8-neighbor structure/kernel for connected components + s = [[1, 1, 1], + [1, 1, 1], + [1, 1, 1]] + grid[semantic_grid == L_UNK] = 0 + new_grid = 1 - grid.copy() + _, num_features = label(new_grid, structure=s) + if num_features > 1: + return False + else: + return True + + # keep track of the boundaries within which parallel line can't be drawn in row and col + row = set() + col = set() + # space between parallel hallways + space_between_parallel = spacing_between_lines + # lower bound of both x and y + xy_lower_bound = 0 + boundary_threshold + 1 + x_upper_bound = grid_size[0] - boundary_threshold - 1 + y_upper_bound = grid_size[1] - boundary_threshold - 1 + + grid = np.ones(grid_size, dtype=int) + final_semantic_grid = grid.copy() * L_TMP + intermediate_semantic_grid = grid.copy() * L_TMP + line_segments = [] + + for _ in range(max_iter): + # Randomly pick a point that is at a safe distance from the + # boundaries before the inflation + random_point = np.random.randint( + xy_lower_bound, [x_upper_bound, y_upper_bound] + ) + + # finds the distance from every boundaries + distance_to_bounds = [x_upper_bound - random_point[0], + random_point[0] - xy_lower_bound + 1, + random_point[1] - xy_lower_bound + 1, + y_upper_bound - random_point[1]] + + # direction specifies where the line should proceed + direction = np.argmax(distance_to_bounds) + sorted_direction = np.argsort(distance_to_bounds)[::-1] + + for direction in sorted_direction: + + if direction == 0: # Draws from top to bottom (top left is (0,0)) + if random_point[1] in col: + continue + intermediate_semantic_grid[random_point[0]:x_upper_bound + 1, + random_point[1]] = L_UNK + + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[1] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[1] + space_between_parallel + 1, y_upper_bound) + lb_buffer = max( + random_point[0] - space_between_parallel, xy_lower_bound) + + line_segments.append(((random_point[0], random_point[1]), + (x_upper_bound, random_point[1]))) + + col.update(range(lb, ub)) + row.update(range(lb_buffer, random_point[0])) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + elif direction == 1: # Draws from bottom to top + if random_point[1] in col: + continue + intermediate_semantic_grid[xy_lower_bound:random_point[0] + 1, random_point[1]] = L_UNK + + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[1] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[1] + space_between_parallel + 1, y_upper_bound) + ub_buffer = min( + random_point[0] + space_between_parallel, x_upper_bound) + + line_segments.append(((random_point[0], random_point[1]), + (xy_lower_bound, random_point[1]))) + + col.update(range(lb, ub)) + row.update(range(random_point[0], ub_buffer)) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + elif direction == 2: # Draws from right to left + if random_point[0] in row: + continue + intermediate_semantic_grid[random_point[0], xy_lower_bound:random_point[1] + 1] = L_UNK + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[0] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[0] + space_between_parallel + 1, x_upper_bound) + ub_buffer = min( + random_point[1] + space_between_parallel, y_upper_bound) + + line_segments.append(((random_point[0], random_point[1]), + (random_point[0], xy_lower_bound))) + row.update(range(lb, ub)) + col.update(range(random_point[1], ub_buffer)) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + elif direction == 3: # Draws from left to right + if random_point[0] in row: + continue + intermediate_semantic_grid[random_point[0], random_point[1]:y_upper_bound + 1] = L_UNK + line_connected = _check_if_connected( + intermediate_semantic_grid, grid.copy()) + if line_connected: + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + grid[final_semantic_grid == L_UNK] = 0 + lb = max(random_point[0] - + space_between_parallel, xy_lower_bound) + ub = min( + random_point[0] + space_between_parallel + 1, x_upper_bound) + lb_buffer = max( + random_point[1] - space_between_parallel, xy_lower_bound) + + line_segments.append(((random_point[0], random_point[1]), + (random_point[0], y_upper_bound))) + + row.update(range(lb, ub)) + col.update(range(lb_buffer, random_point[1])) + break + else: + intermediate_semantic_grid = final_semantic_grid.copy() + + if len(line_segments) >= num_of_lines: + break + else: + print(f"Needed to generate {num_of_lines} lines but only generated {len(line_segments)} lines.") + + return final_semantic_grid, line_segments + + +def inflate_lines_to_create_hallways(grid, hallway_inflation_scale=HALLWAY_WIDTH): + """Inflate the lines by a kernel. + + Args: + grid (2D array): Grid with lines + hallway_inflation_scale (int): Number pixel to grow in 8-neighbor direction + + Returns: + grid_with_hallway (2D array): grid with inflated lines as hallways + """ + original_grid = np.zeros_like(grid) + original_grid[grid == L_UNK] = 1 + kernel_dim = 2 * hallway_inflation_scale + 1 + hallway_inflation_kernel = np.ones((kernel_dim, kernel_dim), dtype=int) + + grid_with_hallway = scipy.ndimage.convolve( + original_grid, hallway_inflation_kernel) + grid_with_hallway[grid_with_hallway > 0] = semantic_labels['hallway'] + grid_with_hallway[grid_with_hallway == 0] = semantic_labels['background'] + + return grid_with_hallway + + +def add_rooms(grid_with_hallway, + line_segments, + hallway_inflation_scale=HALLWAY_WIDTH, + room_b=ROOM_WIDTH, + room_l_range=ROOM_LENGTH_RANGE): + """Add rooms to the hallway grid (along the hallways). + + Args: + grid_with_hallway (2D array): Grid with hallways (can contain special rooms too) + line_segments (list): List of line segments corresponding to hallways, + each segment as ((start_x, start_y), (end_x, end_y)) + hallway_inflation_scale (int): Hallway width (same as kernel size used to create hallways from lines) + room_b (int): Width/breadth of room + room_l_range (tuple): Tuple of two integers representing (minimum, maximum) lengths of rooms + + Returns: + grid_with_room (2D array): Grid with rooms + rooms_coords (list): List of room coordinates, each coordinate as ((start_x, start_y), (end_x, end_y)) + """ + grid_with_room = grid_with_hallway.copy() + rooms_coords = [] + for line in line_segments: + start, end = line + is_horizontal = start[0] == end[0] + axis = int(is_horizontal) + if start[axis] > end[axis]: + start, end = end, start + + if is_horizontal: + # add rooms on horizontal hallway end points + # end 1 + room_l = np.random.randint(*room_l_range) + room_p1 = (start[0] - int(room_l / 2), start[1] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE) + room_p2 = (room_p1[0] + room_l, room_p1[1] + room_b) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (start[0] - int(DOOR_SIZE / 2), start[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE) + door_p2 = (door_p1[0] + DOOR_SIZE, door_p1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + # end 2 + room_l = np.random.randint(*room_l_range) + room_q1 = (end[0] - int(room_l / 2), end[1] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1) + room_q2 = (room_q1[0] + room_l, room_q1[1] + room_b) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (end[0] - int(DOOR_SIZE / 2), end[1] + hallway_inflation_scale + 1) + door_q2 = (door_q1[0] + DOOR_SIZE, door_q1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + # add rooms along horizontal hallway + for y in range(start[1], end[1] - hallway_inflation_scale, 1): + room_l = np.random.randint(*room_l_range) + room_p1 = (start[0] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE, y) + room_p2 = (room_p1[0] + room_b, room_p1[1] + room_l) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (room_p2[0], room_p2[1] - ROOM_DOOR_SPACE - DOOR_SIZE) + door_p2 = (room_p2[0] + HALLWAY_ROOM_SPACE, room_p2[1] - ROOM_DOOR_SPACE) + # correction for door extending beyond hallway end 2 + door_check_slice = grid_with_room[door_p2[0]:door_p2[0] + 1, door_p1[1]:door_p2[1]] + overflow_len = len(np.where(door_check_slice == semantic_labels['background'])[1]) + if overflow_len > 0: + door_p1 = (room_p1[0] + room_b, room_p1[1] + ROOM_DOOR_SPACE) + door_p2 = (door_p1[0] + HALLWAY_ROOM_SPACE, door_p1[1] + DOOR_SIZE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + room_l = np.random.randint(*room_l_range) + room_q1 = (start[0] + hallway_inflation_scale + 1 + HALLWAY_ROOM_SPACE, y) + room_q2 = (room_q1[0] + room_b, room_q1[1] + room_l) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (room_q1[0] - HALLWAY_ROOM_SPACE, room_q1[1] + ROOM_DOOR_SPACE) + door_q2 = (room_q1[0], room_q1[1] + ROOM_DOOR_SPACE + DOOR_SIZE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + else: + # add rooms on vertical hallway end points + # end 1 + room_l = np.random.randint(*room_l_range) + room_p1 = (start[0] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE, start[1] - int(room_l / 2)) + room_p2 = (room_p1[0] + room_b, room_p1[1] + room_l) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (start[0] - hallway_inflation_scale - HALLWAY_ROOM_SPACE, start[1] - int(DOOR_SIZE / 2)) + door_p2 = (door_p1[0] + HALLWAY_ROOM_SPACE, door_p1[1] + DOOR_SIZE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + # end 2 + room_l = np.random.randint(*room_l_range) + room_q1 = (end[0] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1, end[1] - int(room_l / 2)) + room_q2 = (room_q1[0] + room_b, room_q1[1] + room_l) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (end[0] + hallway_inflation_scale + 1, end[1] - int(DOOR_SIZE / 2)) + door_q2 = (door_q1[0] + HALLWAY_ROOM_SPACE, door_q1[1] + DOOR_SIZE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + # add rooms along vertical hallway + for x in range(start[0], end[0] - hallway_inflation_scale, 1): + room_l = np.random.randint(*room_l_range) + room_p1 = (x, start[1] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE) + room_p2 = (room_p1[0] + room_l, room_p1[1] + room_b) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (room_p2[0] - ROOM_DOOR_SPACE - DOOR_SIZE, room_p2[1]) + door_p2 = (room_p2[0] - ROOM_DOOR_SPACE, room_p2[1] + HALLWAY_ROOM_SPACE) + # correction for door extending beyond hallway end 2 + door_check_slice = grid_with_room[door_p1[0]:door_p2[0], door_p2[1]:door_p2[1] + 1] + overflow_len = len(np.where(door_check_slice == semantic_labels['background'])[0]) + if overflow_len > 0: + door_p1 = (room_p1[0] + ROOM_DOOR_SPACE, room_p1[1] + room_b) + door_p2 = (door_p1[0] + DOOR_SIZE, door_p1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + room_l = np.random.randint(*room_l_range) + room_q1 = (x, start[1] + hallway_inflation_scale + 1 + HALLWAY_ROOM_SPACE) + room_q2 = (room_q1[0] + room_l, room_q1[1] + room_b) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (room_q1[0] + ROOM_DOOR_SPACE, room_q1[1] - HALLWAY_ROOM_SPACE) + door_q2 = (room_q1[0] + ROOM_DOOR_SPACE + DOOR_SIZE, room_q1[1]) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + return grid_with_room, rooms_coords + + +def add_special_rooms(grid_with_hallway, + intersections, + hallway_inflation_scale=HALLWAY_WIDTH, + room_length_range=ROOM_LENGTH_RANGE): + """Add special rooms to the hallway grid wherever possible to connect two hallways. + + Args: + grid_with_hallway (2D array): Grid with hallways + intersections (list): List of intersection points + hallway_inflation_scale (int): Hallway width (same as kernel size used to create hallways from lines) + room_l_range (tuple): Tuple of two integers representing (minimum, maximum) lengths of rooms + + Returns: + grid_with_sp_room (2D array): Grid with special rooms + rooms_coords (list): List of special room coordinates, each coordinate as ((start_x, start_y), (end_x, end_y)) + """ + def _check_intersection_or_hallway_end(side_point, extended_point): + check_point_start = side_point[0] + check_point_end = side_point[1] + hallway_end_check_start = extended_point[0] + hallway_end_check_end = extended_point[1] + + another_intersection_met, hallway_end = False, False + + if grid_with_sp_room[check_point_start[0], check_point_start[1]] == semantic_labels['hallway']: + another_intersection_met = True + + if grid_with_sp_room[check_point_end[0], check_point_end[1]] == semantic_labels['hallway']: + another_intersection_met = True + + if grid_with_sp_room[hallway_end_check_start[0], hallway_end_check_start[1]] == semantic_labels['background']: + hallway_end = True + if grid_with_sp_room[hallway_end_check_end[0], hallway_end_check_end[1]] == semantic_labels['background']: + hallway_end = True + + return another_intersection_met, hallway_end + + grid_with_sp_room = grid_with_hallway.copy() + intersections = np.round(intersections).astype(int) + intersection_with_distance = [] + for i, inter in enumerate(intersections): + x, y = inter[0], inter[1] + for next_point in intersections[i + 1:]: + if next_point[0] == x or next_point[1] == y: + intersection_with_distance.append( + [[inter, next_point], np.linalg.norm(inter - next_point)]) + intersection_with_distance.sort(key=lambda x: x[1]) + + # if intersection distance less than a certain room size; remove the intersection + min_room_length, max_room_length = room_length_range[0], room_length_range[1] + min_intersection_distance = min_room_length + 3 * hallway_inflation_scale + max_intersection_distance = max_room_length + 5 * hallway_inflation_scale + + intersection_with_distance = [intersection for intersection in intersection_with_distance if ( + intersection[1] >= min_intersection_distance and intersection[1] < max_intersection_distance)] + + rooms_coords = [] + for intersection in intersection_with_distance: + # find whether the line is horizontal or vertical. + start, end = intersection[0] + is_horizontal = start[0] == end[0] + axis = int(is_horizontal) + if start[axis] > end[axis]: + start, end = end, start + distance = {} + if (is_horizontal): + ''' + find the minimum distance along the hallway in which the room can be expanded + in the ascending direction + ''' + another_intersection_met = False + hallway_end = False + distance_ascending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_ascending += 1 + poi_ascending = start[0] + distance_ascending + + check_point_start = [poi_ascending, + start[1] + hallway_inflation_scale + 1] + check_point_end = [poi_ascending, + end[1] - hallway_inflation_scale - 1] + + hallway_end_check_start = [poi_ascending + 1, start[1]] + hallway_end_check_end = [poi_ascending + 1, end[1]] + + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + + distance['ascending'] = distance_ascending + ''' + find the minimum distance along the hallway in which the room can be expanded + in the descending direction + ''' + another_intersection_met = False + hallway_end = False + distance_descending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_descending += 1 + poi_descending = start[0] - distance_descending + + check_point_start = [poi_descending, + start[1] + hallway_inflation_scale + 1] + check_point_end = [poi_descending, + end[1] - hallway_inflation_scale - 1] + + hallway_end_check_start = [poi_descending - 1, start[1]] + hallway_end_check_end = [poi_descending - 1, end[1]] + + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + distance['descending'] = distance_descending + + # Add "special room" in the ascending direction + if distance['ascending'] > max_room_length: + room_p1 = [start[0] + distance['ascending'] - max_room_length, + start[1] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1] + room_p2 = [end[0] + distance['ascending'], end[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE] + room_slice = grid_with_sp_room[room_p1[0] - + 1:room_p2[0] + 1, room_p1[1]:room_p2[1]] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_p1[0]:room_p2[0], + room_p1[1]:room_p2[1]] = semantic_labels['room2'] + rooms_coords.append((room_p1, room_p2)) + # add doors + grid_with_sp_room[room_p1[0] + ROOM_DOOR_SPACE:room_p1[0] + ROOM_DOOR_SPACE + DOOR_SIZE, + room_p1[1] - HALLWAY_ROOM_SPACE:room_p1[1]] = semantic_labels['door'] + grid_with_sp_room[room_p2[0] - ROOM_DOOR_SPACE - DOOR_SIZE:room_p2[0] - ROOM_DOOR_SPACE, + room_p2[1]:room_p2[1] + HALLWAY_ROOM_SPACE] = semantic_labels['door'] + + # Add "special room" in the descending direction + if distance['descending'] > max_room_length: + room_q1 = [start[0] - distance['descending'] + 1, start[1] + + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1] + room_q2 = [end[0] - distance['descending'] + max_room_length, + end[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE] + room_slice = grid_with_sp_room[room_q1[0] - + 1:room_q2[0] + 1, room_q1[1]:room_q2[1]] + if not (np.any(room_slice == semantic_labels['room2']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_q1[0]:room_q2[0], + room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add doors + grid_with_sp_room[room_q1[0] + ROOM_DOOR_SPACE:room_q1[0] + ROOM_DOOR_SPACE + DOOR_SIZE, + room_q1[1] - HALLWAY_ROOM_SPACE:room_q1[1]] = semantic_labels['door'] + grid_with_sp_room[room_q2[0] - ROOM_DOOR_SPACE - DOOR_SIZE:room_q2[0] - ROOM_DOOR_SPACE, + room_q2[1]:room_q2[1] + HALLWAY_ROOM_SPACE] = semantic_labels['door'] + + else: + ''' + find the minimum distance along the hallway in which the room can be expanded + in the ascending direction + ''' + another_intersection_met = False + hallway_end = False + distance_ascending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_ascending += 1 + poi_ascending = start[1] + distance_ascending + check_point_start = [ + start[0] + hallway_inflation_scale + 1, poi_ascending] + check_point_end = [ + end[0] - hallway_inflation_scale - 1, poi_ascending] + + hallway_end_check_start = [start[0], poi_ascending + 1] + hallway_end_check_end = [end[0], poi_ascending + 1] + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + + distance['ascending'] = distance_ascending + ''' + find the minimum distance along the hallway in which the room can be expanded + in the descending direction + ''' + another_intersection_met = False + hallway_end = False + distance_descending = hallway_inflation_scale + while (not (another_intersection_met or hallway_end)): + distance_descending += 1 + poi_descending = start[1] - distance_descending + check_point_start = [ + start[0] + hallway_inflation_scale + 1, poi_descending] + check_point_end = [ + end[0] - hallway_inflation_scale - 1, poi_descending] + + hallway_end_check_start = [start[0], poi_descending - 1] + hallway_end_check_end = [end[0], poi_descending - 1] + + side_points = [check_point_start, check_point_end] + extended_points = [ + hallway_end_check_start, hallway_end_check_end] + another_intersection_met, hallway_end = _check_intersection_or_hallway_end( + side_points, extended_points) + distance['descending'] = distance_descending + + # Add "special room" in the ascending direction + if distance['ascending'] > max_room_length: + room_p1 = [start[0] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1, + start[1] + distance['ascending'] - max_room_length] + room_p2 = [end[0] - hallway_inflation_scale - + HALLWAY_ROOM_SPACE, end[1] + distance['ascending'] - 1] + room_slice = grid_with_sp_room[room_p1[0]:room_p2[0], room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_p1[0]:room_p2[0], + room_p1[1]:room_p2[1]] = semantic_labels['room2'] + rooms_coords.append((room_p1, room_p2)) + # add doors + grid_with_sp_room[room_p1[0] - HALLWAY_ROOM_SPACE:room_p1[0], + room_p1[1] + ROOM_DOOR_SPACE:room_p1[1] + ROOM_DOOR_SPACE + DOOR_SIZE] = ( + semantic_labels['door']) + grid_with_sp_room[room_p2[0]:room_p2[0] + HALLWAY_ROOM_SPACE, + room_p2[1] - ROOM_DOOR_SPACE - DOOR_SIZE:room_p2[1] - ROOM_DOOR_SPACE] = ( + semantic_labels['door']) + # Add "special room" in the descending direction + if distance['descending'] > max_room_length: + room_q1 = [start[0] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1, + start[1] - distance['descending']] + room_q2 = [end[0] - hallway_inflation_scale - HALLWAY_ROOM_SPACE, + end[1] - distance['descending'] + max_room_length] + room_slice = grid_with_sp_room[room_q1[0] + + 1:room_q2[0] - 1, room_q1[1]:room_q2[1]] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway'])): + grid_with_sp_room[room_q1[0]:room_q2[0], + room_q1[1]:room_q2[1]] = semantic_labels['room2'] + rooms_coords.append((room_q1, room_q2)) + # add doors + grid_with_sp_room[room_q1[0] - HALLWAY_ROOM_SPACE:room_q1[0], + room_q1[1] + ROOM_DOOR_SPACE:room_q1[1] + ROOM_DOOR_SPACE + DOOR_SIZE] = ( + semantic_labels['door']) + grid_with_sp_room[room_q2[0]:room_q2[0] + HALLWAY_ROOM_SPACE, + room_q2[1] - ROOM_DOOR_SPACE - DOOR_SIZE:room_q2[1] - ROOM_DOOR_SPACE] = ( + semantic_labels['door']) + + return grid_with_sp_room, rooms_coords + + +def add_tables(grid_with_rooms, + rooms_coords, + max_tables_per_room=MAX_TABLES_PER_ROOM, + table_size_range=TABLE_SIZE_RANGE, + table_wall_buffer=TABLE_WALL_BUFFER): + """Add tables to grid with rooms. + + Args: + grid_with_rooms (2D array): Grid with rooms + rooms_coords (list): List of all room coordinates, each coordinate as ((start_x, start_y), (end_x, end_y)) + max_tables_per_room (int): Maximum number of tables to per room + table_size_range (tuple): Tuple of two integers representing (minimum, maximum) lengths of tables + table_wall_buffer (int): Minimum spacing between table and room walls + + Returns: + grid_with_tables (2D array): Grid with tables + table_poses_sizes (list): List of tuples containing table center coordinates and lengths, + each tuple as (center_x, center_y, length_x, length_y) + """ + grid_with_tables = grid_with_rooms.copy() + table_poses_sizes = [] + for room_p1, room_p2 in rooms_coords: + for _ in range(max_tables_per_room): + size_x, size_y = np.random.choice(np.arange(table_size_range[0], table_size_range[1] + 1, 2), + size=2) + table_x = np.random.randint(room_p1[0] + int(size_x / 2) + table_wall_buffer, + room_p2[0] - int(size_x / 2) - table_wall_buffer) + table_y = np.random.randint(room_p1[1] + int(size_y / 2) + table_wall_buffer, + room_p2[1] - int(size_y / 2) - table_wall_buffer) + table_p1 = (table_x - int(size_x / 2), table_y - int(size_y / 2)) + table_p2 = (table_x + int(size_x / 2), table_y + int(size_y / 2)) + table_slice = grid_with_tables[table_p1[0]:table_p2[0], + table_p1[1]:table_p2[1]] + if not np.any(table_slice == semantic_labels['clutter']): + grid_with_tables[table_p1[0]:table_p2[0], + table_p1[1]:table_p2[1]] = semantic_labels['clutter'] + table_poses_sizes.append((table_x, table_y, size_x, size_y)) + + return grid_with_tables, table_poses_sizes + + +def determine_intersections(hallway_mask): + """Returns a dictionary containing intersection points and deadend points of hallways.""" + sk = skeletonize(hallway_mask) + graph = sknw.build_sknw(sk) + vertex_data = graph.nodes() + counter = {id: 0 + for id in vertex_data} + edges = graph.edges() + for s, e in edges: + counter[s] += 1 + counter[e] += 1 + pendant_vertices = [key + for key in counter + if counter[key] == 1] + intersection_vertices = list(set(vertex_data) - set(pendant_vertices)) + intersections = np.array([vertex_data[i]['o'] + for i in intersection_vertices]) + pendants = np.array([vertex_data[i]['o'] + for i in pendant_vertices]) + return { + 'intersections': intersections, + 'deadends': pendants + } + + +def count_loops_in_hallways(hallway_mask): + grid = 1 - hallway_mask + _, num_comp = label(grid) + return num_comp - 1 + + +def swap_room_color(seed): + # is_passage_red = seed % 2 + # if is_passage_red == 0: + # return {'hallway': L_HALL, 'blue': L_ROOM, 'red': L_ROOM2} + return {'hallway': L_HALL, 'blue': L_ROOM2, 'red': L_ROOM} + + +def gen_map_office2(random_seed, + resolution=RESOLUTION, + grid_size=GRID_SIZE, + num_of_hallways=NUM_OF_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + min_spacing_hallways=MIN_SPACING_HALLWAYS, + hallway_width=HALLWAY_WIDTH, + room_width=ROOM_WIDTH, + room_length_range=ROOM_LENGTH_RANGE): + np.random.seed(random_seed) + loop_count = 2 + counting_loop = 100 + while loop_count > 0: + grid_with_lines, line_segments = generate_random_lines( + # seed=random_seed, + grid_size=grid_size, + num_of_lines=num_of_hallways, + spacing_between_lines=min_spacing_hallways, + boundary_threshold=boundary_threshold) + grid_with_hallway = inflate_lines_to_create_hallways( + grid_with_lines, hallway_inflation_scale=hallway_width) + loop_count = count_loops_in_hallways(grid_with_hallway == semantic_labels['hallway']) + + counting_loop -= 1 + if counting_loop == 0: + raise ValueError + + # features = determine_intersections(grid_with_hallway == semantic_labels['hallway']) + # grid_with_special_rooms, special_rooms_coords = add_special_rooms(grid_with_hallway, + # intersections=features['intersections'], + # hallway_inflation_scale=hallway_width, + # room_length_range=room_length_range) + grid_with_rooms, rooms_coords = add_rooms(grid_with_hallway, + line_segments, + hallway_inflation_scale=hallway_width, + room_b=room_width, + room_l_range=room_length_range) + # rooms_coords += special_rooms_coords + + occupancy_grid = (grid_with_rooms <= L_CLUTTER).astype(float) + wall_class_index = swap_room_color(seed=random_seed) + polys, walls = calc.split_semantic_grid_to_polys(occupancy_grid, + grid_with_rooms, + wall_class_index, + resolution=resolution, + do_compute_walls=True) + + grid, table_poses_sizes = add_tables(grid_with_rooms, rooms_coords) + occupancy_grid = (grid <= L_CLUTTER).astype(float) + + return { + "occ_grid": occupancy_grid.copy(), + "semantic_grid": grid.copy(), + "semantic_labels": semantic_labels, + "polygons": polys, + "walls": walls, + "x_offset": 0.0, + "y_offset": 0.0, + "resolution": resolution, + # "features": features, + "tables": table_poses_sizes, + "wall_class": wall_class_index + } + + +class MapGenOffice2(base_generator.MapGenBase): + def gen_map(self, random_seed=None): + self.map_data = gen_map_office2(random_seed, + resolution=self.args.base_resolution, + grid_size=GRID_SIZE, + num_of_hallways=NUM_OF_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + min_spacing_hallways=MIN_SPACING_HALLWAYS, + hallway_width=HALLWAY_WIDTH, + room_width=ROOM_WIDTH, + room_length_range=ROOM_LENGTH_RANGE) + + self.hr_grid = self.map_data["occ_grid"].copy() + self.grid = self.map_data["occ_grid"].copy() + + return self.hr_grid, self.grid, self.map_data + + def get_start_goal_poses(self, min_separation=150, max_separation=1e10, num_attemps=1000): + inflation_radius = self.args.inflation_radius_m / self.args.base_resolution + inflated_grid = gridmap.utils.inflate_grid(self.grid, inflation_radius) + free_cells = np.column_stack(np.where(inflated_grid == gridmap.constants.FREE_VAL)) + for _ in range(num_attemps): + rand_indices = np.random.choice(np.arange(len(free_cells)), size=2, replace=False) + start, goal = free_cells[rand_indices] + cost_grid, _ = gridmap.planning.compute_cost_grid_from_position(inflated_grid, goal) + path_cost = cost_grid[start[0], start[1]] + if path_cost >= min_separation and path_cost <= max_separation: + start = Pose(x=start[0], y=start[1]) + goal = Pose(x=goal[0], y=goal[1]) + return (True, start, goal) + else: + raise RuntimeError("Could not find a pair of poses that " + "connect during start/goal pose generation.") diff --git a/modules/lsp_gnn/lsp_gnn/environments/parallel_hallway.py b/modules/lsp_gnn/lsp_gnn/environments/parallel_hallway.py new file mode 100644 index 0000000..1e3f9d4 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/environments/parallel_hallway.py @@ -0,0 +1,342 @@ +import numpy as np +import scipy +from skimage.morphology import binary_dilation + +import gridmap +from environments import base_generator +from environments.utils import calc +from common import Pose + + +L_TMP = 100 +L_UNSET = -1 +L_BKD = 0 +L_CLUTTER = 1 +L_DOOR = 2 +L_HALL = 3 +L_ROOM = 4 +L_ROOM2 = 5 +L_UNK = 6 + +HALLWAY_ROOM_SPACE = 1 +DOOR_SIZE = 6 + +# Default parameters for the map +GRID_SIZE = (200, 210) +NUM_OF_HALLWAYS = 3 +BOUNDARY_THRESHOLD = 30 +MIN_SPACING_HALLWAYS = 30 +HALLWAY_WIDTH = 5 +ROOM_WIDTH = 20 +ROOM_LENGTH_RANGE = (28, 30) + +semantic_labels = { + 'background': L_BKD, + 'clutter': L_CLUTTER, + 'door': L_DOOR, + 'hallway': L_HALL, + 'room': L_ROOM, + 'room2': L_ROOM2, + 'other': L_UNK, + 'block': L_BKD +} + + +def inflate_lines_to_create_hallways(grid, hallway_inflation_scale): + """Inflate the lines by a kernel + + Args: + grid (array of shape m x n): Grid with lines + hallway_inflation_scale (int, optional): Number pixel to grow in + 8-neighbor direction. Defaults to 5. + + Returns: + grid_with_hallways: grid with inflated lines as hallways + """ + original_grid = np.zeros_like(grid) + original_grid[grid == L_UNK] = 1 + kernel_dim = 2 * hallway_inflation_scale + 1 + hallway_inflation_kernel = np.ones((kernel_dim, kernel_dim), dtype=int) + + grid_with_hallway = scipy.ndimage.convolve( + original_grid, hallway_inflation_kernel) + grid_with_hallway[grid_with_hallway > 0] = semantic_labels['hallway'] + grid_with_hallway[grid_with_hallway == 0] = semantic_labels['background'] + + return grid_with_hallway + + +def add_rooms(line_segments, grid_with_hallway, + hallway_inflation_scale, room_b, room_l_range): + grid_with_room = grid_with_hallway.copy() + rooms_coords = [] + for line in line_segments: + start, end = line + is_horizontal = start[0] == end[0] + axis = int(is_horizontal) + if start[axis] > end[axis]: + start, end = end, start + + if is_horizontal: + # add rooms on horizontal hallway end points + # end 1 + room_l = room_l_range[0] + room_p1 = (start[0] - int(room_l / 2), start[1] - hallway_inflation_scale - room_b - HALLWAY_ROOM_SPACE) + room_p2 = (room_p1[0] + room_l, room_p1[1] + room_b) + room_slice = grid_with_room[room_p1[0] - 1:room_p2[0] + 1, room_p1[1] - 1:room_p2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway']) + or np.any(room_slice == semantic_labels['room2'])): + grid_with_room[room_p1[0]:room_p2[0], room_p1[1]:room_p2[1]] = semantic_labels['room'] + rooms_coords.append((room_p1, room_p2)) + # add door + door_p1 = (start[0] - int(DOOR_SIZE / 2), start[1] - hallway_inflation_scale - HALLWAY_ROOM_SPACE) + door_p2 = (door_p1[0] + DOOR_SIZE, door_p1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_p1[0]:door_p2[0], door_p1[1]:door_p2[1]] = semantic_labels['door'] + + # end 2 + room_l = room_l_range[0] + room_q1 = (end[0] - int(room_l / 2), end[1] + hallway_inflation_scale + HALLWAY_ROOM_SPACE + 1) + room_q2 = (room_q1[0] + room_l, room_q1[1] + room_b) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway']) + or np.any(room_slice == semantic_labels['room2'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (end[0] - int(DOOR_SIZE / 2), end[1] + hallway_inflation_scale + 1) + door_q2 = (door_q1[0] + DOOR_SIZE, door_q1[1] + HALLWAY_ROOM_SPACE) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + + # add rooms along horizontal hallway + # step = np.random.randint(1, 10) + y = start[1] + while y < end[1] - hallway_inflation_scale: + room_l = room_l_range[0] + room_q1 = (start[0] + hallway_inflation_scale + 1 + HALLWAY_ROOM_SPACE, y) + room_q2 = (room_q1[0] + room_b, room_q1[1] + room_l) + room_slice = grid_with_room[room_q1[0] - 1:room_q2[0] + 1, room_q1[1] - 1:room_q2[1] + 1] + if not (np.any(room_slice == semantic_labels['room']) + or np.any(room_slice == semantic_labels['hallway']) + or np.any(room_slice == semantic_labels['room2'])): + grid_with_room[room_q1[0]:room_q2[0], room_q1[1]:room_q2[1]] = semantic_labels['room'] + rooms_coords.append((room_q1, room_q2)) + # add door + door_q1 = (room_q1[0] - HALLWAY_ROOM_SPACE, (room_q1[1] + room_q2[1]) // 2 - DOOR_SIZE // 2) + door_q2 = (room_q1[0], (room_q1[1] + room_q2[1]) // 2 + DOOR_SIZE // 2) + grid_with_room[door_q1[0]:door_q2[0], door_q1[1]:door_q2[1]] = semantic_labels['door'] + step = np.random.randint(1, 10) + y += step + + return grid_with_room, rooms_coords + + +def swap_room_color(seed): + is_passage_red = seed % 2 + if is_passage_red == 0: + return {'hallway': L_HALL, 'blue': L_ROOM, 'red': L_ROOM2} + return {'hallway': L_HALL, 'blue': L_ROOM2, 'red': L_ROOM} + + +def add_blocks(grid): + grid_with_furnitures = grid.copy() + rooms_mask = np.ones_like(grid) + rooms_mask[grid == semantic_labels['room']] = 0 + rooms_mask[grid == semantic_labels['room2']] = 0 + + dialated_non_room_area = binary_dilation(rooms_mask, footprint=np.ones((15, 15))) + grid_with_furnitures[dialated_non_room_area == False] = semantic_labels['block'] # noqa + return grid_with_furnitures + + +def generate_parallel_lines( + grid_size, + num_of_lines, + spacing_between_lines, + boundary_threshold, + max_iter=1000): + ii = 0 + xy_lower_bound = boundary_threshold + 1 + y_upper_bound = grid_size[1] - boundary_threshold - 1 + grid = np.ones(grid_size, dtype=int) + final_semantic_grid = grid.copy() * L_TMP + intermediate_semantic_grid = grid.copy() * L_TMP + line_segments = [] + step = grid_size[0] // num_of_lines - 5 + offset = spacing_between_lines // 2 + + while ii < num_of_lines: + # Randomly pick a point that is at a safe distance from the + # boundaries before the inflation + random_point = np.random.randint( + step * ii + offset, min(step * (ii + 1) - offset, y_upper_bound) + ) + + # intermediate_semantic_grid[random_point[0], xy_lower_bound:random_point[1] + 1] = L_UNK + intermediate_semantic_grid[random_point, xy_lower_bound:y_upper_bound + 1] = L_UNK + final_semantic_grid = intermediate_semantic_grid.copy() + grid[final_semantic_grid == L_UNK] = 0 + + line_segments.append(([random_point, xy_lower_bound], [ + random_point, y_upper_bound])) + + ii += 1 + + return final_semantic_grid, line_segments, num_of_lines + + +def get_sorted_line_segments(line_segments): + result = [] + for line in line_segments: + line = list(line) + line.sort(key=lambda x: x[1]) + result.append(line) + result.sort(key=lambda x: x[0][0]) + return result + + +def add_connecting_rooms( + grid, line_segments, hallway_inflation_scale, room_length=10): + grid_with_hallway = grid.copy() + sorted_line_segments = get_sorted_line_segments(line_segments) + rooms_coords = [] + for idx, current_line in enumerate(sorted_line_segments[:-1]): + next_line = sorted_line_segments[idx + 1] + low = max(current_line[0][1], next_line[0][1]) + room_length // 2 + 5 + high = min(current_line[1][1], next_line[1][1]) - room_length // 2 - 5 + if low < high: + point_y = np.random.randint(low, high) + else: + raise RuntimeError('low >= high!') + point_x = [current_line[0][0] + hallway_inflation_scale + 1, + next_line[0][0] - hallway_inflation_scale - 1] + room_p1 = [point_x[0] + 1, point_y - room_length - 1] + room_p2 = [point_x[1], point_y + room_length + 1] + grid_with_hallway[room_p1[0]:room_p2[0], + room_p1[1]:room_p2[1]] = semantic_labels['room2'] + rooms_coords.append((room_p1, room_p2)) + # add door + grid_with_hallway[ + room_p1[0] - HALLWAY_ROOM_SPACE:room_p1[0], + (room_p1[1] + room_p2[1]) // 2 - DOOR_SIZE // 2:(room_p1[1] + room_p2[1]) // 2 + DOOR_SIZE // 2 + ] = semantic_labels['door'] + # add door on the other side + grid_with_hallway[ + room_p2[0]:room_p2[0] + HALLWAY_ROOM_SPACE, + (room_p1[1] + room_p2[1]) // 2 - DOOR_SIZE // 2:(room_p1[1] + room_p2[1]) // 2 + DOOR_SIZE // 2 + ] = semantic_labels['door'] + + return grid_with_hallway, rooms_coords + + +def gen_map_parallel(random_seed, resolution, grid_size, + num_of_hallways, boundary_threshold, + min_spacing_hallways, hallway_width, + room_width, room_length_range): + hallways_count = 0 + grid_with_lines, line_segments, hallways_count = \ + generate_parallel_lines( + grid_size=grid_size, num_of_lines=num_of_hallways, + spacing_between_lines=min_spacing_hallways, + boundary_threshold=boundary_threshold) + + grid_with_hallway = inflate_lines_to_create_hallways( + grid_with_lines, hallway_inflation_scale=hallway_width) + + grid_with_special_rooms, special_rooms_coords = add_connecting_rooms( + grid_with_hallway, line_segments, + hallway_inflation_scale=hallway_width, + room_length=room_length_range[0] // 2) + + grid_with_rooms, rooms_coords = add_rooms( + line_segments, grid_with_special_rooms, + hallway_inflation_scale=hallway_width, room_b=room_width, + room_l_range=room_length_range) + rooms_coords += special_rooms_coords + + # Place blocks to obscure the view inside rooms + grid = add_blocks(grid_with_rooms) + + occupancy_grid = (grid <= L_CLUTTER).astype(float) + + # Gets the wall_class_index for the current seed with change + # like even seed red, odd seed blue connections + wall_class_index = swap_room_color(seed=random_seed) + polys, walls = calc.split_semantic_grid_to_polys(occupancy_grid, + grid, + wall_class_index, + resolution=resolution, + do_compute_walls=True) + + return { + "occ_grid": occupancy_grid.copy(), + "semantic_grid": grid.copy(), + "semantic_labels": semantic_labels, + "polygons": polys, + "walls": walls, + "x_offset": 0.0, + "y_offset": 0.0, + "resolution": resolution, + "hallways_count": hallways_count, + "wall_class": wall_class_index + } + + +class MapGenParallel(base_generator.MapGenBase): + def gen_map(self, random_seed=None): + map_data = gen_map_parallel( + random_seed, resolution=self.args.base_resolution, + grid_size=GRID_SIZE, + num_of_hallways=NUM_OF_HALLWAYS, + boundary_threshold=BOUNDARY_THRESHOLD, + min_spacing_hallways=MIN_SPACING_HALLWAYS, + hallway_width=HALLWAY_WIDTH, + room_width=ROOM_WIDTH, + room_length_range=ROOM_LENGTH_RANGE) + + self.hr_grid = map_data["occ_grid"].copy() + self.grid = map_data["occ_grid"].copy() + self.semantic_grid = map_data['semantic_grid'].copy() + return self.hr_grid, self.grid, map_data + + def get_start_goal_poses(self, min_separation=220, max_separation=1e10, num_attemps=10000): + inflation_radius = self.args.inflation_radius_m / self.args.base_resolution + inflated_grid = gridmap.utils.inflate_grid(self.grid, inflation_radius) + hallway_cells = np.column_stack(np.where( + self.semantic_grid == semantic_labels['hallway'])) + free_cells = np.column_stack(np.where( + inflated_grid == gridmap.constants.FREE_VAL)) + nrows, ncols = hallway_cells.shape + dtype = {'names' : ['f{}'.format(i) for i in range(ncols)], + 'formats' : ncols * [hallway_cells.dtype]} + usable_cells = np.intersect1d(hallway_cells.view(dtype), free_cells.view(dtype)) + usable_cells = usable_cells.view(hallway_cells.dtype).reshape(-1, ncols) + + start_cell_pool = [] + goal_cell_pool = [] + for free_cell in usable_cells: + if free_cell[0] <= 50: + start_cell_pool.append(free_cell) + elif free_cell[0] >= 140: + goal_cell_pool.append(free_cell) + + for _ in range(num_attemps): + rand_start_index = np.random.choice( + np.arange(len(start_cell_pool)), size=1, replace=False)[0] + rand_goal_index = np.random.choice( + np.arange(len(goal_cell_pool)), size=1, replace=False)[0] + start = start_cell_pool[rand_start_index] + goal = goal_cell_pool[rand_goal_index] + + cost_grid, get_path = gridmap.planning. \ + compute_cost_grid_from_position(inflated_grid, goal) + did_plan, _ = get_path([start[0], start[1]], + do_sparsify=False, + do_flip=False) + path_cost = cost_grid[start[0], start[1]] + if path_cost >= min_separation and path_cost <= max_separation and did_plan: + start = Pose(x=start[0], y=start[1]) + goal = Pose(x=goal[0], y=goal[1]) + return (True, start, goal) + return (False, None, None) diff --git a/modules/lsp_gnn/lsp_gnn/learning/__init__.py b/modules/lsp_gnn/lsp_gnn/learning/__init__.py new file mode 100644 index 0000000..cbdfe4d --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/learning/__init__.py @@ -0,0 +1 @@ +from . import models # noqa \ No newline at end of file diff --git a/modules/lsp_gnn/lsp_gnn/learning/models/__init__.py b/modules/lsp_gnn/lsp_gnn/learning/models/__init__.py new file mode 100644 index 0000000..6f3d623 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/learning/models/__init__.py @@ -0,0 +1,4 @@ +from . import auto_encoder # noqa: F401 +from . import gcn # noqa: F401 +from . import cnn_lsp # noqa: F401 +from . import lsp # noqa: F401 diff --git a/modules/lsp_gnn/lsp_gnn/learning/models/auto_encoder.py b/modules/lsp_gnn/lsp_gnn/learning/models/auto_encoder.py new file mode 100644 index 0000000..b80de13 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/learning/models/auto_encoder.py @@ -0,0 +1,228 @@ +import os +import torch +import numpy as np +import torch.nn as nn +from torch.utils.data import DataLoader +from torch.utils.tensorboard import SummaryWriter + +import lsp_gnn +import learning +from learning.data import CSVPickleDataset +from vertexnav.models import EncoderNBlocks, DecoderNBlocks + +MINI_BATCH_SIZE = 40 + + +class AutoEncoder(nn.Module): + name = "AutoEncoder" + + def __init__(self, args=None): + super(AutoEncoder, self).__init__() + torch.manual_seed(8616) + if args.input_type == 'image': + start_dim = 3 + elif args.input_type == 'seg_image': + start_dim = 4 + channel = 32 + hidden = 8 + self._args = args # (3, 32, 16) + self.enc_1 = EncoderNBlocks(start_dim, channel, num_layers=2) # (8, 16, 8) + self.enc_2 = EncoderNBlocks(channel, channel, num_layers=2) # (8, 8, 4) + self.enc_3 = EncoderNBlocks(channel, hidden, num_layers=2) # (4, 4, 2) + + self.dec_1 = DecoderNBlocks(hidden, channel, num_layers=2) + self.dec_2 = DecoderNBlocks(channel, channel, num_layers=2) + self.dec_3 = DecoderNBlocks(channel, start_dim, num_layers=2) + + # The following method is used only during evaluating + def encoder(self, data, device): + x = data['image'].to(device) + x = self.enc_1(x) + x = self.enc_2(x) + x = self.enc_3(x) + latent_features = x + return latent_features + + def decoder(self, x, device): + x = self.dec_1(x) + x = self.dec_2(x) + x = self.dec_3(x) + output = { + 'image': x + } + return output + + # The following method is used only during training + def forward(self, data, device): + x = self.encoder(data, device) + return self.decoder(x, device) # , self.lsp(x, device) + + def loss(self, nn_out, data, device='cpu', + writer=None, index=None): + pred_img = nn_out['image'] + trgt_img = data['image'].to(device) + if self._args.input_type == 'seg_image': + image_logsoftmax = torch.nn.LogSoftmax(dim=1)(pred_img) + loss_img = -torch.sum(image_logsoftmax * trgt_img, dim=1) + loss_img = torch.mean(loss_img) + elif self._args.input_type == 'image': + if self._args.loss == 'l1': + mae_loss = nn.L1Loss() + loss_img = mae_loss(pred_img, trgt_img) + elif self._args.loss == 'l2': + mse_loss = nn.MSELoss() + loss_img = mse_loss(pred_img, trgt_img) + + # Logging + if writer is not None: + writer.add_scalar("Loss_AE/image_loss", + loss_img.item(), + index) + return loss_img + + @classmethod + def get_net_eval_fn(_, network_file, device, preprocess_for=None, args=None): + model = AutoEncoder(args) + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def latent_features_net(datum): + with torch.no_grad(): + if preprocess_for == 'Cond_Eval': + latent_features = torch.zeros(0).to(device) + for idx, image in enumerate(datum['image']): + data = lsp_gnn.utils.preprocess_cnn_data( + datum, idx=idx, args=args) + lf = model.encoder(data, device) + if datum['is_subgoal'][idx] == 0: + lf = torch.mean(lf, dim=0).expand(1, -1, -1, -1) + latent_features = torch.cat(( + latent_features, lf), 0) + elif preprocess_for == 'CNN_Eval': + data = lsp_gnn.utils.preprocess_cnn_eval_data(datum, args) + latent_features = model.encoder(data, device) + else: + data = datum + latent_features = torch.cat([model.encoder({ + 'image': data['image'][idx:idx + MINI_BATCH_SIZE], + }, device) for idx in range(0, len(data['image']), + MINI_BATCH_SIZE)]) + return latent_features.flatten(start_dim=1) + + return latent_features_net + + @learning.logging.tensorboard_plot_decorator + def plot_images(self, fig, out, data): + index = 0 + pred_img = np.transpose( + out['image'][index].detach().cpu().numpy(), (1, 2, 0)) + trgt_img = np.transpose(data['image'][index].cpu().numpy(), (1, 2, 0)) + + axs = fig.subplots(1, 2, squeeze=False) + axs[0][0].imshow(trgt_img, interpolation='none') + axs[0][0].set_title("Input image") + axs[0][1].imshow(pred_img, interpolation='none') + axs[0][1].set_title("Recreated image") + + +def train(args, train_path, test_path): + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + if args.input_type == 'image': + prep_fn = lsp_gnn.utils.preprocess_ae_img + elif args.input_type == 'seg_image': + prep_fn = lsp_gnn.utils.preprocess_ae_seg_img + else: + print("No AE training required for wall class label input_type") + return + + # Create the datasets and loaders + train_dataset = CSVPickleDataset(train_path, prep_fn) + print("Number of training images:", len(train_dataset)) + train_loader = DataLoader(train_dataset, + batch_size=16, + shuffle=True, + num_workers=0) + + train_iter = iter(train_loader) + train_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, "train_autoencoder")) + + test_dataset = CSVPickleDataset(test_path, prep_fn) + print("Number of testing images:", len(test_dataset)) + test_loader = DataLoader(test_dataset, + batch_size=16, + shuffle=True, + num_workers=0) + + test_iter = iter(test_loader) + test_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, "test_autoencoder")) + + # Initialize the network and the optimizer + model = AutoEncoder(args) + model.to(device) + + optimizer = torch.optim.Adam(model.parameters(), lr=args.learning_rate) + scheduler = torch.optim.lr_scheduler.StepLR( + optimizer, step_size=args.epoch_size, + gamma=args.learning_rate_decay_factor) + index = 0 + while index < args.num_steps: + # Get the batches + try: + train_batch = next(train_iter) + except StopIteration: + train_iter = iter(train_loader) + train_batch = next(train_iter) + # out is a dictionary + out = model.forward(train_batch, device) + train_loss = model.loss(out, + data=train_batch, + device=device, + writer=train_writer, + index=index) + if index % args.test_log_frequency == 0: + print(f"[{index}/{args.num_steps}] " + f"Train Loss: {train_loss}") + + # Train the system + optimizer.zero_grad() + train_loss.backward() + optimizer.step() + + if index % args.test_log_frequency == 0: + try: + test_batch = next(test_iter) + except StopIteration: + test_iter = iter(test_loader) + test_batch = next(test_iter) + with torch.no_grad(): + out = model.forward(test_batch, device) + test_loss = model.loss(out, + data=test_batch, + device=device, + writer=test_writer, + index=index) + if args.input_type == 'image': + # Plotting + model.plot_images( + test_writer, 'image', index, + out=out, data=test_batch) + print(f"[{index}/{args.num_steps}] " + f"Test Loss: {test_loss.cpu().numpy()}") + print(f"Learning rate: {scheduler.get_last_lr()[-1]}") + + # Log the learning rate + test_writer.add_scalar("learning_rate/AE", + scheduler.get_last_lr()[-1], + index) + + index += 1 + scheduler.step() + + # Saving the model after training + torch.save(model.state_dict(), + os.path.join(args.save_dir, "AutoEncoder.pt")) diff --git a/modules/lsp_gnn/lsp_gnn/learning/models/cnn_lsp.py b/modules/lsp_gnn/lsp_gnn/learning/models/cnn_lsp.py new file mode 100644 index 0000000..a6f5522 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/learning/models/cnn_lsp.py @@ -0,0 +1,71 @@ +import torch +import torch.nn as nn +import torch.nn.functional as F + +import lsp_gnn +from lsp_gnn.learning.models.lsp import AbstractLSP + + +class WallClassLSP(AbstractLSP): + name = 'LSPforWallClass' + + def __init__(self, args=None): + super(WallClassLSP, self).__init__(args) + + self.fc1 = nn.Linear(3 + 4, 8) + self.fc2 = nn.Linear(8, 8) + self.fc3 = nn.Linear(8, 8) + self.fc4 = nn.Linear(8, 8) + self.fc5 = nn.Linear(8, 8) + self.fc6 = nn.Linear(8, 8) + self.fc7 = nn.Linear(8, 8) + self.classifier = nn.Linear(8, 3) + + self.fc1bn = nn.BatchNorm1d(8) + self.fc2bn = nn.BatchNorm1d(8) + self.fc3bn = nn.BatchNorm1d(8) + self.fc4bn = nn.BatchNorm1d(8) + self.fc5bn = nn.BatchNorm1d(8) + self.fc6bn = nn.BatchNorm1d(8) + self.fc7bn = nn.BatchNorm1d(8) + + def forward(self, data, device): + h, _, _ = self.forward_helper(data, device, cnn=True) + h = F.leaky_relu(self.fc1bn(self.fc1(h)), 0.1) + h = F.leaky_relu(self.fc2bn(self.fc2(h)), 0.1) + h = F.leaky_relu(self.fc3bn(self.fc3(h)), 0.1) + h = F.leaky_relu(self.fc4bn(self.fc4(h)), 0.1) + h = F.leaky_relu(self.fc5bn(self.fc5(h)), 0.1) + h = F.leaky_relu(self.fc6bn(self.fc6(h)), 0.1) + h = F.leaky_relu(self.fc7bn(self.fc7(h)), 0.1) + h = self.classifier(h) + return h + + @classmethod + def get_net_eval_fn(_, network_file, device=None): + model = WallClassLSP() + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def frontier_net(datum, vertex_points, subgoals): + graph = lsp_gnn.utils.preprocess_gcn_data(datum) + prob_feasible_dict = {} + dsc_dict = {} + ec_dict = {} + with torch.no_grad(): + out = model.forward(graph, device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + for subgoal in subgoals: + index_pos, possible_node = lsp_gnn.utils. \ + get_subgoal_node(vertex_points, subgoal) + # Extract subgoal properties for a subgoal + subgoal_props = out[index_pos] + prob_feasible_dict[subgoal] = subgoal_props[0] + dsc_dict[subgoal] = subgoal_props[1] + ec_dict[subgoal] = subgoal_props[2] + return prob_feasible_dict, dsc_dict, ec_dict, out[:, 0] + return frontier_net diff --git a/modules/lsp_gnn/lsp_gnn/learning/models/gcn.py b/modules/lsp_gnn/lsp_gnn/learning/models/gcn.py new file mode 100644 index 0000000..2a71388 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/learning/models/gcn.py @@ -0,0 +1,74 @@ +import torch +import torch.nn as nn +import torch.nn.functional as F +from torch_geometric.nn import GATv2Conv + +import lsp_gnn +from lsp_gnn.learning.models.lsp import AbstractLSP + + +class WallClassGNN(AbstractLSP): + name = 'GNNforWallClass' + + def __init__(self, args=None): + super(WallClassGNN, self).__init__(args) + + self.fc1 = nn.Linear(3 + 3, 8) + self.fc2 = nn.Linear(8, 8) + self.fc3 = nn.Linear(8, 8) + self.conv1 = GATv2Conv(8, 8, edge_dim=1) + self.conv2 = GATv2Conv(8, 8, edge_dim=1) + self.conv3 = GATv2Conv(8, 8, edge_dim=1) + self.conv4 = GATv2Conv(8, 8, edge_dim=1) + self.classifier = nn.Linear(8, 3) + + self.fc1bn = nn.BatchNorm1d(8) + self.fc2bn = nn.BatchNorm1d(8) + self.fc3bn = nn.BatchNorm1d(8) + self.conv1bn = nn.BatchNorm1d(8) + self.conv2bn = nn.BatchNorm1d(8) + self.conv3bn = nn.BatchNorm1d(8) + self.conv4bn = nn.BatchNorm1d(8) + + def forward(self, data, device): + h, edge_index, edge_features = self.forward_helper(data, device) + h = F.leaky_relu(self.fc1bn(self.fc1(h)), 0.1) + h = F.leaky_relu(self.fc2bn(self.fc2(h)), 0.1) + h = F.leaky_relu(self.fc3bn(self.fc3(h)), 0.1) + h = F.leaky_relu(self.conv1bn(self.conv1(h, edge_index, edge_features)), 0.1) + h = F.leaky_relu(self.conv2bn(self.conv2(h, edge_index, edge_features)), 0.1) + h = F.leaky_relu(self.conv3bn(self.conv3(h, edge_index, edge_features)), 0.1) + h = F.leaky_relu(self.conv4bn(self.conv4(h, edge_index, edge_features)), 0.1) + props = self.classifier(h) + return props + + @classmethod + def get_net_eval_fn(_, network_file, + device=None): + model = WallClassGNN() + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def frontier_net(datum, vertex_points, subgoals): + graph = lsp_gnn.utils.preprocess_gcn_data(datum) + prob_feasible_dict = {} + dsc_dict = {} + ec_dict = {} + with torch.no_grad(): + out = model.forward(graph, device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + for subgoal in subgoals: + index_pos, possible_node = lsp_gnn.utils. \ + get_subgoal_node(vertex_points, subgoal) + # Extract subgoal properties for a subgoal + subgoal_props = out[index_pos] + prob_feasible_dict[subgoal] = subgoal_props[0] + dsc_dict[subgoal] = subgoal_props[1] + ec_dict[subgoal] = subgoal_props[2] + return prob_feasible_dict, dsc_dict, ec_dict, out[:, 0] + + return frontier_net diff --git a/modules/lsp_gnn/lsp_gnn/learning/models/lsp.py b/modules/lsp_gnn/lsp_gnn/learning/models/lsp.py new file mode 100644 index 0000000..8312503 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/learning/models/lsp.py @@ -0,0 +1,100 @@ +import torch +import torch.nn as nn +import torch_geometric.utils +import torch.nn.functional as F + + +class AbstractLSP(nn.Module): + name = 'AbstractClassForLSP' + + def __init__(self, args=None): + super(AbstractLSP, self).__init__() + torch.manual_seed(8616) + self._args = args + + def forward(self, data, device): + raise NotImplementedError + + def forward_helper(self, data, device, cnn=False): + lf = data['latent_features'].type(torch.float).to(device) + edge_data = data['edge_data'] + x = torch.cat((edge_data[0], edge_data[1]), 0) + y = torch.cat((edge_data[1], edge_data[0]), 0) + edge_data = torch.reshape(torch.cat((x, y), 0), (2, -1)) + edge_index = edge_data.to(device) + edge_features = data['edge_features'].type(torch.float).to(device) + edge_features = edge_features.repeat(2, 1).to(device) / 200 + + distance = data['goal_distance'].view(-1, 1).to(device) / 200 + history = data['history'].view(-1, 1).to(device) + is_subgoal = data['is_subgoal'].view(-1, 1).to(device) + degree = torch_geometric.utils.degree(edge_index[0]).view(-1, 1).to(device) + degree[history == 1] = 0 + degree = degree / 4 + if cnn: + h = torch.cat((lf, is_subgoal, history, distance, degree), 1) + else: + h = torch.cat((lf, is_subgoal, history, degree), 1) + return h, edge_index, edge_features + + def loss(self, nn_out, data, device='cpu', writer=None, index=None): + # Separate outputs. + is_feasible_logits = nn_out[:, 0] + delta_cost_pred = nn_out[:, 1] + exploration_cost_pred = nn_out[:, 2] + + # Convert the data + is_feasible_label = data.y.to(device) + delta_cost_label = data.dsc.to(device) + exploration_cost_label = data.ec.to(device) + pweight = data.pweight.to(device) # TODO - Remove? + nweight = data.nweight.to(device) # TODO - Remove? + history = data.is_subgoal.to(device) + rpw = self._args.relative_positive_weight + subgoal_weight = history # * (has_updated + 0.1) + + # Compute the contribution from the is_feasible_label + is_feasible_xentropy = rpw * is_feasible_label * -F.logsigmoid( + is_feasible_logits) * pweight / 10 + (1 - is_feasible_label) * \ + -F.logsigmoid(-is_feasible_logits) * nweight / 10 + is_feasible_xentropy = torch.sum(subgoal_weight * is_feasible_xentropy) + is_feasible_xentropy /= torch.sum(subgoal_weight) + 0.001 + # Set the loss type for Delta Success Cost and Exploration Cost + if self._args.loss == 'l1': + cost_loss = torch.abs + else: + cost_loss = torch.square + + # Delta Success Cost + delta_cost_pred_error = cost_loss( + delta_cost_pred - delta_cost_label) \ + / (10 ** 1) * is_feasible_label + delta_cost_pred_error = torch.sum(subgoal_weight * delta_cost_pred_error) + delta_cost_pred_error /= torch.sum(subgoal_weight) + 0.001 + # Exploration Cost + exploration_cost_pred_error = cost_loss( + exploration_cost_pred - exploration_cost_label) / \ + (20 ** 1 * 4) * (1 - is_feasible_label) + exploration_cost_pred_error = torch.sum(subgoal_weight * exploration_cost_pred_error) + exploration_cost_pred_error /= torch.sum(subgoal_weight) + 0.001 + + # Sum the contributions + loss = is_feasible_xentropy + delta_cost_pred_error + \ + exploration_cost_pred_error + + # Logging + if writer is not None: + writer.add_scalar("Loss/is_feasible_xentropy", + is_feasible_xentropy.item(), + index) + writer.add_scalar("Loss/delta_success_cost_loss", + delta_cost_pred_error.item(), + index) + writer.add_scalar("Loss/exploration_cost_loss", + exploration_cost_pred_error.item(), + index) + writer.add_scalar("Loss/total_loss", + loss.item(), + index) + + return loss diff --git a/modules/lsp_gnn/lsp_gnn/planners.py b/modules/lsp_gnn/lsp_gnn/planners.py new file mode 100644 index 0000000..4eb3822 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/planners.py @@ -0,0 +1,610 @@ +import copy +import torch +import numpy as np + +import lsp +import gridmap +import lsp_gnn +from lsp.planners.planner import Planner +# from lsp_gnn.learning.models.auto_encoder import AutoEncoder +from lsp_gnn.learning.models.gcn import WallClassGNN +from lsp_gnn.learning.models.cnn_lsp import WallClassLSP + + +NUM_MAX_FRONTIERS = 8 + + +class ConditionalSubgoalPlanner(Planner): + ''' The parent planner class that takes care of the updated graph representation of + the environment. ''' + def __init__(self, goal, args, device=None, + semantic_grid=None, wall_class=None): + super(ConditionalSubgoalPlanner, self).__init__(goal) + + self.subgoals = set() + self.selected_subgoal = None + self.semantic_grid = semantic_grid + self.wall_class = wall_class + self.args = args + + self.vertex_points = None + self.edge_data = None + + self.inflation_radius = args.inflation_radius_m / args.base_resolution + if self.inflation_radius >= np.sqrt(5): + self.downsample_factor = 2 + else: + self.downsample_factor = 1 + self.verbose = False + self.old_node_dict = {} + + def update(self, observation, observed_map, + subgoals, robot_pose, *args, **kwargs): + """Updates the internal state with the new grid/pose/laser scan. + This function also computes a few necessary items, like which + frontiers have recently been updated and computes their properties + from the known grid. + """ + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=2.0 / self.args.base_resolution, # Was set to 20.0 + chosen_frontier=self.selected_subgoal) + self.original_subgoal = self.subgoals.copy() + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, + self.goal) + + skeletonized_graph_data = lsp_gnn.utils.compute_skeleton( + inflated_grid.copy(), self.subgoals) + self.vertex_points = skeletonized_graph_data['vertex_points'] + self.edge_data = skeletonized_graph_data['edges'] + + # Update the subgoal inputs & get representative nodes for the subgoals + self.subgoal_nodes = self._identify_subgoal_nodes() + + # Once the subgoal inputs are set, compute their properties + self._update_subgoal_properties(robot_pose, self.goal) + self.old_node_dict = self.new_node_dict.copy() + assert len(self.subgoals) == len(self.subgoal_nodes) + + def _identify_subgoal_nodes(self): + """ Loop through subgoals and get the 'input data' + This method also finds the representitive node for each subgoal + on the graph and pairs their image as well + """ + # Update the inputs for each vertex point on the graph based on the new + # observation + self._update_node_inputs() + clean_data = lsp_gnn.utils.prepare_input_clean_graph( + self.subgoals, self.vertex_points, self.edge_data, + self.new_node_dict, self.has_updated, self.semantic_grid, + self.wall_class, self.observation, self.robot_pose + ) + self.vertex_points = clean_data['vertex_points'] + self.edge_data = clean_data['edge_data'] + self.new_node_dict = clean_data['new_node_dict'] + self.has_updated = clean_data['has_updated'] + + return clean_data['subgoal_nodes'] + + def _update_node_inputs(self): + ''' This method computes and assigns input for each of the nodes + present on the graph and maintains a dictionary for it. + ''' + self.new_node_dict = {} + self.has_updated = [] + + for vertex_point in self.vertex_points: + vertex_point = tuple(vertex_point) + # If the vertex point exists in previous step then perform the + # following steps -> + if vertex_point in self.old_node_dict.keys(): + input_data = self.old_node_dict[vertex_point] + self.has_updated.append(0) + # -> Otherwise calculate input data for new vertex point + else: + input_data = lsp_gnn.utils.get_input_data( + self.semantic_grid, self.wall_class, vertex_point, + self.observation, self.robot_pose) + # input_data['last_observed_pose'] = self.robot_pose + self.has_updated.append(1) + self.new_node_dict[vertex_point] = input_data + + def _compute_combined_data(self): + """ This method produces a datum for the GCN and returns it. + make_graph(datum) needs to be called prior to forwording to + the network + """ + is_subgoal = [] + history = [] + # image = [] + # seg_image = [] + input_vector = [] + goal_distance_vector = [] + + for vertex_point in self.vertex_points: + vertex_point = tuple(vertex_point) + # image.append(self.new_node_dict[vertex_point]['image']) + x = self.new_node_dict[vertex_point]['x'] + y = self.new_node_dict[vertex_point]['y'] + goal_distance_vector.append(np.sqrt( + (x - self.goal.x) ** 2 + + (y - self.goal.y) ** 2)) + input_vector.append(self.new_node_dict[vertex_point]['input']) + # seg_image.append(self.new_node_dict[vertex_point]['seg_image']) + if vertex_point in self.subgoal_nodes.keys(): + is_subgoal.append(1) + history.append(1) + else: + is_subgoal.append(0) + history.append(0) + assert len(is_subgoal) == len(self.has_updated) + + edge_features = lsp_gnn.utils.get_edge_features( + edge_data=self.edge_data, + vertex_points=self.vertex_points, + node_dict=self.new_node_dict + ) + + datum = { + 'wall_class': input_vector, + # 'image': image, + # 'seg_image': seg_image, + 'goal_distance': goal_distance_vector, + 'is_subgoal': is_subgoal, + 'history': history, + 'edge_data': self.edge_data, + 'has_updated': self.has_updated, + 'edge_features': edge_features + } + return datum + + def _update_subgoal_properties(self, robot_pose, goal_pose): + raise NotImplementedError("Method for abstract class") + + +class ConditionalKnownSubgoalPlanner(ConditionalSubgoalPlanner): + ''' This planner class is used for data generation using known map ''' + def __init__(self, goal, args, known_map, device=None, + semantic_grid=None, wall_class=None, do_compute_weightings=True): + super(ConditionalKnownSubgoalPlanner, self). \ + __init__(goal, args, device, semantic_grid, wall_class) + + self.known_map = known_map + self.inflated_known_grid = gridmap.utils.inflate_grid( + known_map, inflation_radius=self.inflation_radius) + _, self.get_path = gridmap.planning.compute_cost_grid_from_position( + self.inflated_known_grid, [goal.x, goal.y]) + self.counter = 0 + self.last_saved_training_data = None + self.do_compute_weightings = do_compute_weightings + + def _update_subgoal_properties(self, robot_pose, goal_pose): + new_subgoals = [s for s in self.subgoals if not s.props_set] + lsp.core.update_frontiers_properties_known( + self.inflated_known_grid, + self.inflated_grid, + self.subgoals, new_subgoals, + robot_pose, goal_pose, + self.downsample_factor) + + if self.do_compute_weightings: + lsp.core.update_frontiers_weights_known(self.inflated_known_grid, + self.inflated_grid, + self.subgoals, new_subgoals, + robot_pose, goal_pose, + self.downsample_factor) + + def compute_training_data(self): + """ This method produces training datum for both AutoEncoder and + GCN model. + """ + prob_feasible = [] + delta_success_cost = [] + exploration_cost = [] + positive_weighting_vector = [] + negative_weighting_vector = [] + data = self._compute_combined_data() + for idx, node in enumerate(self.vertex_points): + p = tuple(node) + if p in self.subgoal_nodes.keys(): + if self.subgoal_nodes[p].prob_feasible == 1.0 \ + and data['has_updated'][idx] != 1: + # Checks if an alternate subgoal path is still reachable. + # This changes the label for the subgoal whose + # alternate path has already explored the merging + # point through this subgoal + is_reachable = lsp_gnn.utils.check_if_reachable( + self.inflated_known_grid, self.inflated_grid, + self.goal, self.robot_pose, self.subgoal_nodes[p]) + if is_reachable is False: + data['has_updated'][idx] = 1 + prob_feasible.append(self.subgoal_nodes[p].prob_feasible) + delta_success_cost.append(self.subgoal_nodes[p].delta_success_cost) + exploration_cost.append(self.subgoal_nodes[p].exploration_cost) + positive_weighting_vector.append(self.subgoal_nodes[p].positive_weighting) + negative_weighting_vector.append(self.subgoal_nodes[p].negative_weighting) + else: + prob_feasible.append(0) + delta_success_cost.append(0) + exploration_cost.append(0) + positive_weighting_vector.append(0) + negative_weighting_vector.append(0) + + data['is_feasible'] = prob_feasible + data['delta_success_cost'] = delta_success_cost + data['exploration_cost'] = exploration_cost + data['positive_weighting'] = positive_weighting_vector + data['negative_weighting'] = negative_weighting_vector + data['known_map'] = self.known_map + data['observed_map'] = self.observed_map + data['subgoals'] = self.original_subgoal + data['vertex_points'] = self.vertex_points + data['goal'] = self.goal + data['semantic_grid'] = self.semantic_grid + data['semantic_labels'] = self.wall_class + + return data + + def save_training_data(self, training_data, prob=.2): + do_save = np.random.choice([True, False], 1, p=[prob, 1 - prob]) + if do_save: + # Before saving check so that it is not identical to last saved data + if self.last_saved_training_data: + if lsp_gnn.utils.check_if_same( + training_data, self.last_saved_training_data): + return + lsp_gnn.utils.write_datum_to_file(self.args, + training_data, + self.counter) + self.last_saved_training_data = training_data + self.counter += 1 + + def compute_selected_subgoal(self): + """Use the known map to compute the selected subgoal.""" + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, + self.goal, self.subgoals) + if is_goal_in_range: + print("Goal in Range") + return None + if not self.subgoals: + return None + + # Compute the plan + did_plan, path = self.get_path([self.robot_pose.x, self.robot_pose.y], + do_sparsify=False, + do_flip=True, + bound=None) + if did_plan is False: + print("Plan did not succeed...") + raise NotImplementedError("Not sure what to do here yet") + if np.argmax(self.observed_map[path[0, -1], path[1, -1]] >= 0): + return None + + # Determine the chosen subgoal + ind = np.argmax(self.observed_map[path[0, :], path[1, :]] < 0) + return min(self.subgoals, + key=lambda s: s.get_distance_to_point((path.T)[ind])) + + +class ConditionalUnknownSubgoalPlanner(ConditionalSubgoalPlanner): + ''' This planner class is used for planning under uncertainty by estimating the + properties of the subgoals using a trained graph neural network ''' + def __init__(self, goal, args, semantic_grid=None, + wall_class=None, device=None): + super(ConditionalUnknownSubgoalPlanner, self). \ + __init__(goal, args, device, semantic_grid, wall_class) + + self.out = None + + if device is None: + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + self.device = device + self.super_node_latent_features = None + # if args.input_type == 'image' or self.args.input_type == 'seg_image': + # self.latent_features_net = AutoEncoder. \ + # get_net_eval_fn_old( + # args.autoencoder_network_file, device=self.device, + # preprocess_for='Cond_Eval', args=self.args) + # self.subgoal_property_net = LSPConditionalGNN.get_net_eval_fn( + # args.network_file, device=self.device) + if args.input_type == 'wall_class' and args.train_marginal_lsp: + self.subgoal_property_net = WallClassGNN.get_net_eval_fn( + args.network_file, device=self.device) + # elif args.use_clip: + # self.latent_features_net = AutoEncoder.get_net_eval_fn( + # args.clip_network_file, device=self.device, + # preprocess_for='Cond_Eval') + + def _compute_cnn_data(self): + """ This method produces datum for the AutoEncoder """ + images = [] + is_subgoal = [] + + for vertex_point in self.vertex_points: + vertex_point = tuple(vertex_point) + # Check if the latent features need to be recomputed for the vertex + # points + if 'latent_features' not in self.new_node_dict[vertex_point].keys(): + images.append(self.new_node_dict[vertex_point]['image']) + if vertex_point in self.subgoal_nodes.keys(): + is_subgoal.append(1) + else: + is_subgoal.append(0) + + if self.super_node_latent_features is None: + images.append(np.zeros((128, 512, 3))) + is_subgoal.append(0) + datum = { + 'image': images, + 'is_subgoal': is_subgoal, + } + return datum + + def _calculate_latent_features(self): + ''' This method computes and assigns latent features to their + respective node. + ''' + self.cnn_input = self._compute_cnn_data() + if self.cnn_input['image']: # Check if cnn_input is not empty + latent_features = self.latent_features_net( + datum=self.cnn_input) + + ii = 0 + for vertex_point in self.vertex_points: + vertex_point = tuple(vertex_point) + # Checks and assigns latent features to their nodes + if 'latent_features' not in self.new_node_dict[vertex_point].keys(): + self.new_node_dict[vertex_point]['latent_features'] = \ + latent_features[ii][None, :] # expanding one dimension + ii += 1 + if self.super_node_latent_features is None: + self.super_node_latent_features = latent_features[-1][None, :] + + def _compute_gcn_data(self): + """ This method produces a datum for the GCN and returns it. + make_graph(datum) needs to be called prior to forwording to + the network + """ + # Prior to running GCN, CNN must create the latent features + if self.args.input_type == 'image' or \ + self.args.input_type == 'seg_image': + self._calculate_latent_features() + latent_features = torch.zeros(0).to(self.device) + elif self.args.input_type == 'wall_class': + latent_features = [] + distance_features = [] + is_subgoal = [] + history = [] + + for vertex_point in self.vertex_points: + vertex_point = tuple(vertex_point) + if self.args.input_type == 'image' or \ + self.args.input_type == 'seg_image': + latent_features = torch.cat(( + latent_features, + self.new_node_dict[vertex_point]['latent_features']), 0) + elif self.args.input_type == 'wall_class': + x = self.new_node_dict[vertex_point]['x'] + y = self.new_node_dict[vertex_point]['y'] + distance_features.append(np.sqrt( + (x - self.goal.x) ** 2 + + (y - self.goal.y) ** 2)) + latent_features.append( + self.new_node_dict[vertex_point]['input']) + if vertex_point in self.subgoal_nodes.keys(): + # taking note of the node being a subgoal + is_subgoal.append(1) + # marking if the subgoal will participate + # in conditional probability + history.append(1) + else: + is_subgoal.append(0) + history.append(0) + + edge_features = lsp_gnn.utils.get_edge_features( + edge_data=self.edge_data, + vertex_points=self.vertex_points, + node_dict=self.new_node_dict + ) + + # Add the super node + super_node_idx = len(history) + if self.args.input_type == 'image' or \ + self.args.input_type == 'seg_image': + latent_features = torch.cat( + (latent_features, self.super_node_latent_features), 0) + elif self.args.input_type == 'wall_class': + latent_features.append([0, 0, 0]) + latent_features = torch.tensor(latent_features, dtype=torch.float) + + is_subgoal.append(0) + history = [0] * len(history) + history.append(1) + old_edges = [edge_pair for edge_pair in self.edge_data] + new_edges = [(idx, super_node_idx) for idx in range(super_node_idx)] + updated_edges = old_edges + new_edges + + # Add feature for each new edges connected to the super node + for distance in distance_features: + feature_vector = [] + feature_vector.append(distance) + edge_features.append(feature_vector) + distance_features.append(0) + datum = { + 'is_subgoal': is_subgoal, + 'history': history, + 'edge_data': updated_edges, + 'edge_features': edge_features, + 'latent_features': latent_features, + 'goal_distance': distance_features, + } + return datum + + def _update_subgoal_properties(self, + robot_pose, + goal_pose): + self.gcn_graph_input = self._compute_gcn_data() + prob_feasible_dict, dsc, ec, out = self.subgoal_property_net( + datum=self.gcn_graph_input, + vertex_points=self.vertex_points, + subgoals=self.subgoals + ) + for subgoal in self.subgoals: + subgoal.set_props( + prob_feasible=prob_feasible_dict[subgoal], + delta_success_cost=dsc[subgoal], + exploration_cost=ec[subgoal], + last_observed_pose=robot_pose) + if self.verbose: + print( + f'Ps={subgoal.prob_feasible:8.4f}|' + f'Rs={subgoal.delta_success_cost:8.4f}|' + f'Re={subgoal.exploration_cost:8.4f}' + ) + + if self.verbose: + print(" ") + + self.out = out + # The line below is not getting updated to the last elimination pass + # that is happening before cost calculation, however this is not that + # important because the self.is_subgoal is only used to plot the graph + # not in cost calculation. Will fix it if necessary. + self.is_subgoal = self.gcn_graph_input['is_subgoal'].copy() + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, + self.goal, self.subgoals) + if is_goal_in_range: + print("Goal in Range") + return None + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp_gnn.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + self.vertex_points.copy(), + self.subgoal_nodes.copy(), + self.gcn_graph_input.copy(), + self.subgoal_property_net, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + raise ValueError() + print("Problem with planning.") + return None + self.latest_ordering = frontier_ordering + self.selected_subgoal = list(self.subgoals)[frontier_ordering[0]] + return self.selected_subgoal + + +class LSP(ConditionalUnknownSubgoalPlanner): + def __init__(self, goal, args, device=None, verbose=False, + semantic_grid=None, wall_class=None): + super(LSP, self).__init__(goal, args, device, semantic_grid, wall_class) + + if device is not None: + self.device = device + else: + use_cuda = torch.cuda.is_available() + self.device = torch.device("cuda" if use_cuda else "cpu") + + # if args.input_type == 'image' or args.input_type == 'seg_image': + # self.latent_features_net = AutoEncoder.get_net_eval_fn_old( + # args.autoencoder_network_file, device=self.device, + # preprocess_for='CNN_Eval', args=self.args) + # self.subgoal_property_net = CNNLSP.get_net_eval_fn( + # args.cnn_network_file, device=self.device) + if args.input_type == 'wall_class': + self.subgoal_property_net = WallClassLSP.get_net_eval_fn( + args.cnn_network_file, device=self.device) + + self.semantic_grid = semantic_grid + self.wall_class = wall_class + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + + if is_goal_in_range: + print("Goal in Range") + return None + + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor, + do_correct_low_prob=True)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + print("Problem with planning.") + self.latest_ordering = None + self.selected_subgoal = None + return None + + self.latest_ordering = frontier_ordering + self.selected_subgoal = frontier_ordering[0] + return self.selected_subgoal + + +class GCNLSP(ConditionalUnknownSubgoalPlanner): + def __init__(self, goal, args, semantic_grid=None, + wall_class=None, device=None): + args.network_file = args.gcn_network_file + super(GCNLSP, self).__init__(goal, args, semantic_grid, wall_class, device) + if args.input_type == 'wall_class': + self.subgoal_property_net = WallClassGNN.get_net_eval_fn( + args.network_file, device=self.device) + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + + if is_goal_in_range: + print("Goal in Range") + return None + + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor, + do_correct_low_prob=True)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + print("Problem with planning.") + self.latest_ordering = None + self.selected_subgoal = None + return None + + self.latest_ordering = frontier_ordering + self.selected_subgoal = frontier_ordering[0] + return self.selected_subgoal diff --git a/modules/lsp_gnn/lsp_gnn/plotting.py b/modules/lsp_gnn/lsp_gnn/plotting.py new file mode 100644 index 0000000..9ee8f3d --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/plotting.py @@ -0,0 +1,104 @@ +import numpy as np +import matplotlib.pyplot as plt +from skimage.morphology import erosion + +import lsp +from lsp.constants import (COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL, + OBSTACLE_THRESHOLD) + +FOOT_PRINT = [ + [1, 1, 1], + [1, 1, 1], + [1, 1, 1], +] + + +def plot_pose(ax, pose, color='black', filled=True): + if filled: + ax.scatter(pose.x, pose.y, color=color, s=10, label='point') + else: + ax.scatter(pose.x, + pose.y, + color=color, + s=10, + label='point', + facecolors='none') + + +def plot_path(ax, path, style='m:'): + if path is not None and len(path) == 2: + ax.plot(path[0, :], path[1, :], style) + + +def plot_pose_path(ax, poses, style='m'): + path = np.array([[p.x, p.y] for p in poses]).T + plot_path(ax, path, style) + + +def plot_grid(ax, + grid_map, + known_map, + frontiers=None, + cmap_name='viridis'): + grid = lsp.utils.plotting.make_plotting_grid(grid_map, known_map) + if frontiers is not None: + cmap = plt.get_cmap(cmap_name) + for frontier in frontiers: + color = cmap(frontier.prob_feasible) + grid[frontier.points[0, :], frontier.points[1, :], 0] = color[0] + grid[frontier.points[0, :], frontier.points[1, :], 1] = color[1] + grid[frontier.points[0, :], frontier.points[1, :], 2] = color[2] + + ax.imshow(np.transpose(grid, (1, 0, 2))) + + +def plot_semantic_grid_with_frontiers( + ax, grid_map, known_map, frontiers, + semantic_grid=None, semantic_labels=None, cmap_name='viridis'): + grid = make_plotting_grid( + grid_map, known_map, semantic_grid, semantic_labels) + cmap = plt.get_cmap(cmap_name) + for frontier in frontiers: + color = cmap(frontier.prob_feasible) + grid[frontier.points[0, :], frontier.points[1, :], 0] = color[0] + grid[frontier.points[0, :], frontier.points[1, :], 1] = color[1] + grid[frontier.points[0, :], frontier.points[1, :], 2] = color[2] + ax.imshow(np.transpose(grid, (1, 0, 2))) + + +def make_plotting_grid(grid_map, known_map=None, + semantic_grid=None, semantic_labels=None): + # print(semantic_labels) + # if known_map is not None: + # grid_map = known_map + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + collision = grid_map >= OBSTACLE_THRESHOLD + # Take one pixel boundary of the region collision + thinned = erosion(collision, footprint=FOOT_PRINT) + boundary = np.logical_xor(collision, thinned) + free = np.logical_and(grid_map < OBSTACLE_THRESHOLD, grid_map >= FREE_VAL) + red = np.logical_and(free, semantic_grid == semantic_labels['red']) + grid[:, :, 0][red] = 1 + grid[:, :, 1][red] = 0 + grid[:, :, 2][red] = 0 + blue = np.logical_and(free, semantic_grid == semantic_labels['blue']) + grid[:, :, 0][blue] = 0 + grid[:, :, 1][blue] = 0 + grid[:, :, 2][blue] = 1 + hall = np.logical_and(free, semantic_grid == semantic_labels['hallway']) + grid[:, :, 0][hall] = 1 + grid[:, :, 1][hall] = 1 + grid[:, :, 2][hall] = 1 + grid[:, :, 0][boundary] = 0 + grid[:, :, 1][boundary] = 0 + grid[:, :, 2][boundary] = 0 + + if known_map is not None: + known_collision = known_map == COLLISION_VAL + unobserved = grid_map == UNOBSERVED_VAL + unknown_obstacle = np.logical_and(known_collision, unobserved) + grid[:, :, 0][unknown_obstacle] = 0.65 + grid[:, :, 1][unknown_obstacle] = 0.65 + grid[:, :, 2][unknown_obstacle] = 0.75 + + return grid diff --git a/modules/lsp_gnn/lsp_gnn/scripts/__init__.py b/modules/lsp_gnn/lsp_gnn/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/lsp_gnn/lsp_gnn/scripts/evaluate.py b/modules/lsp_gnn/lsp_gnn/scripts/evaluate.py new file mode 100644 index 0000000..7a155a7 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/scripts/evaluate.py @@ -0,0 +1,208 @@ +import os +import common +import numpy as np +import time as time +import matplotlib.pyplot as plt +import matplotlib.animation as animation +from matplotlib import cm + +import lsp +import gridmap +import lsp_gnn +import environments +from lsp_gnn.planners import ConditionalUnknownSubgoalPlanner, GCNLSP, LSP + +viridis = cm.get_cmap('viridis') + + +def evaluate_main(args, make_video=False): + if args.map_type.lower() == 'ploader': + known_map, map_data, pose, goal = \ + environments.generate.map_and_poses(args) + map_data['wall_class'] = { + 'hallway': map_data['semantic_labels']['hallway'], + 'blue': 100, + 'red': map_data['semantic_labels']['room']} + else: + known_map, map_data, pose, goal = \ + lsp_gnn.environments.generate.map_and_poses(args) + + if make_video: + fig = plt.figure() + writer = animation.FFMpegWriter(12) + writer.setup(fig, os.path.join(args.save_dir, + f'Eval_{args.current_seed}.mp4'), 500) + + # # Initialize the world and builder objects + # world = environments.simulated.OccupancyGridWorld( + # known_map, + # map_data, + # num_breadcrumb_elements=0, + # min_interlight_distance=3.0, + # min_light_to_wall_distance=1) + # # builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + # with builder(args.unity_path) as unity_bridge: + if True: + unity_bridge = None + # unity_bridge.make_world(world) + + # Write starting seed to the log file + logfile = os.path.join(args.save_dir, args.logfile_name) + with open(logfile, "a+") as f: + f.write(f"LOG: {args.current_seed}\n") + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=None) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + if args.logfile_name == 'clsp_logfile.txt': + planner = ConditionalUnknownSubgoalPlanner(goal, args) + cost_str = 'cond_lsp' + elif args.logfile_name == 'mlsp_logfile.txt': + planner = GCNLSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + cost_str = 'gcn_lsp' + elif args.logfile_name == 'lsp_logfile.txt': + planner = LSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + cost_str = 'lsp' + robot = get_robot() + planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, robot, + args, verbose=True) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + s_time = time.time() + planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + print(f"Time taken to update: {time.time() - s_time}") + # Compute the subgoal and set + s_time = time.time() + chosen_subgoal = planner.compute_selected_subgoal() + print(f"Time taken to choose subgoal: {time.time() - s_time}") + planning_loop.set_chosen_subgoal(chosen_subgoal) + + if make_video and args.logfile_name != 'lsp_logfile.txt': + # Mask grid with chosen subgoal (if not None) + # and compute the cost grid for motion planning. + if chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, planner.subgoals, do_not_mask=chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + + # Plotting + plt.ion() + fig = plt.figure(1) + plt.clf() + fig_title = 'Seed: [' + str(args.current_seed) + \ + '] <> Planner: [' + cost_str + ']' + fig.suptitle(fig_title, fontsize='x-large') + ax = plt.subplot(121) + lsp_gnn.plotting.plot_semantic_grid_with_frontiers( + ax, step_data['robot_grid'], None, planner.subgoals, + map_data['semantic_grid'], map_data['wall_class']) + lsp_gnn.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_gnn.plotting.plot_path(ax, path) + lsp_gnn.plotting.plot_pose_path(ax, robot.all_poses) + lsp_gnn.plotting.plot_pose(ax, robot.pose, color='magenta') + is_subgoal = planner.is_subgoal + prob_feasible = planner.out + + ax = plt.subplot(122) + lsp_gnn.plotting.plot_grid( + ax, step_data['robot_grid'], known_map, None + ) + lsp_gnn.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_gnn.plotting.plot_path(ax, path) + lsp_gnn.plotting.plot_pose_path(ax, robot.all_poses) + lsp_gnn.plotting.plot_pose(ax, robot.pose, color='magenta') + for vp_idx, ps in enumerate(planner.vertex_points): + if not is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '+', color=color, markersize=3, markeredgecolor='r') + for vp_idx, ps in enumerate(planner.vertex_points): + if is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + for (start, end) in planner.edge_data: + p1 = planner.vertex_points[start] + p2 = planner.vertex_points[end] + x_values = [p1[0], p2[0]] + y_values = [p1[1], p2[1]] + plt.plot(x_values, y_values, 'c', linestyle="--", linewidth=0.3) + + writer.grab_frame() + if make_video: + writer.finish() + dist = common.compute_path_length(robot.all_poses) + did_succeed = planning_loop.did_succeed + + with open(logfile, "a+") as f: + err_str = '' if did_succeed else '[ERR]' + f.write(f"[Learn] {err_str} s: {args.current_seed:4d}" + f" | {cost_str}: {dist:0.3f}\n") + + if planner.observed_map is None: + planner.observed_map = -1 * np.ones_like(known_map) + + # Write final plot to file + image_file = os.path.join(args.save_dir, args.image_filename) + plt.figure(figsize=(4, 4)) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(planner.observed_map, known_map)) + path = robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + args = lsp_gnn.utils.parse_args() + if args.map_type == 'ploader': + from os import listdir + from os.path import isfile, join + dir_str = '/data/lsp_gnn/university_building_floorplans/test' + file_count = len(listdir(dir_str)) + onlyfiles = [ + join((dir_str + '/'), f) + for f in listdir(dir_str) + if isfile(join((dir_str + '/'), f))] + args.map_file = onlyfiles + args.cirriculum_fraction = None + print(f'Evaluation seed: [{args.current_seed}]') + evaluate_main(args, make_video=True) diff --git a/modules/lsp_gnn/lsp_gnn/scripts/evaluate_all.py b/modules/lsp_gnn/lsp_gnn/scripts/evaluate_all.py new file mode 100644 index 0000000..39b84ca --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/scripts/evaluate_all.py @@ -0,0 +1,237 @@ +import os +import common +import numpy as np +from matplotlib import cm +import matplotlib.pyplot as plt +import matplotlib.animation as animation + +import lsp +import lsp_gnn +import environments +from lsp.planners import KnownPlanner +from lsp_gnn.planners import LSP, GCNLSP + +viridis = cm.get_cmap('viridis') + + +def evaluate_main(args, make_video=False): + if args.map_type.lower() == 'ploader': + known_map, map_data, pose, goal = \ + environments.generate.map_and_poses(args) + map_data['wall_class'] = { + 'hallway': map_data['semantic_labels']['hallway'], + 'blue': 100, + 'red': map_data['semantic_labels']['room']} + else: + known_map, map_data, pose, goal = \ + lsp_gnn.environments.generate.map_and_poses(args) + if make_video: + fig = plt.figure() + writer = animation.FFMpegWriter(15) + writer.setup(fig, os.path.join(args.save_dir, + f'Eval_{args.current_seed}.mp4'), 500) + + # # Initialize the world and builder objects + # world = environments.simulated.OccupancyGridWorld( + # known_map, + # map_data, + # num_breadcrumb_elements=0, + # min_interlight_distance=3.0, + # min_light_to_wall_distance=1) + # # builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + # with builder(args.unity_path) as unity_bridge: + if True: + unity_bridge = None + # unity_bridge.make_world(world) + + # Write starting seed to the log file + logfile = os.path.join(args.save_dir, args.logfile_name) + with open(logfile, "a+") as f: + f.write(f"LOG: {args.current_seed}\n") + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=None) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + ################ + # ~~~ Known ~~ # + ################ + base_planner = KnownPlanner(goal, known_map, args) + base_robot = get_robot() + base_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, base_robot, + args, verbose=True) + + for counter, step_data in enumerate(base_planning_loop): + # Update the planner objects + base_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + chosen_subgoal = base_planner.compute_selected_subgoal() + base_planning_loop.set_chosen_subgoal(chosen_subgoal) + + ################ + # ~~~ Naive ~~ # + ################ + naive_robot = get_robot() + naive_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, naive_robot, + args, verbose=True) + + for counter, step_data in enumerate(naive_planning_loop): + naive_observed_map = step_data['robot_grid'] + + ################ + # ~~ CNN LSP ~ # + ################ + lsp_planner = LSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + lsp_robot = get_robot() + lsp_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, lsp_robot, + args, verbose=True) + + for counter, step_data in enumerate(lsp_planning_loop): + # Update the planner objects + lsp_planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], None) + # Compute the subgoal and set + chosen_subgoal = lsp_planner.compute_selected_subgoal() + lsp_planning_loop.set_chosen_subgoal(chosen_subgoal) + + ################ + # ~~ GCN LSP ~ # + ################ + gcn_lsp_planner = GCNLSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + gcn_lsp_robot = get_robot() + gcn_lsp_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, gcn_lsp_robot, + args, verbose=True) + + for counter, step_data in enumerate(gcn_lsp_planning_loop): + # Update the planner objects + gcn_lsp_planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + # Compute the subgoal and set + chosen_subgoal = gcn_lsp_planner.compute_selected_subgoal() + gcn_lsp_planning_loop.set_chosen_subgoal(chosen_subgoal) + + # learned_dist = common.compute_path_length(learned_robot.all_poses) + base_dist = common.compute_path_length(base_robot.all_poses) + naive_dist = common.compute_path_length(naive_robot.all_poses) + lsp_dist = common.compute_path_length(lsp_robot.all_poses) + gcn_lsp_dist = common.compute_path_length(gcn_lsp_robot.all_poses) + did_succeed = gcn_lsp_planning_loop.did_succeed # \ + # and naive_planning_loop.did_succeed + + with open(logfile, "a+") as f: + err_str = '' if did_succeed else '[ERR]' + f.write(f"[Learn] {err_str} s: {args.current_seed:4d}" + # f" | cond_lsp: {learned_dist:0.3f}" + f" | baseline: {base_dist:0.3f}" + f" | naive: {naive_dist:0.3f}" + f" | lsp: {lsp_dist:0.3f}" + f" | gcn_lsp: {gcn_lsp_dist:0.3f}\n") + + if gcn_lsp_planner.observed_map is None: + # learned_planner.observed_map = -1 * np.ones_like(known_map) + # base_planner.observed_map = -1 * np.ones_like(known_map) + # naive_observed_map = -1 * np.ones_like(known_map) + lsp_planner.observed_map = -1 * np.ones_like(known_map) + gcn_lsp_planner.observed_map = -1 * np.ones_like(known_map) + + # Write final plot to file + image_file = os.path.join(args.save_dir, args.image_filename) + plt.figure(figsize=(16, 16)) + + plt.subplot(221) + plt.imshow( + lsp.utils.plotting.make_plotting_grid( + base_planner.observed_map, known_map)) + path = base_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Known Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + plt.subplot(222) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(naive_observed_map, known_map)) + path = naive_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Naive Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + plt.subplot(223) + plt.imshow( + lsp.utils.plotting.make_plotting_grid( + lsp_planner.observed_map, known_map)) + path = lsp_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"CNN LSP Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + plt.subplot(224) + plt.imshow( + lsp.utils.plotting.make_plotting_grid( + gcn_lsp_planner.observed_map, known_map)) + path = gcn_lsp_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"GNN LSP Cost*: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + args = lsp_gnn.utils.parse_args() + if args.map_type == 'ploader': + from os import listdir + from os.path import isfile, join + dir_str = '/data/lsp_gnn/university_building_floorplans/test' + file_count = len(listdir(dir_str)) + onlyfiles = [ + join((dir_str + '/'), f) + for f in listdir(dir_str) + if isfile(join((dir_str + '/'), f))] + args.map_file = onlyfiles + args.cirriculum_fraction = None + print(f'Evaluation seed: [{args.current_seed}]') + evaluate_main(args) diff --git a/modules/lsp_gnn/lsp_gnn/scripts/gen_data.py b/modules/lsp_gnn/lsp_gnn/scripts/gen_data.py new file mode 100644 index 0000000..f987e6e --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/scripts/gen_data.py @@ -0,0 +1,192 @@ +import os +import gridmap +import lsp +import lsp_gnn +import environments +from lsp_gnn.planners import ConditionalKnownSubgoalPlanner + +import torch +import random +import numpy as np +import matplotlib.pyplot as plt +import matplotlib.animation as animation +from matplotlib import cm + +viridis = cm.get_cmap('viridis') +possible_choice = [True, False] + + +def navigate(args, do_plot=False, make_video=False): + if args.map_type.lower() == 'ploader': + known_map, map_data, pose, goal = \ + environments.generate.map_and_poses(args) + map_data['wall_class'] = { + 'hallway': map_data['semantic_labels']['hallway'], + 'blue': 100, + 'red': map_data['semantic_labels']['room']} + else: + known_map, map_data, pose, goal = \ + lsp_gnn.environments.generate.map_and_poses(args) + if make_video: + fig = plt.figure() + writer = animation.FFMpegWriter(8) + writer.setup(fig, os.path.join(args.save_dir, + f'{args.data_file_base_name}_{args.current_seed}.mp4'), + 500) + + use_known = random.choice(possible_choice) + if use_known: + print('Generating data using known planner') + current_planner_str = 'Known' + else: + print('Generating data using Dijkstra planner') + current_planner_str = 'Dijkstra' + + # # Instantiate the simulation environment + # world = environments.simulated.OccupancyGridWorld( + # known_map, + # map_data, + # num_breadcrumb_elements=0, + # min_interlight_distance=3.0, + # min_light_to_wall_distance=1) + # # builder = environments.simulated.WorldBuildingUnityBridge + + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + # Intialize and update the planner + planner = ConditionalKnownSubgoalPlanner( + goal, args, known_map, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + + # with builder(args.unity_path) as unity_bridge: + if True: # This is here to avoid having to change indentation + # unity_bridge.make_world(world) + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + # unity_bridge=unity_bridge, + world=None) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, None, robot, + args, verbose=False) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + + training_data = planner.compute_training_data() + planner.save_training_data(training_data) + chosen_subgoal = planner.compute_selected_subgoal() + if use_known: + planning_loop.set_chosen_subgoal(chosen_subgoal) + if do_plot: + # Mask grid with chosen subgoal (if not None) + # and compute the cost grid for motion planning. + if chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, planner.subgoals, + do_not_mask=chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning. \ + compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + + # Plotting + plt.ion() + fig = plt.figure(1) + fig_title = 'Seed: [' + str(args.current_seed) + \ + '] <> Planner: [' + current_planner_str + ']' + plt.clf() + fig.suptitle(fig_title, fontsize='x-large') + # Plot the classic lsp version + ax = plt.subplot(121) + ax.set_title('LSP') + lsp_gnn.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_gnn.plotting.plot_grid( + ax, step_data['robot_grid'], known_map, planner.original_subgoal) + lsp_gnn.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_gnn.plotting.plot_path(ax, path) + lsp_gnn.plotting.plot_pose_path(ax, robot.all_poses) + # Plot the skeletonized version + ax = plt.subplot(122) + ax.set_title('GCN-LSP') + + lsp_gnn.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_gnn.plotting.plot_grid( + ax, step_data['robot_grid'], known_map, None + ) + lsp_gnn.plotting.plot_pose( + ax, goal, color='green', filled=False) + + is_subgoal = training_data['is_subgoal'] + prob_feasible = training_data['is_feasible'] + + vertex_points = planner.vertex_points + for vp_idx, ps in enumerate(vertex_points): + if not is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '+', color=color, markersize=3, markeredgecolor='r') + for vp_idx, ps in enumerate(vertex_points): + if is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + for (start, end) in planner.edge_data: + p1 = vertex_points[start] + p2 = vertex_points[end] + x_values = [p1[0], p2[0]] + y_values = [p1[1], p2[1]] + plt.plot(x_values, y_values, 'c', linestyle="--", linewidth=0.3) + + image_file = args.save_dir + 'data_gen_image' + '.png' + plt.savefig(image_file, dpi=200) + if make_video: + writer.grab_frame() + open(os.path.join( + args.save_dir, + 'data_completion_logs', + f'{args.data_file_base_name}_{args.current_seed}.txt'), "x") + if make_video: + writer.finish() + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + args = lsp_gnn.utils.parse_args() + if args.map_type == 'ploader': + from os import listdir + from os.path import isfile, join + dir_str = '/data/lsp_gnn/university_building_floorplans/train' + file_count = len(listdir(dir_str)) + onlyfiles = [ + join((dir_str + '/'), f) + for f in listdir(dir_str) + if isfile(join((dir_str + '/'), f))] + args.map_file = onlyfiles + args.cirriculum_fraction = None + # Always freeze your random seeds + torch.manual_seed(args.current_seed) + np.random.seed(args.current_seed) + random.seed(args.current_seed) + # Generate Training Data + navigate(args, make_video=False, do_plot=False) diff --git a/modules/lsp_gnn/lsp_gnn/scripts/plotting.py b/modules/lsp_gnn/lsp_gnn/scripts/plotting.py new file mode 100644 index 0000000..677d505 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/scripts/plotting.py @@ -0,0 +1,114 @@ +import argparse +import matplotlib +import matplotlib.pyplot as plt +import numpy as np +import pandas as pd +import re +import scipy.stats + + +def process_results_data(args): + """This function prepares the result for all four planning approach from the logfile""" + data = [] + for line in open(args.data_file).readlines(): + d = re.match( + r'.*?s: (.*?) . baseline: (.*?) . naive: (.*?) . lsp: (.*?). gcn_lsp: (.*?)\n', + line) + if d is None: + continue + d = d.groups() + data.append( + [int(d[0]), float(d[1]) * args.base_resolution, + float(d[2]) * args.base_resolution, float(d[3]) * args.base_resolution, + float(d[4]) * args.base_resolution]) + + return pd.DataFrame( + data, + columns=['seed', 'Known', 'Naive', 'CNN_LSP', 'GCN_LSP'] + ) + + +def process_gnn_results_data(args): + """This function prepares the result for gnn planning approach from the mlsp_logfile""" + data = [] + for line in open(args.data_file).readlines(): + d = re.match(r'.*?s: (.*?) . gcn_lsp: (.*?)\n', line) + if d is None: + continue + d = d.groups() + data.append([int(d[0]), float(d[1])]) + + return pd.DataFrame( + data, + columns=['seed', 'GCN_LSP'] + ) + + +def build_plot(fig, data, args, cmap='Blues'): + """Function for scatter plot performance with gnn against others""" + xy = np.vstack([data['Naive'], data['GCN_LSP']]) + z = scipy.stats.gaussian_kde(xy)(xy) + + data['zs'] = z + data = data.sort_values(by=['zs']) + z = data['zs'] + colors = matplotlib.colormaps.get_cmap(cmap)((z - z.min()) / (z.max() - z.min()) * 0.75 + 0.25) + + fig.gca() + ax = plt.subplot(121) + ax.scatter(data['Naive'], data['GCN_LSP'], c=colors) + cb = min(max(data['Naive']), max(data['GCN_LSP'])) + ax.axis(xmin=0, ymin=0) + ax.plot([0, cb], [0, cb], linestyle=':', color='gray') + ax.set_title("LSP-GNN vs Non-learned baseline") + ax.set_xlabel("Non-learned baseline expected cost") + ax.set_ylabel("LSP-GNN expected cost") + xy = np.vstack([data['CNN_LSP'], data['GCN_LSP']]) + z = scipy.stats.gaussian_kde(xy)(xy) + + data['zs'] = z + data = data.sort_values(by=['zs']) + z = data['zs'] + colors = matplotlib.colormaps.get_cmap(cmap)((z - z.min()) / (z.max() - z.min()) * 0.75 + 0.25) + ax = plt.subplot(122) + ax.scatter(data['CNN_LSP'], data['GCN_LSP'], c=colors) + cb = min(max(data['CNN_LSP']), max(data['GCN_LSP'])) + ax.axis(xmin=0, ymin=0) + # ax.xlim([0, cb]) + ax.plot([0, cb], [0, cb], linestyle=':', color='gray') + ax.set_title("LSP-GNN vs LSP-Local") + ax.set_xlabel("LSP-Local expected cost") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description='Generate a figure (and write to file) for results from the interpretability project.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--data_file', + type=str, + required=False, + default=None) + parser.add_argument('--output_image_file', + type=str, + required=False, + default=None) + parser.add_argument('--xpassthrough', + type=str, + required=False, + default='false') + parser.add_argument('--gnn', action='store_true') + parser.add_argument('--base_resolution', + type=float, + required=True, + default='false') + args = parser.parse_args() + + if args.gnn: + data = process_gnn_results_data(args) + print(data.describe()) + else: + data = process_results_data(args) + print(data.describe()) + fig = plt.figure(dpi=300, figsize=(10, 5)) + build_plot(fig, data, args) + plt.savefig(args.output_image_file, dpi=300) diff --git a/modules/lsp_gnn/lsp_gnn/scripts/train.py b/modules/lsp_gnn/lsp_gnn/scripts/train.py new file mode 100644 index 0000000..9043e71 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/scripts/train.py @@ -0,0 +1,160 @@ +import os +import torch +import lsp_gnn +import random + +from torch.utils.tensorboard import SummaryWriter +from torch_geometric.loader import DataLoader +from learning.data import CSVPickleDataset +from lsp_gnn.learning.models.gcn import WallClassGNN +from lsp_gnn.learning.models.cnn_lsp import WallClassLSP + + +def get_model_prep_fn_and_training_strs(args): + preprocess = None + if args.train_marginal_lsp: + print("Training Marginal LSP ... ...") + model = WallClassGNN(args) + prep_fn = lsp_gnn.utils.preprocess_gcn_training_data( + ['marginal'], preprocess, args) + train_writer_str = 'train_mlsp' + test_writer_str = 'test_mlsp' + lr_writer_str = 'learning_rate/mLSP' + model_name_str = 'mlsp.pt' + elif args.train_cnn_lsp: + print("Training Base LSP ... ...") + model = WallClassLSP(args) + prep_fn = lsp_gnn.utils.preprocess_gcn_training_data( + ['marginal'], preprocess, args) + train_writer_str = 'train_lsp' + test_writer_str = 'test_lsp' + lr_writer_str = 'learning_rate/LSP' + model_name_str = 'lsp.pt' + + return { + 'model': model, + 'prep_fn': prep_fn, + 'train_writer_str': train_writer_str, + 'test_writer_str': test_writer_str, + 'lr_writer_str': lr_writer_str, + 'model_name_str': model_name_str + } + + +def train(args, train_path, test_path): + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + + # Assertion since the current project has working results only for wall class labels + assert args.input_type == 'wall_class' + print("Using semantic wall class labels") + + # Get the model and other training info + model_and_training_info = get_model_prep_fn_and_training_strs(args) + model = model_and_training_info['model'] + prep_fn = model_and_training_info['prep_fn'] + train_writer_str = model_and_training_info['train_writer_str'] + test_writer_str = model_and_training_info['test_writer_str'] + lr_writer_str = model_and_training_info['lr_writer_str'] + model_name_str = model_and_training_info['model_name_str'] + + # Create the datasets and loaders + train_dataset = CSVPickleDataset(train_path, prep_fn) + print("Number of training graphs:", len(train_dataset)) + train_loader = DataLoader(train_dataset, batch_size=4, shuffle=True) + train_iter = iter(train_loader) + train_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, train_writer_str)) + + test_dataset = CSVPickleDataset(test_path, prep_fn) + print("Number of testing graphs:", len(test_dataset)) + test_loader = DataLoader(test_dataset, batch_size=2, shuffle=True) + test_iter = iter(test_loader) + test_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, test_writer_str)) + + model.to(device) + + optimizer = torch.optim.Adam(model.parameters(), lr=args.learning_rate) + scheduler = torch.optim.lr_scheduler.StepLR( + optimizer, step_size=args.epoch_size, + gamma=args.learning_rate_decay_factor) + index = 0 + while index < args.num_steps: + try: + train_batch = next(train_iter) + except StopIteration: + train_iter = iter(train_loader) + train_batch = next(train_iter) + out = model.forward({ + 'edge_data': train_batch.edge_index, + 'edge_features': train_batch.edge_features, + 'history': train_batch.history, + 'goal_distance': train_batch.goal_distance, + 'is_subgoal': train_batch.is_subgoal, + 'latent_features': train_batch.x + }, device) + train_loss = model.loss(out, + data=train_batch, + device=device, + writer=train_writer, + index=index) + + if index % args.test_log_frequency == 0: + print(f"[{index}/{args.num_steps}] " + f"Train Loss: {train_loss}") + + # Train the system + optimizer.zero_grad() + train_loss.backward() + optimizer.step() + + if index % args.test_log_frequency == 0: + try: + test_batch = next(test_iter) + except StopIteration: + test_iter = iter(test_loader) + test_batch = next(test_iter) + + with torch.no_grad(): + out = model.forward({ + 'edge_data': test_batch.edge_index, + 'edge_features': test_batch.edge_features, + 'history': test_batch.history, + 'goal_distance': test_batch.goal_distance, + 'is_subgoal': test_batch.is_subgoal, + 'latent_features': test_batch.x + }, device) + test_loss = model.loss(out, + data=test_batch, + device=device, + writer=test_writer, + index=index) + print(f"[{index}/{args.num_steps}] " + f"Test Loss: {test_loss.cpu().numpy()}") + + # Log the learning rate + test_writer.add_scalar(lr_writer_str, + scheduler.get_last_lr()[-1], + index) + index += 1 + scheduler.step() + + # Saving the model after training + torch.save(model.state_dict(), + os.path.join(args.save_dir, model_name_str)) + + +if __name__ == "__main__": + args = lsp_gnn.utils.parse_args() + # Always freeze your random seeds + torch.manual_seed(8616) + random.seed(8616) + train_path, test_path = lsp_gnn.utils.get_data_path_names(args) + # Train the neural network + if args.autoencoder_network_file: + train(args=args, train_path=train_path, test_path=test_path) + else: + print("Training AutoEncoder ... ...") + lsp_gnn.learning.models.auto_encoder.train( + args=args, train_path=train_path, test_path=test_path) diff --git a/modules/lsp_gnn/lsp_gnn/utils.py b/modules/lsp_gnn/lsp_gnn/utils.py new file mode 100644 index 0000000..5d69499 --- /dev/null +++ b/modules/lsp_gnn/lsp_gnn/utils.py @@ -0,0 +1,847 @@ +import os +import math +import glob +import sknw +import torch +import random +import itertools +import numpy as np +import scipy.ndimage +import skimage.measure +from PIL import Image +from torch_geometric.data import Data +from skimage.morphology import skeletonize + +import lsp +import learning +from gridmap import planning +from lsp.constants import UNOBSERVED_VAL, FREE_VAL, COLLISION_VAL + +COMPRESS_LEVEL = 2 + + +def get_n_frontier_points_nearest_to_centroid(subgoal, n): + """ Get n points from the sorted frontier points' middle indices + """ + total_points_on_subgoal = len(subgoal.points[0]) + if total_points_on_subgoal <= n: + return subgoal.points + mid = total_points_on_subgoal // 2 + return subgoal.points[:, mid - 1:mid + 1] + + +def compute_skeleton(partial_map, subgoals): + """Perfom skeletonization on free+unknown space image + """ + data = {} + n = 2 # Set using trial and error + free_unknown_image = \ + lsp.core.mask_grid_with_frontiers(partial_map, subgoals) + for subgoal in subgoals: + points_to_be_opened = \ + get_n_frontier_points_nearest_to_centroid(subgoal, n) + for idx, _ in enumerate(points_to_be_opened[0]): + x = points_to_be_opened[0][idx] + y = points_to_be_opened[1][idx] + free_unknown_image[x][y] = 0 + if partial_map[x][y] == UNOBSERVED_VAL: + partial_map[x][y] = 0 + + free_unknown_image = free_unknown_image != 1 + sk = skeletonize(free_unknown_image) + data['untrimmed_graph'] = sknw.build_sknw(sk) + data['untrimmed_edges'] = [value for value in data['untrimmed_graph'].edges()] + sk[partial_map == UNOBSERVED_VAL] = 0 + + data['graph'] = sknw.build_sknw(sk) + vertex_data = data['graph'].nodes() + data['vertex_points'] = np.array([vertex_data[i]['o'] for i in vertex_data]) + data['edges'] = [value for value in data['graph'].edges() if value[0] != value[1]] + return data + + +def prepare_input_clean_graph(subgoals, vertex_points, edge_data, + new_node_dict, has_updated, semantic_grid, + wall_class, observation, robot_pose): + subgoal_nodes = {} + # This loop checks if a structural node can be replaced as a subgoal + # node, the subgoal(s) that are not assigned any nodes gets marked + # to be processed in the next loop + non_overlapping_subgoals = [] + for subgoal in subgoals: + index_pos, possible_node = \ + get_subgoal_node(vertex_points, subgoal, subgoal_nodes) + # find the index_pos of possible_node in vertex_points + pn = np.array(possible_node) + sn = subgoal.get_frontier_point() # this is an np.array + possible_node = tuple(possible_node) + subgoal_node = tuple(sn) + # Check if there is an existing node exactly on that vertex + if (pn == sn).all(): + if subgoal.props_set and hasattr(subgoal, "nn_input_data"): + new_node_dict[possible_node] = subgoal.nn_input_data + has_updated[index_pos] = 0 + subgoal_nodes[possible_node] = subgoal + continue + subgoal.nn_input_data = get_input_data( + semantic_grid, wall_class, subgoal_node, + observation, robot_pose) + new_node_dict[possible_node] = subgoal.nn_input_data + has_updated[index_pos] = 1 + subgoal_nodes[possible_node] = subgoal + # no need to update edges + else: + non_overlapping_subgoals.append(subgoal) + + # This loop creates a node for the marked subgoal(s) from previous + # loop and connects them to their nearest structural nodes + for subgoal in non_overlapping_subgoals: + index_pos, possible_node = \ + get_subgoal_node(vertex_points, subgoal, subgoal_nodes) + # find the index_pos of possible_node in vertex_points + pn = np.array(possible_node) + sn = subgoal.get_frontier_point() # this is an np.array + possible_node = tuple(possible_node) + subgoal_node = tuple(sn) + subgoal_node_index = len(vertex_points) + # add the subgoal vertex on the graph + vertex_points = np.append(vertex_points, [sn], axis=0) + # add an edge beteen the subgoal vertex and + # the nearest structural node + if index_pos != -1: + # find the adjacent nodes of index_pos'ed vertex + adjacent_nodes = get_adjacent_vertices(index_pos, edge_data) + + # if index_pos'ed vertex is pendant, choose its parent + if len(adjacent_nodes) == 1: + # if the only adjacent node is not a structural node then skip connecting to it + vp_t = tuple(vertex_points[adjacent_nodes[0]]) + if vp_t not in subgoal_nodes: + index_pos = adjacent_nodes[0] + edge_data.append(tuple([index_pos, subgoal_node_index])) + + if subgoal.props_set and hasattr(subgoal, "nn_input_data"): + new_node_dict[subgoal_node] = subgoal.nn_input_data + has_updated.append(0) + subgoal_nodes[subgoal_node] = subgoal + continue + subgoal.nn_input_data = get_input_data( + semantic_grid, wall_class, subgoal_node, + observation, robot_pose) + new_node_dict[subgoal_node] = subgoal.nn_input_data + has_updated.append(1) + subgoal_nodes[subgoal_node] = subgoal + + # This loop prunes any structural node that are too close (see default + # below) to the subgoal nodes + for subgoal in subgoals: + # Get the nearby vertices within certain distance (default is <10) + neighbors = get_neighbors(vertex_points, subgoal, subgoal_nodes) + c = 0 + # remove the vertices along with the edges if the neighbor is a pendant vertex + for neighbor in neighbors: + # Check if this neighbor is a pendent vertex + edge_to_remove = None + neighbor = neighbor - c # the c is here to offset the idx if a vertex is erased + adjacent_nodes = get_adjacent_vertices(neighbor, edge_data) + + if len(adjacent_nodes) == 1: + # 1. Find to remove that edge from the list of edges + if (adjacent_nodes[0], neighbor) in edge_data: + edge_to_remove = tuple([adjacent_nodes[0], neighbor]) + elif (neighbor, adjacent_nodes[0]) in edge_data: + edge_to_remove = tuple([neighbor, adjacent_nodes[0]]) + # 2. Find to remove that vertex from the list of vertices + vertex_points_to_remove = neighbor + if edge_to_remove: + c += 1 + edge_data.remove(edge_to_remove) + has_updated.pop(vertex_points_to_remove) + vertex_points = np.delete(vertex_points, vertex_points_to_remove, axis=0) + refined_edge_data = [] + for edge_pair in edge_data: + t0 , t1 = None, None + if edge_pair[0] > vertex_points_to_remove: + t0 = edge_pair[0] - 1 + else: + t0 = edge_pair[0] + if edge_pair[1] > vertex_points_to_remove: + t1 = edge_pair[1] - 1 + else: + t1 = edge_pair[1] + refined_edge_data.append(tuple([t0, t1])) + edge_data = refined_edge_data + + # This loop prunes the structural nodes with 2 degree except, it is the + # only structural node in the graph + for subgoal_vertex in subgoal_nodes: + idx = np.where((vertex_points == subgoal_vertex).all(axis=1))[0][0] + # find the structural node index that the subgoal node is connected to + temp_parent = get_adjacent_vertices(idx, edge_data) + # Handling the case when no parent is found by continuing + if len(temp_parent) != 1: + continue + else: + parent = temp_parent[0] + + # next find the adjacent nodes to this parent + adjacent_nodes = get_adjacent_vertices(parent, edge_data) + + # if parent node has degree 2, remove parent and connect the subgoal vertex to + # the other node connected with parent of the subgoal vertex creating direct link + while len(adjacent_nodes) == 2: + new_parent = adjacent_nodes[0] if adjacent_nodes[0] != idx else adjacent_nodes[1] + + # if the new_parent is not a structural node then skip connecting to it + vp_t = tuple(vertex_points[new_parent]) + if vp_t in subgoal_nodes: + break + + # 1. Find to remove that edge from the list of edges + if (new_parent, parent) in edge_data: + edge_data.remove(tuple([new_parent, parent])) + elif (parent, new_parent) in edge_data: + edge_data.remove(tuple([parent, new_parent])) + if (idx, parent) in edge_data: + edge_data.remove(tuple([idx, parent])) + elif (parent, idx) in edge_data: + edge_data.remove(tuple([parent, idx])) + edge_data.append(tuple([new_parent, idx])) + # 2. Find to remove that vertex from the list of vertices + vertex_points_to_remove = parent + has_updated.pop(vertex_points_to_remove) + vertex_points = np.delete(vertex_points, vertex_points_to_remove, axis=0) + refined_edge_data = [] + for edge_pair in edge_data: + t0 , t1 = None, None + if edge_pair[0] > vertex_points_to_remove: + t0 = edge_pair[0] - 1 + else: + t0 = edge_pair[0] + if edge_pair[1] > vertex_points_to_remove: + t1 = edge_pair[1] - 1 + else: + t1 = edge_pair[1] + refined_edge_data.append(tuple([t0, t1])) + edge_data = refined_edge_data + if vertex_points_to_remove < new_parent: + parent = new_parent - 1 + else: + parent = new_parent + if vertex_points_to_remove < idx: + idx -= 1 + adjacent_nodes = get_adjacent_vertices(parent, edge_data) + + return { + 'subgoal_nodes': subgoal_nodes, + 'vertex_points': vertex_points, + 'edge_data': edge_data, + 'new_node_dict': new_node_dict, + 'has_updated': has_updated + } + + +def calculate_euclidian_distance(node, subgoal): + return ((node[0] - subgoal[0])**2 + (node[1] - subgoal[1])**2)**.5 + + +def get_subgoal_node(vertex_points, subgoal, subgoal_nodes=None): + possible_node = 0 + index = -1 + distance = 10000 + subgoal_centroid = subgoal.get_frontier_point() + for idx, node in enumerate(vertex_points): + m = tuple(node) + if subgoal_nodes is not None and m in subgoal_nodes: + continue + d = calculate_euclidian_distance(node, subgoal_centroid) + if d < distance: + distance = d + possible_node = node + index = idx + return index, possible_node + + +def get_neighbors(vertex_points, subgoal, subgoal_nodes): + index = [] + distance = 10 + subgoal_centroid = subgoal.get_frontier_point() + # subgoal_centroid = subgoal.get_centroid() + for idx, node in enumerate(vertex_points): + m = tuple(node) + if m in subgoal_nodes: + continue + d = calculate_euclidian_distance(node, subgoal_centroid) + if d < distance: + index.append(idx) + return index + + +def get_adjacent_vertices(vertex, edge_data): + """ This method returns the adjacent node(s) from a given node within + one edge distance depart + """ + adjacent_nodes_idx = [] + for edge_pair in edge_data: + if vertex in edge_pair: + idx = edge_pair[0] if edge_pair[0] != vertex else edge_pair[1] + adjacent_nodes_idx.append(idx) + return adjacent_nodes_idx + + +def preprocess_cnn_data(datum, fn=None, idx=None, args=None): + data = datum.copy() + if fn is None: + if args.input_type == 'image': + ds_img_list = [] + down_sampled_img = downsample_image(np.transpose(datum['image'][idx], (2, 0, 1))) + if datum['is_subgoal'][idx] == 1: + down_sampled_img = down_sampled_img[:, :, 56:72] + ds_img_list.append(down_sampled_img) + else: + _, _, offset = down_sampled_img.shape + offset /= 8 + offset = int(offset) + for patch_idx in range(8): + t_down_sampled_img = down_sampled_img[:, :, patch_idx * offset:(patch_idx + 1) * offset] + ds_img_list.append(t_down_sampled_img) + data['image'] = torch.tensor( + (np.array(ds_img_list).astype(np.float32) / 255), dtype=torch.float) + elif args.input_type == 'seg_image': + ds_img_list = [] + down_sampled_img = np.transpose( + datum['image'][idx], (2, 0, 1))[:, ::4, ::4] + if datum['is_subgoal'][idx] == 1: + down_sampled_img = down_sampled_img[:, :, 56:72] + image = convert_seg_image_to_one_hot_coded_vector(down_sampled_img) + ds_img_list.append(image) + else: + _, _, offset = down_sampled_img.shape + offset /= 8 + offset = int(offset) + for patch_idx in range(8): + t_down_sampled_img = down_sampled_img[:, :, patch_idx * offset:(patch_idx + 1) * offset] + image = convert_seg_image_to_one_hot_coded_vector(t_down_sampled_img) + ds_img_list.append(image) + data['image'] = torch.tensor(np.array( + ds_img_list), dtype=torch.float) + else: + data['image'] = torch.cat([ + # Do the preprocessing for running clip encoder + fn(Image.fromarray(image, mode='RGB')).unsqueeze(0) + for idx, image in enumerate(data['image']) + ]) + return data + + +def preprocess_cnn_eval_data(datum, args=None): + if args.input_type == 'image': + down_sampled_img = downsample_image(np.transpose( + datum['image'], (2, 0, 1))) + down_sampled_img = down_sampled_img[:, :, 56:72] + return { + 'image': torch.tensor(np.expand_dims( + (down_sampled_img.astype(np.float32) / 255), + axis=0), dtype=torch.float) + } + elif args.input_type == 'seg_image': + down_sampled_img = np.transpose( + datum['seg_image'], (2, 0, 1))[:, ::4, ::4] + image = down_sampled_img[:, :, 56:72] + image = convert_seg_image_to_one_hot_coded_vector(image) + return { + 'image': torch.tensor(np.expand_dims( + image, axis=0), dtype=torch.float) + } + + +def downsample_image(image, downsample_factor=2): + return skimage.measure.block_reduce( + image, (1, 2**downsample_factor, 2**downsample_factor), + np.average) + + +def preprocess_ae_img(datum): + data = {} + length = len(datum['image']) + idx = random.randint(0, length - 1) + image = downsample_image(np.transpose(datum['image'][idx], (2, 0, 1))) + if datum['is_subgoal'][idx] == 1: + # take the middle 1/8 of the image: + image = image[:, :, 56:72] + else: + # take any 1/8 of the image + _, _, offset = image.shape + offset /= 8 + offset = int(offset) + patch_idx = random.randint(0, 7) + image = image[:, :, patch_idx * offset:(patch_idx + 1) * offset] + data['image'] = torch.tensor((image / 255), dtype=torch.float) + data['is_feasible'] = torch.tensor(datum['is_feasible'][idx], dtype=torch.float) + data['delta_success_cost'] = torch.tensor(datum['delta_success_cost'][idx], dtype=torch.float) + data['exploration_cost'] = torch.tensor(datum['exploration_cost'][idx], dtype=torch.float) + return data + + +def preprocess_ae_seg_img(datum): + data = {} + length = len(datum['seg_image']) + idx = random.randint(0, length - 1) + image = np.transpose(datum['seg_image'][idx], (2, 0, 1))[:, ::4, ::4] + if datum['is_subgoal'][idx] == 1: + # take the middle 1/8 of the image: + image = image[:, :, 56:72] + else: + # take any 1/8 of the image + _, _, offset = image.shape + offset /= 8 + offset = int(offset) + patch_idx = random.randint(0, 7) + image = image[:, :, patch_idx * offset:(patch_idx + 1) * offset] + image = convert_seg_image_to_one_hot_coded_vector(image) + data['image'] = torch.tensor(image, dtype=torch.float) + data['is_feasible'] = torch.tensor(datum['is_feasible'][idx], dtype=torch.float) + data['delta_success_cost'] = torch.tensor(datum['delta_success_cost'][idx], dtype=torch.float) + data['exploration_cost'] = torch.tensor(datum['exploration_cost'][idx], dtype=torch.float) + return data + + +def convert_seg_image_to_one_hot_coded_vector(image): + red = np.expand_dims(image[0] == 255, axis=0).astype(float) + blue = np.expand_dims(image[2] == 255, axis=0).astype(float) + hallway = np.expand_dims(image[1] == 127, axis=0).astype(float) + new_image = np.concatenate( + [red, blue, hallway], axis=0) + none_of_above = 1 - new_image.max(axis=0) + none_of_above = np.expand_dims(none_of_above, axis=0).astype(float) + vectored_image = np.concatenate([new_image, none_of_above], axis=0) + return vectored_image + + +def preprocess_gcn_data(datum): + data = datum.copy() + temp = [[x[0], x[1]] for x in data['edge_data'] if x[0] != x[1]] + data['edge_data'] = torch.tensor(list(zip(*temp)), dtype=torch.long) + data['edge_features'] = torch.tensor(data['edge_features'], dtype=torch.float) + data['history'] = torch.tensor(data['history'], dtype=torch.long) + data['goal_distance'] = torch.tensor(data['goal_distance'], dtype=torch.float) + data['is_subgoal'] = torch.tensor(data['is_subgoal'], + dtype=torch.long) + return data + + +def add_super_node(data, input_type): + ''' This method adds goal as super node and edges to all nodes from it, + to the graph data. Is used during model training. + ''' + goal_node_idx = len(data['history']) + if input_type == 'image': + data['image'].append(np.zeros((128, 512, 3))) # Add blank img + elif input_type == 'seg_image': + data['seg_image'].append(np.zeros((128, 512, 3))) + elif input_type == 'wall_class': + data['wall_class'].append([0, 0, 0]) + # We use the history vector to set only super node as 1 and rest of the graph + # node as 0 + data['history'] = [0] * len(data['history']) + data['history'].append(1) + + data['is_subgoal'].append(0) + data['has_updated'].append(0) + data['is_feasible'].append(0) + data['delta_success_cost'].append(0) + data['exploration_cost'].append(0) + data['positive_weighting'].append(0) + data['negative_weighting'].append(0) + old_edges = [edge_pair for edge_pair in data['edge_data']] + new_edges = [(idx, goal_node_idx) for idx in range(goal_node_idx)] + updated_edges = old_edges + new_edges + # Add feature for each new edges connected to the super node + for distance in data['goal_distance']: + feature_vector = [] + feature_vector.append(distance) + data['edge_features'].append(feature_vector) + data['edge_data'] = updated_edges + data['goal_distance'].append(0) + return data + + +def get_edge_features(edge_data, vertex_points, node_dict): + ''' Iterate over the edges to get the edge feature for each edge, right now + only using squared distance + ''' + edge_features = [] + for edge in edge_data: + feature_vector = [] + node1_idx = edge[0] + node2_idx = edge[1] + x1 = node_dict[tuple(vertex_points[node1_idx])]['x'] + y1 = node_dict[tuple(vertex_points[node1_idx])]['y'] + x2 = node_dict[tuple(vertex_points[node2_idx])]['x'] + y2 = node_dict[tuple(vertex_points[node2_idx])]['y'] + length = np.sqrt((x1 - x2) ** 2 + (y1 - y2) ** 2) + feature_vector.append(length) + edge_features.append(feature_vector) + return edge_features + + +def preprocess_gcn_training_data(option=None, fn=None, args=None): + ''' This method preprocesses the data for GCN training with two options + marginal history and random history + ''' + if option is None: + option = ['marginal', 'random'] + + def make_graph(data): + data = add_super_node(data, args.input_type) + flag = random.choice(option) + + if args.input_type == 'image': + data['image'] = args.latent_features_net({ + 'image': data['image'], + 'is_subgoal': data['is_subgoal'] + }) + elif args.input_type == 'seg_image': + data['image'] = args.latent_features_net({ + 'image': data['seg_image'], + 'is_subgoal': data['is_subgoal'] + }) + elif args.input_type == 'wall_class': + data['image'] = torch.tensor(data['wall_class'], dtype=torch.float) + elif args.use_clip: + data['image'] = torch.cat([ + # Do the preprocessing for running clip encoder + fn(Image.fromarray(image, mode='RGB')).unsqueeze(0) + for idx, image in enumerate(data['image']) + ]) + + # temp_wall_class = [vector[fov] for vector in data['wall_class']] + # data['wall_class'] = torch.tensor(temp_wall_class, dtype=torch.float) + temp = [[x[0], x[1]] for x in data['edge_data'] if x[0] != x[1]] + data['edge_data'] = torch.tensor(list(zip(*temp)), dtype=torch.long) + data['edge_features'] = torch.tensor(data['edge_features'], dtype=torch.float) + + history = data['history'].copy() + data['history'] = torch.tensor(data['history'], dtype=torch.long) + data['is_subgoal'] = torch.tensor(data['is_subgoal'], dtype=torch.long) + data['has_updated'] = torch.tensor(data['has_updated'], dtype=torch.long) + data['goal_distance'] = torch.tensor(data['goal_distance'], dtype=torch.float) + + label = data['is_feasible'].copy() + data['is_feasible'] = torch.tensor(data['is_feasible'], dtype=torch.float) + data['delta_success_cost'] = torch.tensor( + data['delta_success_cost'], dtype=torch.float) + data['exploration_cost'] = torch.tensor( + data['exploration_cost'], dtype=torch.float) + data['positive_weighting'] = torch.tensor( + data['positive_weighting'], dtype=torch.float) + data['negative_weighting'] = torch.tensor( + data['negative_weighting'], dtype=torch.float) + tg_GCN_format = Data(x=data['image'], + edge_index=data['edge_data'], + edge_features=data['edge_features'], + is_subgoal=data['is_subgoal'], + has_updated=data['has_updated'], + goal_distance=data['goal_distance'], + y=data['is_feasible'], + dsc=data['delta_success_cost'], + ec=data['exploration_cost'], + pweight=data['positive_weighting'], + nweight=data['negative_weighting']) + + if flag == 'marginal': + # Formating for training only with marginal history vector + tg_GCN_format.__setitem__('history', data['history']) + elif flag == 'random': + # Formating for training with randomly chosen + # history vector + history_vector = generate_random_history_combination( + history, label) + data['history'] = torch.tensor(history_vector, + dtype=torch.long) + tg_GCN_format.__setitem__('history', data['history']) + result = tg_GCN_format + return result + return make_graph + + +def generate_random_history_combination(history, node_labels): + pool = [i for i, val in enumerate(history) + if val == 1 and node_labels[i] == 0] + random_history = node_labels.copy() + n = history.count(1) + c = node_labels.count(1) + x = random.randint(0, n - c) + for _ in range(x): + sub = random.choice(pool) + random_history[sub] = 1 + pool.remove(sub) + return random_history + + +def generate_all_rollout_history(history): + pool = [i for i, val in enumerate(history) + if val == 1] + n = history.count(1) + history_vectors = [] + for idx in range(n): + combis = itertools.combinations(pool, idx) + for a_tuple in combis: + temp = history.copy() + for val in a_tuple: + temp[val] = 0 + history_vectors.append(temp) + return history_vectors + + +def write_datum_to_file(args, datum, counter): + """Write a single datum to file and append name to csv record.""" + # Get the data file name + data_filename = os.path.join('pickles', f'dat_{args.current_seed}_{counter}.pgz') + learning.data.write_compressed_pickle( + os.path.join(args.save_dir, data_filename), datum) + csv_filename = f'{args.data_file_base_name}_{args.current_seed}.csv' + with open(os.path.join(args.save_dir, csv_filename), 'a') as f: + f.write(f'{data_filename}\n') + + +def get_data_path_names(args): + training_data_files = glob.glob(os.path.join(args.data_csv_dir, "*train*.csv")) + testing_data_files = glob.glob(os.path.join(args.data_csv_dir, "*test*.csv")) + return training_data_files, testing_data_files + + +def get_input_data(semantic_grid, wall_class, vertex_point, + observation=None, robot_pose=None): + x, y = vertex_point + x, y = int(x), int(y) + if semantic_grid[x][y] == wall_class['red']: + one_hot_coded_vector = [1, 0, 0] + elif semantic_grid[x][y] == wall_class['blue']: + one_hot_coded_vector = [0, 1, 0] + else: + one_hot_coded_vector = [0, 0, 1] + + return {'image': None, + 'seg_image': None, + 'input': one_hot_coded_vector, + 'x': x, + 'y': y, + } + + +def check_if_same(new_data, old_data): + ''' + This method checks if the last saved data and the current data are the same + or not. + ''' + if new_data['vertex_points'].shape[0] == old_data['vertex_points'].shape[0]: + is_same_vertices = (new_data['vertex_points'] == old_data['vertex_points']).all() + else: + is_same_vertices = False + is_same_edges = set(new_data['edge_data']) == set(old_data['edge_data']) + return is_same_vertices and is_same_edges + + +def check_if_reachable( + known_grid, grid, goal_pose, start_pose, + frontier, downsample_factor=1): + ''' + Checks if an alternate subgoal path is still reachable. This changes the + label for the subgoal whose alternate path has already explored the merging + point through this subgoal + ''' + inflated_mixed_grid = np.ones_like(known_grid) + inflated_mixed_grid[np.logical_and( + known_grid == FREE_VAL, + grid == UNOBSERVED_VAL)] = UNOBSERVED_VAL + occupancy_grid = np.copy(inflated_mixed_grid) + occupancy_grid[occupancy_grid == FREE_VAL] = COLLISION_VAL + occupancy_grid[occupancy_grid == UNOBSERVED_VAL] = FREE_VAL + if downsample_factor > 1: + occupancy_grid = skimage.measure.block_reduce( + occupancy_grid, (downsample_factor, downsample_factor), np.min) + + # Compute the cost grid + cost_grid = planning.compute_cost_grid_from_position( + occupancy_grid, + start=[ + goal_pose.x // downsample_factor, goal_pose.y // downsample_factor + ], + use_soft_cost=False, + only_return_cost_grid=True) + + # Compute the cost for each frontier + fpts = frontier.points // downsample_factor + cost = downsample_factor * (cost_grid[fpts[0, :], fpts[1, :]].min()) + + if math.isinf(cost): + cost = 100000000000 + known_cost_grid = planning.compute_cost_grid_from_position( + known_grid, + start=[ + start_pose.x // downsample_factor, + start_pose.y // downsample_factor + ], + only_return_cost_grid=True) + + unk_regions = (inflated_mixed_grid == UNOBSERVED_VAL) + labels, nb = scipy.ndimage.label(unk_regions) + fp = frontier.points // downsample_factor + flabel = labels[fp[0, :], fp[1, :]].max() + cost_region = known_cost_grid[labels == flabel] + min_cost = cost_region.min() + max_cost = cost_region.max() + if min_cost > 1e8: + frontier.set_props(prob_feasible=0.0) + frontier.is_obstructed = True + else: + if max_cost > 1e8: + cost_region[cost_region > 1e8] = 0 + max_cost = cost_region.max() + + exploration_cost = 2 * downsample_factor * (max_cost - + min_cost) + frontier.set_props(prob_feasible=0.0, + exploration_cost=exploration_cost) + # frontier.set_props(prob_feasible=0.0, is_obstructed=True) + frontier.just_set = False + + if frontier.prob_feasible == 1.0: + return True + return False + + +def parse_args(): + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--relative_positive_weight', + default=1.0, + help='Initial learning rate', + type=float) + parser.add_argument('--train_cnn_lsp', action='store_true') + parser.add_argument('--train_marginal_lsp', action='store_true') + parser.add_argument('--fov', type=int, default=None,) + parser.add_argument( + '--input_type', + type=str, + required=False) + parser.add_argument( + '--epoch_size', + type=int, + required=False, + default=10000, + help='The number of steps in epoch. total_input_count / batch_size') + parser.add_argument( + '--current_seed', + type=int) + parser.add_argument( + '--data_file_base_name', + type=str, + required=False) + parser.add_argument('--logfile_name', type=str, default='logfile.txt') + parser.add_argument( + '--learning_rate_decay_factor', + default=0.5, + help='How much learning rate decreases between epochs.', + type=float) + group = parser.add_argument_group('Make Training Data Arguments') + group.add_argument( + '--lsp_weight', + type=float, + required=False, + help='Set the weight of LSP loss contribution during AE training') + group.add_argument( + '--loc_weight', + type=float, + required=False, + help='Set the weight of location loss contribution during AE training') + group.add_argument( + '--loss', + type=str, + required=False, + help='Set the l1 or l2 loss for image loss calucation') + group.add_argument( + '--network_file', + type=str, + required=False, + help='Directory with the name of the conditional gcn model') + group.add_argument( + '--autoencoder_network_file', + type=str, + required=False, + help='Directory with the name of the autoencoder model') + group.add_argument( + '--clip_network_file', + type=str, + required=False, + help='Directory with the name of the clip(by open.ai) encoder model') + group.add_argument( + '--cnn_network_file', + type=str, + required=False, + help='Directory with the name of the base/cnn lsp model') + group.add_argument( + '--gcn_network_file', + type=str, + required=False, + help='Directory with the name of the marginal gcn model') + group.add_argument( + '--image_filename', + type=str, + required=False, + help='File name for the completed evaluations') + group.add_argument( + '--data_csv_dir', + type=str, + required=False, + help='Directory in which to save the data csv') + group.add_argument( + '--pickle_directory', + type=str, + required=False, + help='Directory in which to save the pickle dataums') + group.add_argument( + '--csv_basename', + type=str, + required=False, + help='Directory in which to save the CSV base file') + group = parser.add_argument_group('Neural Network Training Testing \ + Arguments') + group.add_argument( + '--core_directory', + type=str, + required=False, + help='Directory in which to look for data') + group.add_argument( + '--num_training_elements', + type=int, + required=False, + default=5000, + help='Number of training samples') + group.add_argument( + '--num_testing_elements', + type=int, + required=False, + default=1000, + help='Number of testing samples') + group.add_argument( + '--num_steps', + type=int, + required=False, + default=10000, + help='Number of steps while iterating') + group.add_argument( + '--test_log_frequency', + type=int, + required=False, + default=10, + help='Frequecy of testing log to be generated') + group.add_argument( + '--learning_rate', + type=float, + required=False, + default=.001, + help='Learning rate of the model') + group.add_argument('--experiment_name', type=str, default='raihan_v1') + + return parser.parse_args() diff --git a/modules/lsp_gnn/scratch/Makefile.mk b/modules/lsp_gnn/scratch/Makefile.mk new file mode 100644 index 0000000..53890b9 --- /dev/null +++ b/modules/lsp_gnn/scratch/Makefile.mk @@ -0,0 +1,206 @@ +help:: + @echo "Conditional Learned Subgoal Planning (lsp-cond):" + @echo " lsp-cond-gen-graph-data creates the data for the experiments." + @echo " lsp-cond-train-autoencoder trains the auto encoder model." + @echo " lsp-cond-train-cnn trains the base/CNN lsp model." + @echo " lsp-cond-train-marginal trains the marginal GCN model." + @echo " lsp-cond-train trains the conditional GCN model." + @echo " lsp-cond-eval plans using the trained model vs baseline." + @echo "" + +LSP_WEIGHT ?= 1 +LOC_WEIGHT ?= 1 +LOSS ?= l1 +RPW ?= 1 +INPUT_TYPE ?= wall_class + +LSP_COND_BASENAME ?= lsp_conditional +LSP_COND_UNITY_BASENAME ?= rail_sim_2022_07 +LSP_COND_NUM_TRAINING_SEEDS ?= 2000 +LSP_COND_NUM_TESTING_SEEDS ?= 500 +LSP_COND_NUM_EVAL_SEEDS ?= 500 + +LSP_COND_CORE_ARGS ?= --save_dir /data/ \ + --unity_path /unity/$(LSP_COND_UNITY_BASENAME).x86_64 \ + --map_type new_office \ + --base_resolution 0.5 \ + --inflation_radius_m 0.75 \ + --field_of_view_deg 360 \ + --laser_max_range_m 18 \ + --pickle_directory data_pickles + +LSP_COND_DATA_GEN_ARGS ?= $(LSP_COND_CORE_ARGS) \ + --save_dir /data/$(LSP_COND_BASENAME)/ + +LSP_COND_TRAINING_ARGS ?= --test_log_frequency 10 \ + --save_dir /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME) \ + --data_csv_dir /data/$(LSP_COND_BASENAME)/ \ + --lsp_weight $(LSP_WEIGHT) \ + --loc_weight $(LOC_WEIGHT) \ + --loss $(LOSS) \ + --relative_positive_weight $(RPW) \ + --input_type $(INPUT_TYPE) + +LSP_COND_EVAL_ARGS ?= $(LSP_COND_CORE_ARGS) \ + --save_dir /data/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/model.pt \ + --cnn_network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt \ + --gcn_network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt \ + --autoencoder_network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --input_type $(INPUT_TYPE) + +lsp-cond-data-gen-seeds = \ + $(shell for ii in $$(seq 0000 $$((0000 + $(LSP_COND_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/data_completion_logs/data_training_$${ii}.txt"; done) \ + $(shell for ii in $$(seq 30000 $$((30000 + $(LSP_COND_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/data_completion_logs/data_testing_$${ii}.txt"; done) + +$(lsp-cond-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-cond-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-cond-data-gen-seeds): + @echo "Generating Data [seed: $(seed) | $(traintest)"] + @$(call xhost_activate) + @-rm -f $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/data_$(traintest)_$(seed).csv + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/pickles + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/data_completion_logs + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/error_logs + @$(DOCKER_PYTHON) -m lsp_cond.scripts.gen_graph_data \ + $(LSP_COND_DATA_GEN_ARGS) \ + --current_seed $(seed) \ + --data_file_base_name data_$(traintest) + +.PHONY: lsp-cond-gen-graph-data +lsp-cond-gen-graph-data: $(lsp-cond-data-gen-seeds) + +lsp-cond-autoencoder-train-file = $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt +$(lsp-cond-autoencoder-train-file): $(lsp-cond-data-gen-seeds) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_train \ + $(LSP_COND_TRAINING_ARGS) \ + --num_steps 28000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 7000 + +lsp-cond-cnn-train-file = $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/lsp.pt +$(lsp-cond-cnn-train-file): #$(lsp-cond-autoencoder-train-file) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_train \ + $(LSP_COND_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_cnn_lsp + +lsp-cond-marginal-train-file = $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/mlsp.pt +$(lsp-cond-marginal-train-file): #$(lsp-cond-autoencoder-train-file) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_train \ + $(LSP_COND_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-3 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt \ + --train_marginal_lsp + +lsp-cond-train-file = $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/model.pt +$(lsp-cond-train-file): $(lsp-cond-autoencoder-train-file) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_train \ + $(LSP_COND_TRAINING_ARGS) \ + --num_steps 50000 \ + --learning_rate 1e-4 \ + --learning_rate_decay_factor .6 \ + --epoch_size 10000 \ + --autoencoder_network_file /data/$(LSP_COND_BASENAME)/logs/$(EXPERIMENT_NAME)/AutoEncoder.pt + +.PHONY: lsp-cond-train lsp-cond-train-autoencoder lsp-cond-train-cnn lsp-cond-train-marginal +lsp-cond-train-autoencoder: DOCKER_ARGS ?= -it +lsp-cond-train-autoencoder: $(lsp-cond-autoencoder-train-file) +lsp-cond-train-cnn: DOCKER_ARGS ?= -it +lsp-cond-train-cnn: $(lsp-cond-cnn-train-file) +lsp-cond-train-marginal: DOCKER_ARGS ?= -it +lsp-cond-train-marginal: $(lsp-cond-marginal-train-file) +lsp-cond-train: DOCKER_ARGS ?= -it +lsp-cond-train: $(lsp-cond-train-file) + + +LSP_COND_PLOTTING_ARGS = \ + --data_file /data/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME)/logfile.txt \ + --output_image_file /data/$(LSP_COND_BASENAME)/results/results_$(EXPERIMENT_NAME).png + +.PHONY: lsp-cond-results +lsp-cond-results: + @$(DOCKER_PYTHON) -m lsp_cond.scripts.cond_lsp_plotting \ + $(LSP_COND_PLOTTING_ARGS) +.PHONY: lsp-cond-results-marginal +lsp-cond-results-marginal: + @$(DOCKER_PYTHON) -m lsp_cond.scripts.cond_lsp_plotting \ + --data_file /data/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME)/mlsp_logfile.txt \ + --gnn + +lsp-cond-eval-seeds = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_COND_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME)/maze_learned_$${ii}.png"; done) +$(lsp-cond-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-cond-eval-seeds): $(lsp-cond-cnn-train-file) +$(lsp-cond-eval-seeds): $(lsp-cond-marginal-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_evaluate \ + $(LSP_COND_EVAL_ARGS) \ + --current_seed $(seed) \ + --image_filename maze_learned_$(seed).png + +.PHONY: lsp-cond-eval +lsp-cond-eval: $(lsp-cond-eval-seeds) + $(MAKE) lsp-cond-results + +lsp-cond-eval-seeds-base = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_COND_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME)/maze_lsp_$${ii}.png"; done) +$(lsp-cond-eval-seeds-base): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-cond-eval-seeds-base): $(lsp-cond-cnn-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_eval_gcn \ + $(LSP_COND_EVAL_ARGS) \ + --current_seed $(seed) \ + --image_filename maze_lsp_$(seed).png \ + --logfile_name lsp_logfile.txt + +.PHONY: lsp-cond-eval-base +lsp-cond-eval-base: $(lsp-cond-eval-seeds-base) + +lsp-cond-eval-seeds-marginal = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_COND_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME)/maze_mlsp_$${ii}.png"; done) +$(lsp-cond-eval-seeds-marginal): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-cond-eval-seeds-marginal): $(lsp-cond-marginal-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_eval_gcn \ + $(LSP_COND_EVAL_ARGS) \ + --current_seed $(seed) \ + --image_filename maze_mlsp_$(seed).png \ + --logfile_name mlsp_logfile.txt + +.PHONY: lsp-cond-eval-marginal +lsp-cond-eval-marginal: $(lsp-cond-eval-seeds-marginal) + $(MAKE) lsp-cond-results-marginal + +lsp-cond-eval-seeds-conditional = \ + $(shell for ii in $$(seq 50000 $$((50000 + $(LSP_COND_NUM_EVAL_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME)/maze_clsp_$${ii}.png"; done) +$(lsp-cond-eval-seeds-conditional): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-cond-eval-seeds-conditional): $(lsp-cond-train-file) + @mkdir -p $(DATA_BASE_DIR)/$(LSP_COND_BASENAME)/results/$(EXPERIMENT_NAME) + @$(call xhost_activate) + @$(DOCKER_PYTHON) -m lsp_cond.scripts.lsp_cond_eval_gcn \ + $(LSP_COND_EVAL_ARGS) \ + --current_seed $(seed) \ + --image_filename maze_clsp_$(seed).png \ + --logfile_name clsp_logfile.txt + +.PHONY: lsp-cond-eval-conditional +lsp-cond-eval-conditional: $(lsp-cond-eval-seeds-conditional) diff --git a/modules/lsp_gnn/scratch/info_planner.py b/modules/lsp_gnn/scratch/info_planner.py new file mode 100644 index 0000000..907600b --- /dev/null +++ b/modules/lsp_gnn/scratch/info_planner.py @@ -0,0 +1,73 @@ +class InfoKnownSubgoalPlanner(ConditionalKnownSubgoalPlanner): + def __init__(self, goal, args, known_map, semantic_grid=None, + wall_class=None, device=None, do_compute_weightings=True): + super(InfoKnownSubgoalPlanner, self). \ + __init__(goal, args, known_map, device, semantic_grid, wall_class) + if device is None: + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + self.device = device + if args.input_type == 'wall_class': + self.subgoal_property_net = WallClassGNN.get_net_eval_fn( + args.gcn_network_file, device=self.device) + + def compute_training_data(self): + """ This method produces training datum for both AutoEncoder and + GCN model. + """ + prob_feasible = [] + delta_success_cost = [] + exploration_cost = [] + positive_weighting_vector = [] + negative_weighting_vector = [] + data = self._compute_combined_data() + for idx, node in enumerate(self.vertex_points): + p = tuple(node) + if p in self.subgoal_nodes.keys(): + if self.subgoal_nodes[p].prob_feasible == 1.0 \ + and data['has_updated'][idx] != 1: + # Checks if an alternate subgoal path is still reachable. + # This changes the label for the subgoal whose + # alternate path has already explored the merging + # point through this subgoal + is_reachable = lsp_cond.utils.check_if_reachable( + self.inflated_known_grid, self.inflated_grid, + self.goal, self.robot_pose, self.subgoal_nodes[p]) + if is_reachable is False: + data['has_updated'][idx] = 1 + prob_feasible.append(self.subgoal_nodes[p].prob_feasible) + delta_success_cost.append(self.subgoal_nodes[p].delta_success_cost) + exploration_cost.append(self.subgoal_nodes[p].exploration_cost) + positive_weighting_vector.append(self.subgoal_nodes[p].positive_weighting) + negative_weighting_vector.append(self.subgoal_nodes[p].negative_weighting) + else: + prob_feasible.append(0) + delta_success_cost.append(0) + exploration_cost.append(0) + positive_weighting_vector.append(0) + negative_weighting_vector.append(0) + + value_of_information_vector = lsp_cond.utils.get_value_of_information_vector( + self.subgoal_nodes.copy(), self.vertex_points, self.edge_data, + self.semantic_grid, self.wall_class, self.robot_pose, self.goal, + self.subgoal_property_net, self.downsample_factor, + self.args.inflation_radius_m, self.args.base_resolution, + self.inflated_grid, self.observed_map, self.known_map + ) + assert len(value_of_information_vector) == len(prob_feasible) + + data['is_feasible'] = prob_feasible + data['delta_success_cost'] = delta_success_cost + data['exploration_cost'] = exploration_cost + data['positive_weighting'] = positive_weighting_vector + data['negative_weighting'] = negative_weighting_vector + data['known_map'] = self.known_map + data['observed_map'] = self.observed_map + data['subgoals'] = self.original_subgoal + data['vertex_points'] = self.vertex_points + data['goal'] = self.goal + data['semantic_grid'] = self.semantic_grid + data['semantic_labels'] = self.wall_class + data['value_of_information'] = value_of_information_vector + + return data diff --git a/modules/lsp_gnn/scratch/info_util.py b/modules/lsp_gnn/scratch/info_util.py new file mode 100644 index 0000000..ee3c504 --- /dev/null +++ b/modules/lsp_gnn/scratch/info_util.py @@ -0,0 +1,251 @@ +import gridmap +import lsp_cond +from skimage.morphology import dilation + + +def get_frontier_revealing_grid(grid_map, known_map, frontier, frontiers): + ''' This function adds the region through the given frontier to the currently observed + grid. So that we can generate graph on it. + ''' + f_remove_idx = [] + free = known_map != COLLISION_VAL + unknown = grid_map == UNOBSERVED_VAL + unknown_free = np.logical_and(free, unknown) + + grid = np.ones([grid_map.shape[0], grid_map.shape[1]]) + grid[unknown_free] = FREE_VAL + labeled_con_comp = skimage.measure.label(grid, background=1) + f_points = frontier.get_frontier_point() + if labeled_con_comp[f_points[0], f_points[1]] == 0: # if same as background nothing to reveal + result = grid_map.copy() + # result[frontier.points] = COLLISION_VAL + pt_x, pt_y = frontier.points[0], frontier.points[1] + for x, y in zip(pt_x, pt_y): + result[x, y] = COLLISION_VAL + return result, f_remove_idx + + region_of_interest = labeled_con_comp == labeled_con_comp[f_points[0], f_points[1]] + + # Figure out which of the subgoal should be removed because they share the same + # revealed region + for idx, f in enumerate(frontiers): + f_p = f.get_frontier_point() + if labeled_con_comp[f_points[0], f_points[1]] == \ + labeled_con_comp[f_p[0], f_p[1]]: + f_remove_idx.append(idx) + + dialated_roi = dilation(region_of_interest, footprint=lsp_cond.plotting.FOOT_PRINT) + result = grid_map.copy() + result[dialated_roi] = known_map[dialated_roi] + return result, f_remove_idx + + +def get_inflated_occupancy_grid(observed_map, inflation_radius, robot_pose): + """Compute the inflated grid.""" + # Inflate the grid and generate a plan + inflated_grid = gridmap.utils.inflate_grid( + observed_map, inflation_radius=inflation_radius) + + inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + # Prevents robot from getting stuck occasionally: sometimes (very + # rarely) the robot would reveal an obstacle and then find itself + # within the inflation radius of that obstacle. This should have + # no side-effects, since the robot is expected to be in free space. + inflated_grid[int(robot_pose.x), int(robot_pose.y)] = 0 + + return inflated_grid + + +def update_node_inputs(vertex_points, semantic_grid, wall_class, robot_pose): + new_node_dict = {} + has_updated = [] + for vertex_point in vertex_points: + vertex_point = tuple(vertex_point) + input_data = lsp_cond.utils.get_input_data( + semantic_grid, wall_class, vertex_point) + has_updated.append(1) + new_node_dict[vertex_point] = input_data + return new_node_dict + + +def get_gcn_data_adding_supernode( + vertex_points, edge_data, subgoal_nodes, new_node_dict, goal): + latent_features = [] + distance_features = [] + is_subgoal = [] + history = [] + + for vertex_point in vertex_points: + vertex_point = tuple(vertex_point) + x = new_node_dict[vertex_point]['x'] + y = new_node_dict[vertex_point]['y'] + distance_features.append(np.sqrt( + (x - goal.x) ** 2 + + (y - goal.y) ** 2)) + latent_features.append( + new_node_dict[vertex_point]['input']) + if vertex_point in subgoal_nodes.keys(): + is_subgoal.append(1) + history.append(1) + else: + is_subgoal.append(0) + history.append(0) + + # Add the super node + super_node_idx = len(history) + latent_features.append([0, 0, 0]) + latent_features = torch.tensor(latent_features, dtype=torch.float) + distance_features.append(0) + is_subgoal.append(0) + history = [0] * len(history) + history.append(1) + old_edges = [edge_pair for edge_pair in edge_data] + new_edges = [(idx, super_node_idx) for idx in range(super_node_idx)] + updated_edges = old_edges + new_edges + + datum = { + 'is_subgoal': is_subgoal, + 'history': history, + 'edge_data': updated_edges, + 'latent_features': latent_features, + 'goal_distance': distance_features, + } + return datum + + +def get_subgoal_properties(vertex_points, datum, subgoals, robot_pose, subgoal_property_net): + prob_feasible_dict, dsc, ec, out = subgoal_property_net( + datum=datum, + vertex_points=vertex_points, + subgoals=subgoals + ) + for subgoal in subgoals: + subgoal.set_props( + prob_feasible=prob_feasible_dict[subgoal], + delta_success_cost=dsc[subgoal], + exploration_cost=ec[subgoal], + last_observed_pose=robot_pose) + return subgoals + + +def get_value_of_information_vector( + subgoal_nodes, vertex_points, edge_data, + semantic_grid, wall_class, robot_pose, goal, + subgoal_property_net, downsample_factor, + inflation_radius_m, base_resolution, inflated_grid, + observed_map, known_map): + ''' This function calculates the value of information for all vertex-points + that are to be saved as graph input + ''' + + # Preserve the known subgoal properties before overwriting with the estimates + # from the neural netwokr + for subgoal in subgoal_nodes.values(): + subgoal.known_prob_feasible = subgoal.prob_feasible + subgoal.known_delta_success_cost = subgoal.delta_success_cost + subgoal.known_exploration_cost = subgoal.exploration_cost + + for idx, subgoal in enumerate(list(subgoal_nodes.values())): + node_dict = update_node_inputs(vertex_points, semantic_grid, wall_class, robot_pose) + data = get_gcn_data_adding_supernode( + vertex_points, edge_data, subgoal_nodes, node_dict, goal + ) + # Getting the subgoal properties for the actual graph + real_subgoals = get_subgoal_properties( + vertex_points, data, list(subgoal_nodes.values()).copy(), + robot_pose, subgoal_property_net) + if subgoal.known_prob_feasible == 1.0: + subgoal.value_of_information = 0 + else: + voi = calculate_value_of_information( + idx, real_subgoals, robot_pose, goal, + semantic_grid, wall_class, downsample_factor, + inflation_radius_m, base_resolution, inflated_grid, + observed_map, known_map, subgoal_property_net) + subgoal.value_of_information = voi + + value_of_information = [] + for idx, node in enumerate(vertex_points): + p = tuple(node) + if p in subgoal_nodes: + value_of_information.append(subgoal_nodes[p].value_of_information) + else: + value_of_information.append(0) + + # Restore the subgoal properties to known values + for subgoal in subgoal_nodes.values(): + subgoal.prob_feasible = subgoal.known_prob_feasible + subgoal.delta_success_cost = subgoal.known_delta_success_cost + subgoal.exploration_cost = subgoal.known_exploration_cost + + return value_of_information + + +def calculate_value_of_information( + subgoal_idx, subgoals, robot_pose, goal, + semantic_grid, wall_class, downsample_factor, + inflation_radius_m, base_resolution, inflated_grid, + observed_map, known_map, subgoal_property_net): + # Calculate the cost and ordering excluding the subgoal that we image to be revealed + frontiers = [f for f in subgoals] + frontier_to_reveal = frontiers.pop(subgoal_idx) + + min_cost_before, _ = ( + lsp.core.get_best_expected_cost_and_frontier_list( + inflated_grid, + robot_pose, + goal, + frontiers, # Here we pass the list of frontiers excluding subgoal_idx + num_frontiers_max=lsp_cond.planners.NUM_MAX_FRONTIERS, + downsample_factor=downsample_factor, + do_correct_low_prob=True)) + + # Get the revealed grid for the subgoal_idx to create graph + subgoal_revealed_grid, f_remove_idx = get_frontier_revealing_grid( + observed_map, known_map, frontier_to_reveal, frontiers + ) + inflated_grid = get_inflated_occupancy_grid( + subgoal_revealed_grid, inflation_radius_m / base_resolution, robot_pose + ) + + # Remove the frontiers that get revealed along with the revealed region + for idx in f_remove_idx[::-1]: + frontiers.pop(idx) + + uncleaned_graph = compute_skeleton(inflated_grid, frontiers) + vertex_points = uncleaned_graph['vertex_points'] + edge_data = uncleaned_graph['edges'] + new_node_dict = {} + + clean_data = prepare_input_clean_graph( + frontiers, vertex_points, edge_data, + new_node_dict, [0] * len(vertex_points), semantic_grid, + wall_class, None, robot_pose + ) + + node_dict = update_node_inputs( + clean_data['vertex_points'], semantic_grid, + wall_class, robot_pose) + data = get_gcn_data_adding_supernode( + clean_data['vertex_points'], clean_data['edge_data'], + clean_data['subgoal_nodes'], node_dict, goal + ) + # Getting the subgoal properties for the revealed graph + unreal_subgoals = get_subgoal_properties( + clean_data['vertex_points'], data, frontiers, robot_pose, subgoal_property_net) + + min_cost_after, _ = ( + lsp.core.get_best_expected_cost_and_frontier_list( + inflated_grid, + robot_pose, + goal, + unreal_subgoals, # Here we pass the list of frontiers excluding subgoal_idx + num_frontiers_max=lsp_cond.planners.NUM_MAX_FRONTIERS, + downsample_factor=downsample_factor, + do_correct_low_prob=True)) + + if min_cost_after is None and min_cost_before is None: + return 0 + + return min_cost_before - min_cost_after \ No newline at end of file diff --git a/modules/lsp_gnn/scratch/learning/models/cnn_lsp.py b/modules/lsp_gnn/scratch/learning/models/cnn_lsp.py new file mode 100644 index 0000000..88fb5e1 --- /dev/null +++ b/modules/lsp_gnn/scratch/learning/models/cnn_lsp.py @@ -0,0 +1,356 @@ +import os +import clip +import torch +import numpy as np +import torch.nn as nn +import torch.nn.functional as F +import torch_geometric.utils +from torch_geometric.loader import DataLoader +from torch.utils.tensorboard import SummaryWriter + +import lsp_cond +from learning.data import CSVPickleDataset +from vertexnav.models import EncoderNBlocks + + +class CNNLSP(nn.Module): + name = 'LSPforRawImage' + + def __init__(self, args=None): + super(CNNLSP, self).__init__() + torch.manual_seed(8616) + self._args = args + self.fc1 = nn.Linear(64, 32) + self.fc2 = nn.Linear(32, 16) + self.fc3 = nn.Linear(16, 16) + self.fc4 = nn.Linear(16, 8) + self.fc5 = nn.Linear(8, 8) + self.classifier = nn.Linear(8, 3) + + self.fc1bn = nn.BatchNorm1d(32) + self.fc2bn = nn.BatchNorm1d(16) + self.fc3bn = nn.BatchNorm1d(16) + self.fc4bn = nn.BatchNorm1d(8) + self.fc5bn = nn.BatchNorm1d(8) + + def forward(self, data, device): + h = data['latent_features'] + h = F.leaky_relu(self.fc1bn(self.fc1(h)), 0.1) + h = F.leaky_relu(self.fc2bn(self.fc2(h)), 0.1) + h = F.leaky_relu(self.fc3bn(self.fc3(h)), 0.1) + h = F.leaky_relu(self.fc4bn(self.fc4(h)), 0.1) + h = F.leaky_relu(self.fc5bn(self.fc5(h)), 0.1) + h = self.classifier(h) + return h + + def loss(self, nn_out, data, device='cpu', writer=None, index=None): + # Separate outputs. + is_feasible_logits = nn_out[:, 0] + delta_cost_pred = nn_out[:, 1] + exploration_cost_pred = nn_out[:, 2] + + # Convert the data + is_feasible_label = data.y.to(device) + has_updated = data.has_updated.to(device) + delta_cost_label = data.dsc.to(device) + exploration_cost_label = data.ec.to(device) + pweight = data.pweight.to(device) # TODO - Remove? + nweight = data.nweight.to(device) # TODO - Remove? + history = data.is_subgoal.to(device) + rpw = self._args.relative_positive_weight + subgoal_weight = history # * (has_updated + 0.1) + + # Compute the contribution from the is_feasible_label + is_feasible_xentropy = rpw * is_feasible_label * -F.logsigmoid( + is_feasible_logits) * pweight / 10 + (1 - is_feasible_label) * \ + -F.logsigmoid(-is_feasible_logits) * nweight / 10 + is_feasible_xentropy = torch.sum(subgoal_weight * is_feasible_xentropy) + is_feasible_xentropy /= torch.sum(subgoal_weight)+0.001 + # Set the loss type for Delta Success Cost and Exploration Cost + if self._args.loss == 'l1': + cost_loss = torch.abs + else: + cost_loss = torch.square + + # Delta Success Cost + delta_cost_pred_error = cost_loss( + delta_cost_pred - delta_cost_label) \ + / (100 ** 1) * is_feasible_label + delta_cost_pred_error = torch.sum(subgoal_weight * delta_cost_pred_error) + delta_cost_pred_error /= torch.sum(subgoal_weight)+0.001 + # Exploration Cost + exploration_cost_pred_error = cost_loss( + exploration_cost_pred - exploration_cost_label) / \ + (200 ** 1 * 4) * (1 - is_feasible_label) + exploration_cost_pred_error = torch.sum(subgoal_weight * exploration_cost_pred_error) + exploration_cost_pred_error /= torch.sum(subgoal_weight)+0.001 + + # Sum the contributions + loss = is_feasible_xentropy + delta_cost_pred_error + \ + exploration_cost_pred_error + + # Logging + if writer is not None: + writer.add_scalar("Loss/is_feasible_xentropy", + is_feasible_xentropy.item(), + index) + writer.add_scalar("Loss/delta_success_cost_loss", + delta_cost_pred_error.item(), + index) + writer.add_scalar("Loss/exploration_cost_loss", + exploration_cost_pred_error.item(), + index) + writer.add_scalar("Loss/total_loss", + loss.item(), + index) + + return loss + + # def loss(self, nn_out, data, device='cpu', writer=None, index=None): + # # Separate outputs. + # is_feasible_logits = nn_out[:, 0] + # delta_cost_pred = nn_out[:, 1] + # exploration_cost_pred = nn_out[:, 2] + + # # Convert the data + # is_feasible_label = data.y.to(device) + # delta_cost_label = data.dsc.to(device) + # exploration_cost_label = data.ec.to(device) + # pweight = data.pweight.to(device) + # nweight = data.nweight.to(device) + # rpw = self._args.relative_positive_weight + + # # Compute the contribution from the is_feasible_label + # is_feasible_xentropy = torch.mean( + # rpw * is_feasible_label * -F.logsigmoid(is_feasible_logits) + # * pweight / 10 + (1 - is_feasible_label) * + # -F.logsigmoid(-is_feasible_logits) * nweight / 10) + + # # Delta Success Cost + # delta_cost_pred_error = torch.mean(torch.square( + # delta_cost_pred - delta_cost_label) / (100 ** 2) * + # is_feasible_label) + + # # Exploration Cost + # exploration_cost_pred_error = torch.mean(torch.square( + # exploration_cost_pred - exploration_cost_label) / + # (200 ** 2) * (1 - is_feasible_label)) + + # # Sum the contributions + # loss = is_feasible_xentropy + delta_cost_pred_error + \ + # exploration_cost_pred_error + + # # Logging + # if writer is not None: + # writer.add_scalar("Loss/is_feasible_xentropy", + # is_feasible_xentropy.item(), + # index) + # writer.add_scalar("Loss/delta_success_cost_loss", + # delta_cost_pred_error.item(), + # index) + # writer.add_scalar("Loss/exploration_cost_loss", + # exploration_cost_pred_error.item(), + # index) + # writer.add_scalar("Loss/total_loss", + # loss.item(), + # index) + + # return loss + + @classmethod + def get_net_eval_fn(_, network_file, device=None): + model = CNNLSP() + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def frontier_net(datum): + with torch.no_grad(): + out = model.forward({'latent_features': datum}, device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + return out[0, 0], out[0, 1], out[0, 2] + return frontier_net + + +class CNN_CLIP(CNNLSP): + name = 'CNNusingCLIP' + + def __init__(self, args=None): + super(CNN_CLIP, self).__init__() + torch.manual_seed(8616) + self._args = args + + self.fc0 = nn.Linear(512, 256) + self.fc1 = nn.Linear(256, 128) + self.fc2 = nn.Linear(128, 64) + self.fc3 = nn.Linear(64, 32) + self.fc4 = nn.Linear(32, 16) + self.fc5 = nn.Linear(16, 8) + self.classifier = nn.Linear(8, 3) + + self.fc0bn = nn.BatchNorm1d(256) + self.fc1bn = nn.BatchNorm1d(128) + self.fc2bn = nn.BatchNorm1d(64) + self.fc3bn = nn.BatchNorm1d(32) + self.fc4bn = nn.BatchNorm1d(16) + self.fc5bn = nn.BatchNorm1d(8) + + def forward(self, data, device): + h = data['latent_features'].type(torch.float).to(device) + + h = F.leaky_relu(self.fc0bn(self.fc0(h)), 0.1) + h = F.leaky_relu(self.fc1bn(self.fc1(h)), 0.1) + h = F.leaky_relu(self.fc2bn(self.fc2(h)), 0.1) + h = F.leaky_relu(self.fc3bn(self.fc3(h)), 0.1) + h = F.leaky_relu(self.fc4bn(self.fc4(h)), 0.1) + h = F.leaky_relu(self.fc5bn(self.fc5(h)), 0.1) + h = self.classifier(h) + return h + + @classmethod + def get_net_eval_fn(_, network_file, device=None): + model = CNN_CLIP() + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def frontier_net(datum): + with torch.no_grad(): + out = model.forward({'latent_features': datum}, device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + return out[0, 0], out[0, 1], out[0, 2] + return frontier_net + + +def train(args, train_path, test_path): + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + # Initialize the network and the optimizer + if args.use_clip: + print("Using CLIP encoder") + _, preprocess = clip.load(args.clip_network_file, device=device) + model = CNN_CLIP(args) + latent_features_net = lsp_cond.learning.models.auto_encoder. \ + AutoEncoder.get_net_eval_fn(args.clip_network_file, device=device) + else: + preprocess = None + if args.input_type == 'image' or args.input_type == 'seg_image': + print("Using AE on pano_image") + model = CNNLSP(args) + latent_features_net = lsp_cond.learning.models.auto_encoder. \ + AutoEncoder.get_net_eval_fn_old( + args.autoencoder_network_file, device=device, args=args) + elif args.input_type == 'wall_class': + model = WallClassLSP(args) + print("Using semantic wall class labels") + + # prep_fn = lsp_cond.utils.preprocess_cnn_training_data( + # fn=preprocess, args=args) + prep_fn = lsp_cond.utils.preprocess_gcn_training_data( + ['marginal'], preprocess, args) + + # Create the datasets and loaders + train_dataset = CSVPickleDataset(train_path, prep_fn) + print("Number of training graphs:", len(train_dataset)) + train_loader = DataLoader(train_dataset, batch_size=4, + shuffle=True, drop_last=True) + train_iter = iter(train_loader) + train_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, "train_lsp")) + + test_dataset = CSVPickleDataset(test_path, prep_fn) + print("Number of testing graphs:", len(test_dataset)) + test_loader = DataLoader(test_dataset, batch_size=4, + shuffle=True, drop_last=True) + test_iter = iter(test_loader) + test_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, "test_lsp")) + + # Initialize the network and the optimizer + model.to(device) + optimizer = torch.optim.Adam(model.parameters(), lr=args.learning_rate) + scheduler = torch.optim.lr_scheduler.StepLR( + optimizer, step_size=args.epoch_size, + gamma=args.learning_rate_decay_factor) + index = 0 + + while index < args.num_steps: + # Get the batches + try: + train_batch = next(train_iter) + except StopIteration: + train_iter = iter(train_loader) + train_batch = next(train_iter) + if args.input_type == 'wall_class': + train_latent_features = train_batch.x + elif args.input_type == 'image' or args.input_type == 'seg_image': + # Get latent features by running the encoder of AutoEncoder/CLIP + train_latent_features = latent_features_net( + {'image': train_batch.x} + ) + out = model.forward({ + 'edge_data': train_batch.edge_index, + 'history': train_batch.history, + 'goal_distance': train_batch.goal_distance, + 'is_subgoal': train_batch.is_subgoal, + 'latent_features': train_batch.x + }, device) + train_loss = model.loss(out, + data=train_batch, + device=device, + writer=train_writer, + index=index) + + if index % args.test_log_frequency == 0: + print(f"[{index}/{args.num_steps}] " + f"Train Loss: {train_loss}") + + # Train the system + optimizer.zero_grad() + train_loss.backward() + optimizer.step() + + if index % args.test_log_frequency == 0: + try: + test_batch = next(test_iter) + except StopIteration: + test_iter = iter(test_loader) + test_batch = next(test_iter) + if args.input_type == 'wall_class': + test_latent_features = test_batch.x + elif args.input_type == 'image' or args.input_type == 'seg_image': + test_latent_features = latent_features_net( + {'image': test_batch.x} + ) + with torch.no_grad(): + out = model.forward({ + 'edge_data': test_batch.edge_index, + 'history': test_batch.history, + 'goal_distance': test_batch.goal_distance, + 'is_subgoal': test_batch.is_subgoal, + 'latent_features': test_batch.x + }, device) + test_loss = model.loss(out, + data=test_batch, + device=device, + writer=test_writer, + index=index) + print(f"[{index}/{args.num_steps}] " + f"Test Loss: {test_loss.cpu().numpy()}") + + # Log the learning rate + test_writer.add_scalar("learning_rate/LSP", + scheduler.get_last_lr()[-1], + index) + index += 1 + scheduler.step() + + # Saving the model after training + torch.save(model.state_dict(), + os.path.join(args.save_dir, "lsp.pt")) \ No newline at end of file diff --git a/modules/lsp_gnn/scratch/learning/models/gcn.py b/modules/lsp_gnn/scratch/learning/models/gcn.py new file mode 100644 index 0000000..6dcd676 --- /dev/null +++ b/modules/lsp_gnn/scratch/learning/models/gcn.py @@ -0,0 +1,404 @@ +import os +import clip +import torch +import lsp_cond +import learning +import torch.nn as nn +import numpy as np +import torch.nn.functional as F +from torch_geometric.nn import SAGEConv, LEConv +from learning.data import CSVPickleDataset +import torch_geometric.utils +from torch_geometric.loader import DataLoader +from torch.utils.tensorboard import SummaryWriter + + +class LSPConditionalGNN(nn.Module): + name = 'GNNforImage' + + def __init__(self, args=None): + super(LSPConditionalGNN, self).__init__() + torch.manual_seed(8616) + self._args = args + + self.fc1 = nn.Linear(64+2, 32) + self.fc2 = nn.Linear(32, 16) + self.fc3 = nn.Linear(16, 8) + self.conv1 = SAGEConv(8, 8) + self.conv2 = SAGEConv(8, 8) + self.conv3 = SAGEConv(8, 8) + self.classifier = nn.Linear(8, 3) + + self.fc1bn = nn.BatchNorm1d(32) + self.fc2bn = nn.BatchNorm1d(16) + self.fc3bn = nn.BatchNorm1d(8) + self.conv1bn = nn.BatchNorm1d(8) + self.conv2bn = nn.BatchNorm1d(8) + self.conv3bn = nn.BatchNorm1d(8) + + def forward(self, data, device): + lf = data['latent_features'].to(device) + my_tensor = data['edge_data'] + x = torch.cat((my_tensor[0], my_tensor[1]), 0) + y = torch.cat((my_tensor[1], my_tensor[0]), 0) + my_tensor = torch.reshape(torch.cat((x, y), 0), (2, -1)) + edge_index = my_tensor.to(device) + history = data['history'].view(-1, 1).to(device) + is_subgoal = data['is_subgoal'].view(-1, 1).to(device) + h = torch.cat((lf, history), 1) + h = torch.cat((h, is_subgoal), 1) + h = F.leaky_relu(self.fc1bn(self.fc1(h)), 0.1) + h = F.leaky_relu(self.fc2bn(self.fc2(h)), 0.1) + h = F.leaky_relu(self.fc3bn(self.fc3(h)), 0.1) + h = F.leaky_relu(self.conv1bn(self.conv1(h, edge_index)), 0.1) + h = F.leaky_relu(self.conv2bn(self.conv2(h, edge_index)), 0.1) + h = F.leaky_relu(self.conv3bn(self.conv3(h, edge_index)), 0.1) + props = self.classifier(h) + return props + + def loss(self, nn_out, data, device='cpu', writer=None, index=None): + # Separate outputs. + is_feasible_logits = nn_out[:, 0] + delta_cost_pred = nn_out[:, 1] + exploration_cost_pred = nn_out[:, 2] + + # Convert the data + is_feasible_label = data.y.to(device) + has_updated = data.has_updated.to(device) + delta_cost_label = data.dsc.to(device) + exploration_cost_label = data.ec.to(device) + pweight = data.pweight.to(device) # TODO - Remove? + nweight = data.nweight.to(device) # TODO - Remove? + history = data.is_subgoal.to(device) + rpw = self._args.relative_positive_weight + subgoal_weight = history # * (has_updated + 0.1) + + # Compute the contribution from the is_feasible_label + is_feasible_xentropy = rpw * is_feasible_label * -F.logsigmoid( + is_feasible_logits) * pweight / 10 + (1 - is_feasible_label) * \ + -F.logsigmoid(-is_feasible_logits) * nweight / 10 + is_feasible_xentropy = torch.sum(subgoal_weight * is_feasible_xentropy) + is_feasible_xentropy /= torch.sum(subgoal_weight)+0.001 + # Set the loss type for Delta Success Cost and Exploration Cost + if self._args.loss == 'l1': + cost_loss = torch.abs + else: + cost_loss = torch.square + + # Delta Success Cost + delta_cost_pred_error = cost_loss( + delta_cost_pred - delta_cost_label) \ + / (100 ** 1) * is_feasible_label + delta_cost_pred_error = torch.sum(subgoal_weight * delta_cost_pred_error) + delta_cost_pred_error /= torch.sum(subgoal_weight)+0.001 + # Exploration Cost + exploration_cost_pred_error = cost_loss( + exploration_cost_pred - exploration_cost_label) / \ + (200 ** 1 * 4) * (1 - is_feasible_label) + exploration_cost_pred_error = torch.sum(subgoal_weight * exploration_cost_pred_error) + exploration_cost_pred_error /= torch.sum(subgoal_weight)+0.001 + + # Sum the contributions + loss = is_feasible_xentropy + delta_cost_pred_error + \ + exploration_cost_pred_error + + # Logging + if writer is not None: + writer.add_scalar("Loss/is_feasible_xentropy", + is_feasible_xentropy.item(), + index) + writer.add_scalar("Loss/delta_success_cost_loss", + delta_cost_pred_error.item(), + index) + writer.add_scalar("Loss/exploration_cost_loss", + exploration_cost_pred_error.item(), + index) + writer.add_scalar("Loss/total_loss", + loss.item(), + index) + + return loss + + @classmethod + def get_net_eval_fn(_, network_file, + device=None, comb=False): + model = LSPConditionalGNN() + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def frontier_net(datum, vertex_points, subgoals): + graph = lsp_cond.utils.preprocess_gcn_data(datum) + prob_feasible_dict = {} + dsc_dict = {} + ec_dict = {} + with torch.no_grad(): + out = model.forward(graph, device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + for subgoal in subgoals: + index_pos, possible_node = lsp_cond.utils. \ + get_subgoal_node(vertex_points, subgoal) + # Extract subgoal properties for a subgoal + subgoal_props = out[index_pos] + prob_feasible_dict[subgoal] = subgoal_props[0] + dsc_dict[subgoal] = subgoal_props[1] + ec_dict[subgoal] = subgoal_props[2] + return prob_feasible_dict, dsc_dict, ec_dict, out[:, 0] + + return frontier_net + + @learning.logging.tensorboard_plot_decorator + def plot_images(self, fig, out, data): + is_subgoal = data.is_subgoal + subgoal_idx_pool = [ + idx + for idx, val in enumerate(is_subgoal) + if val == 1 + ] + count = len(subgoal_idx_pool) + + # Separate outputs. + is_feasible_logits = out[:, 0] + + COL = 2 + if count % COL == 0: + ROW = count // COL + else: + ROW = count // COL + 1 + if ROW < 2: + ROW = 2 + axs = fig.subplots(ROW, COL) + trgt_img = np.transpose(data.x.cpu().numpy(), (0, 2, 3, 1)) + row_pointer = 0 + col_pointer = 0 + for idx in subgoal_idx_pool: + axs[row_pointer][col_pointer].imshow( + trgt_img[idx], interpolation='none') + axs[row_pointer][col_pointer].set_title( + f"[R]: {data.y[idx].cpu().numpy()} " + f"[P]: {torch.sigmoid(is_feasible_logits[idx]).detach().cpu().numpy():.2f}" + ) + col_pointer += 1 + if col_pointer == COL: + col_pointer = 0 + row_pointer += 1 + + +class GNN_CLIP(LSPConditionalGNN): + name = 'GNNusingCLIP' + + def __init__(self, args=None): + super(GNN_CLIP, self).__init__() + torch.manual_seed(8616) + self._args = args + self.fc1 = nn.Linear(512+2, 256) + self.fc2 = nn.Linear(256, 128) + self.fc3 = nn.Linear(128, 64) + self.fc4 = nn.Linear(64, 32) + self.fc5 = nn.Linear(32, 16) + self.fc6 = nn.Linear(16, 8) + self.conv1 = SAGEConv(8, 8) + self.conv2 = SAGEConv(8, 8) + self.conv3 = SAGEConv(8, 8) + self.classifier = nn.Linear(8, 3) + + self.fc1bn = nn.BatchNorm1d(256) + self.fc2bn = nn.BatchNorm1d(128) + self.fc3bn = nn.BatchNorm1d(64) + self.fc4bn = nn.BatchNorm1d(32) + self.fc5bn = nn.BatchNorm1d(16) + self.fc6bn = nn.BatchNorm1d(8) + self.conv1bn = nn.BatchNorm1d(8) + self.conv2bn = nn.BatchNorm1d(8) + self.conv3bn = nn.BatchNorm1d(8) + + def forward(self, data, device): + props = self.get_subgoal_props( + lf=data['latent_features'].type(torch.float).to(device), + data=data, + device=device + ) + return props + + def get_subgoal_props(self, lf, data, device='cpu'): + edge_index = data['edge_data'].to(device) + history = data['history'].view(-1, 1).to(device) + is_subgoal = data['is_subgoal'].view(-1, 1).to(device) + h = torch.cat((lf, history), 1) + h = torch.cat((h, is_subgoal), 1) + h = F.leaky_relu(self.fc1bn(self.fc1(h)), 0.1) + h = F.leaky_relu(self.fc2bn(self.fc2(h)), 0.1) + h = F.leaky_relu(self.fc3bn(self.fc3(h)), 0.1) + h = F.leaky_relu(self.fc4bn(self.fc4(h)), 0.1) + h = F.leaky_relu(self.fc5bn(self.fc5(h)), 0.1) + h = F.leaky_relu(self.fc6bn(self.fc6(h)), 0.1) + h = F.leaky_relu(self.conv1bn(self.conv1(h, edge_index)), 0.1) + h = F.leaky_relu(self.conv2bn(self.conv2(h, edge_index)), 0.1) + h = F.leaky_relu(self.conv3bn(self.conv3(h, edge_index)), 0.1) + h = self.classifier(h) + return h + + @classmethod + def get_net_eval_fn(_, network_file, get_lf=False, + device=None, comb=False): + model = GNN_CLIP() + model.load_state_dict(torch.load(network_file, + map_location=device)) + model.eval() + model.to(device) + + def latent_features_gcn_net(latent_features): + return latent_features + + def frontier_net(datum, vertex_points, subgoals): + graph = lsp_cond.utils.preprocess_gcn_data(datum) + prob_feasible_dict = {} + dsc_dict = {} + ec_dict = {} + with torch.no_grad(): + if comb: + out = model.forward(graph, device) + else: + out = model.get_subgoal_props( + graph['latent_features'], graph, device) + out = out[:, :3] + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + for subgoal in subgoals: + index_pos, possible_node = lsp_cond.utils. \ + get_subgoal_node(vertex_points, subgoal) + # Extract subgoal properties for a subgoal + subgoal_props = out[index_pos] + prob_feasible_dict[subgoal] = subgoal_props[0] + dsc_dict[subgoal] = subgoal_props[1] + ec_dict[subgoal] = subgoal_props[2] + return prob_feasible_dict, dsc_dict, ec_dict, out[:, 0] + + if get_lf: + return latent_features_gcn_net + else: + return frontier_net + + +def train(args, train_path, test_path): + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + # Initialize the network and the optimizer + preprocess = None + if args.input_type == 'image' or args.input_type == 'seg_image': + model = LSPConditionalGNN(args) + print(f"Using AE on pano_{args.input_type}") + args.latent_features_net = lsp_cond.learning.models.auto_encoder. \ + AutoEncoder.get_net_eval_fn_old( + args.autoencoder_network_file, device=device, + preprocess_for='Cond_Eval', args=args) + elif args.input_type == 'wall_class': + model = WallClassGNN(args) + print("Using semantic wall class labels") + elif args.use_clip: + print("Using CLIP encoder") + _, preprocess = clip.load(args.clip_network_file, device=device) + model = GNN_CLIP(args) + latent_features_net = lsp_cond.learning.models.auto_encoder. \ + AutoEncoder.get_net_eval_fn(args.clip_network_file, device=device) + + if args.train_marginal_lsp: + prep_fn = lsp_cond.utils.preprocess_gcn_training_data( + ['marginal'], preprocess, args) + train_writer_str = 'train_mlsp' + test_writer_str = 'test_mlsp' + lr_writer_str = 'learning_rate/mLSP' + model_name_str = 'mlsp.pt' + else: + prep_fn = lsp_cond.utils.preprocess_gcn_training_data(fn=preprocess) + train_writer_str = 'train' + test_writer_str = 'test' + lr_writer_str = 'learning_rate/cLSP' + model_name_str = 'model.pt' + + # Create the datasets and loaders + train_dataset = CSVPickleDataset(train_path, prep_fn) + print("Number of training graphs:", len(train_dataset)) + train_loader = DataLoader(train_dataset, batch_size=4, shuffle=True) + train_iter = iter(train_loader) + train_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, train_writer_str)) + + test_dataset = CSVPickleDataset(test_path, prep_fn) + print("Number of testing graphs:", len(test_dataset)) + test_loader = DataLoader(test_dataset, batch_size=2, shuffle=True) + test_iter = iter(test_loader) + test_writer = SummaryWriter( + log_dir=os.path.join(args.save_dir, test_writer_str)) + + model.to(device) + + optimizer = torch.optim.Adam(model.parameters(), lr=args.learning_rate) + scheduler = torch.optim.lr_scheduler.StepLR( + optimizer, step_size=args.epoch_size, + gamma=args.learning_rate_decay_factor) + index = 0 + while index < args.num_steps: + try: + train_batch = next(train_iter) + except StopIteration: + train_iter = iter(train_loader) + train_batch = next(train_iter) + out = model.forward({ + 'edge_data': train_batch.edge_index, + 'history': train_batch.history, + 'goal_distance': train_batch.goal_distance, + 'is_subgoal': train_batch.is_subgoal, + 'latent_features': train_batch.x + }, device) + train_loss = model.loss(out, + data=train_batch, + device=device, + writer=train_writer, + index=index) + + if index % args.test_log_frequency == 0: + print(f"[{index}/{args.num_steps}] " + f"Train Loss: {train_loss}") + + # Train the system + optimizer.zero_grad() + train_loss.backward() + optimizer.step() + + if index % args.test_log_frequency == 0: + try: + test_batch = next(test_iter) + except StopIteration: + test_iter = iter(test_loader) + test_batch = next(test_iter) + + with torch.no_grad(): + out = model.forward({ + 'edge_data': test_batch.edge_index, + 'history': test_batch.history, + 'goal_distance': test_batch.goal_distance, + 'is_subgoal': test_batch.is_subgoal, + 'latent_features': test_batch.x + }, device) + test_loss = model.loss(out, + data=test_batch, + device=device, + writer=test_writer, + index=index) + print(f"[{index}/{args.num_steps}] " + f"Test Loss: {test_loss.cpu().numpy()}") + + # Log the learning rate + test_writer.add_scalar(lr_writer_str, + scheduler.get_last_lr()[-1], + index) + index += 1 + scheduler.step() + + # Saving the model after training + torch.save(model.state_dict(), + os.path.join(args.save_dir, model_name_str)) diff --git a/modules/lsp_gnn/scratch/plotting.py b/modules/lsp_gnn/scratch/plotting.py new file mode 100644 index 0000000..305172c --- /dev/null +++ b/modules/lsp_gnn/scratch/plotting.py @@ -0,0 +1,106 @@ +import numpy as np +import matplotlib.pyplot as plt +from skimage.morphology import erosion + +from lsp.constants import (FREE_VAL, OBSTACLE_THRESHOLD) + + +def plot_pose(ax, pose, color='black', filled=True): + if filled: + ax.scatter(pose.x, pose.y, color=color, s=10, label='point') + else: + ax.scatter(pose.x, + pose.y, + color=color, + s=10, + label='point', + facecolors='none') + + +def plot_path(ax, path, ls=':', color='#FF7F00'): + if path is not None: + ax.plot(path[0, :], path[1, :], ls=ls, color=color) + + +def plot_pose_path(ax, poses, ls='-', color='#FF7F00'): + path = np.array([[p.x, p.y] for p in poses]).T + plot_path(ax, path, ls, color) + + +footprint = [ + [1, 1, 1], + [1, 1, 1], + [1, 1, 1], +] + + +def make_plotting_grid( + grid_map, known_map=None, semantic_grid=None, semantic_labels=None): + # print(semantic_labels) + if known_map is not None: + grid_map = known_map + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + collision = grid_map >= OBSTACLE_THRESHOLD + # Take one pixel boundary of the region collision + # thinned = thin(collision, max_num_iter=1) + thinned = erosion(collision, footprint=footprint) + boundary = np.logical_xor(collision, thinned) + # print(boundary.shape) + free = np.logical_and(grid_map < OBSTACLE_THRESHOLD, grid_map >= FREE_VAL) + red = np.logical_and(free, semantic_grid == semantic_labels['red']) + grid[:, :, 0][red] = 1 + grid[:, :, 1][red] = 0 + grid[:, :, 2][red] = 0 + blue = np.logical_and(free, semantic_grid == semantic_labels['blue']) + grid[:, :, 0][blue] = 0 + grid[:, :, 1][blue] = 0 + grid[:, :, 2][blue] = 1 + hall = np.logical_and(free, semantic_grid == semantic_labels['hallway']) + grid[:, :, 0][hall] = 1 + grid[:, :, 1][hall] = 1 + grid[:, :, 2][hall] = 1 + grid[:, :, 0][boundary] = 0 + grid[:, :, 1][boundary] = 0 + grid[:, :, 2][boundary] = 0 + + # if known_map is not None: + # known_collision = known_map == COLLISION_VAL + # unobserved = grid_map == UNOBSERVED_VAL + # unknown_obstacle = np.logical_and(known_collision, unobserved) + # grid[:, :, 0][boundary] = 0.65 + # grid[:, :, 1][boundary] = 0.65 + # grid[:, :, 2][boundary] = 0.75 + + return grid + + +def plot_grid_without_frontiers( + ax, grid_map, known_map, frontiers, + semantic_grid=None, semantic_labels=None): + grid = make_plotting_grid( + grid_map, known_map, semantic_grid, semantic_labels) + ax.imshow(np.transpose(grid, (1, 0, 2))) + + +def plot_grid_with_frontiers(ax, + grid_map, + known_map, + frontiers, + semantic_grid=None, semantic_labels=None, + cmap_name='viridis'): + grid = make_plotting_grid( + grid_map, known_map, semantic_grid, semantic_labels) + + cmap = plt.get_cmap(cmap_name) + for frontier in frontiers: + color = cmap(frontier.prob_feasible) + grid[frontier.points[0, :], frontier.points[1, :], 0] = color[0] + grid[frontier.points[0, :], frontier.points[1, :], 1] = color[1] + grid[frontier.points[0, :], frontier.points[1, :], 2] = color[2] + + ax.imshow(np.transpose(grid, (1, 0, 2))) + + +def plot_grid_for_skeleton(ax, grid_map): + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + ax.imshow(np.transpose(grid, (1, 0, 2))) diff --git a/modules/lsp_gnn/scratch/scripts/lsp_cond_clip.py b/modules/lsp_gnn/scratch/scripts/lsp_cond_clip.py new file mode 100644 index 0000000..ace114f --- /dev/null +++ b/modules/lsp_gnn/scratch/scripts/lsp_cond_clip.py @@ -0,0 +1,14 @@ +from urllib import request + + +if __name__ == "__main__": + # Define the remote file to retrieve + print("Downloading CLIP encoder...") + remote_url = "https://openaipublic.azureedge.net/clip/models/40d36571591"\ + "3c9da98579312b702a82c18be219cc2a73407c4526f58eba950af/"\ + "ViT-B-32.pt" + # Define the local filename to save data + local_file = '/data/lsp_conditional/logs/ViT-B-32.pt' + # Download remote and save locally + request.urlretrieve(remote_url, local_file) + print("Completed Downloading CLIP encoder.") diff --git a/modules/lsp_gnn/scratch/scripts/lsp_cond_eval_gcn.py b/modules/lsp_gnn/scratch/scripts/lsp_cond_eval_gcn.py new file mode 100644 index 0000000..93fb46c --- /dev/null +++ b/modules/lsp_gnn/scratch/scripts/lsp_cond_eval_gcn.py @@ -0,0 +1,213 @@ +import common +import os +import matplotlib.pyplot as plt +import numpy as np +import lsp +import lsp_cond +import environments +import gridmap +import matplotlib.animation as animation +from matplotlib import cm +from matplotlib.gridspec import GridSpec +from lsp_cond.planners import ConditionalUnknownSubgoalPlanner, GCNLSP, LSP +import time as time + +viridis = cm.get_cmap('viridis') + + +def evaluate_main(args, make_video=False): + if args.map_type == 'jshaped': + known_map, map_data, pose, goal = \ + lsp_cond.environments.generate.lsp_cond_map_and_poses(args) + elif args.map_type == 'new_office': + known_map, map_data, pose, goal = \ + lsp_cond.environments.generate.generate_map(args) + if make_video: + fig = plt.figure() + writer = animation.FFMpegWriter(12) + writer.setup(fig, os.path.join(args.save_dir, + f'Eval_{args.current_seed}.mp4'), 500) + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=0, + min_interlight_distance=3.0, + min_light_to_wall_distance=1) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + # with builder(args.unity_path) as unity_bridge: + if True: + unity_bridge = None + # unity_bridge.make_world(world) + + # Write starting seed to the log file + logfile = os.path.join(args.save_dir, args.logfile_name) + with open(logfile, "a+") as f: + f.write(f"LOG: {args.current_seed}\n") + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + if args.logfile_name == 'clsp_logfile.txt': + planner = ConditionalUnknownSubgoalPlanner(goal, args) + cost_str = 'cond_lsp' + elif args.logfile_name == 'mlsp_logfile.txt': + planner = GCNLSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + cost_str = 'gcn_lsp' + elif args.logfile_name == 'lsp_logfile.txt': + planner = LSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + cost_str = 'lsp' + robot = get_robot() + planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, robot, + args, verbose=True) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + s_time = time.time() + planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], None) + print(f"Time taken to update: {time.time() - s_time}") + # Compute the subgoal and set + s_time = time.time() + chosen_subgoal = planner.compute_selected_subgoal() + print(f"Time taken to choose subgoal: {time.time() - s_time}") + planning_loop.set_chosen_subgoal(chosen_subgoal) + + if make_video and args.logfile_name != 'lsp_logfile.txt': + # Mask grid with chosen subgoal (if not None) + # and compute the cost grid for motion planning. + if chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, planner.subgoals, do_not_mask=chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + + # Plotting + plt.ion() + # plt.figure(1) + fig = plt.figure(1) + # gs = GridSpec(2, 2, figure=fig) + plt.clf() + # ax = fig.add_subplot(gs[0, :]) + # if step_data['image'] is not None: + # plt.imshow(step_data['image']) + plt.title('Seed: ['+str(args.current_seed) + + '] <> Planner: ['+cost_str+']') + ax = plt.subplot(121) + lsp_cond.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_cond.plotting.plot_grid_with_frontiers( + ax, step_data['robot_grid'], None, planner.subgoals, + map_data['semantic_grid'], map_data['wall_class']) + lsp_cond.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_cond.plotting.plot_path(ax, path) + lsp_cond.plotting.plot_pose_path(ax, robot.all_poses) + is_subgoal = planner.is_subgoal + prob_feasible = planner.out + # if args.input_type == 'wall_class': + # for vp_idx, ps in enumerate(planner.vertex_points): + # if is_subgoal[vp_idx]: + # lf = planner.gcn_graph_input["latent_features"][vp_idx] + # lf = lf.cpu().detach().numpy() + # color_index = np.argmax(lf) + # if color_index == 0: + # color = 'red' + # elif color_index == 1: + # color = 'blue' + # elif color_index == 2: + # color = 'gray' + # # color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + # plt.plot(ps[0], ps[1], '.', color=color, markersize=2) + ax = plt.subplot(122) + lsp_cond.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_cond.plotting.plot_grid_with_frontiers( + ax, step_data['robot_grid'], None, step_data['subgoals'], + map_data['semantic_grid'], map_data['wall_class']) + lsp_cond.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_cond.plotting.plot_path(ax, path) + lsp_cond.plotting.plot_pose_path(ax, robot.all_poses) + for (s, e) in planner.edges_wo_subgoals: + ps = planner.current_graph[s][e]['pts'] + plt.plot(ps[:, 0], ps[:, 1], 'black') + + for vp_idx, ps in enumerate(planner.vertex_points): + if not is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=3, markeredgecolor='r') + for vp_idx, ps in enumerate(planner.vertex_points): + if is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + # plt.text(ps[0], ps[1], f'{prob_feasible[vp_idx]:.3f}', color=color) + # plt.show() # TODO - add plot pause to render during planning + # plt.pause(.1000) + writer.grab_frame() + if make_video: + writer.finish() + dist = common.compute_path_length(robot.all_poses) + did_succeed = planning_loop.did_succeed + + with open(logfile, "a+") as f: + err_str = '' if did_succeed else '[ERR]' + f.write(f"[Learn] {err_str} s: {args.current_seed:4d}" + f" | {cost_str}: {dist:0.3f}\n") + + if planner.observed_map is None: + planner.observed_map = -1 * np.ones_like(known_map) + + # Write final plot to file + image_file = os.path.join(args.save_dir, args.image_filename) + plt.figure(figsize=(4, 4)) + # plt.subplot(231) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(planner.observed_map, known_map)) + path = robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + args = lsp_cond.utils.parse_args() + print(f'Evaluation seed: [{args.current_seed}]') + evaluate_main(args, make_video=True) diff --git a/modules/lsp_gnn/scratch/scripts/lsp_cond_evaluate.py b/modules/lsp_gnn/scratch/scripts/lsp_cond_evaluate.py new file mode 100644 index 0000000..24ec844 --- /dev/null +++ b/modules/lsp_gnn/scratch/scripts/lsp_cond_evaluate.py @@ -0,0 +1,319 @@ +import common +import os +import matplotlib.pyplot as plt +import numpy as np +import lsp +import lsp_cond +import environments +import matplotlib.animation as animation +from matplotlib import cm +from lsp_cond.planners import ConditionalUnknownSubgoalPlanner, \ + LSP, GCNLSP +from lsp.planners import KnownPlanner +import time as time + +viridis = cm.get_cmap('viridis') + + +def evaluate_main(args, make_video=False): + if args.map_type == 'jshaped': + known_map, map_data, pose, goal = \ + lsp_cond.environments.generate.lsp_cond_map_and_poses(args) + elif args.map_type == 'new_office': + known_map, map_data, pose, goal = \ + lsp_cond.environments.generate.generate_map(args) + if make_video: + fig = plt.figure() + writer = animation.FFMpegWriter(15) + writer.setup(fig, os.path.join(args.save_dir, + f'Eval_{args.current_seed}.mp4'), 500) + # Randomize/Corrupt the initial robot pose + if args.do_randomize_start_pose: + if not args.map_type == 'maze': + raise ValueError('Pose randomization allowed for Maze.') + else: + pose = lsp_cond.utils.get_path_middle_point( + known_map, pose, goal, args) + + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=0, + min_interlight_distance=3.0, + min_light_to_wall_distance=1) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + # with builder(args.unity_path) as unity_bridge: + if True: + unity_bridge = None + # unity_bridge.make_world(world) + + # Write starting seed to the log file + logfile = os.path.join(args.save_dir, args.logfile_name) + with open(logfile, "a+") as f: + f.write(f"LOG: {args.current_seed}\n") + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + # ################ + # # Conditional # + # ################ + # learned_planner = ConditionalUnknownSubgoalPlanner(goal, args) + # learned_robot = get_robot() + # learned_planning_loop = lsp.planners.PlanningLoop( + # goal, known_map, simulator, unity_bridge, learned_robot, + # args, verbose=True) + + # for counter, step_data in enumerate(learned_planning_loop): + # # Update the planner objects + # s_time = time.time() + # learned_planner.update( + # {'image': step_data['image']}, + # step_data['robot_grid'], + # step_data['subgoals'], + # step_data['robot_pose']) + # print(f"Time taken to update: {time.time() - s_time}") + # # Compute the subgoal and set + # s_time = time.time() + # chosen_subgoal = learned_planner.compute_selected_subgoal() + # print(f"Time taken to choose subgoal: {time.time() - s_time}") + # learned_planning_loop.set_chosen_subgoal(chosen_subgoal) + + # if make_video: + # # Mask grid with chosen subgoal (if not None) + # # and compute the cost grid for motion planning. + # if chosen_subgoal is not None: + # planning_grid = lsp.core.mask_grid_with_frontiers( + # learned_planner.inflated_grid, learned_planner.subgoals, do_not_mask=chosen_subgoal) + # else: + # planning_grid = lsp.core.mask_grid_with_frontiers( + # learned_planner.inflated_grid, + # [], + # ) + # # Check that the plan is feasible and compute path + # cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + # planning_grid, [goal.x, goal.y], use_soft_cost=True) + # did_plan, path = get_path([learned_robot.pose.x, learned_robot.pose.y], + # do_sparsify=True, + # do_flip=True) + + # # Plotting + # plt.ion() + # plt.figure(1) + # plt.clf() + # ax = plt.subplot(121) + # plt.imshow(step_data['image']) + # ax = plt.subplot(122) + # lsp_cond.plotting.plot_pose(ax, learned_robot.pose, color='blue') + # lsp_cond.plotting.plot_grid_with_frontiers( + # ax, step_data['robot_grid'], known_map, step_data['subgoals']) + # lsp_cond.plotting.plot_pose(ax, goal, color='green', filled=False) + # lsp_cond.plotting.plot_path(ax, path) + # lsp_cond.plotting.plot_pose_path(ax, learned_robot.all_poses) + # for (s, e) in learned_planner.edge_data: + # ps = learned_planner.current_graph[s][e]['pts'] + # plt.plot(ps[:, 0], ps[:, 1], 'lightgray') + + # is_subgoal = learned_planner.is_subgoal + # prob_feasible = learned_planner.out + # for vp_idx, ps in enumerate(learned_planner.vertex_points): + # if not is_subgoal[vp_idx]: + # color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + # plt.plot(ps[0], ps[1], '.', color=color, markersize=3, markeredgecolor='r') + # for vp_idx, ps in enumerate(learned_planner.vertex_points): + # if is_subgoal[vp_idx]: + # color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + # plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + # # plt.show() # TODO - add plot pause to render during planning + # writer.grab_frame() + # if make_video: + # writer.finish() + + ################ + # ~~~ Known ~~ # + ################ + base_planner = KnownPlanner(goal, known_map, args) + base_robot = get_robot() + base_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, base_robot, + args, verbose=True) + + for counter, step_data in enumerate(base_planning_loop): + # Update the planner objects + base_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + chosen_subgoal = base_planner.compute_selected_subgoal() + base_planning_loop.set_chosen_subgoal(chosen_subgoal) + + ################ + # ~~~ Naive ~~ # + ################ + naive_robot = get_robot() + naive_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, naive_robot, + args, verbose=True) + + for counter, step_data in enumerate(naive_planning_loop): + naive_observed_map = step_data['robot_grid'] + + ################ + # ~~ CNN LSP ~ # + ################ + lsp_planner = LSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + lsp_robot = get_robot() + lsp_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, lsp_robot, + args, verbose=True) + + for counter, step_data in enumerate(lsp_planning_loop): + # Update the planner objects + lsp_planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], None) + # Compute the subgoal and set + chosen_subgoal = lsp_planner.compute_selected_subgoal() + lsp_planning_loop.set_chosen_subgoal(chosen_subgoal) + + ################ + # ~~ GCN LSP ~ # + ################ + gcn_lsp_planner = GCNLSP( + goal, args, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + gcn_lsp_robot = get_robot() + gcn_lsp_planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, unity_bridge, gcn_lsp_robot, + args, verbose=True) + + for counter, step_data in enumerate(gcn_lsp_planning_loop): + # Update the planner objects + gcn_lsp_planner.update( + {'image': step_data['image'], + 'seg_image': step_data['seg_image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + # Compute the subgoal and set + chosen_subgoal = gcn_lsp_planner.compute_selected_subgoal() + gcn_lsp_planning_loop.set_chosen_subgoal(chosen_subgoal) + + # learned_dist = common.compute_path_length(learned_robot.all_poses) + base_dist = common.compute_path_length(base_robot.all_poses) + naive_dist = common.compute_path_length(naive_robot.all_poses) + lsp_dist = common.compute_path_length(lsp_robot.all_poses) + gcn_lsp_dist = common.compute_path_length(gcn_lsp_robot.all_poses) + did_succeed = gcn_lsp_planning_loop.did_succeed # \ + # and naive_planning_loop.did_succeed + + with open(logfile, "a+") as f: + err_str = '' if did_succeed else '[ERR]' + f.write(f"[Learn] {err_str} s: {args.current_seed:4d}" + # f" | cond_lsp: {learned_dist:0.3f}" + f" | baseline: {base_dist:0.3f}" + f" | naive: {naive_dist:0.3f}" + f" | lsp: {lsp_dist:0.3f}" + f" | gcn_lsp: {gcn_lsp_dist:0.3f}\n") + + if gcn_lsp_planner.observed_map is None: + # learned_planner.observed_map = -1 * np.ones_like(known_map) + # base_planner.observed_map = -1 * np.ones_like(known_map) + # naive_observed_map = -1 * np.ones_like(known_map) + lsp_planner.observed_map = -1 * np.ones_like(known_map) + gcn_lsp_planner.observed_map = -1 * np.ones_like(known_map) + + # Write final plot to file + image_file = os.path.join(args.save_dir, args.image_filename) + plt.figure(figsize=(16, 16)) + # plt.subplot(231) + # plt.imshow( + # lsp.utils.plotting.make_plotting_grid( + # learned_planner.observed_map, known_map)) + # path = learned_robot.all_poses + # xs = [p.x for p in path] + # ys = [p.y for p in path] + # plt.plot(ys, xs, 'r') + # plt.plot(path[-1].y, path[-1].x, 'go') + # plt.title(f"Cond LSP Cost: {common.compute_path_length(path):.2f}") + # plt.savefig(image_file, dpi=150) + + plt.subplot(221) + plt.imshow( + lsp.utils.plotting.make_plotting_grid( + base_planner.observed_map, known_map)) + path = base_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Known Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + plt.subplot(222) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(naive_observed_map, known_map)) + path = naive_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"Naive Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + plt.subplot(223) + plt.imshow( + lsp.utils.plotting.make_plotting_grid( + lsp_planner.observed_map, known_map)) + path = lsp_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"CNN LSP Cost: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + plt.subplot(224) + plt.imshow( + lsp.utils.plotting.make_plotting_grid( + gcn_lsp_planner.observed_map, known_map)) + path = gcn_lsp_robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(ys, xs, 'r') + plt.plot(path[-1].y, path[-1].x, 'go') + plt.title(f"GNN LSP Cost*: {common.compute_path_length(path):.2f}") + plt.savefig(image_file, dpi=150) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + args = lsp_cond.utils.parse_args() + print(f'Evaluation seed: [{args.current_seed}]') + evaluate_main(args) diff --git a/modules/lsp_gnn/scratch/test_lsp_cond_plotting.py b/modules/lsp_gnn/scratch/test_lsp_cond_plotting.py new file mode 100644 index 0000000..46b62d9 --- /dev/null +++ b/modules/lsp_gnn/scratch/test_lsp_cond_plotting.py @@ -0,0 +1,180 @@ +import matplotlib.pyplot as plt +from matplotlib import cm +from os.path import exists + +import lsp_cond +import learning + +viridis = cm.get_cmap('viridis') + + +def test_lsp_cond_inspect_graph_datum(do_debug_plot, unity_path): + ''' Visualize as a graph + ''' + pickle_path = '/data/lsp_cond/pickles/dat_1_17.pgz' + if not exists(pickle_path): + print("Pickle file path does not exist") + return True + datum = learning.data.load_compressed_pickle(pickle_path) + if do_debug_plot: + plt.ion() + plt.figure(figsize=(12, 4)) + plt.clf() + ax = plt.subplot(131) + lsp_cond.plotting.plot_semantic_grid_with_frontiers( + ax, datum['observed_map'], datum['known_map'], datum['subgoals'], + datum['semantic_grid'], datum['semantic_labels'] + ) + lsp_cond.plotting.plot_pose(ax, datum['goal'], color='green', filled=False) + + ax = plt.subplot(132) + lsp_cond.plotting.plot_grid( + ax, datum['observed_map'], datum['known_map'], None + ) + is_subgoal = datum['is_subgoal'] + prob_feasible = datum['is_feasible'] + vertex_points = datum['vertex_points'] + for vp_idx, ps in enumerate(vertex_points): + if not is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=3, markeredgecolor='r') + for vp_idx, ps in enumerate(vertex_points): + if is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + for (start, end) in datum['edge_data']: + p1 = vertex_points[start] + p2 = vertex_points[end] + x_values = [p1[0], p2[0]] + y_values = [p1[1], p2[1]] + plt.plot(x_values, y_values, 'c', linestyle="--", linewidth=0.3) + + ax = plt.subplot(133) + lsp_cond.plotting.plot_grid( + ax, datum['observed_map'], datum['known_map'], None) + for vp_idx, ps in enumerate(vertex_points): + if is_subgoal[vp_idx]: + marker = '.' + else: + marker = '+' + x, y = ps + x, y = int(x), int(y) + if datum['semantic_grid'][x][y] == datum['semantic_labels']['red']: + color = 'red' + elif datum['semantic_grid'][x][y] == datum['semantic_labels']['blue']: + color = 'blue' + else: + color = 'gray' + plt.plot(ps[0], ps[1], marker, color=color, markersize=3) + plt.show() + # image_file = '/data/lsp_conditional/inspected_datum.png' + # plt.savefig(image_file, dpi=250) + + +def get_args(): + args = lambda: None # noqa + args.base_resolution = .4 + args.inflation_radius_m = .75 + return args + + +def test_lsp_cond_subgoal_reveal(do_debug_plot, unity_path): + ''' Visualize as a graph + ''' + pickle_path = '/data/lsp_cond/pickles/dat_1_17.pgz' + if not exists(pickle_path): + print("Pickle file path does not exist") + return True + datum = learning.data.load_compressed_pickle(pickle_path) + args = get_args() + if do_debug_plot: + plt.ion() + plt.figure(figsize=(12, 4)) + plt.clf() + ax = plt.subplot(131) + ax.set_title('Underlying symantic grid') + lsp_cond.plotting.plot_semantic_grid_with_frontiers( + ax, datum['observed_map'], datum['known_map'], datum['subgoals'], + datum['semantic_grid'], datum['semantic_labels'] + ) + lsp_cond.plotting.plot_pose(ax, datum['goal'], color='green', filled=False) + + ax = plt.subplot(132) + ax.set_title('Subgoal masked view') + lsp_cond.plotting.plot_grid( + ax, datum['observed_map'], datum['known_map'], None + ) + is_subgoal = datum['is_subgoal'] + prob_feasible = datum['is_feasible'] + vertex_points = datum['vertex_points'] + for vp_idx, ps in enumerate(vertex_points): + if not is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '+', color=color, markersize=3, markeredgecolor='r') + for vp_idx, ps in enumerate(vertex_points): + if is_subgoal[vp_idx]: + color = viridis(is_subgoal[vp_idx] * prob_feasible[vp_idx]) + plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + for (start, end) in datum['edge_data']: + p1 = vertex_points[start] + p2 = vertex_points[end] + x_values = [p1[0], p2[0]] + y_values = [p1[1], p2[1]] + plt.plot(x_values, y_values, 'c', linestyle="--", linewidth=0.3) + + ax = plt.subplot(133) + ax.set_title('Subgoal revealed view') + + from common import Pose + robot_is_here = Pose(x=35, y=65) + + frontiers = [f for f in datum['subgoals']] + forntier_idx = 0 + frontier_to_reveal = frontiers.pop(forntier_idx) + + subgoal_revealed_grid, f_remove_idx = lsp_cond.utils.get_frontier_revealing_grid( + datum['observed_map'], datum['known_map'], frontier_to_reveal, frontiers + ) + + inflated_grid = lsp_cond.utils.get_inflated_occupancy_grid( + subgoal_revealed_grid, args.inflation_radius_m / args.base_resolution, robot_is_here + ) + + # Remove the frontiers that get revealed along with the revealed region + for idx in f_remove_idx[::-1]: + frontiers.pop(idx) + + uncleaned_graph = lsp_cond.utils.compute_skeleton(inflated_grid, frontiers) + vertex_points = uncleaned_graph['vertex_points'] + edge_data = uncleaned_graph['edges'] + new_node_dict = {} + + clean_data = lsp_cond.utils.prepare_input_clean_graph( + frontiers, vertex_points, edge_data, + new_node_dict, [0] * len(vertex_points), datum['semantic_grid'], + datum['wall_class'], None, robot_is_here + ) + + lsp_cond.plotting.plot_grid( + ax, subgoal_revealed_grid, datum['known_map'], None + ) + vertex_points = clean_data['vertex_points'] + edge_data = clean_data['edge_data'] + for vp_idx, ps in enumerate(vertex_points): + ps = tuple(ps) + if ps not in clean_data['subgoal_nodes']: + color = viridis(0) + plt.plot(ps[0], ps[1], '+', color=color, markersize=3, markeredgecolor='r') + for vp_idx, ps in enumerate(vertex_points): + ps = tuple(ps) + if ps in clean_data['subgoal_nodes']: + color = viridis(clean_data['subgoal_nodes'][ps].prob_feasible) + plt.plot(ps[0], ps[1], '.', color=color, markersize=4) + for (start, end) in edge_data: + p1 = vertex_points[start] + p2 = vertex_points[end] + x_values = [p1[0], p2[0]] + y_values = [p1[1], p2[1]] + plt.plot(x_values, y_values, 'c', linestyle="--", linewidth=0.3) + image_file = '/data/lsp_cond/revealed_subgoal.png' + plt.savefig(image_file, dpi=250) diff --git a/modules/lsp_gnn/scratch/utils.py b/modules/lsp_gnn/scratch/utils.py new file mode 100644 index 0000000..44bce6d --- /dev/null +++ b/modules/lsp_gnn/scratch/utils.py @@ -0,0 +1,207 @@ +def generate_all_rollout_history(history): + '''TODO - This funtion will overflow memory at some point, need to think + of an alternative + ''' + pool = [i for i, val in enumerate(history) + if val == 1] + n = history.count(1) + history_vectors = [] + for idx in range(n): + combis = itertools.combinations(pool, idx) + for a_tuple in combis: + temp = history.copy() + for val in a_tuple: + temp[val] = 0 + history_vectors.append(temp) + return history_vectors + + +def image_aligned_to_non_subgoal(image, r_pose, vertex_point): + """Permutes an image from axis-aligned to subgoal-pointing frame. + The subgoal should appear at the center of the image.""" + cols = image.shape[1] + sp = vertex_point + yaw = np.arctan2(sp[1] - r_pose.y, sp[0] - r_pose.x) - r_pose.yaw + roll_amount = int(round(-cols * yaw / (2 * math.pi))) + return np.roll(image, shift=roll_amount, axis=1) + + +def get_rel_goal_loc_vecs(pose, goal_pose, num_bearing, vertex_point=None): + # Lookup vectors + _, vec_bearing = lsp.utils.learning_vision.get_directions(num_bearing) + if vertex_point is None: + vec_bearing = vec_bearing + pose.yaw + else: + sp = vertex_point + vertex_point_yaw = np.arctan2(sp[1] - pose.y, sp[0] - pose.x) + vec_bearing = vec_bearing + vertex_point_yaw + + robot_point = np.array([pose.x, pose.y]) + goal_point = np.array([goal_pose.x, goal_pose.y]) + rel_goal_point = goal_point - robot_point + + goal_loc_x_vec = rel_goal_point[0] * np.cos( + vec_bearing) + rel_goal_point[1] * np.sin(vec_bearing) + goal_loc_y_vec = -rel_goal_point[0] * np.sin( + vec_bearing) + rel_goal_point[1] * np.cos(vec_bearing) + + return (goal_loc_x_vec[:, np.newaxis].T, goal_loc_y_vec[:, np.newaxis].T) + + +def get_path_middle_point(known_map, start, goal, args): + """This function returns the middle point on the path from goal to the + robot starting position""" + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_mask = gridmap.utils.inflate_grid(known_map, + inflation_radius=inflation_radius) + # Now sample the middle point + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + inflated_mask, [goal.x, goal.y]) + _, path = get_path([start.x, start.y], + do_sparsify=False, + do_flip=False) + row, col = path.shape + x = path[0][col // 2] + y = path[1][col // 2] + new_start_pose = common.Pose(x=x, + y=y, + yaw=2 * np.pi * np.random.rand()) + return new_start_pose + + +def get_wall_color_vector(seg_img, robot_pose=None, + vertex_point=None, cone=None): + '''This method gets the [red, blue, gray] + ''' + + # Re-orient the image based on the subgoal centroid + if robot_pose is not None and vertex_point is not None: + seg_img = image_aligned_to_non_subgoal( + seg_img, robot_pose, vertex_point) + seg_img = np.transpose(seg_img, (2, 0, 1)) + if cone == 180: + seg_img = seg_img[:, :, 128:384] + elif cone == 90: + seg_img = seg_img[:, :, 128 + 64:384 - 64] + elif cone == 45: + seg_img = seg_img[:, :, 128 + 64 + 32:384 - 64 - 32] + # plt.imshow(np.transpose(seg_img, (1, 2, 0))) + # plt.show() + blue_count = np.count_nonzero(seg_img[2] == 255) + red_count = np.count_nonzero(seg_img[0] == 255) + gray_count = np.count_nonzero(seg_img[1] == 127) + # brown_count = np.count_nonzero(seg_img[1] == 63) + # green_count = np.count_nonzero(seg_img[1] == 255) + poi_count = red_count + blue_count + gray_count + vect = [red_count / poi_count, + blue_count / poi_count, + gray_count / poi_count] + return np.array(vect) + + +def preprocess_cnn_training_data(fn, args=None): + ''' This method preprocesses the data for training base/cnn lsp + We are interested in only training the subgoal images because that is what + the actual implementation did as well + ''' + def preprocess(data): + datum = {} + features = [ + 'is_feasible', 'delta_success_cost', 'exploration_cost', + 'positive_weighting', 'negative_weighting' + ] + if fn is None: + ds_img_list = [] + for idx, raw_image in enumerate(data['image']): + if data['is_subgoal'][idx] == 1: + down_sampled_img = downsample_image( + np.transpose(raw_image, (2, 0, 1))) + # take the middle 1/8 of the image: + down_sampled_img = down_sampled_img[:, :, 56:72] + ds_img_list.append(down_sampled_img) + datum['image'] = torch.tensor( + (np.array(ds_img_list).astype(np.float32) / 255), dtype=torch.float) + else: # Do the preprocessing for running clip encoder + datum['image'] = torch.cat([ + fn(Image.fromarray(image, mode='RGB')).unsqueeze(0) + for idx, image in enumerate(data['image']) + if data['is_subgoal'][idx] == 1 + ]) + for feature in features: + datum[feature] = torch.tensor(np.array([ + feature_value + for idx, feature_value in enumerate(data[feature]) + if data['is_subgoal'][idx] == 1 + ])) + + return Data(x=datum['image'], + y=datum['is_feasible'], + dsc=datum['delta_success_cost'], + ec=datum['exploration_cost'], + pweight=datum['positive_weighting'], + nweight=datum['negative_weighting']) + + def no_ae_preprocess(data): + datum = {} + features = [ + 'is_feasible', 'delta_success_cost', 'exploration_cost', + 'positive_weighting', 'negative_weighting' + ] + datum['wall_class'] = torch.tensor( + [vector + for idx, vector in enumerate(data['wall_class']) + if data['is_subgoal'][idx] == 1], + dtype=torch.float) + for feature in features: + datum[feature] = torch.tensor(np.array([ + feature_value + for idx, feature_value in enumerate(data[feature]) + if data['is_subgoal'][idx] == 1 + ])) + + return Data(x=datum['wall_class'], + y=datum['is_feasible'], + dsc=datum['delta_success_cost'], + ec=datum['exploration_cost'], + pweight=datum['positive_weighting'], + nweight=datum['negative_weighting']) + + def seg_image_preprocess(data): + datum = {} + features = [ + 'is_feasible', 'delta_success_cost', 'exploration_cost', + 'positive_weighting', 'negative_weighting' + ] + ds_img_list = [] + + for idx, raw_image in enumerate(data['seg_image']): + if data['is_subgoal'][idx] == 1: + down_sampled_img = np.transpose( + raw_image, (2, 0, 1))[:, ::4, ::4] + # take the middle 1/8 of the image: + image = down_sampled_img[:, :, 56:72] + image = convert_seg_image_to_one_hot_coded_vector(image) + ds_img_list.append(image) + datum['image'] = torch.tensor( + (np.array(ds_img_list).astype(np.float32) / 255), dtype=torch.float) + + for feature in features: + datum[feature] = torch.tensor(np.array([ + feature_value + for idx, feature_value in enumerate(data[feature]) + if data['is_subgoal'][idx] == 1 + ])) + + return Data(x=datum['image'], + y=datum['is_feasible'], + dsc=datum['delta_success_cost'], + ec=datum['exploration_cost'], + pweight=datum['positive_weighting'], + nweight=datum['negative_weighting']) + + if args.input_type == 'image': + return preprocess + elif args.input_type == 'seg_image': + return seg_image_preprocess + elif args.input_type == 'wall_class': + return no_ae_preprocess \ No newline at end of file diff --git a/modules/lsp_gnn/setup.py b/modules/lsp_gnn/setup.py new file mode 100644 index 0000000..9924739 --- /dev/null +++ b/modules/lsp_gnn/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='lsp_gnn', + version='1.0.0', + description='Core code for Learned Subgoal Planning using GNN.', + license="MIT", + author='Raihan Islam Arnob', + author_email='rarnob@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/lsp_gnn/tests/test_j_env.py b/modules/lsp_gnn/tests/test_j_env.py new file mode 100644 index 0000000..e4cc2eb --- /dev/null +++ b/modules/lsp_gnn/tests/test_j_env.py @@ -0,0 +1,109 @@ +import environments.generate +import lsp_gnn +import matplotlib.pyplot as plt +from common import Pose +import numpy as np + + +def test_jshaped_env_occupancy_gen(do_debug_plot, unity_path): + args = lambda: None # noqa: E731 + args.current_seed = 0 + args.map_type = 'jshaped' + args.base_resolution = 0.4 + args.inflation_radius_m = 0.75 + known_map, map_data, start_pose, goal_pose = \ + lsp_gnn.environments.generate.map_and_poses(args) + + if do_debug_plot: + import shapely.geometry + + def plot_shapely_linestring(ax, ls, color=[0.25, 0.25, 1.0], alpha=1.0): + if isinstance(ls, shapely.geometry.MultiLineString): + [plot_shapely_linestring(ax, line, color, alpha) for line in ls] + return + + x, y = ls.xy + ax.plot(x, y, color=color, alpha=alpha, linewidth=0.2) + + plt.subplot(121) + plt.imshow(known_map) + plt.subplot(122) + plt.imshow(map_data['semantic_grid']) + plt.show() + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, map_data, + num_breadcrumb_elements=0, # args.num_breadcrumb_elements, + min_interlight_distance=3.0, + min_light_to_wall_distance=1.5) + builder = environments.simulated.WorldBuildingUnityBridge + + with builder(unity_path) as unity_bridge: + unity_bridge.make_world(world) + unity_bridge.move_object_to_pose("robot", args.base_resolution * start_pose) + pano_image = unity_bridge.get_image("robot/pano_camera") + if do_debug_plot: + plt.imshow(pano_image) + plt.show() + + +def test_jshaped_env_wall(do_debug_plot, unity_path): + args = lambda: None # noqa: E731 + args.current_seed = 0 + args.map_type = 'jshaped' + args.base_resolution = 0.4 + args.inflation_radius_m = 0.75 + known_map, map_data, start_pose, goal_pose = \ + lsp_gnn.environments.generate.map_and_poses(args) + + if do_debug_plot: + import shapely.geometry + + def plot_shapely_linestring(ax, ls, color=[0.25, 0.25, 1.0], alpha=1.0): + if isinstance(ls, shapely.geometry.MultiLineString): + [plot_shapely_linestring(ax, line, color, alpha) for line in ls] + return + + x, y = ls.xy + ax.plot(x, y, color=color, alpha=alpha, linewidth=0.2) + + plt.subplot(121) + plt.imshow(known_map) + plt.subplot(122) + plt.imshow(map_data['semantic_grid']) + plt.show() + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, map_data, + num_breadcrumb_elements=0, + min_interlight_distance=3.0, + min_light_to_wall_distance=1.5) + builder = environments.simulated.WorldBuildingUnityBridge + + with builder(unity_path) as unity_bridge: + unity_bridge.make_world(world) + start_pose = Pose(x=55, y=16, yaw=0) + unity_bridge.move_object_to_pose("robot", args.base_resolution * start_pose) + pano_image_0 = unity_bridge.get_image("robot/pano_camera") + pano_seg_image_0 = unity_bridge.get_image("robot/pano_segmentation_camera") + inside_j = Pose(x=15, y=54, yaw=0) + unity_bridge.move_object_to_pose("robot", args.base_resolution * inside_j) + pano_image_1 = unity_bridge.get_image("robot/pano_camera") + pano_seg_image_1 = unity_bridge.get_image("robot/pano_segmentation_camera") + if do_debug_plot: + plt.figure(figsize=(12, 8)) + plt.subplot(221) + plt.imshow(pano_image_0) + plt.title(f"start x: {start_pose.x}, y: {start_pose.y}") + plt.subplot(223) + plt.imshow(pano_seg_image_0) + plt.subplot(222) + plt.imshow(pano_image_1) + plt.subplot(224) + plt.imshow(pano_seg_image_1) + plt.show() + + assert np.std(pano_seg_image_0) > 1 # 1 is just a buffer. It mostly just needs to be nonzero + assert np.std(pano_seg_image_1) > 1 # 1 is just a buffer. It mostly just needs to be nonzero diff --git a/modules/lsp_gnn/tests/test_lsp_gnn_planners.py b/modules/lsp_gnn/tests/test_lsp_gnn_planners.py new file mode 100644 index 0000000..ed8cddd --- /dev/null +++ b/modules/lsp_gnn/tests/test_lsp_gnn_planners.py @@ -0,0 +1,551 @@ +import lsp +import lsp_gnn +import environments +import numpy as np +import pytest +import gridmap +import torch +import random +import itertools +from lsp_gnn.core import RolloutState +from lsp.core import FState +import time as time +import matplotlib.pyplot as plt +from matplotlib import cm +from os.path import exists +import learning + + +DEVICE = torch.device("cuda" if torch.cuda.is_available() else "cpu") +# DEVICE = 'cpu' +BLANK_IMAGE = np.zeros((128, 512, 3), dtype=np.uint8) +viridis = cm.get_cmap('viridis') + + +def _get_env_and_args(): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 786 + args.map_type = 'jshaped' + args.field_of_view_deg = 360 + args.base_resolution = 0.4 + args.inflation_radius_m = 0.75 + args.laser_max_range_m = 12 + args.autoencoder_network_file = \ + '/data/lsp_conditional/logs/dbg/AutoEncoder.pt' + args.network_file = '/data/lsp_conditional/logs/dbg/model.pt' + args.gcn_network_file = '/data/lsp_conditional/logs/dbg/mlsp.pt' + args.experiment_name = 'test' + args.image_file = '/data/lsp_conditional/test/img' + args.pickle_path = '/data/lsp_conditional/pickles/dat_786_0.pgz' + args.clip_file = '/data/lsp_conditional/logs/ViT-B-32.pt' + + # Create the map + known_map, map_data, pose, goal = lsp_gnn.environments.generate.map_and_poses(args) + + return known_map, map_data, pose, goal, args + + +def run_planning_loop(known_map, map_data, pose, goal, args, unity_path, + planners, num_steps=None, do_plan_with_naive=False, + do_yield_planner=False, do_plot=False): + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=0, + min_interlight_distance=3.0, + min_light_to_wall_distance=1) + + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + if not isinstance(planners, list): + planners = [planners] + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + planning_loop = lsp.planners.PlanningLoop( + goal, known_map, simulator, None, robot, args, verbose=False) + + for counter, step_data in enumerate(planning_loop): + for planner in planners: + # Update the planner objects + start_time = time.time() + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose']) + print('Time taken to update:', time.time() - start_time) + chosen_subgoal = planners[0].compute_selected_subgoal() + + if do_plot: # Controls whether to plot the planning graph + if chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planners[0].inflated_grid, planners[0].subgoals, + do_not_mask=chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planners[0].inflated_grid, + [], + ) + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning. \ + compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + + # Plotting + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_gnn.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_gnn.plotting.plot_grid_with_frontiers( + ax, step_data['robot_grid'], + known_map, step_data['subgoals']) + lsp_gnn.plotting.plot_pose(ax, goal, + color='green', filled=False) + lsp_gnn.plotting.plot_path(ax, path) + lsp_gnn.plotting.plot_pose_path(ax, robot.all_poses) + + image_file = args.image_file + str(counter) + '.png' + plt.savefig(image_file, dpi=150) + + if do_yield_planner: + if len(planners) == 1: + yield planners[0] + else: + yield planners + + if planners is not None and not do_plan_with_naive: + planning_loop.set_chosen_subgoal(chosen_subgoal) + + if num_steps is not None and counter >= num_steps: + break + + +def test_lsp_gnn_output(): + torch.manual_seed(8616) + known_map, map_data, pose, goal, args = _get_env_and_args() + if not exists(args.autoencoder_network_file): + pytest.xfail("autoencoder_network_file does not exist") + device = DEVICE + latent_features_net = lsp_gnn.learning.models.auto_encoder.AutoEncoder. \ + get_net_eval_fn(args.autoencoder_network_file, device=device, + preprocess_for='Cond_Eval') + model = lsp_gnn.learning.models.gcn.LSPConditionalGNN() + model.load_state_dict(torch.load(args.network_file, + map_location=DEVICE)) + model.eval() + model.to(device) + + datum = learning.data.load_compressed_pickle(args.pickle_path) + datum['latent_features'] = latent_features_net(datum=datum) + datum['history'] = lsp_gnn.utils.generate_random_history_combination( + history=datum['history'], + node_labels=datum['label'] + ) + + # Some preprocessing + temp = [[x[0], x[1]] for x in datum['edge_data']] + datum['edge_data'] = torch.tensor(list(zip(*temp)), dtype=torch.long) + datum['history'] = torch.tensor(datum['history'], dtype=torch.long) + datum['is_subgoal'] = torch.tensor(datum['is_subgoal'], dtype=torch.long) + with torch.no_grad(): + out = model.forward(datum, device) + out[:, 0] = torch.sigmoid(out[:, 0]) + out = out.detach().cpu().numpy() + # print(out) + for idx, row in enumerate(out): + if datum["is_subgoal"][idx]: + print(f'Subgoal-history[{datum["history"][idx]}] ' + f'P[R]={datum["label"][idx]} P[P]={row[0]:.5f} ' + f'Rs[R]={datum["delta_success_cost"][idx]:.5f} ' + 'Rs[P]={row[1]:.5f} ' + f'Re[R]={datum["exploration_cost"][idx]:.5f} ' + 'Re[P]={row[2]:.5f}') + + +def test_lsp_gnn_cnn_output_test(): + torch.manual_seed(8616) + np.random.seed(8616) + known_map, map_data, pose, goal, args = _get_env_and_args() + if not exists(args.autoencoder_network_file): + pytest.xfail("autoencoder_network_file does not exist") + device = DEVICE + model = lsp_gnn.learning.models.auto_encoder.AutoEncoder() + model.load_state_dict(torch.load(args.autoencoder_network_file, + map_location=DEVICE)) + model.eval() + model.to(device) + + image = [] + goal_loc_x = [] + goal_loc_y = [] + subgoal_loc_x = [] + subgoal_loc_y = [] + + for _ in range(2): + RANDOM_IMAGE = np.random.rand(128, 512, 3) * 255 + image.append(RANDOM_IMAGE) + + for _ in range(2): + BLANK_IMAGE = np.zeros((128, 512, 3)) + image.append(BLANK_IMAGE) + + num_of_nodes = 4 + goal_loc_x = np.random.rand(num_of_nodes, 1, 128) + goal_loc_x[2:] = 0 + goal_loc_y = np.random.rand(num_of_nodes, 1, 128) + goal_loc_y[2:] = 0 + subgoal_loc_x = np.random.rand(num_of_nodes, 1, 128) + subgoal_loc_x[2:] = 0 + subgoal_loc_y = np.random.rand(num_of_nodes, 1, 128) + subgoal_loc_y[2:] = 0 + + datum = { + 'image': image, + 'goal_loc_x': goal_loc_x, + 'goal_loc_y': goal_loc_y, + 'subgoal_loc_x': subgoal_loc_x, + 'subgoal_loc_y': subgoal_loc_y, + } + data = lsp_gnn.utils.preprocess_cnn_data(datum) + + with torch.no_grad(): + latent_features = model.encoder(data, device).detach().cpu().numpy() + np.testing.assert_equal( + np.any(np.not_equal( + latent_features[0], latent_features[1])), True) + np.testing.assert_allclose( + latent_features[2], latent_features[3], rtol=1e-06) + np.testing.assert_equal( + np.any(np.not_equal( + latent_features[0], latent_features[2])), True) + + +def test_lsp_gnn_plan_loop_unknown(do_debug_plot, unity_path): + """Confirm that planning with "no subgoals" does not crash.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + if not exists(args.autoencoder_network_file): + pytest.xfail("autoencoder_network_file does not exist") + planner = lsp_gnn.planners.ConditionalUnknownSubgoalPlanner(goal=goal, + args=args, + device=DEVICE) + planner.verbose = True + for planner in run_planning_loop( + known_map, map_data, pose, goal, args, + unity_path, planner, num_steps=10, + do_plan_with_naive=False, do_plot=False): + pass + + +def test_lsp_gnn_plan_loop_known(do_debug_plot, unity_path): + """Confirm that planning with "no subgoals" does not crash.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + planner = lsp_gnn.planners.ConditionalKnownSubgoalPlanner( + goal=goal, args=args, known_map=known_map, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + for planner in run_planning_loop( + known_map, map_data, pose, goal, args, unity_path, + planner, num_steps=20, do_plan_with_naive=True, + do_plot=False): + pass + + +def test_lsp_gnn_all_node_inputs(do_debug_plot, unity_path): + """ Tests observations for each node + """ + known_map, map_data, pose, goal, args = _get_env_and_args() + if not exists(args.autoencoder_network_file): + pytest.xfail("autoencoder_network_file does not exist") + planner = lsp_gnn.planners.ConditionalUnknownSubgoalPlanner( + goal=goal, + args=args, + device=DEVICE + ) + last_dict_keys = [] + for planner in run_planning_loop( + known_map, map_data, pose, goal, args, unity_path, planner, + num_steps=5, do_plan_with_naive=False, do_yield_planner=True): + assert planner.cnn_input['image'] + assert planner.gcn_graph_input['is_subgoal'] + + total_pixel_values = [ + data['image'].sum() + for data in planner.new_node_dict.values() + ] + + new_dict_keys = list(planner.new_node_dict.keys()) + vp = [tuple(vertex_point) for vertex_point in planner.vertex_points] + # Check if the nn input dictionary has entry for every vertex point + assert new_dict_keys == vp + + # If any new_dict_key is not in last_dict_keys then all the vertices + # are new and this is the first step so all images should be the + # same otherwise if new_dict_keys is not the same as old_dict_keys + # then there must be new vertices with new observations + if last_dict_keys == []: + assert np.std(total_pixel_values) == pytest.approx(0) + elif new_dict_keys != last_dict_keys: + assert np.std(total_pixel_values) > 0 + elif new_dict_keys == last_dict_keys: # Unnecessary + print("same!") + last_dict_keys = list(planner.new_node_dict.keys()) + + +def test_lsp_gnn_ensure_node_for_each_subgoal(do_debug_plot, unity_path): + """ Test to ensure that each and every subgoal node gets associated with + only distinct vertex point + """ + known_map, map_data, pose, goal, args = _get_env_and_args() + if not exists(args.autoencoder_network_file): + pytest.xfail("autoencoder_network_file does not exist") + planner = lsp_gnn.planners.ConditionalUnknownSubgoalPlanner( + goal=goal, + args=args, + device=DEVICE + ) + for planner in run_planning_loop( + known_map, map_data, pose, goal, args, unity_path, planner, + num_steps=50, do_plan_with_naive=False, do_yield_planner=True, + do_plot=False): + assert len(planner.subgoals) == len(planner.subgoal_nodes.keys()) + + +def test_lsp_gnn_plan_loop_datum_correct_properties(do_debug_plot, + unity_path): + """Show that we can get datum for the new subgoals.""" + known_map, map_data, pose, goal, args = _get_env_and_args() + planner = lsp_gnn.planners. \ + ConditionalKnownSubgoalPlanner( + goal=goal, args=args, known_map=known_map, + semantic_grid=map_data['semantic_grid'], + wall_class=map_data['wall_class']) + for planner in run_planning_loop(known_map, map_data, pose, goal, args, + unity_path, planner, num_steps=10, + do_plan_with_naive=True, + do_yield_planner=True): + training_data = planner.compute_training_data() + expected_keys = [ + 'wall_class', 'goal_distance', 'is_subgoal', 'history', 'edge_data', + 'has_updated', 'is_feasible', 'delta_success_cost', 'exploration_cost', + 'positive_weighting', 'negative_weighting', 'known_map', 'observed_map', + 'subgoals', 'vertex_points', 'goal', 'semantic_grid', 'semantic_labels'] + training_data_keys = list(training_data.keys()) + for key in expected_keys: + assert key in training_data_keys + + +def _get_fake_data_old_format(num_subgoals): + """Generate fake subgoal data in the old LSP format.""" + random.seed(8616) + + cost_exp = 100 + cost_ds = 30 + dist_goal = 200 + dist_robot = 20 + dist_frontier = 50 + + # Make a bunch of random data + subgoals = [ + lsp.core.Frontier(np.array([[ii, ii]]).T) for ii in range(num_subgoals) + ] + [ + s.set_props(prob_feasible=random.random(), + delta_success_cost=cost_exp * random.random(), + exploration_cost=cost_ds * random.random()) + for s in subgoals + ] + + goal_distances = {s: dist_goal * random.random() for s in subgoals} + robot_distances = {s: dist_robot * random.random() for s in subgoals} + frontier_distances = { + frozenset(pair): dist_frontier * random.random() + for pair in itertools.combinations(subgoals, 2) + } + + distances = { + 'goal': goal_distances, + 'robot': robot_distances, + 'frontier': frontier_distances + } + + return {'distances': distances, + 'subgoals': subgoals} + + +def convert_old_data_to_marginal_data(subgoals, old_distances, + make_conditional=False): + # Split into two functions to convert the subgoal data and + # the distanes data for the new API + random.seed(8616) + marginal_subgoal_props = np.array([[subgoal.prob_feasible, + subgoal.delta_success_cost, + subgoal.exploration_cost] # Nx3 + for subgoal in subgoals]) + is_subgoal = [1] * len(subgoals) + rollout_histories = lsp_gnn.utils. \ + generate_all_rollout_history(is_subgoal) + + if make_conditional: + new_data = { + tuple(history): np.copy(marginal_subgoal_props) * random.random() + for history in rollout_histories} + else: + new_data = {tuple(history): np.copy(marginal_subgoal_props) + for history in rollout_histories} + subgoal_ind_dict = {subgoal: ii for ii, subgoal in enumerate(subgoals)} + + new_distances = {} + new_distances['goal'] = { + subgoal_ind_dict[subgoal]: goal_dist + for subgoal, goal_dist in old_distances['goal'].items() + } + new_distances['robot'] = { + subgoal_ind_dict[subgoal]: robot_dist + for subgoal, robot_dist in old_distances['robot'].items() + } + new_distances['frontier'] = { + frozenset([subgoal_ind_dict[s] for s in old_key]): subgoal_dist + for old_key, subgoal_dist in old_distances['frontier'].items()} + return new_data, new_distances + + +@pytest.mark.parametrize("subgoal_ordering", + ([1, 2, 0], [2, 3, 1, 0], [0, 1, 2, 3, 4, 5])) +def test_lsp_cond_marginal_match_history_conditioned_cost_given_subgoal_order( + subgoal_ordering +): + """Confirm that we can get a dictionary with the history-conditioned + properties and run some key functions without them crashing.""" + # Get some fake data (assert properties about it) + number_of_subgoals = len(subgoal_ordering) + old_data_dict = _get_fake_data_old_format(number_of_subgoals) + state = None + for subgoal in subgoal_ordering: + state = FState( + old_data_dict['subgoals'][subgoal], + old_data_dict['distances'], + old_state=state + ) + + # use a function to convert the old data format to new format + new_data, new_distances = convert_old_data_to_marginal_data( + subgoals=old_data_dict['subgoals'], + old_distances=old_data_dict['distances'] + ) + + rollout_state = None # Set the initial state to be None + for subgoal_idx in subgoal_ordering: + rollout_state = RolloutState( + new_data, + new_distances, + subgoal_idx, + old_data_dict['subgoals'], + old_state=rollout_state + ) + print(f"Rollout state cost: {rollout_state.cost}") + print(f"State cost: {state.cost}") + assert rollout_state.cost == pytest.approx(state.cost) + + +def test_lsp_cond_changing_props_cost(): + subgoal_ordering = [0, 1, 2] + number_of_subgoals = len(subgoal_ordering) + old_data_dict = _get_fake_data_old_format(number_of_subgoals) + new_data, new_distances = convert_old_data_to_marginal_data( + subgoals=old_data_dict['subgoals'], + old_distances=old_data_dict['distances'] + ) + new_data[(1, 1, 1)][0] = [.4, 3, 1] + new_data[(0, 1, 1)][1] = [.5, 5, 1] + new_data[(0, 0, 1)][2] = [.6, 4, 2] + + rollout_state = None # Set the initial state to be None + for subgoal_idx in subgoal_ordering: + rollout_state = RolloutState( + new_data, + new_distances, + subgoal_idx, + old_data_dict['subgoals'], + old_state=rollout_state + ) + assert 75.415055504 == pytest.approx(rollout_state.cost) + assert .12 == pytest.approx(rollout_state.prob) + + +def test_lsp_cond_ordering_output_slow_and_moderately_fast(): + """ This "slow version" gives you the min ordering that you'll be comparing + against. Your "faster version" should give you the same result. + """ + number_of_subgoals = 4 + old_data_dict = _get_fake_data_old_format(number_of_subgoals) + new_data, new_distances = convert_old_data_to_marginal_data( + subgoals=old_data_dict['subgoals'], + old_distances=old_data_dict['distances'], + make_conditional=True + ) + start_time = time.time() + ordering_cost_dict = {} + subgoals = np.arange(number_of_subgoals) + for subgoal_ordering in itertools.permutations(subgoals): + rollout_state = None # Set the initial state to be None + for subgoal_idx in subgoal_ordering: + rollout_state = RolloutState( + subgoal_props=new_data, + distances=new_distances, + frontier_idx=subgoal_idx, + subgoals=old_data_dict['subgoals'], + old_state=rollout_state) + ordering_cost_dict[subgoal_ordering] = rollout_state.cost + + slow_min_ordering = min(ordering_cost_dict, key=ordering_cost_dict.get) + slow_min_cost = ordering_cost_dict[slow_min_ordering] + print('Slow method timing:', time.time() - start_time) + start_time = time.time() + fast_min_cost, fast_min_ordering = lsp_gnn.core.get_lowest_cost_ordering( + new_data, + new_distances, + old_data_dict['subgoals'] + ) + print('Faster method timing:', time.time() - start_time) + assert fast_min_cost == pytest.approx(slow_min_cost) + assert fast_min_ordering == pytest.approx(slow_min_ordering) + + +def test_lsp_cond_rollout_cost(): + subgoal_ordering = [0, 1, 2] + number_of_subgoals = len(subgoal_ordering) + old_data_dict = _get_fake_data_old_format(number_of_subgoals) + new_data, new_distances = convert_old_data_to_marginal_data( + subgoals=old_data_dict['subgoals'], + old_distances=old_data_dict['distances'], + make_conditional=True + ) + rollout_state = None # Set the initial state to be None + for subgoal_idx in subgoal_ordering: + rollout_state = RolloutState( + new_data, + new_distances, + subgoal_idx, + old_data_dict['subgoals'], + old_state=rollout_state + ) + print(rollout_state.cost, rollout_state.history, + rollout_state.frontier_list) + assert 182.09783746619829 == pytest.approx(rollout_state.cost) + assert 0.09042769080722117 == pytest.approx(rollout_state.prob) diff --git a/modules/lsp_gnn/tests/test_parallel_env.py b/modules/lsp_gnn/tests/test_parallel_env.py new file mode 100644 index 0000000..efd82da --- /dev/null +++ b/modules/lsp_gnn/tests/test_parallel_env.py @@ -0,0 +1,85 @@ +import numpy as np +import matplotlib.pyplot as plt + +import lsp_gnn +import environments + + +def get_args(): + args = lambda: None # noqa + args.current_seed = 0 + args.map_type = 'new_office' + args.base_resolution = .4 + args.inflation_radius_m = .75 + return args + + +def test_parallel_hallway_sim(do_debug_plot, unity_path): + ''' Tests if parallel office is correctly generating the map. + Also checks if the simulator is generating the images/seg-images + from different poses. + ''' + args = get_args() + known_map, map_data, pose, goal = \ + lsp_gnn.environments.generate.map_and_poses(args) + + occupancy_grid = map_data['occ_grid'].copy() + occupancy_grid[int(pose.x)][int(pose.y)] = 3 + occupancy_grid[int(goal.x)][int(goal.y)] = 4 + if do_debug_plot: + plt.subplot(121) + plt.imshow(occupancy_grid) + plt.subplot(122) + plt.imshow(map_data['semantic_grid']) + plt.show() + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + map_data['occ_grid'], map_data, + num_breadcrumb_elements=0, + min_interlight_distance=3.0, + min_light_to_wall_distance=1.5) + builder = environments.simulated.WorldBuildingUnityBridge + + with builder(unity_path) as unity_bridge: + unity_bridge.make_world(world) + unity_bridge.move_object_to_pose("robot", args.base_resolution * pose) + pano_image = unity_bridge.get_image("robot/pano_camera") + unity_bridge.move_object_to_pose("robot", args.base_resolution * goal) + pano_image_1 = unity_bridge.get_image("robot/pano_camera") + if do_debug_plot: + plt.figure(figsize=(16, 8)) + plt.subplot(211) + plt.imshow(pano_image_1) + plt.subplot(212) + plt.imshow(pano_image) + plt.show() + assert np.std(pano_image) > 1 # 1 is just a buffer. It mostly just needs to be nonzero + assert np.std(pano_image_1) > 1 # 1 is just a buffer. It mostly just needs to be nonzero + + +def test_parallel_hallway_semantic(do_debug_plot, unity_path): + '''Tests if parallel office is correctly generating the map.''' + args = get_args() + known_map, map_data, pose, goal = \ + lsp_gnn.environments.generate.map_and_poses(args) + + if do_debug_plot: + occupancy_grid = map_data['occ_grid'].copy() + occupancy_grid[int(pose.x)][int(pose.y)] = 3 + occupancy_grid[int(goal.x)][int(goal.y)] = 4 + plt.subplot(121) + plt.imshow(occupancy_grid) + plt.subplot(122) + plt.imshow(map_data['semantic_grid']) + plt.show() + + +def test_parallel_hallway_count(do_debug_plot, unity_path): + '''Tests if the map generator is creating required number of hallways''' + args = get_args() + for seed in range(100, 101): + args.current_seed = seed + known_map, map_data, pose, goal = \ + lsp_gnn.environments.generate.map_and_poses(args) + assert map_data['hallways_count'] == lsp_gnn.environments.parallel_hallway.NUM_OF_HALLWAYS diff --git a/modules/lsp_select/Makefile.mk b/modules/lsp_select/Makefile.mk new file mode 100644 index 0000000..e3518fc --- /dev/null +++ b/modules/lsp_select/Makefile.mk @@ -0,0 +1,226 @@ + +help:: + @echo "Policy Selection Experiments:" + @echo " lsp-policy-selection-maze Runs the policy selection maze experiments." + @echo " lsp-policy-selection-office Runs the policy selection office experiments." + @echo " lsp-policy-selection-check Runs minimal policy selection maze experiments to verify everything works." + @echo "" + +LSP_SELECT_ENVIRONMENT_NAME ?= mazeA +LSP_SELECT_BASENAME ?= lsp_select +LSP_SELECT_UNITY_BASENAME ?= $(RAIL_SIM_BASENAME) +LSP_SELECT_MAP_TYPE ?= maze + +LSP_SELECT_NUM_TRAINING_SEEDS ?= 500 +LSP_SELECT_NUM_TESTING_SEEDS ?= 100 +LSP_SELECT_CORE_ARGS ?= --unity_path /unity/$(LSP_SELECT_UNITY_BASENAME).x86_64 \ + --map_type $(LSP_SELECT_MAP_TYPE) \ + --inflation_radius_m 0.75 + +# Data Generation and Training +lsp-select-gen-data-seeds = \ + $(shell for ii in $$(seq 0 $$((0 + $(LSP_SELECT_NUM_TRAINING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME)/data_collect_plots/$(LSP_SELECT_ENVIRONMENT_NAME)_training_$${ii}.png"; done) \ + $(shell for ii in $$(seq 500 $$((500 + $(LSP_SELECT_NUM_TESTING_SEEDS) - 1))); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME)/data_collect_plots/$(LSP_SELECT_ENVIRONMENT_NAME)_testing_$${ii}.png"; done) + +lsp-select-gen-data: $(lsp-select-gen-data-seeds) +$(lsp-select-gen-data-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-select-gen-data-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-select-gen-data-seeds): + $(call xhost_activate) + @echo "Generating Data [$(LSP_SELECT_BASENAME) | $(LSP_SELECT_ENVIRONMENT_NAME) | seed: $(seed) | $(traintest)]" + @-rm -f $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME)_$(traintest)_$(seed).csv + @-mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME) + @-mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME)/data + @-mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME)/data_collect_plots + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_vis_gen_data \ + $(LSP_SELECT_CORE_ARGS) \ + --current_seed $(seed) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME) \ + --data_file_base_name $(LSP_SELECT_ENVIRONMENT_NAME)_$(traintest) + +lsp-select-train-file = $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_logs/$(LSP_SELECT_ENVIRONMENT_NAME)/VisLSPOriented.pt +lsp-select-train: $(lsp-select-train-file) +$(lsp-select-train-file): $(lsp-select-gen-data-seeds) +$(lsp-select-train-file): + @echo "Training [$(LSP_SELECT_BASENAME) | $(LSP_SELECT_ENVIRONMENT_NAME)]" + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_logs/$(LSP_SELECT_ENVIRONMENT_NAME) + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_train_net \ + --save_dir /data/$(LSP_SELECT_BASENAME)/training_logs/$(LSP_SELECT_ENVIRONMENT_NAME) \ + --data_csv_dir /data/$(LSP_SELECT_BASENAME)/training_data/$(LSP_SELECT_ENVIRONMENT_NAME) + +GREENFLOOR_SIM_ID ?= greenfloor +WALLSWAP_SIM_ID ?= wallswap + +LSP_SELECT_MAZE_A_ARGS ?= LSP_SELECT_ENVIRONMENT_NAME=mazeA LSP_SELECT_MAP_TYPE=maze +LSP_SELECT_MAZE_B_ARGS ?= LSP_SELECT_ENVIRONMENT_NAME=mazeB LSP_SELECT_MAP_TYPE=maze LSP_SELECT_UNITY_BASENAME=$(RAIL_SIM_BASENAME)_$(GREENFLOOR_SIM_ID) +LSP_SELECT_MAZE_C_ARGS ?= LSP_SELECT_ENVIRONMENT_NAME=mazeC LSP_SELECT_MAP_TYPE=maze + +LSP_SELECT_OFFICE_BASE_ARGS ?= LSP_SELECT_ENVIRONMENT_NAME=office LSP_SELECT_MAP_TYPE=office2 +LSP_SELECT_OFFICE_WALLSWAP_ARGS ?= LSP_SELECT_ENVIRONMENT_NAME=officewall LSP_SELECT_MAP_TYPE=office2 LSP_SELECT_UNITY_BASENAME=$(RAIL_SIM_BASENAME)_$(WALLSWAP_SIM_ID) + + +unity-simulator-additional-files = \ + $(RAIL_SIM_DIR)/v$(RAIL_SIM_VERSION)/$(RAIL_SIM_BASENAME)_$(GREENFLOOR_SIM_ID).x86_64 \ + $(RAIL_SIM_DIR)/v$(RAIL_SIM_VERSION)/$(RAIL_SIM_BASENAME)_$(WALLSWAP_SIM_ID).x86_64 + +.PHONY: unity-simulator-additional-data +unity-simulator-additional-data: $(unity-simulator-additional-files) +$(unity-simulator-additional-files): sim_identifier = $(shell echo $@ | grep -oP '(?<=_)[A-Za-z]+(?=\.x86_64)') +$(unity-simulator-additional-files): + @echo "Downloading the Unity simulator data for $(sim_identifier)" + cd $(RAIL_SIM_DIR)/v$(RAIL_SIM_VERSION) \ + && curl -OL https://github.com/RAIL-group/RAIL-group-simulator/releases/download/v$(RAIL_SIM_VERSION)/data_$(sim_identifier).zip \ + && unzip data_$(sim_identifier).zip \ + && rm data_$(sim_identifier).zip + @echo "Unity simulator data for $(sim_identifier) downloaded and unpacked." + + +## Maze +.PHONY: lsp-select-gen-data-mazeA lsp-select-gen-data-mazeB lsp-select-gen-data-mazeC +lsp-select-gen-data-mazeA: + @$(MAKE) lsp-select-gen-data $(LSP_SELECT_MAZE_A_ARGS) +lsp-select-gen-data-mazeB: unity-simulator-additional-data +lsp-select-gen-data-mazeB: + @$(MAKE) lsp-select-gen-data $(LSP_SELECT_MAZE_B_ARGS) +lsp-select-gen-data-mazeC: + @$(MAKE) lsp-select-gen-data $(LSP_SELECT_MAZE_C_ARGS) + +.PHONY: lsp-select-train-mazeA lsp-select-train-mazeB lsp-select-train-mazeC +lsp-select-train-mazeA: lsp-select-gen-data-mazeA +lsp-select-train-mazeA: + @$(MAKE) lsp-select-train $(LSP_SELECT_MAZE_A_ARGS) +lsp-select-train-mazeB: lsp-select-gen-data-mazeB +lsp-select-train-mazeB: + @$(MAKE) lsp-select-train $(LSP_SELECT_MAZE_B_ARGS) +lsp-select-train-mazeC: lsp-select-gen-data-mazeB +lsp-select-train-mazeC: + @$(MAKE) lsp-select-train $(LSP_SELECT_MAZE_C_ARGS) + +## Office +.PHONY: lsp-select-gen-data-officebase lsp-select-gen-data-officewall +lsp-select-gen-data-officebase: + @$(MAKE) lsp-select-gen-data $(LSP_SELECT_OFFICE_BASE_ARGS) +lsp-select-gen-data-officewall: unity-simulator-additional-data +lsp-select-gen-data-officewall: + @$(MAKE) lsp-select-gen-data $(LSP_SELECT_OFFICE_WALLSWAP_ARGS) + +.PHONY: lsp-select-train-officebase lsp-select-train-officewall +lsp-select-train-officebase: lsp-select-gen-data-officebase +lsp-select-train-officebase: + @$(MAKE) lsp-select-train $(LSP_SELECT_OFFICE_BASE_ARGS) +lsp-select-train-officewall: lsp-select-gen-data-officewall +lsp-select-train-officewall: + @$(MAKE) lsp-select-train $(LSP_SELECT_OFFICE_WALLSWAP_ARGS) + + +# Policy Selection +LSP_SELECT_NUM_SEEDS_DEPLOY ?= 150 + +MAZE_POLICIES ?= "nonlearned lspA lspB lspC" +MAZE_ENVS ?= "envA envB envC" + +OFFICE_POLICIES ?= "nonlearned lspmaze lspoffice lspofficewallswap" +OFFICE_ENVS ?= "mazeA office officewall" + +# Note: *_start seed variable names are used in get_seed function +envA_start_seed ?= 2000 +envB_start_seed ?= 3000 +envC_start_seed ?= 4000 +maze_costs_save_dir ?= policy_selection/maze_costs + +mazeA_start_seed ?= 2000 +office_start_seed ?= 3000 +officewall_start_seed ?= 4000 +office_costs_save_dir ?= policy_selection/office_costs + +define get_seeds + $(eval start := $(1)_start_seed) + $(shell seq $(value $(start)) $$(($(value $(start))+$(2)-1))) +endef + +offline-replay-seeds = $(foreach policy,$(POLICIES_TO_RUN), \ + $(foreach env,$(ENVS_TO_DEPLOY), \ + $(foreach seed,$(call get_seeds, $(env), $(LSP_SELECT_NUM_SEEDS_DEPLOY)), \ + $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(replay_costs_save_dir)/target_plcy_$(policy)_envrnmnt_$(env)_$(seed).txt))) + +lsp-select-offline-replay-costs: $(offline-replay-seeds) +$(offline-replay-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(offline-replay-seeds): policy = $(shell echo $@ | grep -oE 'plcy_[Aa-Zz]+' | cut -d'_' -f2) +$(offline-replay-seeds): env = $(shell echo $@ | grep -oE 'envrnmnt_[Aa-Zz]+' | cut -d'_' -f2) +$(offline-replay-seeds): sim_name = $(if $(filter $(env),envB),_$(GREENFLOOR_SIM_ID),$(if $(filter $(env),officewall),_$(WALLSWAP_SIM_ID))) +$(offline-replay-seeds): LSP_SELECT_MAP_TYPE = $(if $(or $(filter $(env),office),$(filter $(env),officewall)),office2,maze) +$(offline-replay-seeds): LSP_SELECT_UNITY_BASENAME = $(RAIL_SIM_BASENAME)$(sim_name) +$(offline-replay-seeds): + $(call xhost_activate) + @echo "Deploying with Offline Replay [$(policy) | $(env) | seed: $(seed)]" + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(replay_costs_save_dir) + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_offline_replay_costs \ + $(LSP_SELECT_CORE_ARGS) \ + --experiment_type $(EXPERIMENT_TYPE) \ + --seed $(seed) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/$(replay_costs_save_dir) \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --chosen_planner $(policy) \ + --env $(env) + +.PHONY: lsp-select-offline-replay-costs-maze +lsp-select-offline-replay-costs-maze: lsp-select-train-mazeA lsp-select-train-mazeB lsp-select-train-mazeC +lsp-select-offline-replay-costs-maze: + @$(MAKE) lsp-select-offline-replay-costs \ + EXPERIMENT_TYPE=maze \ + POLICIES_TO_RUN=$(MAZE_POLICIES) \ + ENVS_TO_DEPLOY=$(MAZE_ENVS) \ + replay_costs_save_dir=$(maze_costs_save_dir) + +.PHONY: lsp-select-offline-replay-costs-office +lsp-select-offline-replay-costs-office: lsp-select-train-mazeA lsp-select-train-officebase lsp-select-train-officewall +lsp-select-offline-replay-costs-office: + @$(MAKE) lsp-select-offline-replay-costs \ + EXPERIMENT_TYPE=office \ + POLICIES_TO_RUN=$(OFFICE_POLICIES) \ + ENVS_TO_DEPLOY=$(OFFICE_ENVS) \ + replay_costs_save_dir=$(office_costs_save_dir) + +.PHONY: lsp-policy-selection-maze lsp-policy-selection-office +lsp-policy-selection-maze: lsp-select-offline-replay-costs-maze +lsp-policy-selection-maze: DOCKER_ARGS ?= -it +lsp-policy-selection-maze: xhost-activate +lsp-policy-selection-maze: + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_policy_selection_results \ + --save_dir /data/$(LSP_SELECT_BASENAME)/$(maze_costs_save_dir) \ + --experiment_type maze \ + --start_seeds $(envA_start_seed) $(envB_start_seed) $(envC_start_seed) \ + --num_seeds $(LSP_SELECT_NUM_SEEDS_DEPLOY) + +lsp-policy-selection-office: lsp-select-offline-replay-costs-office +lsp-policy-selection-office: DOCKER_ARGS ?= -it +lsp-policy-selection-office: xhost-activate +lsp-policy-selection-office: + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_policy_selection_results \ + --save_dir /data/$(LSP_SELECT_BASENAME)/$(office_costs_save_dir) \ + --experiment_type office + --start_seeds $(mazeA_start_seed) $(office_start_seed) $(officewall_start_seed) \ + --num_seeds $(LSP_SELECT_NUM_SEEDS_DEPLOY) + +.PHONY: offline-replay-demo +offline-replay-demo: DOCKER_ARGS ?= -it +offline-replay-demo: xhost-activate + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/offline-replay-demo + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_offline_replay_demo \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 3087 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/offline-replay-demo \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --chosen_planner lspoffice \ + --env office \ + --do_plot + +.PHONY: lsp-policy-selection-check +lsp-policy-selection-check: + @$(MAKE) lsp-policy-selection-maze \ + LSP_SELECT_NUM_TRAINING_SEEDS=1 \ + LSP_SELECT_NUM_TESTING_SEEDS=1 \ + LSP_SELECT_BASENAME=lsp_select_check \ + LSP_SELECT_NUM_SEEDS_DEPLOY=2 diff --git a/modules/lsp_select/README.md b/modules/lsp_select/README.md new file mode 100644 index 0000000..b5c4c3c --- /dev/null +++ b/modules/lsp_select/README.md @@ -0,0 +1,28 @@ +# Policy Selection for Learning over Subgoals Planning + +This module provides the implementation of all experiments in the paper: + +Abhishek Paudel and Gregory J. Stein. "Data-Efficient Policy Selection for Navigation in Partial Maps via Subgoal-Based Abstraction." International Conference on Intelligent Robots and Systems (IROS). 2023. [paper](https://arxiv.org/abs/2304.01094) + +```bibtex +@inproceedings{paudel2023lspselect, + title={Data-Efficient Policy Selection for Navigation in Partial Maps via Subgoal-Based Abstraction}, + author={Paudel, Abhishek and Stein, Gregory J.}, + booktitle={International Conference on Intelligent Robots and Systems (IROS)}, + year={2023} +} +``` + +## Usage +### Reproducing Results +Note: `make build` (see top-level README) must be successfully run before running the following commands. + +The `Makefile.mk` provides multiple targets for reproducing the results. + +- `make lsp-policy-selection-maze` generates results for simulated maze environments. It first generates all the training data in different variations of maze environments (see paper for details), trains a neural network in each of these environments, and deploys LSP policies using the trained neural networks (as well as a non-learned policy) in all of the maze environments. Finally, it runs our policy selection algorithm to reproduce the results shown in the paper. + +- `make lsp-policy-selection-office` generates the results corresponding to office experiments described in the paper. The process is similar to above. + +- `make lsp-policy-selection-check` runs very minimal policy selection experiments for maze environments (with only few maps) to verify that everything works as intended. + +All targets run in single-threaded mode by default, however data generation and offline-replay costs generation can be run on multiple seeds in parallel. For example `make lsp-select-gen-data-mazeA -j3` will run three concurrent instances of data generation in `mazeA` and `make lsp-select-offline-replay-costs-maze -j3` will run three concurrent deployment experiments in maze environments. diff --git a/modules/lsp_select/lsp_select/__init__.py b/modules/lsp_select/lsp_select/__init__.py new file mode 100644 index 0000000..0b459d0 --- /dev/null +++ b/modules/lsp_select/lsp_select/__init__.py @@ -0,0 +1,5 @@ +from . import scripts # noqa: F401 +from . import planners # noqa: F401 +from . import learning # noqa: F401 +from . import utils # noqa: F401 +from . import offline_replay # noqa diff --git a/modules/lsp_select/lsp_select/learning/__init__.py b/modules/lsp_select/lsp_select/learning/__init__.py new file mode 100644 index 0000000..fe15518 --- /dev/null +++ b/modules/lsp_select/lsp_select/learning/__init__.py @@ -0,0 +1 @@ +from . import models # noqa diff --git a/modules/lsp_select/lsp_select/learning/models/__init__.py b/modules/lsp_select/lsp_select/learning/models/__init__.py new file mode 100644 index 0000000..1700d1d --- /dev/null +++ b/modules/lsp_select/lsp_select/learning/models/__init__.py @@ -0,0 +1 @@ +from .cyclegan import ResnetGenerator # noqa: F401 diff --git a/modules/lsp_select/lsp_select/learning/models/cyclegan.py b/modules/lsp_select/lsp_select/learning/models/cyclegan.py new file mode 100644 index 0000000..eb87dc2 --- /dev/null +++ b/modules/lsp_select/lsp_select/learning/models/cyclegan.py @@ -0,0 +1,159 @@ +import torch +import torch.nn as nn +import functools +import numpy as np +from PIL import Image +from torchvision import transforms + + +# Code adapted from https://github.com/junyanz/pytorch-CycleGAN-and-pix2pix + +class ResnetBlock(nn.Module): + """Define a Resnet block""" + + def __init__(self, dim, padding_type, norm_layer, use_dropout, use_bias): + """Initialize the Resnet block + + A resnet block is a conv block with skip connections + We construct a conv block with build_conv_block function, + and implement skip connections in function. + Original Resnet paper: https://arxiv.org/pdf/1512.03385.pdf + """ + super(ResnetBlock, self).__init__() + self.conv_block = self.build_conv_block(dim, padding_type, norm_layer, use_dropout, use_bias) + + def build_conv_block(self, dim, padding_type, norm_layer, use_dropout, use_bias): + """Construct a convolutional block. + + Parameters: + dim (int) -- the number of channels in the conv layer. + padding_type (str) -- the name of padding layer: reflect | replicate | zero + norm_layer -- normalization layer + use_dropout (bool) -- if use dropout layers. + use_bias (bool) -- if the conv layer uses bias or not + + Returns a conv block (with a conv layer, a normalization layer, and a non-linearity layer (ReLU)) + """ + conv_block = [] + p = 0 + if padding_type == 'reflect': + conv_block += [nn.ReflectionPad2d(1)] + elif padding_type == 'replicate': + conv_block += [nn.ReplicationPad2d(1)] + elif padding_type == 'zero': + p = 1 + else: + raise NotImplementedError('padding [%s] is not implemented' % padding_type) + + conv_block += [nn.Conv2d(dim, dim, kernel_size=3, padding=p, bias=use_bias), norm_layer(dim), nn.ReLU(True)] + if use_dropout: + conv_block += [nn.Dropout(0.5)] + + p = 0 + if padding_type == 'reflect': + conv_block += [nn.ReflectionPad2d(1)] + elif padding_type == 'replicate': + conv_block += [nn.ReplicationPad2d(1)] + elif padding_type == 'zero': + p = 1 + else: + raise NotImplementedError('padding [%s] is not implemented' % padding_type) + conv_block += [nn.Conv2d(dim, dim, kernel_size=3, padding=p, bias=use_bias), norm_layer(dim)] + + return nn.Sequential(*conv_block) + + def forward(self, x): + """Forward function (with skip connections)""" + out = x + self.conv_block(x) # add skip connections + return out + + +class ResnetGenerator(nn.Module): + """Resnet-based generator that consists of Resnet blocks between a few downsampling/upsampling operations. + + We adapt Torch code and idea from Justin Johnson's neural style transfer project + (https://github.com/jcjohnson/fast-neural-style) + """ + + def __init__(self, input_nc, output_nc, ngf=64, norm_layer=nn.BatchNorm2d, use_dropout=False, n_blocks=6, + padding_type='reflect'): + """Construct a Resnet-based generator + + Parameters: + input_nc (int) -- the number of channels in input images + output_nc (int) -- the number of channels in output images + ngf (int) -- the number of filters in the last conv layer + norm_layer -- normalization layer + use_dropout (bool) -- if use dropout layers + n_blocks (int) -- the number of ResNet blocks + padding_type (str) -- the name of padding layer in conv layers: reflect | replicate | zero + """ + assert n_blocks >= 0 + super(ResnetGenerator, self).__init__() + if type(norm_layer) == functools.partial: + use_bias = norm_layer.func == nn.InstanceNorm2d + else: + use_bias = norm_layer == nn.InstanceNorm2d + + model = [nn.ReflectionPad2d(3), + nn.Conv2d(input_nc, ngf, kernel_size=7, padding=0, bias=use_bias), + norm_layer(ngf), + nn.ReLU(True)] + + n_downsampling = 2 + for i in range(n_downsampling): # add downsampling layers + mult = 2 ** i + model += [nn.Conv2d(ngf * mult, ngf * mult * 2, kernel_size=3, stride=2, padding=1, bias=use_bias), + norm_layer(ngf * mult * 2), + nn.ReLU(True)] + + mult = 2 ** n_downsampling + for i in range(n_blocks): # add ResNet blocks + + model += [ResnetBlock(ngf * mult, padding_type=padding_type, norm_layer=norm_layer, + use_dropout=use_dropout, use_bias=use_bias)] + + for i in range(n_downsampling): # add upsampling layers + mult = 2 ** (n_downsampling - i) + model += [nn.ConvTranspose2d(ngf * mult, int(ngf * mult / 2), + kernel_size=3, stride=2, + padding=1, output_padding=1, + bias=use_bias), + norm_layer(int(ngf * mult / 2)), + nn.ReLU(True)] + model += [nn.ReflectionPad2d(3)] + model += [nn.Conv2d(ngf, output_nc, kernel_size=7, padding=0)] + model += [nn.Tanh()] + + self.model = nn.Sequential(*model) + + def forward(self, input): + """Standard forward""" + return self.model(input) + + @classmethod + def get_generator_fn(_, generator_network_file, device): + norm_layer = functools.partial(nn.InstanceNorm2d, affine=False, track_running_stats=False) + generator = ResnetGenerator(input_nc=3, output_nc=3, ngf=64, + norm_layer=norm_layer, use_dropout=False, n_blocks=9) + generator.eval() + generator.load_state_dict(torch.load(generator_network_file)) + generator.to(device) + + transform_fn = transforms.Compose([ + transforms.Resize((256, 265), transforms.InterpolationMode.BICUBIC), + transforms.ToTensor(), + transforms.Normalize((0.5, 0.5, 0.5), (0.5, 0.5, 0.5)) + ]) + + def get_fake_image(real_img): + with torch.no_grad(): + input_img = transform_fn(Image.fromarray(real_img).convert('RGB')) + input_img = input_img.unsqueeze(0).to(device) + output_img = generator(input_img) + output_img = output_img[0].permute(1, 2, 0).cpu().float().numpy() + output_img = ((output_img + 1) / 2 * 255).astype('uint8') + fake_img = Image.fromarray(output_img).resize((real_img.shape[1], real_img.shape[0]), Image.BICUBIC) + return np.array(fake_img) + + return get_fake_image diff --git a/modules/lsp_select/lsp_select/offline_replay.py b/modules/lsp_select/lsp_select/offline_replay.py new file mode 100644 index 0000000..1454a47 --- /dev/null +++ b/modules/lsp_select/lsp_select/offline_replay.py @@ -0,0 +1,264 @@ +import numpy as np +import math +import matplotlib.pyplot as plt + +import environments +from common import Pose +import gridmap +from gridmap import laser, utils +from gridmap.constants import UNOBSERVED_VAL, FREE_VAL, COLLISION_VAL +import lsp.core +import lsp_select + + +class OfflineReplay(lsp.simulators.Simulator): + """Simulator class for offline replay of robot observations + based on data collected during a trial. + + Requires the following to instantiate: + partial_map: The final map obtained at the end of a navigation trial. + poses: List of robot poses seen during a trial. Each pose as (x, y, yaw). + images: List of images corresponding to poses. + nearest_pose_data: A 2D-array with each cell as a dictionary consisting 'index' of + the pose nearest to that cell and 'distance' to the nearest pose. + final_subgoals: List of final subgoals present in the partial_map. + goal: Goal pose + args: args with usual parameters as the parent Simulator class + dist_mask_frontiers: Distance (grid cell units) between robot and frontiers below + which frontiers are masked during replay (so as to prevent + the robot from entering unseen space). + """ + def __init__(self, + partial_map, + poses, + images, + nearest_pose_data, + final_subgoals, + goal, + args, + dist_mask_frontiers=10, + verbose=True): + self.args = args + self.goal = goal + self.resolution = args.base_resolution + self.inflation_radius = args.inflation_radius_m / self.resolution + self.frontier_grouping_inflation_radius = 0 + + self.laser_max_range_m = args.laser_max_range_m + self.disable_known_grid_correction = args.disable_known_grid_correction + + # Store the known grid + self.known_map = partial_map.copy() + + # Create the directions object + self.laser_scanner_num_points = args.laser_scanner_num_points + self.directions = laser.get_laser_scanner_directions( + num_points=self.laser_scanner_num_points, + field_of_view_rad=math.radians(args.field_of_view_deg)) + + self.poses = poses + self.images = images + self.nearest_pose_data = nearest_pose_data + self.final_subgoals = final_subgoals + self.next_subgoals_to_mask = set() + + self.dist_mask_frontiers = dist_mask_frontiers + self.verbose = verbose + + @property + def pessimistic_map(self): + """Represents map where all unknown space is considered as obstacles""" + pessimistic_map = self.known_map.copy() + pessimistic_map[pessimistic_map == UNOBSERVED_VAL] = COLLISION_VAL + return pessimistic_map + + def get_laser_scan(self, robot): + """Get a simulated laser scan.""" + # Get the laser scan + ranges = laser.simulate_sensor_measurement( + self.pessimistic_map, + self.directions, + max_range=self.laser_max_range_m / self.resolution + 2, + sensor_pose=robot.pose) + + return ranges + + def get_image(self, robot, **kwargs): + """Get the image from the stored pose nearest to current robot pose.""" + if self.verbose: + print("Retrieving Image") + + nearest_pose = self.nearest_pose_data[int(robot.pose.x), int(robot.pose.y)] + pose_idx = nearest_pose['index'] + distance = nearest_pose['distance'] + + r_pose = self.poses[pose_idx] + pano_image = self.images[pose_idx] + aligned_pose = Pose(x=r_pose[0], y=r_pose[1], yaw=robot.pose.yaw - r_pose[2]) + + pano_image = environments.utils.convert.image_aligned_to_robot( + image=pano_image, r_pose=aligned_pose) + + if self.verbose: + print(f" image from nearest pose {(r_pose[0], r_pose[1])} at distance: {distance:.2f}") + + return (pano_image, r_pose), None + + def get_updated_frontier_set(self, inflated_grid, robot, saved_frontiers): + """Compute the frontiers, store the new ones and compute properties.""" + new_frontiers = lsp.core.get_frontiers( + inflated_grid, + group_inflation_radius=self.frontier_grouping_inflation_radius) + saved_frontiers = lsp.core.update_frontier_set(saved_frontiers, + new_frontiers) + + lsp.core.update_frontiers_goal_in_frontier(saved_frontiers, self.goal) + + # Mask and remove frontiers if they are in final_subgoals set and also near the robot. + self.next_subgoals_to_mask = set() + pose = np.array([robot.pose.x, robot.pose.y]) + for frontier in self.final_subgoals: + dist_to_frontier = frontier.get_distance_to_point(pose) + if dist_to_frontier <= self.dist_mask_frontiers: + self.known_map = lsp.core.mask_grid_with_frontiers(self.known_map, [frontier]) + self.next_subgoals_to_mask.add(frontier) + if frontier in saved_frontiers: + saved_frontiers.remove(frontier) + + return saved_frontiers + + +def get_lowerbound_planner_costs(navigation_data, planner, args): + """Helper function to get optimistic and simply-connected lower bound cost through offline replay + of a planner based on collected navigation data. + """ + pose = navigation_data['start'] + goal = navigation_data['goal'] + partial_map = navigation_data['partial_map'] + final_subgoals = navigation_data['final_subgoals'] + + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=None) + simulator = OfflineReplay(partial_map, + poses=navigation_data['poses'], + images=navigation_data['images'], + nearest_pose_data=navigation_data['nearest_pose_data'], + final_subgoals=navigation_data['final_subgoals'], + goal=goal, + args=args) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + partial_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + masked_frontiers = set() + all_alt_costs = [] + + for counter, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image'][0]}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + inflated_grid = utils.inflate_grid( + partial_map, inflation_radius=args.inflation_radius_m / args.base_resolution) + + frontier_grid = inflated_grid.copy() + frontier_grid[inflated_grid == FREE_VAL] = COLLISION_VAL + frontier_grid[inflated_grid == UNOBSERVED_VAL] = FREE_VAL + goal_grid = inflated_grid.copy() + goal_grid[inflated_grid == UNOBSERVED_VAL] = COLLISION_VAL + + # Open up all frontiers + for f in final_subgoals: + frontier_grid[f.points[0, :], f.points[1, :]] = FREE_VAL + goal_grid[f.points[0, :], f.points[1, :]] = FREE_VAL + + # Block already masked frontiers in both grids + masked_frontiers.update(simulator.next_subgoals_to_mask) + for f in masked_frontiers: + frontier_grid[f.points[0, :], f.points[1, :]] = COLLISION_VAL + goal_grid[f.points[0, :], f.points[1, :]] = COLLISION_VAL + + # Block 'next mask' frontiers for goal grid + for f in simulator.next_subgoals_to_mask: + frontier_grid[f.points[0, :], f.points[1, :]] = FREE_VAL + goal_grid[f.points[0, :], f.points[1, :]] = COLLISION_VAL + + cost_grid_goal, _ = gridmap.planning.compute_cost_grid_from_position( + goal_grid, [goal.x, goal.y], use_soft_cost=True) + + alt_costs_to_goal = [] + for f in simulator.next_subgoals_to_mask: + cost_grid_frontier, _ = gridmap.planning.compute_cost_grid_from_position( + frontier_grid, f.get_frontier_point(), use_soft_cost=True) + + total_cost_grid = cost_grid_frontier + cost_grid_goal + costs_temp = [] + for frontier in final_subgoals: + if frontier in masked_frontiers: + continue + f_x, f_y = frontier.get_frontier_point() + costs_temp.append(total_cost_grid[f_x, f_y]) + if len(costs_temp) != 0: + alt_costs_to_goal.append(costs_temp) + + if len(alt_costs_to_goal) != 0: + all_alt_costs.append([robot.net_motion, alt_costs_to_goal]) + + if args.do_plot: + plt.ion() + plt.figure(1, figsize=(12, 8)) + plt.clf() + plt.subplot(211) + plt.axis('off') + plt.imshow(step_data['image'][0]) + ax = plt.subplot(224) + plt.axis('off') + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, simulator.known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses, 'r') + alt_costs_min = [] + for net_motion, alt_costs in all_alt_costs: + alt_costs_min.append(net_motion + min([min(c) if len(c) > 0 else float('inf') + for c in alt_costs])) + + lbopt = min(alt_costs_min) if len(alt_costs_min) != 0 else float('inf') + plt.title(f'Offline Replay with {args.planner_names[args.replayed_planner_idx]}\n' + r'$C^{lb,opt}$= ' f'{lbopt:.2f}, ' r'$C^{lb,s.c.}$= ' f'{robot.net_motion:.2f}') + nearest_pose = step_data['image'][1][:2] + plt.scatter(nearest_pose[0], nearest_pose[1], color='darkorange', s=10) + ax = plt.subplot(223) + plt.axis('off') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, simulator.known_map, None, frontiers=[]) + lsp_select.utils.plotting.plot_pose_path(ax, navigation_data['robot_path']) + + plt.title(r'Final partial map $m_{final}$ ' f'and path with {args.planner_names[args.chosen_planner_idx]}' + f'\nTotal cost: {navigation_data["net_motion"]:.2f}') + plt.show() + plt.pause(0.01) + + if robot.net_motion >= 3000: + break + + # Compute optimistic lower bound + alt_costs_min = [] + for net_motion, alt_costs in all_alt_costs: + alt_costs_min.append(net_motion + min([min(c) if len(c) > 0 else float('inf') + for c in alt_costs])) + optimistic_lb = min(alt_costs_min) if len(alt_costs_min) != 0 else float('inf') + simply_connected_lb = robot.net_motion + + return optimistic_lb, simply_connected_lb diff --git a/modules/lsp_select/lsp_select/planners/__init__.py b/modules/lsp_select/lsp_select/planners/__init__.py new file mode 100644 index 0000000..977345e --- /dev/null +++ b/modules/lsp_select/lsp_select/planners/__init__.py @@ -0,0 +1,2 @@ +from .cyclegan_planner import LSPCycleGAN # noqa: F401 +from .policy_selection import PolicySelectionPlanner # noqa: F401 diff --git a/modules/lsp_select/lsp_select/planners/cyclegan_planner.py b/modules/lsp_select/lsp_select/planners/cyclegan_planner.py new file mode 100644 index 0000000..475f184 --- /dev/null +++ b/modules/lsp_select/lsp_select/planners/cyclegan_planner.py @@ -0,0 +1,53 @@ +import copy +import gridmap +import lsp +import lsp_select +from lsp.planners.subgoal_planner import LearnedSubgoalPlanner + + +class LSPCycleGAN(LearnedSubgoalPlanner): + """Class that extends LSP for transforming image observations using CycleGAN.""" + def __init__(self, goal, args, device=None, verbose=False): + super(LSPCycleGAN, self).__init__(goal, args) + + self.cyclegan_generator = lsp_select.learning.models.cyclegan.ResnetGenerator.get_generator_fn( + args.generator_network_file, self.device) + + def update(self, observation, observed_map, subgoals, robot_pose, + visibility_mask): + """Updates the internal state with the new grid/pose/laser scan. + + This function also computes a few necessary items, like which + frontiers have recently been updated and computes their properties + from the known grid. + """ + self.update_counter += 1 + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=2.0 / self.args.base_resolution, + chosen_frontier=self.selected_subgoal) + + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, self.goal) + + self.observation['image'] = self.cyclegan_generator(self.observation['image']) + + # Update the subgoal inputs + self._update_subgoal_inputs(self.observation['image'], robot_pose, self.goal) + + # Once the subgoal inputs are set, compute their properties + self._update_subgoal_properties(robot_pose, self.goal) diff --git a/modules/lsp_select/lsp_select/planners/policy_selection.py b/modules/lsp_select/lsp_select/planners/policy_selection.py new file mode 100644 index 0000000..e65c8b7 --- /dev/null +++ b/modules/lsp_select/lsp_select/planners/policy_selection.py @@ -0,0 +1,93 @@ +import numpy as np +import gridmap +from lsp.planners import Planner +from lsp_select import offline_replay + + +class PolicySelectionPlanner(Planner): + """Meta-planner class that handles selection among multiple planners/policies.""" + def __init__(self, goal, planners, chosen_planner_idx, args): + super(PolicySelectionPlanner, self).__init__(goal) + self.args = args + self.planners = planners + + # Store history of robot poses and images + self.poses = [] + self.images = [] + + self.counter = 0 + self.chosen_planner_idx = chosen_planner_idx + + # Make a grid to store nearest pose data. + # Each cell contrains a dictionary with index of nearest pose and the distance to it. + self.nearest_pose_data = np.array([[{'index': None, 'distance': np.inf} for _ in range(args.map_shape[1])] + for _ in range(args.map_shape[0])]) + self.navigation_data = {'start': self.args.robot_pose, 'goal': self.goal} + + def update(self, observation, observed_map, subgoals, robot_pose, visibility_mask): + """Updates the information in currently chosen planner and records observed poses/images.""" + self.robot_pose = robot_pose + self.observation = observation + self.observed_map = observed_map + self.planners[self.chosen_planner_idx].update(observation, observed_map, subgoals, robot_pose, visibility_mask) + self.inflated_grid = self.planners[self.chosen_planner_idx].inflated_grid + self.subgoals = self.planners[self.chosen_planner_idx].subgoals + + pose = [robot_pose.x, robot_pose.y, robot_pose.yaw] + self.poses.append(pose) + self.images.append(observation['image']) + + # Update nearest pose data + self.update_nearest_pose_data(visibility_mask, [pose[0], pose[1]]) + self.counter += 1 + + def compute_selected_subgoal(self): + """Compute selected subgoal from the chosen planner.""" + return self.planners[self.chosen_planner_idx].compute_selected_subgoal() + + def update_nearest_pose_data(self, visibility_mask, current_pose): + """As the robot navigates, update pose_data to reflect the nearest robot pose + from all poses in the visibility region. + """ + visible_cells = np.where(visibility_mask == 1) + poses = np.column_stack(visible_cells) + cost_grid, _ = gridmap.planning.compute_cost_grid_from_position(visibility_mask != 1, + current_pose, + use_soft_cost=True) + # Update nearest pose data for all cells in the visibility region + for x, y in poses: + distance = cost_grid[x, y] + pose_data = self.nearest_pose_data[x, y] + if pose_data['index'] is None: + pose_data['index'] = self.counter + pose_data['distance'] = distance + elif pose_data['distance'] > distance: + pose_data['index'] = self.counter + pose_data['distance'] = distance + + def get_costs(self): + """ After navigation is complete, get replayed costs for all other planners.""" + self.navigation_data['poses'] = np.array(self.poses) + self.navigation_data['images'] = self.images + self.navigation_data['nearest_pose_data'] = self.nearest_pose_data + self.navigation_data['partial_map'] = self.observed_map + self.navigation_data['final_subgoals'] = self.subgoals + self.navigation_data['net_motion'] = self.args.robot.net_motion + self.navigation_data['robot_path'] = self.args.robot.all_poses + + lb_costs = np.full((len(self.planners), 2), np.nan) + planner_costs = np.full(len(self.planners), np.nan) + self.args.chosen_planner_idx = self.chosen_planner_idx + for i, planner in enumerate(self.planners): + self.args.replayed_planner_idx = i + if i == self.chosen_planner_idx: + # The cost of the chosen planner is the net distance traveled + planner_costs[i] = self.navigation_data['net_motion'] + else: + # For other planners, get lower bound costs via offline replay + optimistic_lb, simply_connected_lb = offline_replay.get_lowerbound_planner_costs(self.navigation_data, + planner, + self.args) + lb_costs[i] = [optimistic_lb, simply_connected_lb] + + return planner_costs, lb_costs diff --git a/modules/lsp_select/lsp_select/scratch/Makefile.mk b/modules/lsp_select/lsp_select/scratch/Makefile.mk new file mode 100644 index 0000000..9daaa91 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/Makefile.mk @@ -0,0 +1,383 @@ + +help:: + @echo "Learned Subgoal Planning (lsp):" + @echo " lsp-maze Runs the 'guided maze' experiments." + @echo "" + +EXPERIMENT_NAME = lsp_select +ENVIRONMENT_NAME = maze +LSP_SELECT_BASENAME = lsp_select +LSP_SELECT_UNITY_BASENAME ?= rail_sim_2022_07 + +LSP_SELECT_CORE_ARGS ?= --unity_path /unity/$(LSP_SELECT_UNITY_BASENAME).x86_64 \ + --step_size 1.8 \ + --field_of_view_deg 360 \ + --map_type office2 \ + --base_resolution 0.5 \ + --inflation_radius_m 0.75 \ + --laser_max_range_m 18 + +lsp-select-gen-data-seeds = \ + $(shell for ii in $$(seq 0 499); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(ENVIRONMENT_NAME)/data_collect_plots/$(ENVIRONMENT_NAME)_training_$${ii}.png"; done) \ + $(shell for ii in $$(seq 500 599); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(ENVIRONMENT_NAME)/data_collect_plots/$(ENVIRONMENT_NAME)_testing_$${ii}.png"; done) + +.PHONY: lsp-select-gen-data +lsp-select-gen-data: $(lsp-select-gen-data-seeds) +# $(lsp-select-gen-data-seeds): DOCKER_ARGS ?= -it +$(lsp-select-gen-data-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(lsp-select-gen-data-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-select-gen-data-seeds): + $(call xhost_activate) + @echo "Generating Data [$(LSP_SELECT_BASENAME) | seed: $(seed) | $(traintest)]" + @-rm -f $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(ENVIRONMENT_NAME)_$(traintest)_$(seed).csv + @-mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME) + @-mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(ENVIRONMENT_NAME)/data + @-mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_data/$(ENVIRONMENT_NAME)/data_collect_plots + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_vis_gen_data \ + $(LSP_SELECT_CORE_ARGS) \ + --current_seed $(seed) \ + --save_dir /data/lsp_select/training_data/$(ENVIRONMENT_NAME) \ + --data_file_base_name $(ENVIRONMENT_NAME)_$(traintest) + +.PHONY: lsp-select-gen-data-mazeA +lsp-select-gen-data-mazeA: ENVIRONMENT_NAME = mazeA +lsp-select-gen-data-mazeA: $(lsp-select-gen-data-seeds) + +.PHONY: lsp-select-gen-data-mazeB +lsp-select-gen-data-mazeB: ENVIRONMENT_NAME = mazeB +lsp-select-gen-data-mazeB: LSP_SELECT_UNITY_BASENAME = rail_sim_2022_07_greenfloor +lsp-select-gen-data-mazeB: $(lsp-select-gen-data-seeds) + +.PHONY: lsp-select-gen-data-mazeC +lsp-select-gen-data-mazeC: ENVIRONMENT_NAME = mazeC +lsp-select-gen-data-mazeC: $(lsp-select-gen-data-seeds) + + +lsp-select-train-file = $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_logs/$(ENVIRONMENT_NAME)/VisLSPOriented.pt +$(lsp-select-train-file): $(lsp-select-gen-data-seeds) +$(lsp-select-train-file): DOCKER_ARGS ?= -it +$(lsp-select-train-file): + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/training_logs/$(ENVIRONMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_vis_train \ + --save_dir /data/$(LSP_SELECT_BASENAME)/training_logs/$(ENVIRONMENT_NAME) \ + --data_csv_dir /data/$(LSP_SELECT_BASENAME)/training_data/$(ENVIRONMENT_NAME) \ + --num_epochs 11 \ + --learning_rate 0.003 \ + --id 42 + +.PHONY: lsp-select-train +lsp-select-train: $(lsp-select-train-file) + +.PHONY: lsp-select-train-mazeA +lsp-select-train-mazeA: ENVIRONMENT_NAME = mazeA +lsp-select-train-mazeA: $(lsp-select-train-file) + +.PHONY: lsp-select-train-mazeB +lsp-select-train-mazeB: ENVIRONMENT_NAME = mazeB +lsp-select-train-mazeB: LSP_SELECT_UNITY_BASENAME = rail_sim_2022_07_greenfloor +lsp-select-train-mazeB: $(lsp-select-train-file) + +.PHONY: lsp-select-train-mazeC +lsp-select-train-mazeC: ENVIRONMENT_NAME = mazeC +lsp-select-train-mazeC: $(lsp-select-train-file) + + +.PHONY: lsp-cost-dist +lsp-cost-dist: DOCKER_ARGS ?= -it +lsp-cost-dist: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/nav_cost_data + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_cost_dist \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 0 300 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/nav_cost_data \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/VisLSPOriented_std2.pt + +.PHONY: lsp-model-selection +lsp-model-selection: DOCKER_ARGS ?= -it +lsp-model-selection: xhost-activate arg-check-data arg-check-unity + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_model_selection \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 0 1000 \ + --save_dir /data/$(LSP_SELECT_BASENAME) \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/VisLSPOriented_std2.pt \ + --corrupt_pose_prob 1.0 + +.PHONY: lsp-gen-nav-cost-data +lsp-gen-nav-cost-data: DOCKER_ARGS ?= -it +lsp-gen-nav-cost-data: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/nav_cost_data + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/nav_cost_data/data + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_gen_nav_cost_data \ + $(LSP_SELECT_CORE_ARGS) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/nav_cost_data \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/VisLSPOriented_std2.pt \ + --seed 702 \ + --no_of_maps 250 + +.PHONY: lsp-model-selection-eval +lsp-model-selection-eval: DOCKER_ARGS ?= -it +lsp-model-selection-eval: xhost-activate arg-check-data arg-check-unity + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_model_selection_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/nav_cost_data \ + --stepwise_eval + +.PHONY: cyclegan-data-gen-A +cyclegan-data-gen-A: DOCKER_ARGS ?= -it +cyclegan-data-gen-A: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeA2A/trainB + @$(DOCKER_PYTHON) -m lsp_select.scripts.cyclegan_data_gen \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 10 23 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeA2A/trainB + +.PHONY: cyclegan-data-gen-B +cyclegan-data-gen-B: LSP_SELECT_UNITY_BASENAME = rail_sim_urp_2022B +cyclegan-data-gen-B: DOCKER_ARGS ?= -it +cyclegan-data-gen-B: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeA2B/trainB + @$(DOCKER_PYTHON) -m lsp_select.scripts.cyclegan_data_gen \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 10 23 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeA2B/trainB + +.PHONY: cyclegan-data-gen-C +cyclegan-data-gen-C: DOCKER_ARGS ?= -it +cyclegan-data-gen-C: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeA2C/trainB + @$(DOCKER_PYTHON) -m lsp_select.scripts.cyclegan_data_gen \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 10 20 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeA2C/trainB \ + --envC + +.PHONY: lsp-gen-threshold +lsp-gen-threshold: DOCKER_ARGS ?= -it +lsp-gen-threshold: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/subgoal_labels_data/EnvA + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_gen_threshold \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 0 100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/subgoal_labels_data/EnvA \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/EnvA.pt + +.PHONY: lsp-rtm-eval-A +lsp-rtm-eval-A: DOCKER_ARGS ?= -it +lsp-rtm-eval-A: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/planner_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_rtm_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 2000 2100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/planner_eval \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/EnvA.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2A/latest_net_G_B.pth \ + --env envA \ + --threshold 1.8 + +.PHONY: lsp-rtm-eval-B +lsp-rtm-eval-B: DOCKER_ARGS ?= -it +lsp-rtm-eval-B: LSP_SELECT_UNITY_BASENAME = rail_sim_urp_2022B +lsp-rtm-eval-B: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/planner_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_rtm_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 3000 3100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/planner_eval \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/EnvA.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2B/latest_net_G_B.pth \ + --env envB \ + --threshold 1.8 + +.PHONY: lsp-rtm-eval-C +lsp-rtm-eval-C: DOCKER_ARGS ?= -it +lsp-rtm-eval-C: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/planner_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_rtm_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 4000 4100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/planner_eval \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/EnvA.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2C/latest_net_G_B.pth \ + --env envC \ + --threshold 1.8 + +.PHONY: lsp-planner-eval-A +lsp-planner-eval-A: DOCKER_ARGS ?= -it +lsp-planner-eval-A: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeABC_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_planner_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 2000 2100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/mazeA/mazeA.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2A/latest_net_G_B.pth \ + --planner nonlearned \ + --env envA + +.PHONY: lsp-planner-eval-B +lsp-planner-eval-B: LSP_SELECT_UNITY_BASENAME = rail_sim_2022_07_greenfloor +lsp-planner-eval-B: DOCKER_ARGS ?= -it +lsp-planner-eval-B: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeABC_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_planner_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 3000 3100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/mazeA/mazeA.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2B/latest_net_G_B.pth \ + --planner nonlearned \ + --env envB + +.PHONY: lsp-planner-eval-C +lsp-planner-eval-C: DOCKER_ARGS ?= -it +lsp-planner-eval-C: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeABC_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_planner_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 4000 4100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/mazeC/mazeC.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2C/latest_net_G_B.pth \ + --planner nonlearned \ + --env envC + +.PHONY: lsp-planner-results +lsp-planner-results: DOCKER_ARGS ?= -it +lsp-planner-results: arg-check-data + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_planner_results \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval + +.PHONY: lsp-estimated-cost +lsp-estimated-cost: DOCKER_ARGS ?= -it +lsp-estimated-cost: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/delta_cost + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_estimated_cost \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 900 1000 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/delta_cost/ \ + --network_file /data/$(LSP_SELECT_BASENAME)/training_logs/maze/EnvA.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2B/latest_net_G_A.pth + +.PHONY: lsp-rtm-lb-eval-A +lsp-rtm-lb-eval-A: DOCKER_ARGS ?= -it +lsp-rtm-lb-eval-A: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeABC_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_rtm_lb_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 2000 2100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --network_files mazeA/mazeA.pt mazeB/mazeB.pt mazeC/mazeC.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2A/latest_net_G_B.pth \ + --env envA + +.PHONY: lsp-rtm-lb-eval-B +lsp-rtm-lb-eval-B: DOCKER_ARGS ?= -it +lsp-rtm-lb-eval-B: LSP_SELECT_UNITY_BASENAME = rail_sim_2022_07_greenfloor +lsp-rtm-lb-eval-B: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeABC_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_rtm_lb_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 3000 3100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --network_files mazeA/mazeA.pt mazeB/mazeB.pt mazeC/mazeC.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2B/latest_net_G_B.pth \ + --env envB + +.PHONY: lsp-rtm-lb-eval-C +lsp-rtm-lb-eval-C: DOCKER_ARGS ?= -it +lsp-rtm-lb-eval-C: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/mazeABC_eval + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_rtm_lb_eval \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 4000 4100 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/mazeABC_eval \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --network_files mazeA/mazeA.pt mazeB/mazeB.pt mazeC/mazeC.pt \ + --generator_network_file /data/$(LSP_SELECT_BASENAME)/mazeA2C/latest_net_G_B.pth \ + --env envC + +chosen_planner ?= nonlearned +sim_costs_dir ?= simulated_lb_costs +envA_name = mazeA +envB_name = office +envC_name = officewall + +sim-costs-seeds-envA = \ +$(shell for ii in $$(seq 2000 2060); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(sim_costs_dir)/target_$(chosen_planner)_$(envA_name)_$${ii}.txt"; done) +sim-costs-seeds-envB = \ +$(shell for ii in $$(seq 3000 3060); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(sim_costs_dir)/target_$(chosen_planner)_$(envB_name)_$${ii}.txt"; done) +sim-costs-seeds-envC = \ +$(shell for ii in $$(seq 4001 4061); \ + do echo "$(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(sim_costs_dir)/target_$(chosen_planner)_$(envC_name)_$${ii}.txt"; done) + +.PHONY: lsp-simulated-costs-A +lsp-simulated-costs-A: $(sim-costs-seeds-envA) +$(sim-costs-seeds-envA): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(sim-costs-seeds-envA): + $(call xhost_activate) + @echo "Running [$(chosen_planner) | $(envA_name) | seed: $(seed)]" + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(sim_costs_dir) + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_simulated_costs \ + $(LSP_SELECT_CORE_ARGS) \ + --seed $(seed) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/$(sim_costs_dir) \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --chosen_planner $(chosen_planner) \ + --env $(envA_name) + +.PHONY: lsp-simulated-costs-B +lsp-simulated-costs-B: $(sim-costs-seeds-envB) +$(sim-costs-seeds-envB): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(sim-costs-seeds-envB): + $(call xhost_activate) + @echo "Running [$(chosen_planner) | $(envB_name) | seed: $(seed)]" + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(sim_costs_dir) + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_simulated_costs \ + $(LSP_SELECT_CORE_ARGS) \ + --seed $(seed) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/$(sim_costs_dir) \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --chosen_planner $(chosen_planner) \ + --env $(envB_name) + +.PHONY: lsp-simulated-costs-C +lsp-simulated-costs-C: LSP_SELECT_UNITY_BASENAME = rail_sim_2022_07_wallswap +lsp-simulated-costs-C: $(sim-costs-seeds-envC) +$(sim-costs-seeds-envC): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(sim-costs-seeds-envC): + $(call xhost_activate) + @echo "Running [$(chosen_planner) | $(envC_name) | seed: $(seed)]" + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/$(sim_costs_dir) + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_simulated_costs \ + $(LSP_SELECT_CORE_ARGS) \ + --seed $(seed) \ + --save_dir /data/$(LSP_SELECT_BASENAME)/$(sim_costs_dir) \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --chosen_planner $(chosen_planner) \ + --env $(envC_name) + +.PHONY: lsp-planner-results-offline +lsp-planner-results-offline: DOCKER_ARGS ?= -it +lsp-planner-results-offline: xhost-activate arg-check-data + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_planner_results_offline \ + --save_dir /data/$(LSP_SELECT_BASENAME)/simulated_lb_costs \ + --experiment_name maze + +.PHONY: lsp-simulate-planning +lsp-simulate-planning: DOCKER_ARGS ?= -it +lsp-simulate-planning: xhost-activate arg-check-data arg-check-unity + @mkdir -p $(DATA_BASE_DIR)/$(LSP_SELECT_BASENAME)/simulate_planning + @$(DOCKER_PYTHON) -m lsp_select.scripts.lsp_simulate_planning \ + $(LSP_SELECT_CORE_ARGS) \ + --seed 3000 \ + --save_dir /data/$(LSP_SELECT_BASENAME)/simulate_planning \ + --network_path /data/$(LSP_SELECT_BASENAME)/training_logs \ + --chosen_planner lspoffice \ + --env office \ + --do_plot diff --git a/modules/lsp_select/lsp_select/scratch/models/laser_lsp.py b/modules/lsp_select/lsp_select/scratch/models/laser_lsp.py new file mode 100644 index 0000000..be8662e --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/models/laser_lsp.py @@ -0,0 +1,91 @@ +import numpy as np +import torch +import torch.nn as nn +import torch.nn.functional as F + + +class Hidden(nn.Module): + + def __init__(self, in_size, out_size): + super(Hidden, self).__init__() + self.linear = nn.Linear(in_size, out_size) + self.batchnorm = nn.BatchNorm1d(out_size) + self.dropout = nn.Dropout(0.5) + self.activation = nn.Sigmoid() + + def forward(self, x): + x = self.linear(x) + x = self.batchnorm(x) + x = self.dropout(x) + x = self.activation(x) + return x + + +class LaserLSP(nn.Module): + + def __init__(self): + super(LaserLSP, self).__init__() + self.l1 = Hidden(260, 256) + self.l2 = Hidden(256, 128) + self.l3 = Hidden(128, 48) + self.l4 = Hidden(48, 16) + self.out = nn.Linear(16, 3) + + def forward(self, x, device): + x = x.to(device) + x = self.l1(x) + x = self.l2(x) + x = self.l3(x) + x = self.l4(x) + out = self.out(x) + prob_feasible = torch.sigmoid(out[..., 0:1]) + delta_success_cost = out[..., 1:2] + exploration_cost = out[..., 2:3] + return prob_feasible, delta_success_cost, exploration_cost + + def loss(self, predicted, target, device='cpu', writer=None, index=None): + prob_feasible = target[..., 0:1].to(device) + delta_success_cost = target[..., 1:2].to(device) + exploration_cost = target[..., 2:3].to(device) + loss_prob_feasible = 80 * F.binary_cross_entropy(predicted[0], prob_feasible, reduction='mean') + loss_delta_success_cost = 0.3 * torch.mean(prob_feasible * (predicted[1] - delta_success_cost)**2) + loss_exploration_cost = 0.01 * torch.mean((1 - prob_feasible) * (predicted[2] - exploration_cost)**2) + loss_total = loss_prob_feasible + loss_delta_success_cost + loss_exploration_cost + + if writer is not None: + writer.add_scalar("Loss/total", + loss_total.item(), + index) + writer.add_scalar("Loss/prob_feasible", + loss_prob_feasible.item(), + index) + writer.add_scalar("Loss/delta_success_cost", + loss_delta_success_cost.item(), + index) + writer.add_scalar("Loss/exploration_cost", + loss_exploration_cost.item(), + index) + return loss_total + + @classmethod + def preprocess_data(_, datum, is_training=True): + datum = np.concatenate([datum['laser_scan'], + datum['goal_rel_pos'], + datum['frontier_rel_pos']]) + datum = torch.as_tensor(datum[None], dtype=torch.float32) + return datum + + @classmethod + def get_net_eval_fn(_, network_file, device): + model = LaserLSP() + model.load_state_dict(torch.load(network_file)) + model.eval() + model.to(device) + + def frontier_net(nn_input_data): + with torch.no_grad(): + nn_input_data = LaserLSP.preprocess_data(nn_input_data, is_training=False) + prob_feasible, delta_success_cost, exploration_cost = model(nn_input_data, device=device) + return prob_feasible.item(), delta_success_cost.item(), exploration_cost.item() + + return frontier_net diff --git a/modules/lsp_select/lsp_select/scratch/planners/subgoal_planner.py b/modules/lsp_select/lsp_select/scratch/planners/subgoal_planner.py new file mode 100644 index 0000000..e6a46ab --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/planners/subgoal_planner.py @@ -0,0 +1,545 @@ +import copy +import torch +import numpy as np +import gridmap +import lsp +import lsp_select +from lsp.planners.subgoal_planner import BaseSubgoalPlanner +from lsp.planners.subgoal_planner import LearnedSubgoalPlanner as LSP +from lsp.planners import Planner, DijkstraPlanner +from sklearn.metrics import log_loss +from lsp_select.utils import delta_cost, simulators +from lsp.planners.subgoal_planner import NUM_MAX_FRONTIERS + + +class LearnedSubgoalPlannerLaser(BaseSubgoalPlanner): + + def __init__(self, goal, args, device=None, verbose=False): + super(LearnedSubgoalPlannerLaser, self).__init__(goal, args) + + if device is not None: + self.device = device + else: + use_cuda = torch.cuda.is_available() + self.device = torch.device("cuda" if use_cuda else "cpu") + + self.subgoal_property_net = lsp_select.learning.models.LaserLSP.get_net_eval_fn( + args.network_file, device=self.device) + + def update(self, observation, observed_map, subgoals, robot_pose, + visibility_mask): + """Updates the internal state with the new grid/pose/laser scan. + + This function also computes a few necessary items, like which + frontiers have recently been updated and computes their properties + from the known grid. + """ + self.update_counter += 1 + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=2.0 / self.args.base_resolution, + chosen_frontier=self.selected_subgoal) + + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, self.goal) + + # Update the subgoal inputs + self._update_subgoal_inputs(observation['ranges'], robot_pose, self.goal) + + # Once the subgoal inputs are set, compute their properties + self._update_subgoal_properties(robot_pose, self.goal) + + def _update_subgoal_inputs(self, ranges, robot_pose, goal_pose): + # Loop through subgoals and get the 'input data' + for subgoal in self.subgoals: + if subgoal.props_set: + continue + + # Compute the data that will be passed to the neural net + input_data = lsp_select.utils.learning_laser.get_frontier_data_vector( + ranges[::4] * self.args.base_resolution, robot_pose, goal_pose, subgoal) + + # Store the input data alongside each subgoal + subgoal.nn_input_data = input_data + + def _update_subgoal_properties(self, robot_pose, goal_pose): + + for subgoal in self.subgoals: + if subgoal.props_set: + continue + + [prob_feasible, delta_success_cost, exploration_cost] = \ + self.subgoal_property_net(subgoal.nn_input_data) + delta_success_cost = 0 if delta_success_cost < 0 else delta_success_cost + exploration_cost = 0 if exploration_cost < 0 else exploration_cost + subgoal.set_props(prob_feasible=prob_feasible, + delta_success_cost=delta_success_cost, + exploration_cost=exploration_cost, + last_observed_pose=robot_pose) + + for subgoal in self.subgoals: + if not self.args.silence and subgoal.prob_feasible > 0.0: + print(" " * 20 + "PLAN (%.2f %.2f) | %.6f | %7.2f | %7.2f" % + (subgoal.get_centroid()[0], subgoal.get_centroid()[1], + subgoal.prob_feasible, subgoal.delta_success_cost, + subgoal.exploration_cost)) + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + + if is_goal_in_range: + print("Goal in Range") + return None + + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor, + do_correct_low_prob=True)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + print("Problem with planning.") + self.latest_ordering = None + self.selected_subgoal = None + return None + + self.latest_ordering = frontier_ordering + self.selected_subgoal = frontier_ordering[0] + return self.selected_subgoal + + +class LearnedSubgoalPlanner(BaseSubgoalPlanner): + + def __init__(self, goal, args, device=None, verbose=False): + super(LearnedSubgoalPlanner, self).__init__(goal, args) + + if device is not None: + self.device = device + else: + use_cuda = torch.cuda.is_available() + self.device = torch.device("cuda" if use_cuda else "cpu") + + self.subgoal_property_net = lsp.learning.models.VisLSPOriented.get_net_eval_fn_std( + args.network_file, device=self.device) + + def _update_subgoal_properties(self, robot_pose, goal_pose): + + for subgoal in self.subgoals: + if subgoal.props_set: + continue + + [prob_feasible, delta_success_cost, exploration_cost, delta_success_cost_std, exploration_cost_std] = \ + self.subgoal_property_net(subgoal.nn_input_data) + + subgoal.set_props(prob_feasible=prob_feasible, + delta_success_cost=delta_success_cost, + exploration_cost=exploration_cost, + delta_success_cost_std=delta_success_cost_std, + exploration_cost_std=exploration_cost_std, + last_observed_pose=robot_pose) + + for subgoal in self.subgoals: + if not self.args.silence and subgoal.prob_feasible > 0.0: + print(" " * 20 + "PLAN (%.2f %.2f) | %.6f | %7.2f | %7.2f" % + (subgoal.get_centroid()[0], subgoal.get_centroid()[1], + subgoal.prob_feasible, subgoal.delta_success_cost, + subgoal.exploration_cost)) + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + + if is_goal_in_range: + print("Goal in Range") + return None + + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor, + do_correct_low_prob=True)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + print("Problem with planning.") + self.latest_ordering = None + self.selected_subgoal = None + return None + + self.expected_cost = min_cost + self.latest_ordering = frontier_ordering + self.selected_subgoal = frontier_ordering[0] + return self.selected_subgoal + + +class LSPCycleGAN(LSP): + + def __init__(self, goal, args, device=None, verbose=False): + super(LSPCycleGAN, self).__init__(goal, args) + + self.cyclegan_generator = lsp_select.learning.models.cyclegan.ResnetGenerator.get_generator_fn( + args.generator_network_file, self.device) + + def update(self, observation, observed_map, subgoals, robot_pose, + visibility_mask): + """Updates the internal state with the new grid/pose/laser scan. + + This function also computes a few necessary items, like which + frontiers have recently been updated and computes their properties + from the known grid. + """ + self.update_counter += 1 + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=2.0 / self.args.base_resolution, + chosen_frontier=self.selected_subgoal) + + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, self.goal) + + if not self.args.disable_cyclegan: + observation['image'] = self.cyclegan_generator(observation['image']) + self.observation = observation + + # Update the subgoal inputs + self._update_subgoal_inputs(observation['image'], robot_pose, self.goal) + + # Once the subgoal inputs are set, compute their properties + self._update_subgoal_properties(robot_pose, self.goal) + + +class RuntimeMonitoringPlanner(Planner): + + def __init__(self, goal, planners, priors, threshold, args): + super(RuntimeMonitoringPlanner, self).__init__(goal) + self.args = args + self.default_planner = DijkstraPlanner(goal=goal, args=args) + self.planners = planners + self.priors = np.array(priors) + self.threshold = threshold + self.chosen_planner_idx = None + + # avg cross entropy = total_xentropy / number of observations + self.xentropy_avg = self.priors[:, 0] / self.priors[:, 1] + lowest_idx = np.argmin(self.xentropy_avg) + if self.xentropy_avg[lowest_idx] < self.threshold: + self.chosen_planner_idx = lowest_idx + self.subgoals_data = [[] for _ in self.planners] + if self.chosen_planner_idx is not None: + self.chosen_planner_name = type(self.planners[self.chosen_planner_idx]).__name__ + else: + self.chosen_planner_name = type(self.default_planner).__name__ + + def update(self, observation, observed_map, subgoals, robot_pose, visibility_mask): + self.robot_pose = robot_pose + self.observation = observation + self.observed_map = observed_map + self.default_planner.update(observation, observed_map, subgoals, robot_pose, visibility_mask) + for i, planner in enumerate(self.planners): + planner.update(observation, observed_map, subgoals, robot_pose, visibility_mask) + is_goal_in_range = lsp.core.goal_in_range(planner.inflated_grid, robot_pose, self.goal, subgoals) + if not is_goal_in_range: + self.subgoals_data[i].append({'subgoals': planner.subgoals, + 'robot_pose': robot_pose}) + self.inflated_grid = self.planners[0].inflated_grid + if self.chosen_planner_idx is not None: + self.subgoals = self.planners[self.chosen_planner_idx].subgoals + else: + self.subgoals = self.default_planner.subgoals + + def compute_selected_subgoal(self): + if self.chosen_planner_idx is not None: + return self.planners[self.chosen_planner_idx].compute_selected_subgoal() + return self.default_planner.compute_selected_subgoal() + + def compute_new_priors(self): + inflated_grid = self.planners[0].inflated_grid + subgoals = self.planners[0].subgoals + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, subgoals) + for i in range(len(self.planners)): + if len(self.subgoals_data[i]) == 0: + break + subgoal_labels = lsp_select.utils.misc.get_subgoal_labels(self.subgoals_data[i], planning_grid, self.goal) + xentropy_avg = log_loss(subgoal_labels[:, 2], subgoal_labels[:, 1], labels=[0, 1]) + no_of_obs = len(subgoal_labels) + self.priors[i] += [xentropy_avg * no_of_obs, no_of_obs] + return self.priors + + +class RTMDelta(Planner): + + def __init__(self, goal, planners, priors, args): + super(RTMDelta, self).__init__(goal) + self.args = args + self.planners = [DijkstraPlanner(goal=goal, args=args)] + planners + if priors is None: + self.priors = np.zeros((len(self.planners), 2)) + self.avg_estimated_costs = np.zeros(len(self.planners)) + self.chosen_planner_idx = 0 + else: + self.priors = np.array(priors) + self.avg_estimated_costs = self.priors[:, 0] / self.priors[:, 1] + self.chosen_planner_idx = np.argmin(self.avg_estimated_costs) + + self.navigation_data = {'policies': [[] for _ in self.planners], + 'steps': [], + 'spidx': self.chosen_planner_idx, + 'start_pose': self.args.robot_pose, + 'goal_pose': self.goal, + 'net_motion': None, + 'correct_subgoals': [], + 'final_masked_grid': None, + 'known_path': [], + 'known_cost': None} + self.chosen_planner_name = type(self.planners[self.chosen_planner_idx]).__name__ + + def update(self, observation, observed_map, subgoals, robot_pose, visibility_mask): + self.robot_pose = robot_pose + self.observation = observation + self.observed_map = observed_map + for planner in self.planners: + planner.update(observation, observed_map, subgoals, robot_pose, visibility_mask) + self.inflated_grid = self.planners[self.chosen_planner_idx].inflated_grid + self.subgoals = self.planners[self.chosen_planner_idx].subgoals + + def compute_selected_subgoal(self): + chosen_subgoal = None + for i, planner in enumerate(self.planners): + is_goal_in_range = lsp.core.goal_in_range(planner.inflated_grid, self.robot_pose, self.goal, self.subgoals) + if not is_goal_in_range: + selected_subgoal = planner.compute_selected_subgoal() + if i == self.chosen_planner_idx: + chosen_subgoal = selected_subgoal + planner.latest_ordering = delta_cost.get_full_policy(planner.latest_ordering, + planner.subgoals, + planner.inflated_grid, + planner.robot_pose, + planner.goal) + self.navigation_data['policies'][i].append(planner.latest_ordering) + self.navigation_data['steps'].append([self.robot_pose, + self.subgoals, + self.inflated_grid, + is_goal_in_range]) + return chosen_subgoal + + def compute_new_priors(self): + step_data = self.navigation_data['steps'] + pose = self.navigation_data['start_pose'] + goal = self.navigation_data['goal_pose'] + final_subgoals = step_data[-1][1] + final_masked_grid = lsp.core.mask_grid_with_frontiers(step_data[-1][2], final_subgoals) + known_path = delta_cost.get_path_in_known_grid(final_masked_grid, + pose, + goal, + final_subgoals, + do_not_mask=None) + known_cost = delta_cost.compute_cost_from_path(known_path) + correct_subgoals = [] + for i, (robot_pose, subgoals, inflated_grid, is_goal_in_range) in enumerate(step_data): + if is_goal_in_range: + break + for subgoal in subgoals: + if lsp_select.utils.misc.is_feasible_subgoal(subgoal, final_masked_grid, subgoals, robot_pose, goal): + correct_subgoals.append(subgoal) + break + self.navigation_data['correct_subgoals'] = correct_subgoals + self.navigation_data['final_masked_grid'] = final_masked_grid + self.navigation_data['net_motion'] = self.args.robot.net_motion + self.navigation_data['known_path'] = known_path + self.navigation_data['known_cost'] = known_cost + + delta_costs_array = np.zeros((len(self.planners), + len(self.navigation_data['policies'][self.chosen_planner_idx]))) + estimated_lb_costs = np.zeros(len(self.planners)) + for i in range(len(self.planners)): + if i == self.chosen_planner_idx: + estimated_lb_costs[i] = self.navigation_data['net_motion'] + continue + delta_costs_array[i, :] = delta_cost.eval_alternate_policies(self.navigation_data['steps'], + self.navigation_data['correct_subgoals'], + self.navigation_data['policies'][i], + self.navigation_data['start_pose'], + self.navigation_data['goal_pose']) + estimated_lb_costs[i] = (delta_cost.aggregate_delta_costs(delta_costs_array[i, :]) + + self.navigation_data['known_cost']) + priors = np.zeros_like(self.priors) + priors[:, 0] = self.priors[:, 0] + estimated_lb_costs + priors[:, 1] = self.priors[:, 1] + 1 + return priors + + +class RTMLowerBound(Planner): + + def __init__(self, goal, planners, priors, args): + super(RTMLowerBound, self).__init__(goal) + self.args = args + self.planners = [DijkstraPlanner(goal=goal, args=args)] + planners + self.poses = [] + self.images = [] + self.counter = 0 + + if priors is None: + self.priors = np.zeros((len(self.planners), 2)) + self.avg_estimated_costs = np.zeros(len(self.planners)) + self.chosen_planner_idx = 0 + else: + self.priors = np.array(priors) + self.avg_estimated_costs = self.priors[:, 0] / self.priors[:, 1] + self.chosen_planner_idx = np.argmin(self.avg_estimated_costs) + + self.nearest_pose_data = np.array([[{'index': None, 'distance': np.inf} for _ in range(args.map_shape[1])] + for _ in range(args.map_shape[0])]) + self.navigation_data = {'start': self.args.robot_pose, + 'goal': self.goal, + 'planner': type(self.planners[self.chosen_planner_idx]).__name__} + self.chosen_planner_name = type(self.planners[self.chosen_planner_idx]).__name__ + + def update(self, observation, observed_map, subgoals, robot_pose, visibility_mask): + self.robot_pose = robot_pose + self.observation = observation + self.observed_map = observed_map + self.planners[self.chosen_planner_idx].update(observation, observed_map, subgoals, robot_pose, visibility_mask) + self.inflated_grid = self.planners[self.chosen_planner_idx].inflated_grid + self.subgoals = self.planners[self.chosen_planner_idx].subgoals + + pose = [robot_pose.x, robot_pose.y, robot_pose.yaw] + self.poses.append(pose) + self.images.append(observation['image']) + + self.update_nearest_pose_data(visibility_mask, [pose[0], pose[1]]) + self.counter += 1 + + def compute_selected_subgoal(self): + return self.planners[self.chosen_planner_idx].compute_selected_subgoal() + + def compute_new_priors(self): + self.navigation_data['poses'] = np.array(self.poses), + self.navigation_data['images'] = self.images, + self.navigation_data['nearest_pose_data'] = self.nearest_pose_data + self.navigation_data['partial_map'] = self.observed_map + self.navigation_data['final_subgoals'] = self.subgoals + self.navigation_data['net_motion'] = self.args.robot.net_motion + self.navigation_data['robot_path'] = self.args.robot.all_poses + + priors = np.zeros_like(self.priors) + for i, planner in enumerate(self.planners): + if i == self.chosen_planner_idx: + cost = self.navigation_data['net_motion'] + else: + cost = simulators.get_simulated_planner_cost(self.navigation_data, planner, self.args) + priors[i, 0] = self.priors[i, 0] + cost + priors[i, 1] = self.priors[i, 1] + 1 + return priors + + def update_nearest_pose_data(self, visibility_mask, current_pose): + visible_cells = np.where(visibility_mask == 1) + poses = np.column_stack(visible_cells) + cost_grid, _ = gridmap.planning.compute_cost_grid_from_position(visibility_mask != 1, + current_pose, + use_soft_cost=True) + for x, y in poses: + distance = cost_grid[x, y] + pose_data = self.nearest_pose_data[x, y] + if pose_data['index'] is None: + pose_data['index'] = self.counter + pose_data['distance'] = distance + continue + if pose_data['distance'] > distance: + pose_data['index'] = self.counter + pose_data['distance'] = distance + + +class RTMSimulate(RTMLowerBound): + def __init__(self, goal, planners, chosen_planner_idx, args): + super(RTMLowerBound, self).__init__(goal) + self.args = args + self.planners = planners + self.poses = [] + self.images = [] + self.counter = 0 + self.chosen_planner_idx = chosen_planner_idx + self.nearest_pose_data = np.array([[{'index': None, 'distance': np.inf} for _ in range(args.map_shape[1])] + for _ in range(args.map_shape[0])]) + self.navigation_data = {'start': self.args.robot_pose, + 'goal': self.goal, + 'planner': type(self.planners[self.chosen_planner_idx]).__name__} + self.chosen_planner_name = type(self.planners[self.chosen_planner_idx]).__name__ + + def get_costs(self): + self.navigation_data['poses'] = np.array(self.poses), + self.navigation_data['images'] = self.images, + self.navigation_data['nearest_pose_data'] = self.nearest_pose_data + self.navigation_data['partial_map'] = self.observed_map + self.navigation_data['final_subgoals'] = self.subgoals + self.navigation_data['net_motion'] = self.args.robot.net_motion + self.navigation_data['robot_path'] = self.args.robot.all_poses + + planner_costs = np.zeros(len(self.planners)) + for i, planner in enumerate(self.planners): + if i == self.chosen_planner_idx: + cost = self.navigation_data['net_motion'] + else: + cost = simulators.get_simulated_planner_cost(self.navigation_data, planner, self.args) + planner_costs[i] = cost + return planner_costs + + +class RTMSimulateLB(RTMSimulate): + def get_costs(self): + self.navigation_data['poses'] = np.array(self.poses), + self.navigation_data['images'] = self.images, + self.navigation_data['nearest_pose_data'] = self.nearest_pose_data + self.navigation_data['partial_map'] = self.observed_map + self.navigation_data['final_subgoals'] = self.subgoals + self.navigation_data['net_motion'] = self.args.robot.net_motion + self.navigation_data['robot_path'] = self.args.robot.all_poses + + alt_costs_data = {} + planner_costs = np.zeros(len(self.planners)) + for i, planner in enumerate(self.planners): + if i == self.chosen_planner_idx: + cost = self.navigation_data['net_motion'] + alt_costs_data[i] = None + else: + all_alt_costs, cost = simulators.get_lowerbound_planner_cost(self.navigation_data, planner, self.args) + alt_costs_data[i] = all_alt_costs + planner_costs[i] = cost + return planner_costs, alt_costs_data diff --git a/modules/lsp_select/lsp_select/scratch/scripts/cyclegan_data_gen.py b/modules/lsp_select/lsp_select/scratch/scripts/cyclegan_data_gen.py new file mode 100644 index 0000000..3941152 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/cyclegan_data_gen.py @@ -0,0 +1,84 @@ +import environments +import lsp +import matplotlib.pyplot as plt +from pathlib import Path +from PIL import Image +import lsp_select +from lsp.planners import DijkstraPlanner +from lsp_select.utils.distribution import corrupt_robot_pose + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + goal = corrupt_robot_pose(known_map, args) if args.envC else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planner = DijkstraPlanner(goal=goal, args=args) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(None) + + # Save image + im = Image.fromarray(step_data['image']) + im.save(Path(args.save_dir) / f'img_{args.current_seed}_{counter}.png') + + # if args.do_plot: + if True: + plt.ion() + plt.figure(1) + plt.clf() + # plt.subplot(211) + # plt.imshow(step_data['image']) + ax = plt.subplot(111) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.savefig(Path(args.save_dir) / f'grid_{args.current_seed}_{counter}.pdf', dpi=300) + plt.show() + plt.pause(0.01) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--envC', action='store_true') + args = parser.parse_args() + for seed in range(args.seed[0], args.seed[1]): + print(f'{seed=}') + args.current_seed = seed + maze_eval(args) diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_cost_dist.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_cost_dist.py new file mode 100644 index 0000000..1bcded6 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_cost_dist.py @@ -0,0 +1,137 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +import gridmap +from pathlib import Path +import scipy.stats as stats +import sys +from lsp_select.planners import LearnedSubgoalPlanner +from lsp_select.utils.distribution import get_cost_distribution + + +def maze_eval(args): + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planner = LearnedSubgoalPlanner(goal=goal, args=args) + probs_costs_motion = {'probs': [], 'costs': [], 'motion': []} + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + chosen_frontier = planner.compute_selected_subgoal() + if chosen_frontier is not None: + distances = lsp.core.compute_distances(planner.latest_ordering, + step_data['robot_grid'], + step_data['robot_pose'], + goal) + probs, costs = get_cost_distribution(planner.latest_ordering, distances) + # expected_cost = planner.expected_cost + probs_costs_motion['probs'].append(probs) + probs_costs_motion['costs'].append(costs) + probs_costs_motion['motion'].append(robot.net_motion) + planning_loop.set_chosen_subgoal(chosen_frontier) + + if args.do_plot: + if planning_loop.chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + planner.subgoals, + do_not_mask=planning_loop.chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(234) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + + if chosen_frontier is not None: + plt.subplot(235) + plt.title('Individual Gaussians') + pdfs = [] + min_mu_idx, max_mu_idx = costs[:, 0].argmin(), costs[:, 0].argmax() + x = np.linspace(costs[min_mu_idx, 0] - 3 * costs[min_mu_idx, 1], + costs[max_mu_idx, 0] + 3 * costs[max_mu_idx, 1], 1000) + for p, (mu, sigma) in zip(probs, costs): + y = stats.norm.pdf(x, mu, sigma) + plt.plot(x, y) + pdfs.append(p * y) + plt.subplot(236) + plt.plot(x, np.sum(np.array(pdfs), axis=0), color='tab:blue') + plt.title('Gaussion Mixture') + + plt.show() + plt.pause(0.1) + likelihood = [] + tot_distance = robot.net_motion + for probs, costs, motion in zip(*probs_costs_motion.values()): + mu, sigma = costs.T + pdf = stats.norm.pdf(tot_distance - motion, mu, sigma) + likelihood.append(np.sum(probs * pdf)) + return likelihood + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + args = parser.parse_args() + count = 0 + for seed in range(*args.seed): + with open(Path(args.save_dir) / 'likelihood_stepwise.txt', 'a') as file: + args.current_seed = seed + stdout = sys.stdout + sys.stdout = open('/dev/null', 'w') + likelihood = maze_eval(args) + sys.stdout = stdout + for lh in likelihood: + file.write(f'{seed} {lh}\n') + count += 1 + print(f'Saved {len(likelihood)} data points from seed {seed}. Total data points: {count}\n') diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost.py new file mode 100644 index 0000000..fe05cb2 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost.py @@ -0,0 +1,210 @@ +import numpy as np +import environments +import lsp +import lsp_select +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner +from lsp_select.planners import LSPCycleGAN +import gridmap + +from lsp.constants import FREE_VAL, UNOBSERVED_VAL, COLLISION_VAL + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + # goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + planners = [LearnedSubgoalPlanner(goal=goal, args=args), + LSPCycleGAN(goal=goal, args=args)] + spidx = 0 # selected planner index + + delta_cost_array = [] + + alt_visited_subgoals = set() + + navigation_data = {'policies': [[] for _ in planners], + 'steps': []} + + for counter, step_data in enumerate(planning_loop): + policies = [] # stores (subgoal, policy) for each planner + for pid, planner in enumerate(planners): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + selected_subgoal = planner.compute_selected_subgoal() + latest_ordering = planner.latest_ordering if selected_subgoal is not None else [] + policies.append([selected_subgoal, latest_ordering]) + navigation_data['policies'][pid].append(latest_ordering) + + chosen_subgoal, chosen_policy = policies[spidx] + planning_loop.set_chosen_subgoal(chosen_subgoal) + + is_goal_visible = chosen_subgoal is None + + navigation_data['steps'].append(planner.robot_pose, + planner.subgoals, + planner.inflated_grid, + is_goal_visible) + _, _, sel_cost = get_subgoals_path_cost(chosen_policy, chosen_policy, + planners[spidx].subgoals, + planners[spidx].robot_pose, + planners[spidx].inflated_grid, + is_goal_visible) + + for i, planner in enumerate(planners): + if i == spidx: + continue + other_policy = policies[i][1] + alt_subgoals, alt_path, alt_cost = get_subgoals_path_cost(chosen_policy, other_policy, + planner.subgoals, + planner.robot_pose, + planner.inflated_grid, + is_goal_visible, + visited_subgoals=alt_visited_subgoals) + alt_visited_subgoals.update(alt_subgoals) + delta_cost = max(0, alt_cost - sel_cost) + delta_cost_array.append(delta_cost) + + planner = planners[spidx] + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + for i, s in enumerate(alt_subgoals): + point = s.get_frontier_point() + plt.scatter(*point) + plt.text(*point, str(i)) + lsp_select.utils.plotting.plot_path(ax, alt_path, style='r:') + + plt.title(f'{type(planner).__name__}, {delta_cost=:.2f}') + plt.xlabel(f'seed={args.current_seed}') + plt.pause(0.01) + input() + + delta_cost_array = np.array(delta_cost_array, dtype=float) + delta_cost_array[delta_cost_array == 0] = np.inf + total_delta_cost = 0 + for sub_cost in np.split(delta_cost_array, np.where(delta_cost_array == np.inf)[0]): + if len(sub_cost) > 1: + total_delta_cost += np.min(sub_cost) + print(f'{total_delta_cost=}') + + +def check_identical_subgoals(current_subgoal, last_subgoal, inflated_grid, current_all_subgoals, robot_pose, goal_pose): + masked_grid_s1 = lsp.core.mask_grid_with_frontiers(inflated_grid, current_all_subgoals, do_not_mask=current_subgoal) + masked_grid_s2 = lsp.core.mask_grid_with_frontiers(masked_grid_s1, [last_subgoal]) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + masked_grid_s2, [goal_pose.x, goal_pose.y], use_soft_cost=False) + did_plan, _ = get_path([robot_pose.x, robot_pose.y], + do_sparsify=False, + do_flip=False) + return not did_plan + + +def get_subgoals_path_cost(policy1, policy2, all_subgoals, pose, inflated_grid, + is_goal_visible, visited_subgoals=set()): + if is_goal_visible: + return [], np.array([[], []]), 0 + alt_subgoals = compute_alt_subgoals(policy1, policy2, visited_subgoals=visited_subgoals) + alt_path = compute_subgoals_path(alt_subgoals, all_subgoals, pose, inflated_grid) + alt_cost = compute_cost_from_path(alt_path) + return alt_subgoals, alt_path, alt_cost + + +def compute_alt_subgoals(policy1, policy2, visited_subgoals=set()): + if policy1[0] == policy2[0]: + return [policy1[0]] + alt_subgoals = [] + for s in policy2: + if s not in visited_subgoals: + alt_subgoals.append(s) + if s == policy1[0]: + break + return alt_subgoals + + +def compute_subgoals_path(path_subgoals, all_subgoals, pose, inflated_grid): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, all_subgoals) + path_points = [[pose.x, pose.y]] + for subgoal in path_subgoals: + planning_grid[subgoal.points[0], subgoal.points[1]] = FREE_VAL + planning_grid[planning_grid == UNOBSERVED_VAL] = COLLISION_VAL + path_points.append(subgoal.get_frontier_point()) + path_points = np.array(path_points) + + alt_path = [[], []] + for i in range(len(path_points) - 1): + start = path_points[i] + end = path_points[i + 1] + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, end, use_soft_cost=True) + did_plan, path = get_path(start, do_sparsify=True, do_flip=True) + if did_plan: + alt_path[0].extend(path[0]) + alt_path[1].extend(path[1]) + return np.array(alt_path) + + +def compute_cost_from_path(path): + return np.linalg.norm(path[:, 1:] - path[:, :-1], axis=0).sum() + + +def get_path_in_known_grid(inflated_grid, pose, goal, subgoals, do_not_mask=None): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, subgoals, do_not_mask=do_not_mask) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, goal, use_soft_cost=True) + _, path = get_path([pose.x, pose.y], do_sparsify=True, do_flip=True) + return path + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--planner', choices=['lsp', 'lspcyclegan', 'nonlearned']) + parser.add_argument('--env', choices=['envA', 'envB', 'envC']) + args = parser.parse_args() + + args.current_seed = args.seed[0] + maze_eval(args) diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost_gen.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost_gen.py new file mode 100644 index 0000000..c91f73e --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_delta_cost_gen.py @@ -0,0 +1,226 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +import gridmap +from pathlib import Path + +from lsp.planners import KnownSubgoalPlanner, LearnedSubgoalPlanner +from lsp_select.planners import LSPCycleGAN + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + known_planner = KnownSubgoalPlanner(goal=goal, known_map=known_map, args=args) + planners = [LearnedSubgoalPlanner(goal=goal, args=args), + LSPCycleGAN(goal=goal, args=args)] + + delta_path_array = [] + delta_cost_array = [] + # last_subgoal_for_path = None + min_delta_cost = 0 + min_delta_path = [] + total_delta_cost = 0 + total_delta_path = [] + count_identical_subgoals = 0 + subgoal_data = {'subgoals': [], 'subgoal_centroids': []} + recorded_subgoals = [] + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + known_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + + selected_subgoals = [known_planner.compute_selected_subgoal()] + for planner in planners: + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + selected_subgoal = planner.compute_selected_subgoal() + selected_subgoals.append(selected_subgoal) + selected_planner_idx = 0 + planner = planners[selected_planner_idx] + subgoal_centroids = [] + + # if goal is not visible, chosen subgoal is not None + if None not in selected_subgoals: + for subgoal in selected_subgoals: + subgoal_centroids.extend(subgoal.get_frontier_point()) + if counter == 0: + is_identical_to_last = False + else: + last_subgoal_m2 = subgoal_data['subgoals'][-1][2] + is_identical_to_last = check_identical_subgoals(selected_subgoals[2], + last_subgoal_m2, + planner.inflated_grid, + step_data['subgoals'], + step_data['robot_pose'], + goal) + subgoal_data['subgoals'].append(selected_subgoals) + subgoal_data['subgoal_centroids'].append(subgoal_centroids) + if selected_subgoals[0] != selected_subgoals[2]: + recorded_subgoals.append(selected_subgoals[2]) + distances = lsp.core.compute_distances(step_data['subgoals'], + step_data['robot_grid'], + step_data['robot_pose'], + goal) + delta_cost = distances['robot'][selected_subgoals[2]] + delta_cost_array.append(delta_cost) + delta_path_array.append(get_path_in_known_grid(planner.inflated_grid, + step_data['robot_pose'], + selected_subgoals[2].get_frontier_point(), + planner.subgoals)) + if is_identical_to_last: + del recorded_subgoals[-2] + count_identical_subgoals += 1 + # temp_last_subgoal_for_path = subgoal_data['subgoals'][-count_identical_subgoals:] + temp_delta_cost_array = delta_cost_array[-count_identical_subgoals:] + temp_delta_path_array = delta_path_array[-count_identical_subgoals:] + min_idx = np.argmin(temp_delta_cost_array) + min_delta_cost = temp_delta_cost_array[min_idx] + min_delta_path = temp_delta_path_array[min_idx] + # min_last_subgoal = temp_last_subgoal_for_path[min_idx] + else: + count_identical_subgoals = 0 + total_delta_cost += min_delta_cost + total_delta_path.append(min_delta_path) + min_delta_cost = 0 + min_delta_path = [] + + subgoal_centroids.append(delta_cost) + + else: + delta_cost = 0 + delta_cost_array.append(delta_cost) + delta_path_array.append(None) + subgoal_centroids.append(delta_cost) + subgoal_centroids.append(int(is_identical_to_last)) + + planning_loop.set_chosen_subgoal(selected_subgoals[selected_planner_idx + 1]) + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + if step_data['image'] is not None: + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + else: + ax = plt.subplot(111) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + if planning_loop.chosen_subgoal is not None: + model2_centroid = selected_subgoals[2].get_centroid().astype(int) + path2 = get_path_in_known_grid(planner.inflated_grid, + robot.pose, + model2_centroid, + planner.subgoals, + do_not_mask=planning_loop.chosen_subgoal) + # point = selected_subgoals[1].points[:, 0] + plt.title(f'{delta_cost=:.2f},{model2_centroid},{is_identical_to_last=}') + lsp_select.utils.plotting.plot_path(ax, path2, style='r:') + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + # if min_delta_path is not None and len(min_delta_path): + # lsp_select.utils.plotting.plot_path(ax, min_delta_path, style='c:') + + plt.show() + plt.pause(0.1) + # input() + masked_grid = lsp.core.mask_grid_with_frontiers(planner.inflated_grid, step_data['subgoals']) + + path_points = [[pose.x, pose.y]] + for subgoal in recorded_subgoals: + path_points.append(subgoal.get_frontier_point()) + path_points.append([goal.x, goal.y]) + path_points = np.array(path_points) + plt.ioff() + plt.figure(1) + ax = plt.subplot(111) + for i in range(len(path_points) - 1): + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + start = path_points[i] + end = path_points[i + 1] + _, get_path = gridmap.planning.compute_cost_grid_from_position( + masked_grid, end, use_soft_cost=True) + _, path2 = get_path(start, do_sparsify=True, do_flip=True) + print(path2) + if len(path2) == 2: + lsp_select.utils.plotting.plot_path(ax, path2, style='r-') + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + + plt.show() + + return subgoal_data + + +def check_identical_subgoals(current_subgoal, last_subgoal, inflated_grid, current_all_subgoals, robot_pose, goal_pose): + masked_grid_s1 = lsp.core.mask_grid_with_frontiers(inflated_grid, current_all_subgoals, do_not_mask=current_subgoal) + masked_grid_s2 = lsp.core.mask_grid_with_frontiers(masked_grid_s1, [last_subgoal]) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + masked_grid_s2, [goal_pose.x, goal_pose.y], use_soft_cost=False) + did_plan, _ = get_path([robot_pose.x, robot_pose.y], + do_sparsify=False, + do_flip=False) + return not did_plan + + +def get_path_in_known_grid(inflated_grid, pose, goal, subgoals, do_not_mask=None): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, subgoals, do_not_mask=do_not_mask) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, goal, use_soft_cost=True) + _, path = get_path([pose.x, pose.y], do_sparsify=True, do_flip=True) + return path + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--env', choices=['envA', 'envB', 'envC'], default='envA') + args = parser.parse_args() + args.current_seed = args.seed[0] + subgoal_data = maze_eval(args) + np.savetxt(Path(args.save_dir) / f'{args.env}_{args.current_seed}.txt', + subgoal_data['subgoal_centroids'], + fmt='%.0f') diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_estimated_cost.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_estimated_cost.py new file mode 100644 index 0000000..9c1940a --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_estimated_cost.py @@ -0,0 +1,472 @@ +import numpy as np +import environments +import lsp +import lsp_select +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner +from lsp_select.planners import LSPCycleGAN +import gridmap +from lsp_select.utils.misc import is_feasible_subgoal +from lsp.constants import FREE_VAL, UNOBSERVED_VAL, COLLISION_VAL +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + # goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + planners = [planner(goal=goal, args=args) for planner in args.planners] + spidx = 0 # selected planner index + + navigation_data = {'policies': [[] for _ in planners], + 'steps': [], + 'spidx': spidx, + 'start_pose': pose, + 'goal_pose': goal, + 'net_motion': None, + 'correct_subgoals': [], + 'final_masked_grid': None, + 'known_path': [], + 'known_cost': None} + + for counter, step_data in enumerate(planning_loop): + policies = [] # stores (subgoal, policy) for each planner + for pid, planner in enumerate(planners): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + selected_subgoal = planner.compute_selected_subgoal() + # latest_ordering = planner.latest_ordering if selected_subgoal is not None else [] + if selected_subgoal is None: + latest_ordering = [] + else: + # latest_ordering = planner.latest_ordering + latest_ordering = get_full_policy(planner.latest_ordering, + planner.subgoals, + planner.inflated_grid, + planner.robot_pose, + goal) + policies.append([selected_subgoal, latest_ordering]) + navigation_data['policies'][pid].append(latest_ordering) + + chosen_subgoal, chosen_policy = policies[spidx] + planning_loop.set_chosen_subgoal(chosen_subgoal) + + is_goal_visible = chosen_subgoal is None + + navigation_data['steps'].append([planner.robot_pose, + planner.subgoals, + planner.inflated_grid, + is_goal_visible]) + + planner = planners[spidx] + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + for j, s in enumerate(planners[0].latest_ordering): + point = s.get_frontier_point() + plt.scatter(*point) + plt.text(*point, str(j)) + plt.title(f'{type(planner).__name__}') + plt.xlabel(f'seed={args.current_seed}') + plt.pause(0.01) + + step_data = navigation_data['steps'] + final_subgoals = step_data[-1][1] + final_masked_grid = lsp.core.mask_grid_with_frontiers(step_data[-1][2], final_subgoals) + known_path = get_path_in_known_grid(final_masked_grid, pose, goal, final_subgoals, do_not_mask=None) + known_cost = compute_cost_from_path(known_path) + correct_subgoals = [] + for i, (robot_pose, subgoals, inflated_grid, is_goal_visible) in enumerate(step_data): + if is_goal_visible: + break + for subgoal in subgoals: + if is_feasible_subgoal(subgoal, final_masked_grid, subgoals, robot_pose, goal): + correct_subgoals.append(subgoal) + break + navigation_data['correct_subgoals'] = correct_subgoals + navigation_data['final_masked_grid'] = final_masked_grid + navigation_data['net_motion'] = robot.net_motion + navigation_data['known_path'] = known_path + navigation_data['known_cost'] = known_cost + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(111) + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + # lsp_select.utils.plotting.plot_path(ax, navigation_data['known_path'], style='g:') + plt.title(f'net_motion={navigation_data["net_motion"]:.2f}, known_cost={navigation_data["known_cost"]:.2f}') + plt.show() + plt.pause(0.01) + input() + + return navigation_data + + +def get_full_policy(latest_ordering, subgoals, inflated_grid, robot_pose, goal, num_frontiers_max=12): + remaining_frontiers = [f for f in subgoals if f not in latest_ordering] + distances = lsp.core.compute_distances(subgoals, + inflated_grid, + robot_pose, + goal) + while len(latest_ordering) < len(subgoals): + remaining_frontiers = [f for f in subgoals if f not in latest_ordering] + if len(remaining_frontiers) > num_frontiers_max: + remaining_frontiers = lsp.core.get_top_n_frontiers(remaining_frontiers, + distances['goal'], + distances['robot'], + num_frontiers_max) + # "move" the robot to the last frontier. + distances['robot'] = { + f: distances['frontier'][frozenset([f, latest_ordering[-1]])] for f in remaining_frontiers + } + _, updated_ordering = lsp.core.get_lowest_cost_ordering(remaining_frontiers, distances) + latest_ordering += updated_ordering + remaining_frontiers = [f for f in subgoals if f not in latest_ordering] + return latest_ordering + + +def eval_alternate_policies(step_data, correct_subgoals, alternate_policies, start_pose, goal_pose): + # final_subgoals = step_data[-1][1] + # final_masked_grid = lsp.core.mask_grid_with_frontiers(step_data[-1][2], final_subgoals) + # known_path = get_path_in_known_grid(final_masked_grid, start_pose, goal_pose, final_subgoals, do_not_mask=None) + # known_cost = compute_cost_from_path(known_path) + # correct_subgoals = [] + # for i, (robot_pose, subgoals, inflated_grid, is_goal_visible) in enumerate(step_data): + # if is_goal_visible: + # break + # for subgoal in subgoals: + # if is_feasible_subgoal(subgoal, final_masked_grid, subgoals, robot_pose, goal_pose): + # correct_subgoals.append(subgoal) + # break + + alt_visited_subgoals = set() + delta_cost_array = [] + for i, (robot_pose, subgoals, inflated_grid, is_goal_visible) in enumerate(step_data): + if is_goal_visible: + break + correct_subgoal = correct_subgoals[i] + # plt.ion() + # plt.figure(1) + # plt.clf() + # ax = plt.subplot(111) + # lsp_select.utils.plotting.plot_pose(ax, robot_pose, color='blue') + # lsp_select.utils.plotting.plot_grid_with_frontiers( + # ax, inflated_grid, None, subgoals) + # plt.scatter(*correct_subgoal.get_frontier_point()) + # plt.show() + # plt.pause(0.01) + # input() + _, _, sel_cost = get_subgoals_path_cost([correct_subgoal], [correct_subgoal], + subgoals, + robot_pose, + inflated_grid, + is_goal_visible) + alternate_policy = [s for s in alternate_policies[i] if s not in alt_visited_subgoals] + # alternate_policy = alternate_policies[i] + # print(f'correct_subgoal:{correct_subgoal.get_frontier_point()}') + # print(f'alternate_policy:\n {[s.get_frontier_point() for s in alternate_policy]}') + alt_subgoals, alt_path, alt_cost = get_subgoals_path_cost([correct_subgoal], alternate_policy, + subgoals, + robot_pose, + inflated_grid, + is_goal_visible) + # print([s.get_frontier_point() for s in alt_subgoals]) + delta_cost = max(0, alt_cost - sel_cost) + delta_cost_array.append(delta_cost) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(111) + lsp_select.utils.plotting.plot_pose(ax, robot_pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, inflated_grid, None, subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal_pose, color='green', filled=False) + # lsp_select.utils.plotting.plot_path(ax, alt_path, style='r:') + for j, s in enumerate(alternate_policies[i]): + # if s == correct_subgoal: + # # break + # point = s.get_frontier_point() + # plt.scatter(*point, c='green') + # for j, s in enumerate(alt_subgoals): # noqa:E115 + # if s in alt_visited_subgoals: + # continue + point = s.get_frontier_point() + plt.scatter(*point, c='red') + # plt.text(*point, str(j)) + correct_point = correct_subgoal.get_frontier_point() + plt.scatter(*correct_point, c='green') + # plt.text(*correct_point, ' true') + plt.title(f'{delta_cost=:.2f}') + plt.show() + plt.pause(0.01) + input() + + alt_visited_subgoals.update(alt_subgoals[:-1]) + + return delta_cost_array + + +def aggregate_delta_costs(delta_costs, min_non_zero_len=2, min_zero_len=2): + def remove_conjecutive_zeros(delta_costs, min_zero_len=1): + for _ in range(min_zero_len - 1): + final_arr = [] + was_prev_zero = False + for i in range(len(delta_costs)): + if delta_costs[i] == 0: + if was_prev_zero: + final_arr.append(delta_costs[i]) + continue + else: + was_prev_zero = True + else: + final_arr.append(delta_costs[i]) + was_prev_zero = False + delta_costs = np.array(final_arr) + return delta_costs + delta_costs = np.array(delta_costs, dtype=float) + delta_costs = remove_conjecutive_zeros(delta_costs, min_zero_len) + # print(delta_costs) + delta_costs[delta_costs == 0] = np.inf + aggregate_array = [] + for sub_cost in np.split(delta_costs, np.where(delta_costs == np.inf)[0]): + if len(sub_cost) > min_non_zero_len: + aggregate_array.append(np.min(sub_cost)) + aggregate_array = np.array(aggregate_array) + # print(aggregate_array) + return aggregate_array.sum() + + +# def aggregate_delta_costs(delta_costs, min_len=1): +# delta_costs = np.array(delta_costs, dtype=float) +# delta_costs[delta_costs == 0] = np.inf +# total_delta_cost = 0 +# for sub_cost in np.split(delta_costs, np.where(delta_costs == np.inf)[0]): +# if len(sub_cost) > min_len: +# total_delta_cost += np.min(sub_cost) +# return total_delta_cost + + +def check_identical_subgoals(current_subgoal, last_subgoal, inflated_grid, current_all_subgoals, robot_pose, goal_pose): + masked_grid_s1 = lsp.core.mask_grid_with_frontiers(inflated_grid, current_all_subgoals, do_not_mask=current_subgoal) + masked_grid_s2 = lsp.core.mask_grid_with_frontiers(masked_grid_s1, [last_subgoal]) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + masked_grid_s2, [goal_pose.x, goal_pose.y], use_soft_cost=False) + did_plan, _ = get_path([robot_pose.x, robot_pose.y], + do_sparsify=False, + do_flip=False) + return not did_plan + + +def get_subgoals_path_cost(policy1, policy2, all_subgoals, pose, inflated_grid, + is_goal_visible): + if is_goal_visible: + return [], np.array([[], []]), 0 + alt_subgoals = compute_alt_subgoals(policy1, policy2) + alt_path = compute_subgoals_path(alt_subgoals, all_subgoals, pose, inflated_grid) + alt_cost = compute_cost_from_path(alt_path) + return alt_subgoals, alt_path, alt_cost + + +def compute_alt_subgoals(policy1, policy2): + if len(policy2) == 0 or policy1[0] == policy2[0]: + return [policy1[0]] + alt_subgoals = [] + for s in policy2: + alt_subgoals.append(s) + if s == policy1[0]: + break + return alt_subgoals + + +def compute_subgoals_path(path_subgoals, all_subgoals, pose, inflated_grid): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, all_subgoals) + path_points = [[pose.x, pose.y]] + for subgoal in path_subgoals: + planning_grid[subgoal.points[0], subgoal.points[1]] = FREE_VAL + planning_grid[planning_grid == UNOBSERVED_VAL] = COLLISION_VAL + path_points.append(subgoal.get_frontier_point()) + path_points = np.array(path_points) + + alt_path = [[], []] + for i in range(len(path_points) - 1): + start = path_points[i] + end = path_points[i + 1] + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, end, use_soft_cost=True) + did_plan, path = get_path(start, do_sparsify=True, do_flip=True) + if did_plan: + alt_path[0].extend(path[0]) + alt_path[1].extend(path[1]) + return np.array(alt_path) + + +def compute_cost_from_path(path): + return np.linalg.norm(path[:, 1:] - path[:, :-1], axis=0).sum() + + +def get_path_in_known_grid(inflated_grid, pose, goal, subgoals, do_not_mask=None): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, subgoals, do_not_mask=do_not_mask) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + _, path = get_path([pose.x, pose.y], do_sparsify=True, do_flip=True) + return path + + +def generate_cost_data(args): + args.planners = [LearnedSubgoalPlanner, LSPCycleGAN] + navigation_data_1 = maze_eval(args) + actual_cost_1 = navigation_data_1['net_motion'] + known_cost = navigation_data_1['known_cost'] + delta_cost_2_array = eval_alternate_policies(navigation_data_1['steps'], + navigation_data_1['correct_subgoals'], + navigation_data_1['policies'][1], + navigation_data_1['start_pose'], + navigation_data_1['goal_pose']) + args.planners = args.planners[::-1] + navigation_data_2 = maze_eval(args) + actual_cost_2 = navigation_data_2['net_motion'] + delta_cost_1_array = eval_alternate_policies(navigation_data_2['steps'], + navigation_data_2['correct_subgoals'], + navigation_data_2['policies'][1], + navigation_data_2['start_pose'], + navigation_data_2['goal_pose']) + return known_cost, actual_cost_1, actual_cost_2, delta_cost_1_array, delta_cost_2_array + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--planner', choices=['lsp', 'lspcyclegan', 'nonlearned']) + parser.add_argument('--env', choices=['envA', 'envB', 'envC']) + args = parser.parse_args() + + # args.current_seed = 923 + # costs_data = generate_cost_data(args) + + for seed in range(*args.seed): + filepath = Path(args.save_dir) / f'actualcosts_{seed}.txt' + if filepath.is_file(): + print(f'Data already exists for {seed=}.') + continue + + print(f'Generating data for {seed=}.') + args.current_seed = seed + costs_data = generate_cost_data(args) + np.savetxt(filepath, costs_data[:3], fmt='%.4f') + np.savetxt(Path(args.save_dir) / f'deltacosts1_{seed}.txt', costs_data[3], fmt='%.4f') + np.savetxt(Path(args.save_dir) / f'deltacosts2_{seed}.txt', costs_data[4], fmt='%.4f') + + files = Path(args.save_dir).glob('actualcosts_*.txt') + actual_costs = np.array([np.loadtxt(f) for f in sorted(files)]) + known_cost = actual_costs[:, 0] + actual_cost_1 = actual_costs[:, 1] + actual_cost_2 = actual_costs[:, 2] + + files1 = Path(args.save_dir).glob('deltacosts1_*.txt') + delta_costs_1 = [np.loadtxt(f) for f in sorted(files1)] + files2 = Path(args.save_dir).glob('deltacosts2_*.txt') + delta_costs_2 = [np.loadtxt(f) for f in sorted(files2)] + + delta_cost_1 = [aggregate_delta_costs(dc, 3, 2) for dc in delta_costs_1] + delta_cost_2 = [aggregate_delta_costs(dc, 3, 2) for dc in delta_costs_2] + + if args.do_plot: + plt.ioff() + plt.subplot(121) + # act_delta_cost_2 = np.maximum(0, actual_cost_2 - known_cost) + # plt.scatter(actual_cost_2, known_cost + delta_cost_2) + for i, (x, y) in enumerate(zip(actual_cost_2, known_cost + delta_cost_2), 900): + plt.scatter(x, y, color='tab:blue', alpha=0.6) + # plt.text(x, y, str(i), fontdict={'size': 8}) + plt.plot([0, 1400], [0, 1400], 'r:') + + # A1 = np.vstack([est_delta_cost_1, np.ones(len(est_delta_cost_1))]).T + # m1, c1 = np.linalg.lstsq(A1, delta_cost_2, rcond=None)[0] + # plt.plot(est_delta_cost_1, m1 * est_delta_cost_1 + c1, 'g', label='Fitted line') + + plt.xlabel(r'$P_B$') + plt.ylabel(r'$\hat{P_B}$') + plt.axis('equal') + plt.title(r'LearnedSubgoalPlanner ($P_A$) in control') + + plt.subplot(122) + # act_delta_cost_1 = np.maximum(0, actual_cost_1 - known_cost) + # plt.scatter(actual_cost_1, known_cost + delta_cost_1) + for i, (x, y) in enumerate(zip(actual_cost_1, known_cost + delta_cost_1), 900): + plt.scatter(x, y, color='tab:blue', alpha=0.6) + # plt.text(x, y, str(i), fontdict={'size': 8}) + plt.plot([0, 400], [0, 400], 'r:') + + # A2 = np.vstack([est_delta_cost_2, np.ones(len(est_delta_cost_2))]).T + # m2, c2 = np.linalg.lstsq(A2, delta_cost_1, rcond=None)[0] + # plt.plot(est_delta_cost_2, m2 * est_delta_cost_2 + c2, 'g', label='Fitted line') + plt.xlabel(r'$P_A$') + plt.ylabel(r'$\hat{P_A}$') + plt.axis('equal') + plt.title(r'LSPCycleGAN ($P_B$) in control') + # plt.xlabel('True delta cost') + # plt.ylabel('Estimated delta cost') + # plt.axis('equal') + # plt.title('LSPCycleGAN in control') + + # plt.subplot(223) + # plt.scatter(act_delta_cost_1 - act_delta_cost_2, act_delta_cost_1 - delta_cost_2) + # plt.xlabel(r'$\nabla P_A - \hat{\nabla} P_B$') + # plt.ylabel(r'$\nabla P_A - \nabla P_B$') + # plt.axis('equal') + + # plt.subplot(224) + # plt.scatter(act_delta_cost_2 - act_delta_cost_1, act_delta_cost_2 - delta_cost_1) + # plt.xlabel(r'$\nabla P_B - \hat{\nabla} P_A$') + # plt.ylabel(r'$\nabla P_B - \nabla P_A$') + # plt.axis('equal') + plt.show() diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_nav_cost_data.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_nav_cost_data.py new file mode 100644 index 0000000..4ceef96 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_nav_cost_data.py @@ -0,0 +1,183 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +import gridmap +from pathlib import Path +import scipy.stats as stats +from lsp_select.planners import LearnedSubgoalPlanner +from lsp_select.utils.distribution import get_cost_distribution, corrupt_robot_pose +import sys + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + np.random.seed(args.current_seed) + pose = corrupt_robot_pose(known_map, args) if args.do_corrupt_pose else pose + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planner = LearnedSubgoalPlanner(goal=goal, args=args) + probs_costs_motion = {'probs': [], 'costs': [], 'motion': []} + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + if args.chosen_model == 'learned': + chosen_frontier = planner.compute_selected_subgoal() + planning_loop.set_chosen_subgoal(chosen_frontier) + + if planning_loop.chosen_subgoal is not None: + distances = lsp.core.compute_distances(planner.latest_ordering, + step_data['robot_grid'], + step_data['robot_pose'], + goal) + probs, costs = get_cost_distribution(planner.latest_ordering, distances) + # expected_cost = planner.expected_cost + probs_costs_motion['probs'].append(probs) + probs_costs_motion['costs'].append(costs) + probs_costs_motion['motion'].append(robot.net_motion) + + if args.do_plot: + if planning_loop.chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + planner.subgoals, + do_not_mask=planning_loop.chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(234) + plt.title(f'Using {args.chosen_model}') + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + + if planning_loop.chosen_subgoal is not None: + plt.subplot(235) + plt.title('Individual Gaussians') + pdfs = [] + min_mu_idx, max_mu_idx = costs[:, 0].argmin(), costs[:, 0].argmax() + x = np.linspace(costs[min_mu_idx, 0] - 3 * costs[min_mu_idx, 1], + costs[max_mu_idx, 0] + 3 * costs[max_mu_idx, 1], 1000) + for p, (mu, sigma) in zip(probs, costs): + y = stats.norm.pdf(x, mu, sigma) + plt.plot(x, y) + pdfs.append(p * y) + plt.subplot(236) + plt.plot(x, np.sum(np.array(pdfs), axis=0), color='tab:blue') + plt.title('Gaussian Mixture') + + plt.show() + plt.pause(0.1) + distance = [] + likelihood = [] + tot_distance = robot.net_motion + for probs, costs, motion in zip(*probs_costs_motion.values()): + # print(probs, costs, motion) + mu, sigma = costs.T + pdf = stats.norm.pdf(tot_distance - motion, mu, sigma) + distance.append(tot_distance - motion) + likelihood.append(np.sum(probs * pdf)) + # plt.savefig(Path(args.save_dir)/f'end_map.png', dpi=150) + return distance, likelihood, tot_distance + + +def save_data_2(nll, tot_distance, model, do_corrupt_pose, args): + filename = model + '_corrupted' if do_corrupt_pose else model + '_uncorrupted' + with open(f'{Path(args.save_dir)/filename}.csv', 'a') as file: + file.write(f'{args.current_seed},{tot_distance},{nll}\n') + + +def save_data(distance, likelihood, tot_distance, model, do_corrupt_pose, args): + filename = model + '_corrupted' if do_corrupt_pose else model + '_uncorrupted' + if model == 'non_learned': + data, fmt = [tot_distance], '%.2f' + else: + data, fmt = np.vstack([distance, likelihood]).T, ['%.2f', '%.20e'] + np.savetxt(Path(args.save_dir) / 'data' / f'{filename}_{args.current_seed}.gz', data, fmt=fmt) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--no_of_maps', type=int) + args = parser.parse_args() + + setup = [('learned', False), + ('learned', True), + ('non_learned', False), + ('non_learned', True)] + + args.current_seed = args.seed[0] + no_of_explored_maps = 0 + + while no_of_explored_maps < args.no_of_maps: + cost_data = {i: None for i in setup} + for model, do_corrupt_pose in setup: + args.chosen_model = model + args.do_corrupt_pose = do_corrupt_pose + stdout = sys.stdout + sys.stdout = open('/dev/null', 'w') + distance, likelihood, tot_distance = maze_eval(args) + sys.stdout = stdout + print(f'{args.current_seed} {model} {do_corrupt_pose}\n{tot_distance}, {-np.log(np.mean(likelihood))}') + if args.chosen_model == 'learned' and len(likelihood) == 0: + break + cost_data[(model, do_corrupt_pose)] = distance, likelihood, tot_distance + + if None in cost_data.values(): + print(f'Skipping seed {args.current_seed}') + args.current_seed += 1 + continue + + print(f'Map {no_of_explored_maps+1}/{args.no_of_maps} successfully saved with seed {args.current_seed}.') + for (model, do_corrupt_pose), (distance, likelihood, tot_distance) in cost_data.items(): + save_data(distance, likelihood, tot_distance, model, do_corrupt_pose, args) + + args.current_seed += 1 + no_of_explored_maps += 1 diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_threshold.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_threshold.py new file mode 100644 index 0000000..7e95ed4 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_gen_threshold.py @@ -0,0 +1,118 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +from pathlib import Path +from lsp.planners import LearnedSubgoalPlanner +from sklearn.metrics import log_loss + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planner = LearnedSubgoalPlanner(goal=goal, args=args) + + subgoals_data = [] + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + # If goal is not visible (in which case chosen_subgoal is not None), collect data. + if planning_loop.chosen_subgoal is not None: + subgoals_data.append({ + 'subgoals': planner.subgoals, + 'robot_pose': planner.robot_pose}) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'{type(planner).__name__} (seed={args.current_seed})') + plt.show() + plt.pause(0.01) + + final_grid = lsp.core.mask_grid_with_frontiers(planner.inflated_grid, planner.subgoals) + return subgoals_data, final_grid, goal + + +def save_threshold(path): + path = Path(path) + files = path.glob('subgoal_probs_*.txt') + subgoal_data = [] + for f in sorted(files): + data = np.loadtxt(f) + subgoal_data.extend(data) + subgoal_data = np.array(subgoal_data) + cross_entropy = log_loss(subgoal_data[:, 2], subgoal_data[:, 1]) + with open(path / 'threshold.txt', 'w') as f: + f.write(f'{cross_entropy}') + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + args = parser.parse_args() + + for seed in range(*args.seed): + filepath = Path(args.save_dir) / f'subgoal_probs_{seed}.txt' + if filepath.is_file(): + print(f'Data already exists for {seed=}.') + continue + + print(f'Generating data for {seed=}.') + args.current_seed = seed + subgoals_data, final_grid, goal_pose = maze_eval(args) + + with open(filepath, 'w') as f: + if len(subgoals_data) != 0: + subgoal_labels = lsp_select.utils.misc.get_subgoal_labels(subgoals_data, final_grid, goal_pose) + np.savetxt(f, subgoal_labels, fmt=['%d', '%.6f', '%d']) + else: + f.write('') + print(f'No data to save for {seed=}.') + + save_threshold(args.save_dir) diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_laser_maze_eval.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_laser_maze_eval.py new file mode 100644 index 0000000..7954d1d --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_laser_maze_eval.py @@ -0,0 +1,91 @@ +import environments +import lsp +import lsp_select +import matplotlib.pyplot as plt +import gridmap + +from lsp_select.planners import LearnedSubgoalPlannerLaser + + +def maze_eval(args): + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planner = LearnedSubgoalPlannerLaser(goal=goal, args=args) + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image'], 'ranges': step_data['ranges']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + if planning_loop.chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + planner.subgoals, + do_not_mask=planning_loop.chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + plt.ion() + plt.figure(1) + plt.clf() + if step_data['image'] is not None: + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + else: + ax = plt.subplot(111) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.show() + plt.pause(0.01) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + args = parser.parse_args() + args.current_seed = args.seed[0] + maze_eval(args) diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection.py new file mode 100644 index 0000000..c0cb23e --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection.py @@ -0,0 +1,195 @@ +import environments +import lsp +import common +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +import gridmap +from pathlib import Path +import scipy.stats as stats + +from lsp_select.planners import LearnedSubgoalPlanner +from lsp_select.utils.distribution import get_cost_distribution + + +def maze_eval(args): + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + do_corrupt = np.random.binomial(1, args.corrupt_pose_prob) + pose = corrupt_robot_pose(known_map, args) if do_corrupt else pose + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planner = LearnedSubgoalPlanner(goal=goal, args=args) + probs_costs_motion = {'probs': [], 'costs': [], 'motion': []} + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + if args.chosen_model == 'learned': + chosen_frontier = planner.compute_selected_subgoal() + planning_loop.set_chosen_subgoal(chosen_frontier) + + if planning_loop.chosen_subgoal is not None: + distances = lsp.core.compute_distances(planner.latest_ordering, + step_data['robot_grid'], + step_data['robot_pose'], + goal) + probs, costs = get_cost_distribution(planner.latest_ordering, distances) + # expected_cost = planner.expected_cost + probs_costs_motion['probs'].append(probs) + probs_costs_motion['costs'].append(costs) + probs_costs_motion['motion'].append(robot.net_motion) + + if args.do_plot: + if planning_loop.chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + planner.subgoals, + do_not_mask=planning_loop.chosen_subgoal) + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(234) + plt.title(f'Using {args.chosen_model} model\nLast Avg NLL={args.avg_nll}') + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + + if planning_loop.chosen_subgoal is not None: + plt.subplot(235) + plt.title('Individual Gaussians') + pdfs = [] + min_mu_idx, max_mu_idx = costs[:, 0].argmin(), costs[:, 0].argmax() + x = np.linspace(costs[min_mu_idx, 0] - 3 * costs[min_mu_idx, 1], + costs[max_mu_idx, 0] + 3 * costs[max_mu_idx, 1], 1000) + for p, (mu, sigma) in zip(probs, costs): + y = stats.norm.pdf(x, mu, sigma) + plt.plot(x, y) + pdfs.append(p * y) + plt.subplot(236) + # for p in pdfs: + # plt.plot(x, p, '-.') + plt.plot(x, np.sum(np.array(pdfs), axis=0), color='tab:blue') + plt.title('Gaussion Mixture') + + plt.show() + plt.pause(0.1) + likelihood = [] + tot_distance = robot.net_motion + for probs, costs, motion in zip(*probs_costs_motion.values()): + # print(probs, costs, motion) + mu, sigma = costs.T + pdf = stats.norm.pdf(tot_distance - motion, mu, sigma) + likelihood.append(np.sum(probs * pdf)) + plt.savefig(Path(args.save_dir) / 'end_map.png', dpi=150) + return -np.log(np.mean(likelihood)) + + +def corrupt_robot_pose(known_map, args): + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_mask = gridmap.utils.inflate_grid(known_map, + inflation_radius=inflation_radius, + collision_val=lsp.constants.COLLISION_VAL) < 1 + # Now sample a random point + allowed_indices = np.where(inflated_mask) + idx_start = np.random.randint(0, allowed_indices[0].size - 1) + new_start_pose = common.Pose(x=allowed_indices[0][idx_start], + y=allowed_indices[1][idx_start], + yaw=2 * np.pi * np.random.rand()) + + return new_start_pose + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('-save_dir', type=str) + parser.add_argument('--network_file', type=str) + parser.add_argument('--corrupt_pose_prob', type=float, default=1.0) + args = parser.parse_args() + args.current_seed = args.seed[0] + np.random.seed(42) + likelihood_data = np.genfromtxt('/data/lsp_select/likelihood.txt', delimiter=',')[:, 1] + threshold = np.percentile(likelihood_data, 95) # 5.24 + prior_num_samples = 10 + mean_likelihood = np.mean(likelihood_data) + # prior_nll = (prior_num_samples + 1) * threshold - prior_num_samples * mean_likelihood + prior_nll = 48 + nll_history = [] + args.chosen_model = 'learned' + args.avg_nll = prior_nll / prior_num_samples + outfilename = f'nll_history_{args.corrupt_pose_prob}.txt' + with open(Path(args.save_dir) / outfilename, 'a') as file: + file.write(f'{args.corrupt_pose_prob=},{threshold=},{prior_nll=},{prior_num_samples=},{args.avg_nll=}\n') + maps_until_switch = [] + for seed in range(*args.seed): + args.current_seed = seed + nll = maze_eval(args) + if np.isnan(nll): + continue + nll_history.append(nll) + args.avg_nll = (np.sum(nll_history) + prior_nll) / (len(nll_history) + prior_num_samples) + print(f'{threshold=}\n{nll=}\n{args.avg_nll=}\n{len(nll_history)=}') + with open(Path(args.save_dir) / outfilename, 'a') as file: + file.write(f'{seed},{nll=},{args.avg_nll=}\n') + if args.avg_nll > threshold: + args.chosen_model = 'non-learned' + with open(Path(args.save_dir) / outfilename, 'a') as file: + file.write(f'Switching to non-learned model after {len(nll_history)} maps\n') + print(f'Switching to non-learned model after {len(nll_history)} maps') + maps_until_switch.append(len(nll_history)) + if len(maps_until_switch) >= 10: + with open(Path(args.save_dir) / outfilename, 'a') as file: + file.write(f'{maps_until_switch=}\navg_number_of_maps={np.mean(maps_until_switch)}') + break + # Reset experiment + nll_history = [] + args.chosen_model = 'learned' + args.avg_nll = prior_nll / prior_num_samples + outfilename = f'nll_history_{args.corrupt_pose_prob}.txt' + with open(Path(args.save_dir) / outfilename, 'a') as file: + file.write(f'{args.corrupt_pose_prob=},{threshold=},{prior_nll=},' + f'{prior_num_samples=},{args.avg_nll=}\n') diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection_eval.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection_eval.py new file mode 100644 index 0000000..47dd8f3 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_model_selection_eval.py @@ -0,0 +1,173 @@ +import lsp +import numpy as np +import matplotlib.pyplot as plt +from pathlib import Path +import re + + +def get_cost_learned(cost_data, args): + do_corrupt = np.random.binomial(1, args.corrupt_pose_prob, size=args.no_of_maps) + cost = (cost_data['learned_corrupted'][:, 1] * do_corrupt + + cost_data['learned_uncorrupted'][:, 1] * (1 - do_corrupt)) + return np.mean(cost) + + +def get_cost_non_learned(cost_data, args): + do_corrupt = np.random.binomial(1, args.corrupt_pose_prob, size=args.no_of_maps) + cost = (cost_data['non_learned_corrupted'][:, 1] * do_corrupt + + cost_data['non_learned_uncorrupted'][:, 1] * (1 - do_corrupt)) + return np.mean(cost) + + +def get_cost_ideal_model_selection(cost_data, args): + do_corrupt = np.random.binomial(1, args.corrupt_pose_prob, size=args.no_of_maps) + cost_learned = (cost_data['learned_corrupted'][:, 1] * do_corrupt + + cost_data['learned_uncorrupted'][:, 1] * (1 - do_corrupt)) + cost_non_learned = (cost_data['non_learned_corrupted'][:, 1] * do_corrupt + + cost_data['non_learned_uncorrupted'][:, 1] * (1 - do_corrupt)) + switch = do_corrupt + cost = cost_learned * (1 - switch) + cost_non_learned * switch + return np.mean(cost) + + +def get_cost_our_model_selection(cost_data, args): + do_corrupt = np.random.binomial(1, args.corrupt_pose_prob, size=args.no_of_maps) + nll_learned = (cost_data['learned_corrupted'][:, 2] * do_corrupt + + cost_data['learned_uncorrupted'][:, 2] * (1 - do_corrupt)) + num_samples = (cost_data['learned_corrupted'][:, 3] * do_corrupt + + cost_data['learned_uncorrupted'][:, 3] * (1 - do_corrupt)) + if args.stepwise_eval: + avg_nll = ((np.cumsum(nll_learned) + args.prior_nll) + / (np.cumsum(num_samples) + args.prior_num_samples)) + avg_nll = -np.log(avg_nll) + else: + avg_nll = ((np.cumsum(-np.log(nll_learned / num_samples)) + args.prior_nll) + / (np.arange(1, args.no_of_maps + 1) + args.prior_num_samples)) + switch = avg_nll > args.threshold + switch_idx = np.where(switch)[0] + switch_idx = switch_idx[0] if len(switch_idx) else len(switch) - 1 + args.switch_idx = switch_idx + switch[switch_idx:] = True + cost_learned = (cost_data['learned_corrupted'][:, 1] * do_corrupt + + cost_data['learned_uncorrupted'][:, 1] * (1 - do_corrupt)) + cost_non_learned = (cost_data['non_learned_corrupted'][:, 1] * do_corrupt + + cost_data['non_learned_uncorrupted'][:, 1] * (1 - do_corrupt)) + cost = cost_learned * (1 - switch) + cost_non_learned * switch + return np.mean(cost) + + +def read_data(data_files, args, aggregate=True): + path = Path(args.save_dir) / 'data' + files = {x: path.glob(f'{x}_*.gz') for x in data_files} + cost_data = {x: [] for x in data_files} + for model, data_path in files.items(): + for f in sorted(data_path): + seed = re.findall(r'\d+', f.name) + seed = int(seed[0]) if len(seed) != 0 else -1 + data = np.loadtxt(f) + data = data.reshape(-1, 2) if data.size != 1 else data + cost_data[model].append([seed, data]) + if not aggregate: + return cost_data + # Aggregate data per map + for model, seed_data in cost_data.items(): + map_data = [] + for seed, d in seed_data: + if d.ndim == 0: + map_data.append([seed, d, np.nan]) + else: + cost = d[0, 0] + likelihood_sum = d[:, 1].sum() + map_data.append([seed, cost, likelihood_sum, len(d)]) + cost_data[model] = np.array(map_data) + return cost_data + + +def set_parameters(args, plot=False): + likelihood_data = np.genfromtxt(Path(args.save_dir) / 'likelihood_stepwise.txt', delimiter=',') + if args.stepwise_eval: + likelihood_data = likelihood_data[:, 1] + args.threshold = np.percentile(-np.log(likelihood_data), 82) + args.prior_num_samples = 1000 + args.prior_nll = np.mean(likelihood_data) * args.prior_num_samples + if plot: + plt.hist(likelihood_data, bins=np.arange(0, 0.025, 0.001)) + th = np.exp(-args.threshold) + plt.axvline(x=th, color='tab:orange') + plt.title(f'stepwise_likelihood_training {th=:.4f}') + plt.show() + else: + seeds = np.unique(likelihood_data[:, 0]) + avg_likelihood = [] + for s in seeds: + idx = np.where(likelihood_data[:, 0] == s)[0] + avg_likelihood.append([s, likelihood_data[:, 1][idx].mean()]) + likelihood_data = np.array(avg_likelihood) + likelihood_data = -np.log(likelihood_data[:, 1]) + args.threshold = np.percentile(likelihood_data, 90) + args.prior_num_samples = 10 + args.prior_nll = np.mean(likelihood_data) * args.prior_num_samples + if plot: + plt.hist(likelihood_data, bins=np.arange(0, 10, 0.1)) + th = args.threshold + plt.axvline(x=th, color='tab:orange') + plt.title(f'mapwise_likelihood_training {th=:.4f}') + plt.show() + + +def plot_likelihood(cost_data, model, args): + seed_data = cost_data[model] + likelihood = [] + for seed, d in seed_data: + likelihood.extend([x for x in d[:, 1]]) + likelihood = np.array(likelihood) + plt.hist(likelihood, bins=np.arange(0, 0.025, 0.001)) + th = np.exp(-args.threshold) + plt.axvline(x=th, color='tab:orange') + plt.title(f'{model} ({th=:.4f})') + plt.show() + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--stepwise_eval', action='store_true') + args = parser.parse_args() + + data_files = ['learned_uncorrupted', 'learned_corrupted', 'non_learned_uncorrupted', 'non_learned_corrupted'] + cost_data = read_data(data_files, args, aggregate=True) + set_parameters(args) + # plot_likelihood(cost_data, 'learned_corrupted', args) + args.no_of_maps = len(cost_data['learned_uncorrupted']) + + models = ['learned', 'non_learned', 'ideal_model_selection', 'our_model_selection'] + dist_shift_proportion = np.arange(0, 1, 0.001) + results = {m: np.zeros_like(dist_shift_proportion) for m in models} + switch_data = np.zeros((len(dist_shift_proportion), 2)) + + for i, corrupt_pose_prob in enumerate(dist_shift_proportion): + np.random.seed(i) + args.corrupt_pose_prob = corrupt_pose_prob + cost_learned = get_cost_learned(cost_data, args) + results['learned'][i] = cost_learned + cost_non_learned = get_cost_non_learned(cost_data, args) + results['non_learned'][i] = cost_non_learned + cost_ideal_model_selection = get_cost_ideal_model_selection(cost_data, args) + results['ideal_model_selection'][i] = cost_ideal_model_selection + cost_our_model_selection = get_cost_our_model_selection(cost_data, args) + results['our_model_selection'][i] = cost_our_model_selection + switch_data[i] = [corrupt_pose_prob, args.switch_idx] + + plt.subplot(211) + for model, results in results.items(): + plt.plot(dist_shift_proportion, results, label=model) + + plt.xlabel('Proportion of distribution shifted maps') + plt.ylabel('Average cost of navigation') + plt.legend() + + plt.subplot(212) + plt.plot(switch_data[:, 0], switch_data[:, 1]) + plt.xlabel('Proportion of distribution shifted maps') + plt.ylabel('Number of maps until\nswitching to non-learned model') + plt.show() diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_eval.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_eval.py new file mode 100644 index 0000000..9511e20 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_eval.py @@ -0,0 +1,112 @@ +import environments +import lsp +import lsp_select +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner, DijkstraPlanner +from lsp_select.planners import LSPCycleGAN +from lsp_select.utils.distribution import corrupt_robot_pose +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + planner_dict = {'lspA': LearnedSubgoalPlanner, + 'lspB': LearnedSubgoalPlanner, + 'lspC': LearnedSubgoalPlanner, + 'lspcyclegan': LSPCycleGAN, + 'nonlearned': DijkstraPlanner} + planner = planner_dict[args.planner](goal=goal, args=args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'{type(planner).__name__} ({args.env})') + plt.xlabel(f'seed={args.current_seed}') + plt.show() + plt.pause(0.01) + plt.close() + plt.ioff() + plt.figure(2) + ax = plt.subplot(111) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'Cost: {robot.net_motion:.2f}') + plt.xlabel(f'seed={args.current_seed}') + plt.savefig(Path(args.save_dir) / f'plan_{args.planner}_{args.env}_{args.current_seed}.png') + + return robot.net_motion + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--planner', choices=['lspA', 'lspB', 'lspC', 'lspcyclegan', 'nonlearned']) + parser.add_argument('--env', choices=['envA', 'envB', 'envC']) + args = parser.parse_args() + + for seed in range(*args.seed): + filepath = Path(args.save_dir) / f'cost_{args.planner}_{args.env}_{seed}.txt' + if filepath.is_file(): + print(f'Data already exists for {args.planner}_{args.env}_{seed}.') + continue + + print(f'Generating data for {args.planner}_{args.env}_{seed}.') + args.current_seed = seed + tot_distance = maze_eval(args) + + with open(filepath, 'w') as f: + f.write(f'{tot_distance}') diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_results.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_results.py new file mode 100644 index 0000000..d2f9d95 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_planner_results.py @@ -0,0 +1,80 @@ +import lsp +import numpy as np +from pathlib import Path + + +def compute_bandit_cost(env_results, planners, c=4): + num_pulls_per_bandit = np.zeros(len(planners)) + tot_reward_per_bandit = np.zeros(len(planners)) + all_rewards = [] + num_steps = len(env_results) + + for i in range(num_steps): + min_idx = np.argmin(num_pulls_per_bandit) + if num_pulls_per_bandit[min_idx] == 0: + bandit_ind = min_idx + else: + mean_reward_per_bandit = tot_reward_per_bandit / num_pulls_per_bandit + bandit_ind = np.argmin(mean_reward_per_bandit - c * np.sqrt(np.log(num_pulls_per_bandit.sum()) + / num_pulls_per_bandit)) + + # Data Storage + reward = env_results[i, bandit_ind] + tot_reward_per_bandit[bandit_ind] += reward + num_pulls_per_bandit[bandit_ind] += 1 + all_rewards.append(reward) + + return np.mean(all_rewards), num_pulls_per_bandit + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args() + + planners = ['lspA', 'lspB', 'lspC', 'nonlearned', 'rtmlb'] + envs = ['envA', 'envB', 'envC'] + + print('--------------------Planner Results-------------------------') + results = np.zeros((len(planners), len(envs))) + for i, planner in enumerate(planners): + for j, env in enumerate(envs): + files = Path(args.save_dir).glob(f'cost_{planner}_{env}_*.txt') + costs = np.array([np.loadtxt(f) for f in sorted(files)]) + results[i, j] = costs.mean() + print(f'Rows: {planners}\nColumns: {envs}') + print('Average Cost:') + print(results) + + print('--------------------RTM-LB Results--------------------') + for env in envs: + files = Path(args.save_dir).glob(f'selected_rtmlb_{env}_*.txt') + selected = np.array([np.loadtxt(f, dtype=str) for f in sorted(files)]) + print(f'--------------------{env}--------------------') + print('Number of times each planner was selected:') + for planner, count in zip(*np.unique(selected, return_counts=True)): + print(f'{planner:<25}{count:>4}') + idx = np.where(selected == 'DijkstraPlanner[0]')[0] + print(f'\nLast map where non-learned planner was selected: {idx[-1]}\n') + + print('--------------------UCB-Bandit Results--------------------') + planners = ['nonlearned', 'lspA', 'lspB', 'lspC'] + bandit_costs = np.zeros(len(envs)) + planner_counts = np.zeros((len(planners), len(envs))) + for i, env in enumerate(envs): + env_results = [] + for j, planner in enumerate(planners): + files = Path(args.save_dir).glob(f'cost_{planner}_{env}_*.txt') + costs = np.array([np.loadtxt(f) for f in sorted(files)]) + env_results.append(costs) + env_results = np.array(env_results).T + avg_cost, counts = compute_bandit_cost(env_results, planners) + bandit_costs[i] = avg_cost + planner_counts[:, i] = counts + + print('Average Costs') + print(envs) + print(bandit_costs) + print('Number of times each planner was selected:') + print(f'Rows: {planners}\nColumns: {envs}') + print(planner_counts) diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_delta_eval.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_delta_eval.py new file mode 100644 index 0000000..3fb420b --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_delta_eval.py @@ -0,0 +1,116 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner +from lsp_select.planners import LSPCycleGAN, RTMDelta +from lsp_select.utils.distribution import corrupt_robot_pose +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + np.random.seed(args.current_seed) + goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planners = [LearnedSubgoalPlanner(goal=goal, args=args), + LSPCycleGAN(goal=goal, args=args)] + args.robot = robot + args.robot_pose = pose + planner = RTMDelta(goal, planners, args.priors, args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'RTMDelta - {planner.chosen_planner_name} ({args.env})') + plt.xlabel(f'seed={args.current_seed}\n' + f'Avg. Estimated Cost: Dijkstra={planner.avg_estimated_costs[0]:.2f}, ' + f'LSP={planner.avg_estimated_costs[1]:.2f}, ' + f'LSPCycleGAN={planner.avg_estimated_costs[2]:.2f}') + plt.show() + plt.pause(0.01) + + return robot.net_motion, planner + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--env', choices=['envA', 'envB', 'envC']) + + args = parser.parse_args() + + args.planner = 'rtmdelta' + args.priors = None + + for seed in range(*args.seed): + cost_file = Path(args.save_dir) / f'cost_{args.planner}_{args.env}_{seed}.txt' + priors_file = Path(args.save_dir) / f'priors_{args.planner}_{args.env}_{seed}.txt' + if cost_file.is_file() and priors_file.is_file(): + print(f'Data already exists for {seed=}.') + args.priors = np.genfromtxt(priors_file)[-1].reshape(-1, 2) + continue + + print(f'Generating data for {seed=}.') + args.current_seed = seed + tot_distance, planner = maze_eval(args) + + priors = planner.compute_new_priors() + chosen_planner = planner.chosen_planner_name + with open(cost_file, 'w') as f: + f.write(f'{tot_distance}') + with open(priors_file, 'w') as f: + np.savetxt(f, planner.priors.reshape(1, -1)) + np.savetxt(f, priors.reshape(1, -1)) + with open(Path(args.save_dir) / f'selected_{args.planner}_{args.env}_{seed}.txt', 'w') as f: + f.write(f'{chosen_planner}') + args.priors = priors diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_eval.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_eval.py new file mode 100644 index 0000000..5c4f3f7 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_eval.py @@ -0,0 +1,116 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner +from lsp_select.planners import LSPCycleGAN, RuntimeMonitoringPlanner +from lsp_select.utils.distribution import corrupt_robot_pose +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + np.random.seed(args.current_seed) + goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planners = [LearnedSubgoalPlanner(goal=goal, args=args), + LSPCycleGAN(goal=goal, args=args)] + planner = RuntimeMonitoringPlanner(goal, planners, args.priors, args.threshold, args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'RTM - {planner.chosen_planner_name} ({args.env})') + plt.xlabel(f'seed={args.current_seed}, threshold={args.threshold}\n' + f'Cross Entropy: LSP={planner.xentropy_avg[0]:.6f}, ' + f'LSPCycleGAN={planner.xentropy_avg[1]:.6f}') + plt.show() + plt.pause(0.01) + + return robot.net_motion, planner + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_file', type=str) + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--env', choices=['envA', 'envB', 'envC']) + parser.add_argument('--threshold', type=float, default=0.09) + + args = parser.parse_args() + + args.planner = 'rtm' + prior_no_of_obs = 5000 + args.priors = np.array([[2.0 * prior_no_of_obs, prior_no_of_obs], + [2.0 * prior_no_of_obs, prior_no_of_obs]]) + + for seed in range(*args.seed): + cost_file = Path(args.save_dir) / f'cost_{args.planner}_{args.env}_{seed}.txt' + priors_file = Path(args.save_dir) / f'priors_{args.planner}_{args.env}_{seed}.txt' + if cost_file.is_file() and priors_file.is_file(): + print(f'Data already exists for {seed=}.') + args.priors = np.genfromtxt(priors_file)[-1].reshape(-1, 2) + continue + + print(f'Generating data for {seed=}.') + args.current_seed = seed + tot_distance, planner = maze_eval(args) + + priors = planner.compute_new_priors() + chosen_planner = planner.chosen_planner_name + with open(cost_file, 'w') as f: + f.write(f'{tot_distance}') + with open(priors_file, 'w') as f: + np.savetxt(f, args.priors.reshape(1, -1)) + np.savetxt(f, priors.reshape(1, -1)) + with open(Path(args.save_dir) / f'selected_{args.planner}_{args.env}_{seed}.txt', 'w') as f: + f.write(f'{chosen_planner}') + args.priors = priors diff --git a/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_lb_eval.py b/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_lb_eval.py new file mode 100644 index 0000000..2f6c622 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/scripts/lsp_rtm_lb_eval.py @@ -0,0 +1,120 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner +from lsp_select.planners import RTMLowerBound +from lsp_select.utils.distribution import corrupt_robot_pose +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + planners = [] + for network in args.network_files: + args.network_file = str(Path(args.network_path) / network) + planners.append(LearnedSubgoalPlanner(goal=goal, args=args)) + args.robot = robot + args.robot_pose = pose + args.map_shape = known_map.shape + args.known_map = known_map + planner = RTMLowerBound(goal, planners, args.priors, args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'RTMLB - {planner.chosen_planner_name}[{planner.chosen_planner_idx}] ({args.env})') + plt.xlabel(f'seed={args.current_seed}\n' + f'Avg. Cost: Dijkstra={planner.avg_estimated_costs[0]:.2f}, ' + f'LSP-A={planner.avg_estimated_costs[1]:.2f}, ' + f'LSP-B={planner.avg_estimated_costs[2]:.2f}, ' + f'LSP-C={planner.avg_estimated_costs[3]:.2f}') + plt.show() + plt.pause(0.01) + + return robot.net_motion, planner + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_path', type=str) + parser.add_argument('--network_files', type=str, nargs='+') + parser.add_argument('--generator_network_file', type=str) + parser.add_argument('--disable_cyclegan', action='store_true') + parser.add_argument('--env', choices=['envA', 'envB', 'envC']) + + args = parser.parse_args() + + args.planner = 'rtmlb' + args.priors = None + + for seed in range(*args.seed): + cost_file = Path(args.save_dir) / f'cost_{args.planner}_{args.env}_{seed}.txt' + priors_file = Path(args.save_dir) / f'priors_{args.planner}_{args.env}_{seed}.txt' + if cost_file.is_file() and priors_file.is_file(): + print(f'Data already exists for {args.planner}_{args.env}_{seed}.') + args.priors = np.genfromtxt(priors_file)[-1].reshape(-1, 2) + continue + + print(f'Generating data for {args.planner}_{args.env}_{seed}.') + args.current_seed = seed + tot_distance, planner = maze_eval(args) + + priors = planner.compute_new_priors() + with open(cost_file, 'w') as f: + f.write(f'{tot_distance}') + with open(priors_file, 'w') as f: + np.savetxt(f, planner.priors.reshape(1, -1)) + np.savetxt(f, priors.reshape(1, -1)) + with open(Path(args.save_dir) / f'selected_{args.planner}_{args.env}_{seed}.txt', 'w') as f: + f.write(f'{planner.chosen_planner_name}[{planner.chosen_planner_idx}]') + args.priors = priors diff --git a/modules/lsp_select/lsp_select/scratch/tests/test_cost_distribution.py b/modules/lsp_select/lsp_select/scratch/tests/test_cost_distribution.py new file mode 100644 index 0000000..3a51178 --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/tests/test_cost_distribution.py @@ -0,0 +1,53 @@ +import numpy as np +import lsp +import lsp_select + + +def test_cost_distribution(): + f1 = lsp.core.Frontier(points=np.array([[1, 2, 3], [2, 3, 4]])) + f1.set_props(prob_feasible=0.8, + delta_success_cost=11, + exploration_cost=33, + delta_success_cost_std=2, + exploration_cost_std=3) + f2 = lsp.core.Frontier(points=np.array([[3, 4, 5], [5, 6, 7]])) + f2.set_props(prob_feasible=0.2, + delta_success_cost=14, + exploration_cost=26, + delta_success_cost_std=4, + exploration_cost_std=5) + f3 = lsp.core.Frontier(points=np.array([[6, 7, 8], [7, 8, 9]])) + f3.set_props(prob_feasible=0.3, + delta_success_cost=15, + exploration_cost=27, + delta_success_cost_std=6, + exploration_cost_std=7) + distances = { + 'frontier': {frozenset([f1, f2]): 17, frozenset([f1, f3]): 12, frozenset([f2, f3]): 10}, + 'robot': {f1: 5, f2: 8, f3: 6}, + 'goal': {f1: 21, f2: 23, f3: 25} + } + probs, costs = lsp_select.utils.distribution.get_cost_distribution([f1, f2, f3], distances) + + actual_probs = [f1.prob_feasible, + (1 - f1.prob_feasible) * f2.prob_feasible, + (1 - f1.prob_feasible) * (1 - f2.prob_feasible) * f3.prob_feasible, + (1 - f1.prob_feasible) * (1 - f2.prob_feasible) * (1 - f3.prob_feasible)] + assert np.allclose(probs, actual_probs) + + actual_costs_mean = [distances['robot'][f1] + distances['goal'][f1] + f1.delta_success_cost, + distances['robot'][f1] + f1.exploration_cost + distances['frontier'][frozenset([f1, f2])] + + distances['goal'][f2] + f2.delta_success_cost, + distances['robot'][f1] + f1.exploration_cost + distances['frontier'][frozenset([f1, f2])] + + f2.exploration_cost + distances['frontier'][frozenset([f2, f3])] + + distances['goal'][f3] + f3.delta_success_cost, + distances['robot'][f1] + f1.exploration_cost + distances['frontier'][frozenset([f1, f2])] + + f2.exploration_cost + distances['frontier'][frozenset([f2, f3])] + + f3.exploration_cost] + assert np.allclose(costs[:, 0], actual_costs_mean) + + actual_costs_std = [f1.delta_success_cost_std, + (f1.exploration_cost_std**2 + f2.delta_success_cost_std**2)**0.5, + (f1.exploration_cost_std**2 + f2.exploration_cost_std**2 + f3.delta_success_cost_std**2)**0.5, + (f1.exploration_cost_std**2 + f2.exploration_cost_std**2 + f3.exploration_cost_std**2)**0.5] + assert np.allclose(costs[:, 1], actual_costs_std) diff --git a/modules/lsp_select/lsp_select/scratch/utils/delta_cost.py b/modules/lsp_select/lsp_select/scratch/utils/delta_cost.py new file mode 100644 index 0000000..273fbbd --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/utils/delta_cost.py @@ -0,0 +1,233 @@ +import numpy as np +import lsp +import copy +import gridmap +from lsp.constants import FREE_VAL, UNOBSERVED_VAL, COLLISION_VAL + + +def get_full_policy(latest_ordering, subgoals, inflated_grid, robot_pose, goal, num_frontiers_max=12): + if latest_ordering is None and len(subgoals) == 1: + latest_ordering = [list(subgoals)[0]] + remaining_frontiers = [f for f in subgoals if f not in latest_ordering] + distances = lsp.core.compute_distances(subgoals, + inflated_grid, + robot_pose, + goal) + while len(latest_ordering) < len(subgoals): + distances_ = copy.copy(distances) + remaining_frontiers = [f for f in subgoals if f not in latest_ordering] + if len(remaining_frontiers) > num_frontiers_max: + remaining_frontiers = lsp.core.get_top_n_frontiers(remaining_frontiers, + distances_['goal'], + distances_['robot'], + num_frontiers_max) + # "move" the robot to the last frontier. + distances_['robot'] = { + f: distances_['frontier'][frozenset([f, latest_ordering[-1]])] for f in remaining_frontiers + } + _, updated_ordering = lsp.core.get_lowest_cost_ordering(remaining_frontiers, distances_) + latest_ordering += updated_ordering + remaining_frontiers = [f for f in subgoals if f not in latest_ordering] + return latest_ordering + + +def eval_alternate_policies(step_data, correct_subgoals, alternate_policies, start_pose, goal_pose): + alt_visited_subgoals = set() + delta_cost_array = [] + for i, (robot_pose, subgoals, inflated_grid, is_goal_visible) in enumerate(step_data): + if is_goal_visible: + break + correct_subgoal = correct_subgoals[i] + _, _, sel_cost = get_subgoals_path_cost([correct_subgoal], [correct_subgoal], + subgoals, + robot_pose, + inflated_grid, + is_goal_visible) + alternate_policy = [s for s in alternate_policies[i] if s not in alt_visited_subgoals] + # alternate_policy = alternate_policies[i] + # print(f'correct_subgoal:{correct_subgoal.get_frontier_point()}') + # print(f'alternate_policy:\n {[s.get_frontier_point() for s in alternate_policy]}') + alt_subgoals, alt_path, alt_cost = get_subgoals_path_cost([correct_subgoal], alternate_policy, + subgoals, + robot_pose, + inflated_grid, + is_goal_visible) + # print([s.get_frontier_point() for s in alt_subgoals]) + delta_cost = max(0, alt_cost - sel_cost) + delta_cost_array.append(delta_cost) + + # if args.do_plot: + # plt.ion() + # plt.figure(1) + # plt.clf() + # ax = plt.subplot(111) + # lsp_select.utils.plotting.plot_pose(ax, robot_pose, color='blue') + # lsp_select.utils.plotting.plot_grid_with_frontiers( + # ax, inflated_grid, None, subgoals) + # lsp_select.utils.plotting.plot_pose(ax, goal_pose, color='green', filled=False) + # lsp_select.utils.plotting.plot_path(ax, alt_path, style='r:') + # # for j, s in enumerate(alternate_policies[i]): + # # if s == correct_subgoal: + # # break + # # point = s.get_frontier_point() + # # plt.scatter(*point) + # for j, s in enumerate(alt_subgoals): + # # if s in alt_visited_subgoals: + # # continue + # point = s.get_frontier_point() + # plt.scatter(*point) + # plt.text(*point, str(j)) + # correct_point = correct_subgoal.get_frontier_point() + # plt.scatter(*correct_point, c='green') + # plt.text(*correct_point, ' true') + # plt.title(f'{delta_cost=:.2f}') + # plt.show() + # plt.pause(0.01) + # input() + + alt_visited_subgoals.update(alt_subgoals[:-1]) + + return delta_cost_array + + +def aggregate_delta_costs(delta_costs, min_non_zero_len=3, min_zero_len=3): + def remove_conjecutive_zeros(delta_costs, min_zero_len=1): + for _ in range(min_zero_len - 1): + final_arr = [] + was_prev_zero = False + for i in range(len(delta_costs)): + if delta_costs[i] == 0: + if was_prev_zero: + final_arr.append(delta_costs[i]) + continue + else: + was_prev_zero = True + else: + final_arr.append(delta_costs[i]) + was_prev_zero = False + delta_costs = np.array(final_arr) + return delta_costs + delta_costs = np.array(delta_costs, dtype=float) + delta_costs = remove_conjecutive_zeros(delta_costs, min_zero_len) + # print(delta_costs) + delta_costs[delta_costs == 0] = np.inf + aggregate_array = [] + for sub_cost in np.split(delta_costs, np.where(delta_costs == np.inf)[0]): + if len(sub_cost) > min_non_zero_len: + aggregate_array.append(np.min(sub_cost)) + aggregate_array = np.array(aggregate_array) + # print(aggregate_array) + return aggregate_array.sum() + + +# def aggregate_delta_costs(delta_costs, min_len=1): +# delta_costs = np.array(delta_costs, dtype=float) +# delta_costs[delta_costs == 0] = np.inf +# total_delta_cost = 0 +# for sub_cost in np.split(delta_costs, np.where(delta_costs == np.inf)[0]): +# if len(sub_cost) > min_len: +# total_delta_cost += np.min(sub_cost) +# return total_delta_cost + + +def check_identical_subgoals(current_subgoal, last_subgoal, inflated_grid, current_all_subgoals, robot_pose, goal_pose): + masked_grid_s1 = lsp.core.mask_grid_with_frontiers(inflated_grid, current_all_subgoals, do_not_mask=current_subgoal) + masked_grid_s2 = lsp.core.mask_grid_with_frontiers(masked_grid_s1, [last_subgoal]) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + masked_grid_s2, [goal_pose.x, goal_pose.y], use_soft_cost=False) + did_plan, _ = get_path([robot_pose.x, robot_pose.y], + do_sparsify=False, + do_flip=False) + return not did_plan + + +def get_subgoals_path_cost(policy1, policy2, all_subgoals, pose, inflated_grid, + is_goal_visible): + if is_goal_visible: + return [], np.array([[], []]), 0 + alt_subgoals = compute_alt_subgoals(policy1, policy2) + alt_path = compute_subgoals_path(alt_subgoals, all_subgoals, pose, inflated_grid) + alt_cost = compute_cost_from_path(alt_path) + return alt_subgoals, alt_path, alt_cost + + +def compute_alt_subgoals(policy1, policy2): + if len(policy2) == 0 or policy1[0] == policy2[0]: + return [policy1[0]] + alt_subgoals = [] + for s in policy2: + alt_subgoals.append(s) + if s == policy1[0]: + break + return alt_subgoals + + +def compute_subgoals_path(path_subgoals, all_subgoals, pose, inflated_grid): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, all_subgoals) + path_points = [[pose.x, pose.y]] + for subgoal in path_subgoals: + planning_grid[subgoal.points[0], subgoal.points[1]] = FREE_VAL + planning_grid[planning_grid == UNOBSERVED_VAL] = COLLISION_VAL + path_points.append(subgoal.get_frontier_point()) + path_points = np.array(path_points) + + alt_path = [[], []] + for i in range(len(path_points) - 1): + start = path_points[i] + end = path_points[i + 1] + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, end, use_soft_cost=True) + did_plan, path = get_path(start, do_sparsify=True, do_flip=True) + if did_plan: + alt_path[0].extend(path[0]) + alt_path[1].extend(path[1]) + return np.array(alt_path) + + +def compute_cost_from_path(path): + return np.linalg.norm(path[:, 1:] - path[:, :-1], axis=0).sum() + + +def get_path_in_known_grid(inflated_grid, pose, goal, subgoals, do_not_mask=None): + planning_grid = lsp.core.mask_grid_with_frontiers(inflated_grid, subgoals, do_not_mask=do_not_mask) + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + _, path = get_path([pose.x, pose.y], do_sparsify=True, do_flip=True) + return path + + +def is_feasible_subgoal(subgoal, final_masked_grid, subgoals, robot_pose, goal_pose): + masked_grid = lsp.core.mask_grid_with_frontiers(final_masked_grid, set(subgoals), do_not_mask=subgoal) + _, get_path = gridmap.planning.compute_cost_grid_from_position(masked_grid, + [goal_pose.x, goal_pose.y], + use_soft_cost=False) + did_plan, _ = get_path([robot_pose.x, robot_pose.y], do_sparsify=False, do_flip=False) + + return did_plan + + +def get_subgoal_labels(subgoals_data, final_masked_grid, goal_pose): + prob_feasible_array = [] + for counter, data in enumerate(subgoals_data): + subgoals = data['subgoals'] + robot_pose = data['robot_pose'] + for subgoal in subgoals: + prob_feasible_true = is_feasible_subgoal(subgoal, final_masked_grid, subgoals, robot_pose, goal_pose) + prob_feasible_array.append([counter, subgoal.prob_feasible, prob_feasible_true]) + return np.array(prob_feasible_array) + + +def compute_distances(frontiers, grid, robot_pose, goal_pose, downsample_factor=1): + goal_distances = lsp.core.get_goal_distances(grid, goal_pose, frontiers=frontiers, + downsample_factor=downsample_factor) + robot_distances = lsp.core.get_robot_distances( + grid, robot_pose, frontiers=frontiers, + downsample_factor=downsample_factor) + frontier_distances = lsp.core.get_frontier_distances( + grid, frontiers=frontiers, downsample_factor=downsample_factor) + distances = { + 'frontier': frontier_distances, + 'robot': robot_distances, + 'goal': goal_distances, + } + return distances diff --git a/modules/lsp_select/lsp_select/scratch/utils/distribution.py b/modules/lsp_select/lsp_select/scratch/utils/distribution.py new file mode 100644 index 0000000..51c0f4d --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/utils/distribution.py @@ -0,0 +1,39 @@ +import numpy as np +import gridmap +import common +import lsp + + +def get_cost_distribution(frontiers, distances): + probs = [1] + costs = [[distances['robot'][frontiers[0]], 0]] + prev_cost_std = 0 + for i in range(len(frontiers)): + f = frontiers[i] + if i > 0: + costs[-1][0] += distances['frontier'][frozenset([f, frontiers[i - 1]])] + prev_cost_mean, prev_cost_std = costs[-1] + success_cost_mean = prev_cost_mean + distances['goal'][f] + f.delta_success_cost + success_cost_std = (f.delta_success_cost_std**2 + prev_cost_std**2)**0.5 + costs[-1] = [success_cost_mean, success_cost_std] + prev_prob = probs[-1] + probs[-1] *= f.prob_feasible + probs.append(prev_prob * (1 - f.prob_feasible)) + costs.append([prev_cost_mean + f.exploration_cost, (prev_cost_std**2 + f.exploration_cost_std**2)**0.5]) + return np.array(probs), np.array(costs) + + +def corrupt_robot_pose(known_map, args): + np.random.seed(args.current_seed) + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_mask = gridmap.utils.inflate_grid(known_map, + inflation_radius=inflation_radius, + collision_val=lsp.constants.COLLISION_VAL) < 1 + # Now sample a random point + allowed_indices = np.where(inflated_mask) + idx_start = np.random.randint(0, allowed_indices[0].size - 1) + new_start_pose = common.Pose(x=allowed_indices[0][idx_start], + y=allowed_indices[1][idx_start], + yaw=2 * np.pi * np.random.rand()) + + return new_start_pose diff --git a/modules/lsp_select/lsp_select/scratch/utils/learning_laser.py b/modules/lsp_select/lsp_select/scratch/utils/learning_laser.py new file mode 100644 index 0000000..83ca2bd --- /dev/null +++ b/modules/lsp_select/lsp_select/scratch/utils/learning_laser.py @@ -0,0 +1,38 @@ +import numpy as np +import math + + +def get_frontier_data_vector(ranges, + robot_pose, + goal_pose, + frontier): + """Get the vector provided to the learner (laser scan) for a chosen frontier.""" + # Store the goal pose (in the frame of the robot) + grx, gry = transform_to_robot_frame(robot_pose, + goal_pose.x, goal_pose.y) + + # Store the frontier centroid point (in the frame of the robot) + centroid = frontier.get_centroid() + frx, fry = transform_to_robot_frame(robot_pose, + centroid[0], centroid[1]) + + return { + 'laser_scan': ranges, + 'goal_rel_pos': np.array([grx, gry]), + 'frontier_rel_pos': np.array([frx, fry]), + } + + +def transform_to_robot_frame(robot_pose, x, y): + """Transforms an x, y pair to the frame of the robot.""" + cx = x - robot_pose.x + cy = y - robot_pose.y + + rotation_mat = np.array( + [[math.cos(robot_pose.yaw), -math.sin(robot_pose.yaw)], + [math.sin(robot_pose.yaw), + math.cos(robot_pose.yaw)]]) + + out = np.matmul(rotation_mat.T, np.array([cx, cy])) + + return out[0], out[1] diff --git a/modules/lsp_select/lsp_select/scripts/__init__.py b/modules/lsp_select/lsp_select/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/lsp_select/lsp_select/scripts/lsp_offline_replay_costs.py b/modules/lsp_select/lsp_select/scripts/lsp_offline_replay_costs.py new file mode 100644 index 0000000..c446524 --- /dev/null +++ b/modules/lsp_select/lsp_select/scripts/lsp_offline_replay_costs.py @@ -0,0 +1,166 @@ +import environments +import lsp +import lsp_select +import numpy as np +import matplotlib.pyplot as plt +from lsp.planners import LearnedSubgoalPlanner, DijkstraPlanner +from lsp_select.planners import PolicySelectionPlanner +from lsp_select.utils.misc import corrupt_robot_pose +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + args.robot = robot + args.robot_pose = pose + args.map_shape = known_map.shape + args.known_map = known_map + + planners = [] + for network in args.network_files: + if network is None: + planners.append(DijkstraPlanner(goal=goal, args=args)) + else: + args.network_file = str(Path(args.network_path) / network) + planners.append(LearnedSubgoalPlanner(goal=goal, args=args)) + chosen_planner_idx = args.planner_names.index(args.chosen_planner) + + planner = PolicySelectionPlanner(goal, planners, chosen_planner_idx, args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'Policy Selection - {args.chosen_planner} ({args.env})') + plt.xlabel(f'seed={args.current_seed}') + plt.show() + plt.pause(0.01) + + plt.figure(figsize=(10, 10)) + plt.subplot(211) + plt.imshow(step_data['image']) + plt.subplot(212) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(planner.observed_map.T, known_map.T)) + path = robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(xs, ys, 'r') + plt.plot(pose.x, pose.y, 'bo') + plt.plot(goal.x, goal.y, 'go') + plt.title(f'{args.chosen_planner} ({args.env})') + plt.xlabel(f'seed={args.current_seed}') + plt.savefig(Path(args.save_dir) / f'img_{args.chosen_planner}_{args.env}_{args.current_seed}.png', dpi=200) + + return planner + + +if __name__ == "__main__": + maze_params = { + 'envs': ['envA', 'envB', 'envC'], + 'planners': ['nonlearned', 'lspA', 'lspB', 'lspC'], + 'network_files': [None, 'mazeA/VisLSPOriented.pt', 'mazeB/VisLSPOriented.pt', 'mazeC/VisLSPOriented.pt'] + } + office_params = { + 'envs': ['mazeA', 'office', 'officewall'], + 'planners': ['nonlearned', 'lspmaze', 'lspoffice', 'lspofficewallswap'], + 'network_files': [None, 'mazeA/VisLSPOriented.pt', 'office/VisLSPOriented.pt', 'officewall/VisLSPOriented.pt'] + } + env_params = { + 'maze': maze_params, + 'office': office_params + } + + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--experiment_type', choices=['maze', 'office']) + args, _ = parser.parse_known_args() + EXPERIMENT_TYPE = args.experiment_type + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_path', type=str) + parser.add_argument('--env', choices=env_params[EXPERIMENT_TYPE]['envs']) + parser.add_argument('--chosen_planner', choices=env_params[EXPERIMENT_TYPE]['planners']) + args = parser.parse_args() + + args.planner_names = env_params[EXPERIMENT_TYPE]['planners'] + args.network_files = env_params[EXPERIMENT_TYPE]['network_files'] + + all_planners = '_'.join(args.planner_names) + + args.current_seed = args.seed[0] + path = Path(args.save_dir) + cost_file = path / f'cost_{args.chosen_planner}_all_{all_planners}_{args.env}_{args.current_seed}.txt' + err_file = path / f'error_{args.chosen_planner}_all_{all_planners}_{args.env}_{args.current_seed}.txt' + lb_costs_file = path / f'lbc_{args.chosen_planner}_all_{all_planners}_{args.env}_{args.current_seed}.txt' + target_file = path / f'target_plcy_{args.chosen_planner}_envrnmnt_{args.env}_{args.current_seed}.txt' + + if cost_file.is_file(): + print(f'Data already exists for {args.chosen_planner}_all_{all_planners}_{args.env}_{args.current_seed}.') + exit() + if err_file.is_file(): + print(f'Error file exists for {args.chosen_planner}_all_{all_planners}_{args.env}_{args.current_seed}.') + exit() + + print(f'Generating data for {args.chosen_planner}_all_{all_planners}_{args.env}_{args.current_seed}.') + + planner = maze_eval(args) + try: + costs, lb_costs = planner.get_costs() + + with open(cost_file, 'w') as f: + np.savetxt(f, costs) + with open(lb_costs_file, 'w') as f: + np.savetxt(f, lb_costs) + with open(target_file, 'w') as f: + f.write('\n') + except TypeError as e: + with open(err_file, 'w') as f: + f.write(f'{e}') + print(f'{e}') + with open(target_file, 'w') as f: + f.write('\n') diff --git a/modules/lsp_select/lsp_select/scripts/lsp_offline_replay_demo.py b/modules/lsp_select/lsp_select/scripts/lsp_offline_replay_demo.py new file mode 100644 index 0000000..9d22e8f --- /dev/null +++ b/modules/lsp_select/lsp_select/scripts/lsp_offline_replay_demo.py @@ -0,0 +1,134 @@ +import numpy as np +import matplotlib.pyplot as plt +import environments +import lsp +import lsp_select +from lsp.planners import LearnedSubgoalPlanner, DijkstraPlanner +from lsp_select.planners import PolicySelectionPlanner +from lsp_select.utils.misc import corrupt_robot_pose +from pathlib import Path + + +def maze_eval(args): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + goal = corrupt_robot_pose(known_map, args) if args.env == 'envC' else goal + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + args.robot = robot + args.robot_pose = pose + args.map_shape = known_map.shape + args.known_map = known_map + + planners = [] + for network in args.network_files: + if network is None: + planners.append(DijkstraPlanner(goal=goal, args=args)) + else: + args.network_file = str(Path(args.network_path) / network) + planners.append(LearnedSubgoalPlanner(goal=goal, args=args)) + chosen_planner_idx = args.planner_names.index(args.chosen_planner) + planner = PolicySelectionPlanner(goal, planners, chosen_planner_idx, args) + + for counter, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1, figsize=(12, 8)) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + plt.axis('off') + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'Policy Selection - {args.chosen_planner} ({args.env}), Cost: {robot.net_motion:.2f}') + plt.xlabel(f'seed={args.current_seed}') + plt.axis('off') + plt.savefig(Path(args.save_dir) / f'deploy_{args.chosen_planner}_{args.env}_' + f'{args.current_seed}_{counter}.png', dpi=300) + plt.show() + plt.pause(0.01) + + plt.figure(figsize=(12, 8)) + plt.subplot(211) + plt.axis('off') + plt.imshow(step_data['image']) + plt.subplot(212) + plt.axis('off') + plt.imshow( + lsp.utils.plotting.make_plotting_grid(planner.observed_map.T, known_map.T)) + path = robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(xs, ys, 'blue') + plt.plot(pose.x, pose.y, 'bo') + plt.plot(goal.x, goal.y, 'go') + plt.title(f'{args.chosen_planner} ({args.env})') + plt.xlabel(f'seed={args.current_seed}') + plt.savefig(Path(args.save_dir) / f'img_{args.chosen_planner}_{args.env}_{args.current_seed}.png', dpi=300) + + return planner + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--do_plot', action='store_true') + parser.add_argument('--network_path', type=str) + parser.add_argument('--env', choices=['mazeA', 'office', 'officewall']) + parser.add_argument('--chosen_planner', choices=['nonlearned', 'lspmaze', 'lspoffice', 'lspofficewallswap']) + + args = parser.parse_args() + args.current_seed = args.seed[0] + + if args.env == 'mazeA' and args.map_type != 'maze': + raise ValueError('map_type should be "maze" when env is "mazeA"') + + args.planner_names = ['nonlearned', 'lspmaze', 'lspoffice', 'lspofficewallswap'] + args.network_files = [None, 'mazeA/mazeA.pt', 'office/office_base.pt', 'office_wallswap/office_wallswap.pt'] + + planner = maze_eval(args) + costs, lb_costs = planner.get_costs() + print(costs) + print(lb_costs) + cost_file = Path(args.save_dir) / f'cost_{args.chosen_planner}_{args.env}_{args.current_seed}.txt' + lb_costs_file = Path(args.save_dir) / f'lbc_{args.chosen_planner}_{args.env}_{args.current_seed}.txt' + with open(cost_file, 'w') as f: + np.savetxt(f, costs) + with open(lb_costs_file, 'w') as f: + np.savetxt(f, lb_costs) diff --git a/modules/lsp_select/lsp_select/scripts/lsp_policy_selection_results.py b/modules/lsp_select/lsp_select/scripts/lsp_policy_selection_results.py new file mode 100644 index 0000000..d6d87bb --- /dev/null +++ b/modules/lsp_select/lsp_select/scripts/lsp_policy_selection_results.py @@ -0,0 +1,404 @@ +import lsp +import numpy as np +from pathlib import Path +import matplotlib.pyplot as plt +import matplotlib +matplotlib.rcParams['pdf.fonttype'] = 42 +matplotlib.rcParams['mathtext.fontset'] = 'stix' +matplotlib.rcParams['font.family'] = 'STIXGeneral' + +NUM_TRIALS = 100 +NUM_SAMPLING = 200 + + +def compute_ucb_bandit_cost(env, planners, c=100, random_seed=42): + """Computes UCB bandit cost when deployed in a given environment. + Cost of a planner for each trial is read from file based on + chosen planner, all available planers, environment name and map seed. + + Returns cumulative costs over trials, selection rates and chosen planner indices. + """ + seeds = np.arange(*env_seeds[env]) + np.random.seed(random_seed) + + # Shuffle seeds to randomize the order of maps + np.random.shuffle(seeds) + tot_cost_per_planner = np.zeros(len(planners)) + num_selection_per_planner = np.zeros(len(planners)) + + chosen_indices = [] + all_costs = [] + for _ in range(NUM_TRIALS): + seed = np.random.choice(seeds) + num_trials = num_selection_per_planner.sum() + if num_trials < 1: + num_trials = 1 + mean_cost_per_planner = tot_cost_per_planner / (num_selection_per_planner + 0.001) + + # Compute the planner index with minimum UCB cost + ucb_cost = mean_cost_per_planner - c * np.sqrt(np.log(num_trials) + / ((num_selection_per_planner + 0.001))) + min_value = np.min(ucb_cost) + min_indices = np.where(ucb_cost == min_value)[0] + min_idx = np.random.choice(min_indices) + # Update the chosen planner + chosen_planner = planners[min_idx] + chosen_indices.append(min_idx) + + # Get cost of chosen planner for current trial + cost_file = Path(args.save_dir) / f'cost_{chosen_planner}_all_{all_planners}_{env}_{seed}.txt' + cost = np.loadtxt(cost_file)[min_idx] + + # Update costs and times selected + all_costs.append(cost) + tot_cost_per_planner[min_idx] += cost + num_selection_per_planner[min_idx] += 1 + + return (np.cumsum(all_costs) / (np.arange(NUM_TRIALS) + 1), + num_selection_per_planner / NUM_TRIALS, chosen_indices) + + +def compute_base_planner_costs(env, planners, seed=42): + """Computes cumulative costs of each planner over trials in an environment + without performing any selection. + """ + seeds = np.arange(*env_seeds[env]) + np.random.seed(seed) + np.random.shuffle(seeds) + costs_per_planner = np.zeros((NUM_TRIALS, len(planners))) + for i in range(NUM_TRIALS): + seed = np.random.choice(seeds) + for j, chosen_planner in enumerate(planners): + cost_file = Path(args.save_dir) / f'cost_{chosen_planner}_all_{all_planners}_{env}_{seed}.txt' + cost = np.loadtxt(cost_file) + costs_per_planner[i, j] = cost[j] + + return np.cumsum(costs_per_planner, axis=0) / (np.arange(NUM_TRIALS).reshape(-1, 1) + 1) + + +def compute_lbcost_wavg(env, chosen_planner, env_seed, prob_shortcut=0): + """Computes weighted average of optimistic and simply-connected lower bound cost + for a planner in a given map seed based on likelihood of finding a shorter path to goal + in the environment. For chosen planner, true cost is computed. + """ + lb_costs_file = Path(args.save_dir) / f'lbc_{chosen_planner}_all_{all_planners}_{env}_{env_seed}.txt' + cost_file = Path(args.save_dir) / f'cost_{chosen_planner}_all_{all_planners}_{env}_{env_seed}.txt' + true_costs = np.loadtxt(cost_file) + lb_costs = np.loadtxt(lb_costs_file) + optimistic_lb = lb_costs[:, 0] + simply_connected_lb = lb_costs[:, 1] + # Use simply connected lb values if optimistic lb values are infinity + optimistic_lb[np.isinf(optimistic_lb)] = simply_connected_lb[np.isinf(optimistic_lb)] + # Compute weighted average + wavg = prob_shortcut * optimistic_lb + (1 - prob_shortcut) * simply_connected_lb + chosen_planner_idx = planners.index(chosen_planner) + # For chosen planner, true cost is returned instead + wavg[chosen_planner_idx] = true_costs[chosen_planner_idx] + + return wavg + + +def compute_lb_selection_cost(env, planners, c=100, prob_shortcut=0, random_seed=42): + """Computes Const-UCB (ours) cost when deployed in a given environment. + The function 'compute_lbcost_wavg' is used to get true cost for chosen planner and + weighted lowerbound costs for other planners which are used to select among planners + using modified UCB bandit appoach. + + Returns cumulative costs over trials, selection rates and chosen planner indices. + """ + seeds = np.arange(*env_seeds[env]) + np.random.seed(random_seed) + np.random.shuffle(seeds) + # Store true cost (first row) and simulated lb costs (second row) + tot_cost_per_planner = np.zeros((2, len(planners))) + num_selection_per_planner = np.zeros((2, len(planners))) + + chosen_indices = [] + all_costs = [] + for _ in range(NUM_TRIALS): + seed = np.random.choice(seeds) + num_trials = num_selection_per_planner[0].sum() + if num_trials < 1: + num_trials = 1 + # Compute mean costs for each planner + mean_cost_per_planner = tot_cost_per_planner / (num_selection_per_planner + 0.001) + # Compute weighted average cost based on true and simulated lb costs + cost_wavg = (num_selection_per_planner[0] * mean_cost_per_planner[0] + + num_selection_per_planner[1] * mean_cost_per_planner[1]) / num_trials + # Compute exploration magnitude of UCB + bandit_exploration_magnitude = np.sqrt(np.log(num_trials) / + (num_selection_per_planner[0] + 0.001)) + # Compute UCB bandit cost as usual + bandit_cost = (mean_cost_per_planner[0] - c * bandit_exploration_magnitude) + # Compute final cost used for selection (Const-UCB cost) + our_cost = np.maximum(bandit_cost, cost_wavg) + # Compute the planner index with minimum Const-UCB cost + min_idx = np.argmin(our_cost) + # Update the chosen planner + chosen_planner = planners[min_idx] + chosen_indices.append(min_idx) + + # Get true cost (for chosen planner) and simulated lb costs (for other planners) for current trial + costs = compute_lbcost_wavg(env, chosen_planner, seed, prob_shortcut=prob_shortcut) + + # Make updates to planner costs and times selected + all_costs.append(costs[min_idx]) + costs_try = np.zeros_like(costs) + costs_try[min_idx] = costs[min_idx] + costs_sim = costs.copy() + costs_sim[min_idx] = 0 + tot_cost_per_planner[0] += costs_try + tot_cost_per_planner[1] += costs_sim + num_selection_per_planner[0, min_idx] += 1 + num_selection_per_planner[1] += 1 + num_selection_per_planner[1, min_idx] -= 1 + + return (np.cumsum(all_costs) / (np.arange(NUM_TRIALS) + 1), + num_selection_per_planner[0] / NUM_TRIALS, chosen_indices) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--experiment_type', choices=['maze', 'office']) + parser.add_argument('--start_seeds', type=int, nargs='+', default=[2000, 3000, 4000]) + parser.add_argument('--num_seeds', type=int, default=150) + args = parser.parse_args() + + if args.experiment_type == 'maze': + planners = ['nonlearned', 'lspA', 'lspB', 'lspC'] + planner_names = ['Non-learned', 'LSP-Maze-Green', 'LSP-Maze-Gray', 'LSP-Maze-Random'] + planner_colors = ['brown', 'green', 'gray', 'darkorange'] + envs = ['envA', 'envB', 'envC'] + env_names = ['Maze-Green', 'Maze-Gray', 'Maze-Random'] + env_seeds = {'envA': (args.start_seeds[0], args.start_seeds[0] + args.num_seeds), + 'envB': (args.start_seeds[1], args.start_seeds[1] + args.num_seeds), + 'envC': (args.start_seeds[2], args.start_seeds[2] + args.num_seeds)} + + elif args.experiment_type == 'office': + planners = ['nonlearned', 'lspmaze', 'lspoffice', 'lspofficewallswap'] + planner_names = ['Non-learned', 'LSP-Maze-Green', 'LSP-Office-Base', 'LSP-Office-Diff'] + planner_colors = ['brown', 'green', 'cyan', 'purple'] + envs = ['mazeA', 'office', 'officewall'] + env_names = ['Maze-Green', 'Office-Base', 'Office-Diff'] + env_seeds = {'mazeA': (args.start_seeds[0], args.start_seeds[0] + args.num_seeds), + 'office': (args.start_seeds[1], args.start_seeds[1] + args.num_seeds), + 'officewall': (args.start_seeds[2], args.start_seeds[2] + args.num_seeds)} + + else: + raise ValueError(f'Experiment name "{args.experiment_type}" is not valid.') + + all_planners = '_'.join(planners) + + trials_to_print = np.array([10, 40, 100]) - 1 + trial_markers = ['^', 'd', 's'] + trial_marker_size = 9 + ucb_color = 'deepskyblue' + best_policy_color = 'darkorange' + fill_alpha = 0.08 + xticks = list(range(0, NUM_TRIALS + 1, 20)) + xticks[0] = 1 + + env_planner_costs = {} + + print('------------------------Base Planner Results----------------------------') + for i, env in enumerate(envs): + print(f'-------------------------------{env_names[i]}-------------------------------') + dat = [compute_base_planner_costs(env, planners, seed=seed) for seed in range(NUM_SAMPLING)] + dat = np.array(dat) + planner_costs = {} + for j, planner in enumerate(planners): + all_runs = dat[:, :, j] + planner_avg_cost = np.mean(all_runs, axis=0)[-1] + planner_costs[j] = planner_avg_cost + print(f'Incurred Cost [{planner_names[j]:<20}]: {planner_avg_cost:.2f}') + env_planner_costs[i] = planner_costs + + if args.experiment_type == 'office': + probs = [1.0, 0.5, 0.0] + tags = [r'$C^{lb,opt}$', r'$C_{p=0.5}^{lb,wgt}$', r'$C^{lb,s.c.}$'] + y_labels = ['Optimistic LB', 'Weighted LB', 'Simply-Connected LB'] + colors = ['green', 'blue', 'purple'] + elif args.experiment_type == 'maze': + probs = [1.0, 0.0] + tags = [r'$C^{lb,opt}$', r'$C^{lb,s.c.}$'] + y_labels = ['Optimistic LB', 'Simply-Connected LB'] + colors = ['green', 'purple'] + + fig_costs, axs_costs = plt.subplots(1, len(envs), figsize=(17, 3)) + fig_regret, axs_regret = plt.subplots(1, len(envs), figsize=(17, 2.1)) + fig_costs.subplots_adjust(wspace=0.3, top=0.95, bottom=0.03, left=0.06, right=0.985) + fig_regret.subplots_adjust(wspace=0.3, top=1, bottom=0.276, left=0.06, right=0.985) + + for i, env in enumerate(envs): + print(f'\n-------------------------------{env_names[i]}-------------------------------') + print('----------------------UCB-Bandit Results-----------------------') + dat = [compute_ucb_bandit_cost(env, planners, random_seed=seed) for seed in range(NUM_SAMPLING)] + all_runs, pull_rates, all_chosen_indx = zip(*dat) + avg_costs_ucb = np.mean(all_runs, axis=0) + p10_costs_ucb = np.percentile(all_runs, 10, axis=0) + p90_costs_ucb = np.percentile(all_runs, 90, axis=0) + + best_asymp_cost = min(env_planner_costs[i].values()) + + # UCB Cost + plt.sca(axs_costs[i]) + axs_costs[i].spines['top'].set_visible(False) + axs_costs[i].spines['right'].set_visible(False) + + plt.plot(range(1, NUM_TRIALS + 1), + avg_costs_ucb, + color=ucb_color, + label='UCB-Bandit (baseline)') + plt.fill_between(range(1, NUM_TRIALS + 1), + p10_costs_ucb, + p90_costs_ucb, + alpha=fill_alpha, + color=ucb_color) + + for m, trial in enumerate(trials_to_print): + plt.plot(trial + 1, + avg_costs_ucb[trial], + marker=trial_markers[m], + markersize=trial_marker_size, + color=ucb_color) + print(f'Trial {trial + 1} Cost: {avg_costs_ucb[trial]:.2f}') + + plt.xticks(xticks, fontsize='x-large') + plt.xlim([1, NUM_TRIALS + 2]) + plt.gca().set_xticklabels([]) + plt.ylabel('Avg. Navigation Cost', fontsize='x-large') + if 'maze' in env_names[i].lower(): + plt.ylim([0, 400]) + plt.yticks(range(0, 401, 100), fontsize='x-large') + else: + plt.ylim([0, 1300]) + plt.yticks(range(0, 1300, 300), fontsize='x-large') + + regrets_ucb = np.cumsum(all_runs - best_asymp_cost, axis=1) + avg_regrets_ucb = regrets_ucb.mean(0) + + # Const-UCB Pull Rate + print('Percentage of times each planner was selected:') + selection_counts = [[] for _ in planners] + for chosen_indices in all_chosen_indx: + for planner_idx, count in zip(*np.unique(chosen_indices, return_counts=True)): + selection_counts[planner_idx].append(count) + mean_counts = np.array([np.mean(counts) for counts in selection_counts]) + print(planner_names) + print(mean_counts / NUM_TRIALS * 100) + + # UCB Regret + plt.sca(axs_regret[i]) + axs_regret[i].spines['top'].set_visible(False) + axs_regret[i].spines['right'].set_visible(False) + plt.plot(range(1, NUM_TRIALS + 1), + avg_regrets_ucb, + color=ucb_color, + label='UCB-Bandit (baseline)') + plt.fill_between(range(1, NUM_TRIALS + 1), + np.percentile(regrets_ucb, 10, axis=0), + np.percentile(regrets_ucb, 90, axis=0), + alpha=fill_alpha, + color=ucb_color) + + for m, trial in enumerate(trials_to_print): + plt.plot(trial + 1, + avg_regrets_ucb[trial], + marker=trial_markers[m], + markersize=trial_marker_size, + color=ucb_color, + fillstyle='none') + print(f'Trial {trial + 1} Regret: {avg_regrets_ucb[trial]:.1f}') + + plt.xlabel(f'Num of Trials ({r"$k$"}) in {env_names[i]}', fontsize='x-large') + plt.xticks(xticks, fontsize='x-large') + plt.xlim([1, NUM_TRIALS + 2]) + plt.ylabel('Cumulative Regret', fontsize='x-large') + if 'maze' in env_names[i].lower(): + plt.ylim([-3000, 9000]) + plt.yticks(range(-3000, 9000, 3000), fontsize='x-large') + else: + plt.ylim([-4000, 15000]) + plt.yticks(range(-4000, 15000, 4000), fontsize='x-large') + + print('----------------------Constrained-UCB Results--------------------------') + for k, p_short in enumerate(probs): + print(f'--------------------------{p_short=}--------------------------') + dat = [compute_lb_selection_cost(env, planners, prob_shortcut=p_short, random_seed=seed) + for seed in range(NUM_SAMPLING)] + all_runs, pull_rates, all_chosen_indx = zip(*dat) + avg_costs_const_ucb = np.mean(all_runs, axis=0) + p10_costs_const_ucb = np.percentile(all_runs, 10, axis=0) + p90_costs_const_ucb = np.percentile(all_runs, 90, axis=0) + + # Const-UCB Cost + plt.sca(axs_costs[i]) + axs_costs[i].spines['top'].set_visible(False) + axs_costs[i].spines['right'].set_visible(False) + + plt.plot(range(1, NUM_TRIALS + 1), + avg_costs_const_ucb, + color=colors[k], + label=f'Const-UCB: {tags[k]} (ours)') + plt.fill_between(range(1, NUM_TRIALS + 1), + p10_costs_const_ucb, + p90_costs_const_ucb, + alpha=fill_alpha, + color=colors[k]) + + plt.sca(axs_costs[i]) + for m, trial in enumerate(trials_to_print): + plt.plot(trial + 1, avg_costs_const_ucb[trial], + marker=trial_markers[m], + markersize=trial_marker_size, + color=colors[k]) + print(f'Trial {trial + 1} Cost: {avg_costs_const_ucb[trial]:.2f}') + + regrets_const_ucb = np.cumsum(all_runs - best_asymp_cost, axis=1) + avg_regrets_const_ucb = regrets_const_ucb.mean(0) + + # Const-UCB Pull Rate + print('Number of times each planner was selected:') + selection_counts = [[] for _ in planners] + for chosen_indices in all_chosen_indx: + for planner_idx, count in zip(*np.unique(chosen_indices, return_counts=True)): + selection_counts[planner_idx].append(count) + mean_counts = [np.mean(counts) for counts in selection_counts] + print(planner_names) + print(mean_counts) + + # Const-UCB Regret + plt.sca(axs_regret[i]) + plt.plot(range(1, NUM_TRIALS + 1), + avg_regrets_const_ucb, + color=colors[k], + label=f'Const-UCB: {tags[k]}') + plt.fill_between(range(1, NUM_TRIALS + 1), + np.percentile(regrets_const_ucb, 10, axis=0), + np.percentile(regrets_const_ucb, 90, axis=0), + alpha=fill_alpha, + color=colors[k]) + + for m, trial in enumerate(trials_to_print): + plt.plot(trial + 1, + avg_regrets_const_ucb[trial], + marker=trial_markers[m], + markersize=trial_marker_size, + color=colors[k], + fillstyle='none') + print(f'Trial {trial + 1} Regret: {avg_regrets_const_ucb[trial]:.1f}') + + plt.sca(axs_regret[i]) + plt.hlines(y=0, xmin=1, xmax=NUM_TRIALS, + colors=best_policy_color, linestyles='--', label='Best Single Policy') + plt.sca(axs_costs[i]) + plt.hlines(y=best_asymp_cost, xmin=1, xmax=NUM_TRIALS, + colors=best_policy_color, linestyles='--', label='Best Single Policy') + plt.legend(fontsize='large') + fig_costs.savefig(Path(args.save_dir) / f'results_{args.experiment_type}_costs.png') + fig_regret.savefig(Path(args.save_dir) / f'results_{args.experiment_type}_regret.png') + print(f'Results plots saved in {args.save_dir} as ' + f'results_{args.experiment_type}_costs.png' + f'and results_{args.experiment_type}_regret.png') + plt.show() diff --git a/modules/lsp_select/lsp_select/scripts/lsp_vis_gen_data.py b/modules/lsp_select/lsp_select/scripts/lsp_vis_gen_data.py new file mode 100644 index 0000000..b46a02b --- /dev/null +++ b/modules/lsp_select/lsp_select/scripts/lsp_vis_gen_data.py @@ -0,0 +1,102 @@ +import os +import matplotlib.pyplot as plt +import lsp +import environments +from lsp_select.utils.misc import corrupt_robot_pose + + +def data_gen_main(args, do_plan_with_naive=True): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + goal = corrupt_robot_pose(known_map, args) if args.data_file_base_name[:5] == 'mazeC' else goal + + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + known_planner = lsp.planners.KnownSubgoalPlanner( + goal=goal, known_map=known_map, args=args, + do_compute_weightings=True) + + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge, + robot, + args, + verbose=True) + + for counter, step_data in enumerate(planning_loop): + # Update the planner objects + known_planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + + # Get and write the data + subgoal_training_data = known_planner.get_subgoal_training_data() + lsp.utils.data.write_training_data_to_pickle( + subgoal_training_data, + step_counter=known_planner.update_counter, + args=known_planner.args) + + if not do_plan_with_naive: + planning_loop.set_chosen_subgoal( + known_planner.compute_selected_subgoal()) + + # Write final plot to file + image_file = os.path.join( + args.save_dir, 'data_collect_plots', + os.path.splitext(args.data_file_base_name)[0] + f'_{args.current_seed}.png') + print(image_file) + + plt.figure(figsize=(10, 10)) + plt.subplot(211) + plt.imshow(step_data['image']) + plt.subplot(212) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(known_planner.observed_map.T, known_map.T)) + path = robot.all_poses + xs = [p.x for p in path] + ys = [p.y for p in path] + plt.plot(xs, ys, 'r') + plt.plot(pose.x, pose.y, 'bo') + plt.plot(goal.x, goal.y, 'go') + plt.savefig(image_file, dpi=200) + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--current_seed', type=int) + parser.add_argument('--data_file_base_name', type=str) + parser.add_argument('--logfile_name', type=str, default='logfile.txt') + args = parser.parse_args() + + data_gen_main(args) diff --git a/modules/lsp_select/lsp_select/utils/__init__.py b/modules/lsp_select/lsp_select/utils/__init__.py new file mode 100644 index 0000000..c57681e --- /dev/null +++ b/modules/lsp_select/lsp_select/utils/__init__.py @@ -0,0 +1,2 @@ +from . import plotting # noqa +from . import misc # noqa diff --git a/modules/lsp_select/lsp_select/utils/misc.py b/modules/lsp_select/lsp_select/utils/misc.py new file mode 100644 index 0000000..58ee48c --- /dev/null +++ b/modules/lsp_select/lsp_select/utils/misc.py @@ -0,0 +1,21 @@ +import numpy as np +import lsp +import common +import gridmap + + +def corrupt_robot_pose(known_map, args): + """Returns a randomly sampled pose in free space. Uses args.current_seed as random seed.""" + np.random.seed(args.current_seed) + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_mask = gridmap.utils.inflate_grid(known_map, + inflation_radius=inflation_radius, + collision_val=lsp.constants.COLLISION_VAL) < 1 + # Now sample a random point + allowed_indices = np.where(inflated_mask) + idx_start = np.random.randint(0, allowed_indices[0].size - 1) + new_pose = common.Pose(x=allowed_indices[0][idx_start], + y=allowed_indices[1][idx_start], + yaw=2 * np.pi * np.random.rand()) + + return new_pose diff --git a/modules/lsp_select/lsp_select/utils/plotting.py b/modules/lsp_select/lsp_select/utils/plotting.py new file mode 100644 index 0000000..257c23e --- /dev/null +++ b/modules/lsp_select/lsp_select/utils/plotting.py @@ -0,0 +1,92 @@ +import numpy as np +import matplotlib.pyplot as plt +import scipy + +from lsp.constants import (COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL, + OBSTACLE_THRESHOLD) + + +def plot_pose(ax, pose, color='black', filled=True): + if filled: + ax.scatter(pose.x, pose.y, color=color, s=10, label='point') + else: + ax.scatter(pose.x, + pose.y, + color=color, + s=10, + label='point', + facecolors='none') + + +def plot_path(ax, path, style='b:'): + if path is not None: + ax.plot(path[0, :], path[1, :], style) + + +def plot_pose_path(ax, poses, style='b'): + path = np.array([[p.x, p.y] for p in poses]).T + plot_path(ax, path, style) + + +def make_plotting_grid(grid_map, known_map=None): + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + collision = grid_map >= OBSTACLE_THRESHOLD + free = np.logical_and(grid_map < OBSTACLE_THRESHOLD, grid_map >= FREE_VAL) + grid[:, :, 0][free] = 1 + grid[:, :, 0][collision] = 0 + grid[:, :, 1][free] = 1 + grid[:, :, 1][collision] = 0 + grid[:, :, 2][free] = 1 + grid[:, :, 2][collision] = 0 + + if known_map is not None: + known_collision = known_map == COLLISION_VAL + unobserved = grid_map == UNOBSERVED_VAL + unknown_obstacle = np.logical_and(known_collision, unobserved) + grid[:, :, 0][unknown_obstacle] = 0.65 + grid[:, :, 1][unknown_obstacle] = 0.65 + grid[:, :, 2][unknown_obstacle] = 0.75 + + return grid + + +def plot_grid_with_frontiers(ax, + grid_map, + known_map, + frontiers, + cmap_name='viridis'): + grid = make_plotting_grid(grid_map, known_map) + + cmap = plt.get_cmap(cmap_name) + for frontier in frontiers: + color = cmap(frontier.prob_feasible) + grid[frontier.points[0, :], frontier.points[1, :], 0] = color[0] + grid[frontier.points[0, :], frontier.points[1, :], 1] = color[1] + grid[frontier.points[0, :], frontier.points[1, :], 2] = color[2] + + ax.imshow(np.transpose(grid, (1, 0, 2))) + + +def make_known_grid(known_map): + kernel = np.ones((3, 3)) / 9 + grid = scipy.ndimage.convolve(known_map, kernel) + walls = (known_map == 1) & (grid < 1) + grid_map = known_map.copy() + grid_map += 1 + grid_map[known_map == 0] = 0 + grid_map[known_map == 1] = 1 + grid_map[walls] = 2 + + grid = np.ones([grid_map.shape[0], grid_map.shape[1], 3]) * 0.75 + grid[:, :, 0][grid_map == 0] = 1 + grid[:, :, 0][grid_map == 2] = 0 + grid[:, :, 1][grid_map == 0] = 1 + grid[:, :, 1][grid_map == 2] = 0 + grid[:, :, 2][grid_map == 0] = 1 + grid[:, :, 2][grid_map == 2] = 0 + + grid[:, :, 0][grid_map == 1] = 0.65 + grid[:, :, 1][grid_map == 1] = 0.65 + grid[:, :, 2][grid_map == 1] = 0.75 + + return grid diff --git a/modules/lsp_select/setup.py b/modules/lsp_select/setup.py new file mode 100644 index 0000000..8d68325 --- /dev/null +++ b/modules/lsp_select/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='lsp_select', + version='1.0.0', + description='LSP Model Selection', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/lsp_select/tests/conftest.py b/modules/lsp_select/tests/conftest.py new file mode 100644 index 0000000..7c7e5f6 --- /dev/null +++ b/modules/lsp_select/tests/conftest.py @@ -0,0 +1,25 @@ +import os.path +import pytest + + +def pytest_addoption(parser): + """Shared command line options for pytest.""" + pass + + +@pytest.fixture() +def lsp_select_network_file(pytestconfig): + net_path_str = pytestconfig.getoption("--lsp-select-network-file") + if net_path_str is not None: + if not os.path.exists(net_path_str): + raise ValueError(f"Net path '{net_path_str}' does not exist.") + return net_path_str + + +@pytest.fixture() +def lsp_select_generator_network_file(pytestconfig): + net_path_str = pytestconfig.getoption("--lsp-select-generator-network-file") + if net_path_str is not None: + if not os.path.exists(net_path_str): + raise ValueError(f"Net path '{net_path_str}' does not exist.") + return net_path_str diff --git a/modules/lsp_select/tests/test_lsp_cyclegan.py b/modules/lsp_select/tests/test_lsp_cyclegan.py new file mode 100644 index 0000000..5122bbf --- /dev/null +++ b/modules/lsp_select/tests/test_lsp_cyclegan.py @@ -0,0 +1,86 @@ +import environments +import lsp +import lsp_select +import matplotlib.pyplot as plt +from lsp_select.planners import LSPCycleGAN +import pytest + + +def test_lsp_cyclegan(unity_path, do_debug_plot, lsp_select_network_file, lsp_select_generator_network_file): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 100 + args.step_size = 1.8 + args.field_of_view_deg = 360 + args.map_type = 'maze' + args.base_resolution = 0.3 + args.inflation_radius_m = 0.75 + args.laser_max_range_m = 18 + args.unity_path = unity_path + args.network_file = lsp_select_network_file + args.generator_network_file = lsp_select_generator_network_file + + if args.network_file is None: + pytest.xfail("Argument lsp_select_network_file is required.") + if args.generator_network_file is None: + pytest.xfail("Argument lsp_select_generator_network_file is required.") + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + planner = LSPCycleGAN(goal=goal, args=args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if do_debug_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(311) + plt.imshow(step_data['image']) + plt.title('Real View') + plt.subplot(312) + plt.imshow(planner.observation['image']) + plt.title('CycleGAN Transformed View') + ax = plt.subplot(313) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'{type(planner).__name__}') + plt.show() + plt.pause(0.01) diff --git a/modules/lsp_select/tests/test_maze_navigation.py b/modules/lsp_select/tests/test_maze_navigation.py new file mode 100644 index 0000000..880a8ef --- /dev/null +++ b/modules/lsp_select/tests/test_maze_navigation.py @@ -0,0 +1,77 @@ +import environments +import lsp +import lsp_select +import matplotlib.pyplot as plt + +from lsp.planners import KnownSubgoalPlanner, LearnedSubgoalPlanner + + +def test_maze_navigation(unity_path, do_debug_plot, lsp_select_network_file): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 100 + args.step_size = 1.8 + args.field_of_view_deg = 360 + args.map_type = 'maze' + args.base_resolution = 0.3 + args.inflation_radius_m = 0.75 + args.laser_max_range_m = 18 + args.unity_path = unity_path + args.network_file = lsp_select_network_file + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + if args.network_file: + planner = LearnedSubgoalPlanner(goal=goal, args=args) + else: + planner = KnownSubgoalPlanner(goal=goal, known_map=known_map, args=args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if do_debug_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'{type(planner).__name__}') + plt.show() + plt.pause(0.01) diff --git a/modules/lsp_select/tests/test_offline_replay.py b/modules/lsp_select/tests/test_offline_replay.py new file mode 100644 index 0000000..7b2a88d --- /dev/null +++ b/modules/lsp_select/tests/test_offline_replay.py @@ -0,0 +1,97 @@ +import numpy as np +import matplotlib.pyplot as plt +import environments +import lsp +import lsp_select +from lsp.planners import KnownSubgoalPlanner, DijkstraPlanner +from lsp_select.planners import PolicySelectionPlanner + + +def test_offline_replay(unity_path, do_debug_plot): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 400 + args.step_size = 1.8 + args.field_of_view_deg = 360 + args.map_type = 'maze' + args.base_resolution = 0.3 + args.inflation_radius_m = 0.75 + args.laser_max_range_m = 18 + args.unity_path = unity_path + args.do_plot = do_debug_plot + args.planner_names = ['nonlearned', 'known'] + args.chosen_planner = 'known' + args.env = 'Maze' + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + builder = environments.simulated.WorldBuildingUnityBridge + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + args.robot = robot + args.robot_pose = pose + args.map_shape = known_map.shape + args.known_map = known_map + + planners = [DijkstraPlanner(goal=goal, args=args), + KnownSubgoalPlanner(goal=goal, known_map=known_map, args=args)] + chosen_planner_idx = args.planner_names.index(args.chosen_planner) + + planner = PolicySelectionPlanner(goal, planners, chosen_planner_idx, args) + + for _, step_data in enumerate(planning_loop): + planner.update( + {'image': step_data['image']}, + step_data['robot_grid'], + step_data['subgoals'], + step_data['robot_pose'], + step_data['visibility_mask']) + planning_loop.set_chosen_subgoal(planner.compute_selected_subgoal()) + + if args.do_plot: + plt.ion() + plt.figure(1) + plt.clf() + plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + lsp_select.utils.plotting.plot_pose(ax, robot.pose, color='blue') + lsp_select.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + lsp_select.utils.plotting.plot_pose(ax, goal, color='green', filled=False) + lsp_select.utils.plotting.plot_path(ax, planning_loop.current_path) + lsp_select.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.title(f'Policy Selection - {args.chosen_planner} ({args.env}), Cost: {robot.net_motion:.2f}') + plt.xlabel(f'seed={args.current_seed}') + plt.show() + plt.pause(0.01) + + costs, lb_costs = planner.get_costs() + + assert np.isnan(costs[0]) + assert np.allclose(costs[1], 176.4) + assert np.allclose(lb_costs[0], [440.41814055, 210.6]) + assert np.all(np.isnan(lb_costs[1])) diff --git a/modules/lsp_xai/Makefile.mk b/modules/lsp_xai/Makefile.mk new file mode 100644 index 0000000..72d594f --- /dev/null +++ b/modules/lsp_xai/Makefile.mk @@ -0,0 +1,293 @@ + +MAZE_XAI_BASENAME ?= maze +FLOORPLAN_XAI_BASENAME ?= floorplan +SP_LIMIT_NUM ?= -1 +LSP-XAI_LEARNING_SEED ?= 8616 +LSP-XAI_LEARNING_XENT_FACTOR ?= 1 +LSP-XAI_UNITY_BASENAME ?= $(UNITY_BASENAME) + +## ==== Core arguments ==== + +TEST_ADDITIONAL_ARGS += --lsp-xai-maze-net-0SG-path=/resources/testing/lsp_xai_maze_0SG.ExpNavVisLSP.pt + +SIM_ROBOT_ARGS ?= --step_size 1.8 \ + --num_primitives 32 \ + --field_of_view_deg 360 +INTERP_ARGS ?= --summary_frequency 100 \ + --num_epochs 1 \ + --learning_rate 2.0e-2 \ + --batch_size 4 + +## ==== Maze Arguments and Experiments ==== +MAZE_CORE_ARGS ?= --unity_path /unity/$(LSP-XAI_UNITY_BASENAME).x86_64 \ + --map_type maze \ + --base_resolution 0.3 \ + --inflation_rad 0.75 \ + --laser_max_range_m 18 \ + --save_dir /data/lsp_xai/$(MAZE_XAI_BASENAME)/ +MAZE_DATA_GEN_ARGS = $(MAZE_CORE_ARGS) --logdir /data/lsp_xai/$(MAZE_XAI_BASENAME)/training/data_gen +MAZE_EVAL_ARGS = $(MAZE_CORE_ARGS) --logdir /data/lsp_xai/$(MAZE_XAI_BASENAME)/training/$(EXPERIMENT_NAME) \ + --logfile_name logfile_final.txt + +lsp-xai-maze-dir = $(DATA_BASE_DIR)/lsp_xai/$(MAZE_XAI_BASENAME) + +# Initialize the Learning +lsp-xai-maze-init-learning = $(lsp-xai-maze-dir)/training/data_gen/ExpNavVisLSP.init.pt +$(lsp-xai-maze-init-learning): + @echo "Writing the 'initial' neural network: $@" + @mkdir -p $(lsp-xai-maze-dir)/training/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(MAZE_DATA_GEN_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_init_learning + +# Generate Data +lsp-xai-maze-data-gen-seeds = $(shell for ii in $$(seq 1000 1299); do echo "$(lsp-xai-maze-dir)/data_collect_plots/learned_planner_$$ii.png"; done) +$(lsp-xai-maze-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-xai-maze-data-gen-seeds): $(lsp-xai-maze-init-learning) + @echo "Generating Data: $@" + @$(call xhost_activate) + @$(call arg_check_unity) + @rm -f $(lsp-xai-maze-dir)/lsp_data_$(seed).*.csv + @mkdir -p $(lsp-xai-maze-dir)/data + @mkdir -p $(lsp-xai-maze-dir)/data_collect_plots + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(MAZE_DATA_GEN_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_data_gen \ + --current_seed $(seed) + +# Train the Network +lsp-xai-maze-train-learning = $(lsp-xai-maze-dir)/training/$(EXPERIMENT_NAME)/ExpNavVisLSP.final.pt +$(lsp-xai-maze-train-learning): $(lsp-xai-maze-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --sp_limit_num $(SP_LIMIT_NUM) \ + --learning_seed $(LSP-XAI_LEARNING_SEED) \ + --xent_factor $(LSP-XAI_LEARNING_XENT_FACTOR) \ + --do_train + +# Evaluate Performance +lsp-xai-maze-eval-seeds = $(shell for ii in $$(seq 11000 11099); do echo "$(lsp-xai-maze-dir)/results/$(EXPERIMENT_NAME)/learned_planner_$$ii.png"; done) +$(lsp-xai-maze-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-xai-maze-eval-seeds): $(lsp-xai-maze-train-learning) + @echo "Evaluating Performance: $@" + @$(call xhost_activate) + @$(call arg_check_unity) + @mkdir -p $(lsp-xai-maze-dir)/results/$(EXPERIMENT_NAME) + $(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_eval \ + --save_dir /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + --current_seed $(seed) + + +## ==== University Building (Floorplan) Environment Experiments ==== +FLOORPLAN_CORE_ARGS ?= --unity_path /unity/$(LSP-XAI_UNITY_BASENAME).x86_64 \ + --map_type ploader \ + --base_resolution 0.6 \ + --inflation_radius_m 1.5 \ + --laser_max_range_m 72 \ + --save_dir /data/lsp_xai/$(FLOORPLAN_XAI_BASENAME)/ +FLOORPLAN_DATA_GEN_ARGS ?= $(FLOORPLAN_CORE_ARGS) \ + --map_file /resources/university_building_floorplans/train/*.pickle \ + --logdir /data/lsp_xai/$(FLOORPLAN_XAI_BASENAME)/training/data_gen +FLOORPLAN_EVAL_ARGS ?= $(FLOORPLAN_CORE_ARGS) \ + --map_file /resources/university_building_floorplans/test/*.pickle \ + --logdir /data/lsp_xai/$(FLOORPLAN_XAI_BASENAME)/training/$(EXPERIMENT_NAME) \ + --logfile_name logfile_final.txt +lsp-xai-floorplan-dir = $(DATA_BASE_DIR)/lsp_xai/$(FLOORPLAN_XAI_BASENAME) + + +# Initialize the Learning +lsp-xai-floorplan-init-learning = $(lsp-xai-floorplan-dir)/training/data_gen/ExpNavVisLSP.init.pt +$(lsp-xai-floorplan-init-learning): + @echo "Writing the 'initial' neural network [Floorplan: $(FLOORPLAN_XAI_BASENAME)]" + @mkdir -p $(lsp-xai-floorplan-dir)/training/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_DATA_GEN_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_init_learning + +# Generate Data +lsp-xai-floorplan-data-gen-seeds = $(shell for ii in $$(seq 1000 1009); do echo "$(lsp-xai-floorplan-dir)/data_collect_plots/learned_planner_$$ii.png"; done) +$(lsp-xai-floorplan-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-xai-floorplan-data-gen-seeds): $(lsp-xai-floorplan-init-learning) + @echo "Generating Data: $@" + @$(call xhost_activate) + @rm -f $(lsp-xai-floorplan-dir)/lsp_data_$(seed).*.csv + @mkdir -p $(lsp-xai-floorplan-dir)/data + @mkdir -p $(lsp-xai-floorplan-dir)/data_collect_plots + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_DATA_GEN_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_data_gen \ + --current_seed $(seed) + +# Train the Network +lsp-xai-floorplan-train-learning = $(lsp-xai-floorplan-dir)/training/$(EXPERIMENT_NAME)/ExpNavVisLSP.final.pt +$(lsp-xai-floorplan-train-learning): $(lsp-xai-floorplan-data-gen-seeds) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --sp_limit_num $(SP_LIMIT_NUM) \ + --learning_seed $(LSP-XAI_LEARNING_SEED) \ + --xent_factor $(LSP-XAI_LEARNING_XENT_FACTOR) \ + --do_train + +# Evaluate Performance +lsp-xai-floorplan-eval-seeds = $(shell for ii in $$(seq 11000 11999); do echo "$(lsp-xai-floorplan-dir)/results/$(EXPERIMENT_NAME)/learned_planner_$$ii.png"; done) +$(lsp-xai-floorplan-eval-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(lsp-xai-floorplan-eval-seeds): $(lsp-xai-floorplan-train-learning) + @echo "Evaluating Performance: $@" + @$(call xhost_activate) + @$(call arg_check_unity) + @mkdir -p $(lsp-xai-floorplan-dir)/results/$(EXPERIMENT_NAME) + $(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_eval \ + --current_seed $(seed) \ + --save_dir /data/lsp_xai/$(FLOORPLAN_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + + +# Some helper targets to run code individually +lsp-xai-floorplan-intervene-seeds-4SG = $(shell for ii in 11304 11591 11870 11336 11245 11649 11891 11315 11069 11202 11614 11576 11100 11979 11714 11430 11267 11064 11278 11367 11193 11670 11385 11180 11923 11195 11642 11462 11010 11386 11913 11103 11474 11855 11823 11641 11408 11899 11449 11393 11041 11435 11101 11610 11422 11546 11048 11070 11699 11618; do echo "$(lsp-xai-floorplan-dir)/results/$(EXPERIMENT_NAME)/learned_planner_$${ii}_intervened_4SG.png"; done) +lsp-xai-floorplan-intervene-seeds-allSG = $(shell for ii in 11304 11591 11870 11336 11245 11649 11891 11315 11069 11202 11614 11576 11100 11979 11714 11430 11267 11064 11278 11367 11193 11670 11385 11180 11923 11195 11642 11462 11010 11386 11913 11103 11474 11855 11823 11641 11408 11899 11449 11393 11041 11435 11101 11610 11422 11546 11048 11070 11699 11618; do echo "$(lsp-xai-floorplan-dir)/results/$(EXPERIMENT_NAME)/learned_planner_$${ii}_intervened_allSG.png"; done) +$(lsp-xai-floorplan-intervene-seeds-4SG): $(lsp-xai-floorplan-train-learning) + @mkdir -p $(DATA_BASE_DIR)/$(FLOORPLAN_XAI_BASENAME)/results/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_intervene \ + --sp_limit_num 4 \ + --current_seed $(shell echo $@ | grep -Eo '[0-9]+' | tail -2 | head -1) \ + --save_dir /data/lsp_xai/$(FLOORPLAN_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + --logfile_name logfile_intervene_4SG.txt + +$(lsp-xai-floorplan-intervene-seeds-allSG): $(lsp-xai-floorplan-train-learning) + @mkdir -p $(DATA_BASE_DIR)/$(FLOORPLAN_XAI_BASENAME)/results/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_intervene \ + --current_seed $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) \ + --save_dir /data/lsp_xai/$(FLOORPLAN_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + --logfile_name logfile_intervene_allSG.txt \ + +## ==== Results & Plotting ==== +.PHONY: lsp-xai-process-results +lsp-xai-process-results: + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_results \ + --data_file /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME)/logfile_final.txt \ + --output_image_file /data/tmp.png + @echo "==== Maze Results ====" + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_results \ + --data_file /data/$(MAZE_XAI_BASENAME)/results/base_allSG/logfile_final.txt \ + /data/$(MAZE_XAI_BASENAME)/results/base_4SG/logfile_final.txt \ + /data/$(MAZE_XAI_BASENAME)/results/base_0SG/logfile_final.txt \ + --output_image_file /data/maze_results.png + @echo "==== Floorplan Results ====" + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_results \ + --data_file /data/$(FLOORPLAN_XAI_BASENAME)/results/base_allSG/logfile_final.txt \ + /data/$(FLOORPLAN_XAI_BASENAME)/results/base_4SG/logfile_final.txt \ + /data/$(FLOORPLAN_XAI_BASENAME)/results/base_0SG/logfile_final.txt \ + --output_image_file /data/floorplan_results.png + @echo "==== Floorplan Intervention Results ====" + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_results \ + --data_file /data/$(FLOORPLAN_XAI_BASENAME)/results/base_4SG/logfile_intervene_4SG.txt \ + /data/$(FLOORPLAN_XAI_BASENAME)/results/base_4SG/logfile_intervene_allSG.txt \ + --do_intervene \ + --xpassthrough $(XPASSTHROUGH) \ + --output_image_file /data/floorplan_intervene_results.png \ + +.PHONY: lsp-xai-explanations +lsp-xai-explanations: + @mkdir -p $(DATA_BASE_DIR)/lsp_xai/explanations/ + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_explain \ + --explain_at 3 \ + --sp_limit_num -1 \ + --current_seed 1037 \ + --save_dir /data/lsp_xai/explanations/ \ + --logdir /data/lsp_xai/maze/training/dbg099 + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(FLOORPLAN_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_explain \ + --explain_at 289 \ + --sp_limit_num 4 \ + --current_seed 11591 \ + --save_dir /data/explanations/ \ + --logdir /data/$(FLOORPLAN_XAI_BASENAME)/training/base_4SG + +lsp-xai-assip: seed ?= 11035 +lsp-xai-assip: + mkdir -p $(DATA_BASE_DIR)/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME) + mkdir -p $(DATA_BASE_DIR)/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME)/data + @$(DOCKER_PYTHON) -m lsp_xai.scripts.explainability_train_eval \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + $(INTERP_ARGS) \ + --do_intervene \ + --current_seed $(seed) \ + --save_dir /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m lsp_xai.scripts.interpret_datum \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + --datum_name dat_$(seed)_intervention.combined.pgz \ + --save_dir /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME)/learned_planner_$(seed)_intervention_weights.before.pt \ + --image_base_name learned_planner_$(seed)_attr_before + @$(DOCKER_PYTHON) -m lsp_xai.scripts.interpret_datum \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + --datum_name dat_$(seed)_intervention.combined.pgz \ + --save_dir /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME)/learned_planner_$(seed)_intervention_weights.after.pt \ + --image_base_name learned_planner_$(seed)_attr_after + @$(DOCKER_PYTHON) -m lsp_xai.scripts.interpret_datum \ + $(MAZE_EVAL_ARGS) \ + $(SIM_ROBOT_ARGS) \ + --datum_name dat_$(seed)_intervention.combined.pgz \ + --save_dir /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME) \ + --network_file /data/lsp_xai/maze_scratch_new_sim/training/$(EXPERIMENT_NAME)/ExpNavVisLSP.final.pt \ + --image_base_name learned_planner_$(seed)_attr_smart + +## ==== Some helper targets to run code individually ==== +# Maze +lsp-xai-maze-data-gen: $(lsp-xai-maze-data-gen-seeds) +lsp-xai-maze-train: $(lsp-xai-maze-train-learning) +lsp-xai-maze-eval: $(lsp-xai-maze-eval-seeds) +lsp-xai-maze: lsp-xai-maze-eval + $(MAKE) lsp-xai-maze-results + +lsp-xai-maze-results: + @$(DOCKER_PYTHON) -m lsp.scripts.vis_lsp_plotting \ + --data_file /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/$(EXPERIMENT_NAME)/logfile_final.txt \ + --output_image_file /data/lsp_xai/$(MAZE_XAI_BASENAME)/results/results_$(EXPERIMENT_NAME).png + +# Floorplan +lsp-xai-floorplan-data-gen: $(lsp-xai-floorplan-data-gen-seeds) +lsp-xai-floorplan-train: $(lsp-xai-floorplan-train-learning) +lsp-xai-floorplan-eval: $(lsp-xai-floorplan-eval-seeds) +lsp-xai-floorplan: lsp-xai-floorplan-eval + +lsp-xai-floorplan-data-gen: $(lsp-xai-floorplan-data-gen-seeds) +lsp-xai-floorplan-intervene: $(lsp-xai-floorplan-intervene-seeds-allSG) $(lsp-xai-floorplan-intervene-seeds-4SG) diff --git a/modules/lsp_xai/README.md b/modules/lsp_xai/README.md new file mode 100644 index 0000000..4fc2551 --- /dev/null +++ b/modules/lsp_xai/README.md @@ -0,0 +1,72 @@ +# LSP XAI: Generating High-Quality Explanations for Navigation in Partially-Revealed Environments + +This work presents an approach to *explainable navigation under uncertainty*. + +This is the code release associated with the NeurIPS 2021 paper *Generating High-Quality Explanations for Navigation in Partially-Revealed Environments*. In this repository, we provide all the code, data, and simulation environments necessary to reproduce our results. These results include (1) training, (2) large-scale evaluation, (3) explaining robot behavior, and (4) interveneing-via-explaining. + +Gregory J. Stein. "Generating High-Quality Explanations for Navigation in Partially-Revealed Environments." In: Neural Information Processing Systems (NeurIPS). 2021. [paper](https://proceedings.neurips.cc/paper/2021/hash/926ec030f29f83ce5318754fdb631a33-Abstract.html), [video (13 min)](https://youtu.be/rWxHJJMEPFI), [blog post](https://cs.gmu.edu/~gjstein/2021/11/explainable-navigation-under-uncertainty/). + +```bibtex +@inproceedings{stein2021xailsp, + title = {Generating High-Quality Explanations for Navigation in Partially-Revealed Environments}, + author = {Gregory J. Stein}, + booktitle = {Advances in Neural Information Processing Systems (NeurIPS)}, + year = 2021, + keywords = {explainability; planning under uncertainty; subgoal-based planning; interpretable-by-design}, +} +``` + +Here we show an example of an explanation automatically generated by our approach in one of our simulated environments, in which the green path on the ground indicates a likely route to the goal: +

+ +

+ +## Getting Started + +We use Docker (with the Nvidia runtime) and GNU Make to run our code, so both are required to run our code. First, docker must be installed by following [the official docker install guide](https://docs.docker.com/engine/install/ubuntu/) +(the official docker install guide). Second, our docker environments will require that the NVIDIA docker runtime is installed (via `nvidia-container-toolkit`. Follow the install instructions on the [nvidia-docker GitHub page](https://github.com/NVIDIA/nvidia-docker#quickstart) to get it. See the top level readme for more instructions. + +# Running Results Experiments + +We also provide targets for re-running the results for each of our simulated experimental setups: + +```bash +# Build the repo +make build + +# Maze Environments +make lsp-xai-maze EXPERIMENT_NAME=base_allSG +make lsp-xai-maze EXPERIMENT_NAME=base_4SG SP_LIMIT_NUM=4 +make lsp-xai-maze EXPERIMENT_NAME=base_0SG SP_LIMIT_NUM=0 + +# University Building (floorplan) Environments +make lsp-xai-floorplan EXPERIMENT_NAME=base_allSG +make lsp-xai-floorplan EXPERIMENT_NAME=base_4SG SP_LIMIT_NUM=4 +make lsp-xai-floorplan EXPERIMENT_NAME=base_0SG SP_LIMIT_NUM=0 + +# Results Plotting +make lsp-xai-process-results +``` + +The make commands above can be augmented to run the trials in parallel, by adding `-jN` (where `N` is the number of trials to be run in parallel) to each of the Make commands. On our NVIDIA 2060 SUPER, we are limited by GPU RAM, and so we limit to `N=4`. Running with higher N is *possible* but sometimes our simulator tries to allocate memory that does not exist and will crash, requiring that the trial be rerun. It is in principle possible to also generate data and train the learned planners from scratch, though (for now) this part of the pipeline has not been as extensively tested; data generation consumes roughly 1.5TB of disk space, so be sure to have that space available if you wish to run that part of the pipeline. Even with 4 parallel trials, we estimate that running all the above code from scratch (including data generation, training, and evaluation) will take roughly 2 weeks, half of which is evaluation. + +## Generating Explanations + +We have provided a make target that generates two explanations that correspond to those included in the paper. Running the following make targets in a command prompt will generate these: + +```bash +# Build the repo +make build +# Generate explanation plots +make lsp-xai-explanations +``` + +For each, the planner is run for a set number of steps and an explanation is generated by the agent and its learned model to justify its behavior compared to what the oracle planner specifies as the action known to lead to the unseen goal. A plot will be generated for each of the explanations and added to `./data/explanations`. + +# Code Organization + +The `src` folder contains a number of python packages necessary for this paper. Most of the *algorithmic* code that reflects our primary *research* contributions is predominantly spread across three files: + +- `lsp_xai.planners.subgoal_planner` The `SubgoalPlanner` class is the one which encapsulates much of the logic for deciding where the robot should go including its calculation of which action it should take and what is the "next best" action. This class is the primary means by which the agent collects information and dispatches it elsewhere to make decisions. +- `lsp_xai.learning.models.exp_nav_vis_lsp` The `ExpVisNavLSP` defines the neural network along with its loss terms used to train it. Also critical are the functions included in this and the `xai.utils.data` file for "updating" the policies to reflect the newly estimated subgoal properties even after the network has been retrained. This class also includes the functionality for computing the delta subgoal properties that primarily define our counterfactual explanations. Virtuall all of this functionality heavily leverages PyTorch, which makes it easy to compute the gradients of the expected cost for each of the policies. +- `lsp_xai.planners.explanation` This file defines the `Explanation` class that stores the subgoal properties and their deltas (computed via `ExpVisNavLSP`) and composes these into a natural language explanation and a helpful visualization showing all the information necessary to understand the agent's decision-making process. diff --git a/modules/lsp_xai/lsp_xai/__init__.py b/modules/lsp_xai/lsp_xai/__init__.py new file mode 100644 index 0000000..7e348dd --- /dev/null +++ b/modules/lsp_xai/lsp_xai/__init__.py @@ -0,0 +1,7 @@ +from . import learning # noqa: F401 +from . import planners # noqa: F401 +from . import scripts # noqa: F401 +from . import utils # noqa: F401 + +DEBUG_PLOT_PLAN = False +DEBUG_PLOT_EXPLAIN = False diff --git a/modules/lsp_xai/lsp_xai/learning/__init__.py b/modules/lsp_xai/lsp_xai/learning/__init__.py new file mode 100644 index 0000000..ce9807d --- /dev/null +++ b/modules/lsp_xai/lsp_xai/learning/__init__.py @@ -0,0 +1 @@ +from . import models # noqa: F401 diff --git a/modules/lsp_xai/lsp_xai/learning/models.py b/modules/lsp_xai/lsp_xai/learning/models.py new file mode 100644 index 0000000..49cc739 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/learning/models.py @@ -0,0 +1,658 @@ +from collections import namedtuple +import itertools +import numpy as np +import torch +import torch.nn as nn +from learning.logging import tensorboard_plot_decorator + +import lsp_xai +from lsp.learning.models.shared import EncoderNBlocks + + +class Subgoal(object): + def __init__(self, prob_feasible, delta_success_cost, exploration_cost, + id): + self.prob_feasible = prob_feasible + self.delta_success_cost = delta_success_cost + self.exploration_cost = exploration_cost + self.id = int(id) + self.is_from_last_chosen = False + + def __hash__(self): + return self.id + + +SubgoalPropDat = namedtuple('SubgoalPropDat', [ + 'ind', 'prop_name', 'delta', 'weight', 'delta_cost', 'delta_cost_fraction', + 'net_data_cost_fraction', 'rank' +]) + + +def compute_subgoal_props(is_feasibles, + delta_success_costs, + exploration_costs, + subgoal_data, + ind_mapping, + device='cpu', + callback_dict=None, + limit_subgoals_num=-1, + delta_subgoal_data=None): + # Populate variables of relevance + subgoal_props = {} + + delta_success_neg = [] + exploration_neg = [] + + softplus = torch.nn.Softplus() + + if callback_dict is not None: + + def save_grad(ind, name): + def hook(grad): + callback_dict[(ind, name)] = grad + + return hook + + # Populate the storage lists + for ind, subgoal_datum in subgoal_data.items(): + counter = ind_mapping[ind] + is_feasible = is_feasibles[counter] + delta_success_cost = delta_success_costs[counter] + exploration_cost = exploration_costs[counter] + delta_success_neg.append(softplus(-delta_success_cost).cpu()) + exploration_neg.append(softplus(-exploration_cost).cpu()) + + # Detatch if requested + if limit_subgoals_num >= 0: + if delta_subgoal_data[( + ind, 'prob_feasible')].rank >= limit_subgoals_num: + is_feasible = is_feasible.detach() + if delta_subgoal_data[( + ind, 'delta_success_cost')].rank >= limit_subgoals_num: + delta_success_cost = delta_success_cost.detach() + if delta_subgoal_data[( + ind, 'exploration_cost')].rank >= limit_subgoals_num: + exploration_cost = exploration_cost.detach() + + if callback_dict is not None: + is_feasible.register_hook(save_grad(ind, 'prob_feasible')) + delta_success_cost.register_hook( + save_grad(ind, 'delta_success_cost')) + exploration_cost.register_hook(save_grad(ind, 'exploration_cost')) + + subgoal_props[ind] = Subgoal( + prob_feasible=is_feasible.cpu(), + delta_success_cost=delta_success_cost.cpu(), + exploration_cost=exploration_cost.cpu(), + id=ind) + + return subgoal_props, delta_success_neg, exploration_neg + + +class ExpNavVisLSP(nn.Module): + name = "ExpNavVisLSP" + + def __init__(self, args=None, num_outputs=3): + super(ExpNavVisLSP, self).__init__() + + # Store arguments + self._args = args + + # Initialize the blocks + self.enc_1 = EncoderNBlocks(3, 16, num_layers=2) + self.enc_2 = EncoderNBlocks(16, 16, num_layers=2) + self.enc_3 = EncoderNBlocks(16 + 4, 32, num_layers=2) + self.enc_4 = EncoderNBlocks(32, 32, num_layers=2) + self.enc_5 = EncoderNBlocks(32, 32, num_layers=2) + self.enc_6 = EncoderNBlocks(32, 32, num_layers=2) + + # Initialize remaining layers + self.conv_1x1 = nn.Conv2d(32, 4, kernel_size=1, bias=False) + self.fc_outs = nn.Sequential( + nn.BatchNorm2d(4, momentum=0.01), + nn.LeakyReLU(0.1, inplace=True), + nn.Flatten(), + nn.Linear(64, 32, bias=False), + nn.BatchNorm1d(32, momentum=0.01), + nn.LeakyReLU(0.1, inplace=True), + nn.Linear(32, 16, bias=False), + nn.BatchNorm1d(16, momentum=0.01), + nn.LeakyReLU(0.1, inplace=True), + nn.Linear(16, num_outputs), + ) + + # Not used; remains for backwards compatability reasons + self.goal_bn = nn.BatchNorm2d(2, momentum=0.001) + + def forward(self, batch, device='cpu'): + ind_mapping = {} + for counter, ind in enumerate(batch['subgoal_data'].keys()): + ind_mapping[ind] = counter + + # Initialize the temporary storage lists + num_subgoals = len(ind_mapping.keys()) + images = [None] * num_subgoals + goal_loc_xs = [None] * num_subgoals + goal_loc_ys = [None] * num_subgoals + subgoal_loc_xs = [None] * num_subgoals + subgoal_loc_ys = [None] * num_subgoals + + # Populate the storage lists + try: + is_numpy = (len(batch['subgoal_data'][ind]['image'].shape) == 3) + except KeyError: + is_numpy = False + + if is_numpy: + for ind, subgoal_datum in batch['subgoal_data'].items(): + counter = ind_mapping[ind] + images[counter] = torch.Tensor(subgoal_datum['image']) + goal_loc_xs[counter] = torch.Tensor( + subgoal_datum['goal_loc_x']) + goal_loc_ys[counter] = torch.Tensor( + subgoal_datum['goal_loc_y']) + subgoal_loc_xs[counter] = torch.Tensor( + subgoal_datum['subgoal_loc_x']) + subgoal_loc_ys[counter] = torch.Tensor( + subgoal_datum['subgoal_loc_y']) + + processed_batch = { + 'image': torch.stack(images, dim=0).permute( + (0, 3, 1, 2)).float(), + 'goal_loc_x': torch.stack(goal_loc_xs, dim=0).float(), + 'goal_loc_y': torch.stack(goal_loc_ys, dim=0).float(), + 'subgoal_loc_x': torch.stack(subgoal_loc_xs, dim=0).float(), + 'subgoal_loc_y': torch.stack(subgoal_loc_ys, dim=0).float(), + } + else: + for ind, subgoal_datum in batch['subgoal_data'].items(): + counter = ind_mapping[ind] + images[counter] = subgoal_datum['image'] + goal_loc_xs[counter] = subgoal_datum['goal_loc_x'] + goal_loc_ys[counter] = subgoal_datum['goal_loc_y'] + subgoal_loc_xs[counter] = subgoal_datum['subgoal_loc_x'] + subgoal_loc_ys[counter] = subgoal_datum['subgoal_loc_y'] + + processed_batch = { + 'image': torch.cat(images, dim=0).permute( + (0, 3, 1, 2)).float(), + 'goal_loc_x': torch.cat(goal_loc_xs, dim=0).float(), + 'goal_loc_y': torch.cat(goal_loc_ys, dim=0).float(), + 'subgoal_loc_x': torch.cat(subgoal_loc_xs, dim=0).float(), + 'subgoal_loc_y': torch.cat(subgoal_loc_ys, dim=0).float() + } + + return self.forward_supervised(processed_batch, device), ind_mapping + + def forward_supervised(self, data, device): + image = data['image'].to(device) + + # Compute goal info tensor + if 'goal_loc_x' in data.keys(): + g = torch.stack( + (data['goal_loc_x'], data['goal_loc_y']), 1).expand( + [-1, -1, 32, -1]).float().to(device) / 100.0 + s = torch.stack( + (data['subgoal_loc_x'], data['subgoal_loc_y']), 1).expand( + [-1, -1, 32, -1]).float().to(device) / 100.0 + else: + raise ValueError("Missing goal location data.") + + # Encoding layers + x = image + x = self.enc_1(x) + x = self.enc_2(x) + x = torch.cat((x, g, s), 1) # Add the goal info tensor + x = self.enc_3(x) + x = self.enc_4(x) + x = self.enc_5(x) + x = self.enc_6(x) + x = self.conv_1x1(x) + x = self.fc_outs(x) + + return x + + def compute_subgoal_props(_, + is_feasible_mat, + delta_success_cost_mat, + exploration_cost_mat, + subgoal_data, + ind_mapping, + device='cpu', + callback_dict=None, + limit_subgoals_num=-1, + delta_subgoal_data=None): + return compute_subgoal_props(is_feasible_mat, delta_success_cost_mat, + exploration_cost_mat, subgoal_data, + ind_mapping, device, callback_dict, + limit_subgoals_num, delta_subgoal_data) + + def get_subgoal_prop_impact(self, + datum, + device='cpu', + delta_cost_limit=None): + # Initialize the simple SGD optimizer + optimizer = torch.optim.SGD(self.parameters(), lr=1e-6) + + # Put network in eval mode if necessary + is_in_training_mode = self.training + if is_in_training_mode: + self.eval() + + # Compute the base subgoal properties + out, ind_map = self(datum, device) + nn_out_processed = out[:, :3] + is_feasible_mat = torch.nn.Sigmoid()(nn_out_processed[:, 0]) + delta_success_cost_mat = nn_out_processed[:, 1] + exploration_cost_mat = nn_out_processed[:, 2] + callback_dict_base = {} + subgoal_props_base, _, _ = self.compute_subgoal_props( + is_feasible_mat, delta_success_cost_mat, exploration_cost_mat, + datum['subgoal_data'], ind_map, device, callback_dict_base) + + target_cost = lsp_xai.utils.data.compute_expected_cost_for_policy( + subgoal_props_base, datum['target_subgoal_policy']) + + backup_cost = lsp_xai.utils.data.compute_expected_cost_for_policy( + subgoal_props_base, datum['backup_subgoal_policy']) + + delta_cost = target_cost - backup_cost + + # If the target cost is sufficiently below the backup cost + # don't compute the subgoal properties. + if delta_cost_limit is not None and delta_cost < -np.abs( + delta_cost_limit): + print(f"Bypassing subgoal prop limiting: {delta_cost}.") + spd_list = [ + SubgoalPropDat(ind, prop_name, 0, 0, 0, 0, 0, 0) for ind, + prop_name in itertools.product(subgoal_props_base.keys( + ), ['prob_feasible', 'delta_success_cost', 'exploration_cost']) + ] + + return {(spd.ind, spd.prop_name): spd for spd in spd_list} + + # Update the model parameters + optimizer.zero_grad() + delta_cost.backward() + optimizer.step() + + # Now compute the updated subgoal properties + with torch.no_grad(): + # Compute the base subgoal properties + out, ind_map = self(datum, device) + nn_out_processed = out[:, :3] + is_feasible_mat = torch.nn.Sigmoid()(nn_out_processed[:, 0]) + delta_success_cost_mat = nn_out_processed[:, 1] + exploration_cost_mat = nn_out_processed[:, 2] + subgoal_props_upd, _, _ = self.compute_subgoal_props( + is_feasible_mat, delta_success_cost_mat, exploration_cost_mat, + datum['subgoal_data'], ind_map, device) + + # Compute the data to be returned + subgoal_prop_data_list = [] + for ind in subgoal_props_base.keys(): + d = (subgoal_props_upd[ind].prob_feasible - + subgoal_props_base[ind].prob_feasible).detach().cpu().numpy() + w = callback_dict_base[(ind, + 'prob_feasible')].detach().cpu().numpy() + subgoal_prop_data_list.append([ind, 'prob_feasible', d, w, d * w]) + + d = (subgoal_props_upd[ind].delta_success_cost - + subgoal_props_base[ind].delta_success_cost + ).detach().cpu().numpy() + w = callback_dict_base[( + ind, 'delta_success_cost')].detach().cpu().numpy() + subgoal_prop_data_list.append( + [ind, 'delta_success_cost', d, w, d * w]) + + d = (subgoal_props_upd[ind].exploration_cost - + subgoal_props_base[ind].exploration_cost + ).detach().cpu().numpy() + w = callback_dict_base[( + ind, 'exploration_cost')].detach().cpu().numpy() + subgoal_prop_data_list.append( + [ind, 'exploration_cost', d, w, d * w]) + + # Revert via a backwards gradient step + optimizer.param_groups[0]['lr'] *= -1 + optimizer.step() + optimizer.zero_grad() + + # Restore network to training mode if necessary + if is_in_training_mode: + self.train() + + # Compute the 'rank' of each term and return + subgoal_prop_data_list.sort(key=lambda spd: abs(spd[-1]), reverse=True) + abs_delta_cost = [abs(spd[4]) for spd in subgoal_prop_data_list] + net_data_cost = list(np.cumsum(abs_delta_cost)) + sc = max(net_data_cost) + is_rank = 1 + if sc == 0: + sc = 1.0 + is_rank = 0 + + spd_list = [ + SubgoalPropDat(ind=spd[0], + prop_name=spd[1], + delta=spd[2] / sc, + weight=spd[3] / sc, + delta_cost=spd[4] / sc, + delta_cost_fraction=adc / sc, + net_data_cost_fraction=ndc / sc, + rank=is_rank * rank) + for rank, (spd, adc, ndc) in enumerate( + zip(subgoal_prop_data_list, abs_delta_cost, net_data_cost)) + ] + + return {(spd.ind, spd.prop_name): spd for spd in spd_list} + + def loss(self, + nn_out, + batch, + ind_mapping, + device='cpu', + writer=None, + index=None, + limit_subgoals_num=-1, + delta_subgoal_data=None, + do_include_limit_costs=True, + do_include_negative_costs=True): + + do_limit = ((limit_subgoals_num >= 0) + and delta_subgoal_data is not None + and max([dsd.rank + for dsd in delta_subgoal_data.values()]) > 0) + + # Separate outputs. + nn_out_processed = nn_out[:, :3] + is_feasible_mat = torch.nn.Sigmoid()(nn_out_processed[:, 0]) + delta_success_cost_mat = nn_out_processed[:, 1] + exploration_cost_mat = nn_out_processed[:, 2] + + limited_subgoal_props, delta_success_neg, exploration_neg = self.compute_subgoal_props( + is_feasible_mat, + delta_success_cost_mat, + exploration_cost_mat, + batch['subgoal_data'], + ind_mapping, + device, + limit_subgoals_num=limit_subgoals_num, + delta_subgoal_data=delta_subgoal_data) + + target_cost = lsp_xai.utils.data.compute_expected_cost_for_policy( + limited_subgoal_props, batch['target_subgoal_policy']) + backup_cost = lsp_xai.utils.data.compute_expected_cost_for_policy( + limited_subgoal_props, batch['backup_subgoal_policy']) + + loss_diff = torch.sqrt(1 - torch.nn.LogSigmoid() + (-(target_cost - backup_cost))) - 1 + if limit_subgoals_num == 0: + print("No subgoal properties; no loss_diff.") + loss = 0 * loss_diff + else: + loss = loss_diff + + print(f"Target: {target_cost.cpu().detach().numpy()} < " + f"Backup: {backup_cost.cpu().detach().numpy()} | " + f"loss_diff: {loss_diff.cpu().detach().numpy()}") + + # Recompute the subgoal properties with all terms if needed + if do_limit and do_include_limit_costs: + subgoal_props, delta_success_neg, exploration_neg = self.compute_subgoal_props( + is_feasible_mat, delta_success_cost_mat, exploration_cost_mat, + batch['subgoal_data'], ind_mapping, device) + + target_cost = lsp_xai.utils.data.compute_expected_cost_for_policy( + subgoal_props, batch['target_subgoal_policy']) + backup_cost = lsp_xai.utils.data.compute_expected_cost_for_policy( + subgoal_props, batch['backup_subgoal_policy']) + else: + subgoal_props = limited_subgoal_props + + if do_include_limit_costs: + loss_target_upper = torch.nn.ReLU()( + (target_cost - batch['net_cost_remaining'])) + loss_target_lower = torch.nn.ReLU()( + (batch['net_cost_remaining_known'] - target_cost)) + loss = loss + loss_target_upper / 50 + loss = loss + loss_target_lower / 500 + print(f" Target Upper Bound: {batch['net_cost_remaining_known']}") + else: + print(" No limit costs") + + if do_include_negative_costs: + loss_negative_costs = 0 + loss_negative_costs += sum(delta_success_neg) + loss_negative_costs += sum(exploration_neg) + loss = loss + loss_negative_costs / 50 + else: + print(" No negative costs") + + # Write some things + if writer is not None and index is not None: + writer.add_scalar("Loss/compare_total", loss.item(), index) + writer.add_scalar("Loss/compare_diff", loss_diff.item(), index) + + if delta_subgoal_data is not None: + for dsd in delta_subgoal_data.values(): + if dsd.rank == (limit_subgoals_num - 1): + writer.add_scalar("Debug/subgoal_limit_fraction", + dsd.net_data_cost_fraction, index) + if np.isnan(dsd.net_data_cost_fraction): + print(dsd) + raise ValueError() + + if do_include_limit_costs: + writer.add_scalar("Loss/compare_target_upper", + loss_target_upper.item(), index) + writer.add_scalar("Loss/compare_target_lower", + loss_target_lower.item(), index) + + if do_include_negative_costs: + writer.add_scalar("Loss/compare_negative_costs", + loss_negative_costs.item(), index) + writer.add_scalar("Debug/delta_success_neg_avg", + (sum(delta_success_neg) / + len(subgoal_props)).item(), index) + writer.add_scalar("Debug/exploration_neg_avg", + (sum(exploration_neg) / + len(subgoal_props)).item(), index) + + return loss + + def loss_supervised(self, + nn_out, + data, + device='cpu', + writer=None, + index=None, + positive_weight=None): + # Separate outputs. + is_feasible_logits = nn_out[:, 0] + is_feasible_label = data['is_feasible'].to(device) + if positive_weight is None: + positive_weight = 1.0 + + # Compute the contribution from the is_feasible_label + weights = 1.0 + (positive_weight - 1.0) * is_feasible_label + print("RAND", self._args.learning_seed) + print("XENT", (1 / 10) * self._args.xent_factor) + is_feasible_xentropy = ( + 1 / 10) * self._args.xent_factor * torch.nn.BCEWithLogitsLoss( + weight=weights)(is_feasible_logits, is_feasible_label) + + # Sum the contributions + loss = is_feasible_xentropy + + # Logging + if writer is not None: + writer.add_scalar("Loss/supervised_is_feasible_xentropy", + is_feasible_xentropy.item(), index) + writer.add_scalar("Loss/supervised_total", loss.item(), index) + + return loss + + def update_datum(self, datum, device): + with torch.no_grad(): + out, ind_map = self(datum, device) + out_det = out.detach() + is_feasibles = torch.nn.Sigmoid()(out_det[:, 0]) + delta_success_costs = out_det[:, 1] + exploration_costs = out_det[:, 2] + subgoal_props, delta_success_neg, exploration_neg = self.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + datum = lsp_xai.utils.data.update_datum_policies( + subgoal_props, datum) + + if datum is None: + return None + + relevant_inds = list( + set(datum['target_subgoal_policy']['policy']) + | set(datum['backup_subgoal_policy']['policy'])) + + datum['subgoal_data'] = { + ind: sg + for ind, sg in datum['subgoal_data'].items() + if ind in relevant_inds + } + + return datum + + @classmethod + def compute_expected_cost_for_policy(_, subgoal_props, + subgoal_policy_data): + return lsp_xai.utils.data.compute_expected_cost_for_policy( + subgoal_props, subgoal_policy_data) + + @classmethod + def get_net_eval_fn(_, network_file, device, do_return_model=False): + model = ExpNavVisLSP() + if network_file is not None: + model.load_state_dict(torch.load(network_file, + map_location=torch.device('cpu')), + strict=False) + model.eval() + model.to(device) + + def frontier_net(image, goal_loc_x, goal_loc_y, subgoal_loc_x, + subgoal_loc_y): + with torch.no_grad(): + image = np.transpose(image, (2, 0, 1)) + out = model.forward_supervised( + { + 'image': + torch.tensor(np.expand_dims(image, axis=0)).float(), + 'goal_loc_x': + torch.tensor(np.expand_dims(goal_loc_x, + axis=0)).float(), + 'goal_loc_y': + torch.tensor(np.expand_dims(goal_loc_y, + axis=0)).float(), + 'subgoal_loc_x': + torch.tensor(np.expand_dims(subgoal_loc_x, + axis=0)).float(), + 'subgoal_loc_y': + torch.tensor(np.expand_dims(subgoal_loc_y, + axis=0)).float() + }, + device=device) + out[0, 0] = torch.sigmoid(out[0, 0]) + out = out.detach().cpu().numpy() + return out[0, 0], out[0, 1], out[0, 2] + + if do_return_model: + return frontier_net, model + else: + return frontier_net + + @classmethod + def preprocess_data(_, datum, is_training=True): + datum['image'] = np.transpose(datum['image'], + (2, 0, 1)).astype(np.float32) / 255 + return datum + + @tensorboard_plot_decorator + def plot_data_supervised(self, fig, out, data): + image = data['image'][0] + image = np.transpose(image, (1, 2, 0)) + out_base = out[0, :3] + is_feasible_base = torch.sigmoid(out_base[0]).cpu().numpy() + is_feasible_base = is_feasible_base + + axs = fig.subplots(4, 1) + axs[0].imshow(image, interpolation='none') + + def update_model_counterfactual(self, datum, limit_num, + margin, learning_rate, device, num_steps=5000): + import copy + + datum = copy.deepcopy(datum) + delta_subgoal_data = self.get_subgoal_prop_impact( + datum, device, delta_cost_limit=-1e10) + + # Initialize some terms for the optimization + optimizer = torch.optim.SGD(self.parameters(), lr=learning_rate) + + # Now we perfrom iterative gradient descent until the expected cost of the + # new target subgoal is lower than that of the originally selected subgoal. + for ii in range(5000): + # Update datum to reflect new neural network state + datum = self.update_datum(datum, device) + + # Compute the subgoal properties by passing images through the network. + # (PyTorch implicitly builds a graph of these operations so that we can + # differentiate them later.) + nn_out, ind_mapping = self(datum, device) + is_feasibles = torch.nn.Sigmoid()(nn_out[:, 0]) + delta_success_costs = nn_out[:, 1] + exploration_costs = nn_out[:, 2] + limited_subgoal_props, _, _ = self.compute_subgoal_props( + is_feasibles, + delta_success_costs, + exploration_costs, + datum['subgoal_data'], + ind_mapping, + device, + limit_subgoals_num=limit_num, + delta_subgoal_data=delta_subgoal_data) + + if ii == 0: + base_subgoal_props = limited_subgoal_props + + # Compute the expected of the new target subgoal: + q_target = self.compute_expected_cost_for_policy( + limited_subgoal_props, datum['target_subgoal_policy']) + # Cost of the 'backup' (formerly the agent's chosen subgoal): + q_backup = self.compute_expected_cost_for_policy( + limited_subgoal_props, datum['backup_subgoal_policy']) + print( + f"{ii:5} | Q_dif = {q_target - q_backup:6f} | Q_target = {q_target:6f} | Q_backup = {q_backup:6f}" + ) + assert q_target > 0 + assert q_backup > 0 + + # The zero-crossing of the difference between the two is the decision + # boundary we are hoping to cross by updating the paramters of the + # neural network via gradient descent. + q_diff = q_target - q_backup + + if q_diff <= -margin: + # When it's less than zero, we're done. + break + + # Via PyTorch magic, gradient descent is easy: + optimizer.zero_grad() + q_diff.backward() + optimizer.step() + else: + # If it never crossed the boundary, we have failed. + raise ValueError("Decision boundary never crossed.") + + upd_subgoal_props = limited_subgoal_props + + return (datum, delta_subgoal_data, base_subgoal_props, + upd_subgoal_props) diff --git a/modules/lsp_xai/lsp_xai/planners/__init__.py b/modules/lsp_xai/lsp_xai/planners/__init__.py new file mode 100644 index 0000000..67d1d98 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/planners/__init__.py @@ -0,0 +1,3 @@ +from . import evaluate # noqa: F401 +from .known_subgoal_planner import KnownSubgoalPlanner # noqa: F401 +from .subgoal_planner import SubgoalPlanner # noqa: F401 diff --git a/modules/lsp_xai/lsp_xai/planners/evaluate.py b/modules/lsp_xai/lsp_xai/planners/evaluate.py new file mode 100644 index 0000000..3b24598 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/planners/evaluate.py @@ -0,0 +1,397 @@ +import math +import numpy as np +import time +import logging +import gzip +import _pickle as cPickle +import os +import torch + +import gridmap +from gridmap.constants import UNOBSERVED_VAL +import lsp +from lsp.planners.utils import COMPRESS_LEVEL +import lsp_xai + +logging.basicConfig(filename="/data/interp.log", level=logging.DEBUG) + + +def run_model_eval(args, + goal, + known_map, + simulator, + unity_bridge, + robot, + eval_planner, + known_planner=None, + do_write_data=False, + do_plan_with_naive=False, + do_plan_with_known=False, + return_planner_after_steps=None, + do_explain=False, + intervene_at=None): + """Main function for evaluation (and optional data writing) for a given model class.""" + if do_write_data and known_planner is None: + raise ValueError( + "Writing data requires the known_planner not be 'None'.") + + counter = 0 + count_since_last_turnaround = 100 + fn_start_time = time.time() + travel_data = [] + robot_grid = UNOBSERVED_VAL * np.ones(known_map.shape) + + did_succeed = True + agrees_with_oracle = [] + intervene_pose = None + did_intervene = False + chosen_planner = 'chosen' + planners = {'chosen': eval_planner} + if known_planner is not None: + planners['known'] = known_planner + elif do_plan_with_known: + raise ValueError("Cannot plan with known planner if no known planner " + "provided. 'known_planner' cannot be None or" + "'do_plan_with_known' should be False.") + + # Main planning loop + while (math.fabs(robot.pose.x - goal.x) >= 3 * args.step_size + or math.fabs(robot.pose.y - goal.y) >= 3 * args.step_size): + logger = logging.getLogger("evaluate") + + if not args.silence: + print(("Goal: {}, {}".format(goal.x, goal.y))) + print(("Robot: {}, {} [motion: {}]".format(robot.pose.x, + robot.pose.y, + robot.net_motion))) + print(f"Counter: {counter} | Count since last turnaround: " + f"{count_since_last_turnaround}") + + stime = time.time() + + # Compute observations and update map + pano_image = simulator.get_image(robot) + _, robot_grid, visible_region = ( + simulator.get_laser_scan_and_update_map(robot, robot_grid, True)) + logger.debug(f"[{counter}] time to observation: {time.time() - stime}") + + # Compute intermediate map grids for planning + update_map_time = time.time() + visibility_mask = gridmap.utils.inflate_grid(visible_region, 1.8, -0.1, + 1.0) + inflated_grid = simulator.get_inflated_grid(robot_grid, robot) + inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot.pose) + logger.debug( + f"[{counter}] time to update map: {time.time() - update_map_time}") + + # Compute the subgoal + subgoal_time = time.time() + subgoals = simulator.get_updated_frontier_set(inflated_grid, robot, + set()) + logger.debug( + f"[{counter}] time to compute subgoals (# {len(subgoals)}): {time.time() - subgoal_time}" + ) + + # Update the planner objects + planner_update_time = time.time() + for planner in planners.values(): + planner.update({'image': pano_image}, robot_grid, subgoals, + robot.pose, visibility_mask) + logger.debug( + f"[{counter}] time to update planners: {time.time() - planner_update_time}" + ) + + # Compute the subgoals for the different planners + chosen_subgoal_time = time.time() + chosen_subgoal = planners[chosen_planner].compute_selected_subgoal() + logger.debug( + f"[{counter}] time to compute_selected_subgoal: {time.time() - chosen_subgoal_time}" + ) + + if known_planner is not None and chosen_subgoal is not None: + target_subgoal_time = time.time() + target_subgoal = planners['known'].compute_selected_subgoal() + logger.debug( + f"[{counter}] time to target_selected_subgoal: {time.time() - target_subgoal_time}" + ) + + # Say whether the two planners agree + agrees_with_oracle.append(chosen_subgoal == target_subgoal) + + def get_subgoal_path_angle(subgoal): + planning_grid = lsp.core.mask_grid_with_frontiers( + inflated_grid, subgoals, do_not_mask=subgoal) + + # Check that the plan is feasible and compute path + _, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + _, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + try: + return np.arctan2(path[1][1] - path[1][0], + path[0][1] - path[0][0]) + except IndexError: + return 0.0 + + syaw_ch = get_subgoal_path_angle(chosen_subgoal) + syaw_ta = get_subgoal_path_angle(target_subgoal) + + rel_angle = abs(((syaw_ch - syaw_ta) + np.pi) % (2 * np.pi) - + np.pi) + elif do_explain: + raise ValueError("known_planner is None yet is required " + "to generate explainations.") + else: + target_subgoal = None + + if (do_explain and counter >= args.explain_at): + try: + explanation = planners[ + chosen_planner].generate_counterfactual_explanation( + target_subgoal, + limit_num=args.sp_limit_num, + do_freeze_selected=False) + return explanation + except: # noqa + return None + + if (intervene_at is not None and not did_intervene + and counter >= intervene_at and rel_angle > np.pi / 2): + # Intervene: change the learned model to 'fix' behavior + try: + update_counter = planners[chosen_planner].update_counter + planners[chosen_planner].update_counter = 'intervention' + lsp.planners.utils.write_comparison_training_datum( + planners[chosen_planner], target_subgoal) + planners[chosen_planner].update_counter = update_counter + + base_name = f"learned_planner_{args.current_seed}" + net_name_base = f"{base_name}_intervention_weights" + + # Save the base model weights + torch.save(planners[chosen_planner].model.state_dict(), + os.path.join(args.save_dir, net_name_base + '.before.pt')) + + # Compute the explanation + explanation = planners[chosen_planner].generate_counterfactual_explanation( + target_subgoal, + limit_num=args.sp_limit_num, + do_freeze_selected=False, + keep_changes=True, + margin=0.1) + + # Save the explanation image to file + plot_name = f"{base_name}_intervention_exp_{intervene_at}.png" + explanation.visualize(os.path.join(args.save_dir, plot_name)) + + chosen_subgoal = planners[ + chosen_planner].compute_selected_subgoal() + intervene_pose = [robot.pose.x, robot.pose.y] + did_intervene = True + if (not chosen_subgoal == target_subgoal): + planners[ + chosen_planner].generate_counterfactual_explanation( + target_subgoal, + limit_num=args.sp_limit_num, + do_freeze_selected=False, + keep_changes=True, + margin=5.0) + chosen_subgoal = planners[ + chosen_planner].compute_selected_subgoal() + if (not chosen_subgoal == target_subgoal): + planners[ + chosen_planner].generate_counterfactual_explanation( + target_subgoal, + limit_num=args.sp_limit_num, + do_freeze_selected=False, + keep_changes=True, + margin=10.0) + chosen_subgoal = planners[ + chosen_planner].compute_selected_subgoal() + + # Save the base model weights + torch.save(planners[chosen_planner].model.state_dict(), + os.path.join(args.save_dir, net_name_base + '.after.pt')) + + assert chosen_subgoal == target_subgoal + except TypeError: + pass + except: # noqa + did_succeed = False + raise ValueError + break + + stime = time.time() + + if do_write_data: + # Generate and write the supervised data + lsp.planners.utils.write_supervised_training_datum_oriented( + planners['known']) + + # Comparison Data + did_write, pickle_name = ( + lsp.planners.utils.write_comparison_training_datum( + planners[chosen_planner], target_subgoal)) + + if did_write: + _, _, known_distance = planners['known'].compute_path_to_goal() + travel_data.append({ + 'pickle_name': pickle_name, + 'robot_motion': robot.net_motion, + 'known_distance': known_distance, + }) + print(f"Time to write data: {time.time() - stime}") + + # Plotting + if lsp_xai.DEBUG_PLOT_PLAN and counter % 2 == 0: + import matplotlib.pyplot as plt + fig = plt.figure(figsize=(12, 6)) + planners[chosen_planner].plot_map_with_plan(None, robot.all_poses, image=pano_image) + if intervene_at is not None: + plt.savefig(f"/data/tmp/planner_intervene_{counter:04}.png", dpi=300) + else: + plt.savefig(f"/data/tmp/planner_base_{counter:04}.png", dpi=300) + + plt.clf() + plt.close(fig) + plt.close('all') + import gc + gc.collect() + + # Mask grid with chosen subgoal (if not None) + # and compute the cost grid for motion planning. + if do_plan_with_known and target_subgoal is not None: + # Plan using the known planner + print("Planning with known planner.") + planning_grid = lsp.core.mask_grid_with_frontiers( + inflated_grid, subgoals, do_not_mask=target_subgoal) + elif do_plan_with_naive or chosen_subgoal is None: + # Plan using the 'naive' planner + print("Planning with naive planner.") + planning_grid = lsp.core.mask_grid_with_frontiers( + inflated_grid, + [], + ) + else: + # Plan using the learned planner + print("Planning with learned planner.") + planning_grid = lsp.core.mask_grid_with_frontiers( + inflated_grid, subgoals, do_not_mask=chosen_subgoal) + + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + + # Move the robot + motion_primitives = robot.get_motion_primitives() + do_use_path = (count_since_last_turnaround > 10) + costs, _ = lsp.primitive.get_motion_primitive_costs( + planning_grid, + cost_grid, + robot.pose, + path, + motion_primitives, + do_use_path=do_use_path) + if abs(min(costs)) < 1e10: + primitive_ind = np.argmin(costs) + robot.move(motion_primitives, primitive_ind) + if primitive_ind == len(motion_primitives) - 1: + count_since_last_turnaround = -1 + else: + # Force the robot to return to known space + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], + use_soft_cost=True, + obstacle_cost=1e5) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + costs, _ = lsp.primitive.get_motion_primitive_costs( + planning_grid, + cost_grid, + robot.pose, + path, + motion_primitives, + do_use_path=False) + robot.move(motion_primitives, np.argmin(costs)) + + # Check that the robot is not 'stuck'. + if robot.max_travel_distance( + num_recent_poses=100) < 5 * args.step_size: + print("Planner stuck") + did_succeed = False + break + + if robot.net_motion > 4000: + print("Reached maximum distance.") + did_succeed = False + break + + logger.debug(f"[{counter}] total step time: {time.time() - stime}") + counter += 1 + count_since_last_turnaround += 1 + if not args.silence: + print("") + + # For testing and debugging purposes + if return_planner_after_steps is not None and counter > return_planner_after_steps: + return eval_planner + + if not args.silence: + print("TOTAL TIME:", time.time() - fn_start_time) + + # Update the pickles with the final motion data + if do_write_data: + net_travel = robot.net_motion + planners['known'].robot_pose = robot.pose + did_plan, _, final_known_distance = planners[ + 'known'].compute_path_to_goal() + + if not did_succeed: + final_known_distance += 1000 + if not did_plan: + raise ValueError( + f"Robot ending away from goal (seed: {args.current_seed}.") + for dat in travel_data: + # Open the pickle + pickle_name = dat['pickle_name'] + with gzip.GzipFile(pickle_name, 'rb') as pfile: + pdat = cPickle.load(pfile) + + # Update the data + pdat['net_cost_remaining'] = (final_known_distance + net_travel - + dat['robot_motion']) + pdat['net_cost_remaining_known'] = dat['known_distance'] + + # Dump the pickle + with gzip.GzipFile(pickle_name, 'wb', + compresslevel=COMPRESS_LEVEL) as f: + cPickle.dump(pdat, f, protocol=-1) + + print("AGREES") + print(agrees_with_oracle) + + agrees_with_oracle + idx_pairs = np.where( + np.diff( + np.hstack(([False], np.logical_not(agrees_with_oracle), + [False]))))[0].reshape(-1, 2) + try: + start_longest_disagreement = ( + idx_pairs[np.diff(idx_pairs, axis=1).argmax(), 0]) + except ValueError: + start_longest_disagreement = 0 + + return { + 'did_succeed': did_succeed, + 'map': robot_grid, + 'path': robot.all_poses, + 'agrees_with_oracle': agrees_with_oracle, + 'start_of_longest_disagreement': start_longest_disagreement, + 'intervene_pose': intervene_pose + } diff --git a/modules/lsp_xai/lsp_xai/planners/explanation.py b/modules/lsp_xai/lsp_xai/planners/explanation.py new file mode 100644 index 0000000..44dbeab --- /dev/null +++ b/modules/lsp_xai/lsp_xai/planners/explanation.py @@ -0,0 +1,604 @@ +import matplotlib.pyplot as plt +from matplotlib.patches import ConnectionPatch +import numpy as np +import textwrap + +import gridmap +from gridmap.constants import COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL + +# for Palatino and other serif fonts use: +plt.rcParams.update({ + "text.usetex": True, + "font.family": "serif", + "font.serif": ["Palatino"], +}) + + +class SubgoalDiff(object): + def __init__(self, subgoal_prop_base, subgoal_prop_upd): + self.prob_feasible_diff = (subgoal_prop_upd.prob_feasible - + subgoal_prop_base.prob_feasible).item() + self.delta_success_cost_diff = ( + subgoal_prop_upd.delta_success_cost - + subgoal_prop_base.delta_success_cost).item() + self.exploration_cost_diff = ( + subgoal_prop_upd.exploration_cost - + subgoal_prop_base.exploration_cost).item() + + +class Explanation(object): + def __init__(self, + subgoals, + subgoal_ind_dict, + base_datum, + base_subgoal_props, + updated_datum, + updated_subgoal_props, + delta_subgoal_data, + partial_grid, + inflated_partial_grid, + goal_pose, + robot_pose, + limit_num=-1): + # Want to store the subgoal properties and datum before and after the + # updates. Also store the 'delta_subgoal_data' which will tell us which + # of the subgoal properties we allowed the derivative to update. Also + # the map, from which it can compute the paths. + self.subgoals = subgoals + self.subgoal_ind_dict = subgoal_ind_dict + self.base_datum = base_datum + self.base_subgoal_props = base_subgoal_props + self.updated_datum = updated_datum + self.updated_subgoal_props = updated_subgoal_props + self.delta_subgoal_data = delta_subgoal_data + self.partial_grid = partial_grid + self.inflated_partial_grid = inflated_partial_grid + self.goal_pose = goal_pose + self.robot_pose = robot_pose + self.limit_num = limit_num + + def get_subgoal_prop_changes(self): + return { + k: SubgoalDiff(self.base_subgoal_props[k], + self.updated_subgoal_props[k]) + for k in self.base_subgoal_props.keys() + } + + def visualize(self, plot_name=None, show_plot=False): + # Some setup + ind_p_ind_dict = {} + prop_changes = self.get_subgoal_prop_changes() + num_subgoals = len( + self.updated_datum['target_subgoal_policy']['policy']) + import matplotlib.cm + cmap = matplotlib.cm.get_cmap('viridis') + colors = [cmap(ii / num_subgoals) for ii in range(num_subgoals)] + + print("Base policy for chosen subgoal:") + for p_ind, ind in enumerate( + self.base_datum['backup_subgoal_policy']['policy']): + if (ind, 'prob_feasible') not in self.delta_subgoal_data.keys(): + print("ERROR: dsd") + continue + + ind_p_ind_dict[ind] = p_ind + sp_base = self.base_subgoal_props[ind] + + print( + f"ind: {p_ind:3d} " + f"| Ps: {sp_base.prob_feasible:.4f} " + f"[D: {prop_changes[ind].prob_feasible_diff:4f}] " + f"| rank: {self.delta_subgoal_data[(ind, 'prob_feasible')].rank:3d}" + ) + print( + f" " + f"| Rs: {sp_base.delta_success_cost:.4f} " + f"[D: {prop_changes[ind].delta_success_cost_diff:4f}] " + f"| rank: {self.delta_subgoal_data[(ind, 'delta_success_cost')].rank:3d}" + ) + print( + f" " + f"| Re: {sp_base.exploration_cost:.4f} " + f"[D: {prop_changes[ind].exploration_cost_diff:4f}] " + f"| rank: {self.delta_subgoal_data[(ind, 'exploration_cost')].rank:3d}" + ) + + print("Updated policy for query subgoal.") + for ind in self.updated_datum['target_subgoal_policy']['policy']: + if (ind, 'prob_feasible') not in self.delta_subgoal_data.keys(): + print("ERROR: dsd") + continue + + if ind in ind_p_ind_dict.keys(): + p_ind = ind_p_ind_dict[ind] + else: + p_ind = len(ind_p_ind_dict.keys()) + ind_p_ind_dict[ind] = p_ind + sp_upd = self.updated_subgoal_props[ind] + + dsd_ps = self.delta_subgoal_data[(ind, 'prob_feasible')] + dsd_rs = self.delta_subgoal_data[(ind, 'delta_success_cost')] + dsd_re = self.delta_subgoal_data[(ind, 'exploration_cost')] + + print(f"ind: {p_ind:3d} " + f"| Ps: {sp_upd.prob_feasible:.4f} " + f"| rank: {dsd_ps.rank:3d} [{dsd_ps.rank < self.limit_num}] " + f"[{dsd_ps.net_data_cost_fraction:4f}]") + print(f" " + f"| Rs: {sp_upd.delta_success_cost:.4f} " + f"| rank: {dsd_rs.rank:3d} [{dsd_rs.rank < self.limit_num}] " + f"[{dsd_rs.net_data_cost_fraction:4f}]") + print(f" " + f"| Re: {sp_upd.exploration_cost:.4f} " + f"| rank: {dsd_re.rank:3d} [{dsd_re.rank < self.limit_num}] " + f"[{dsd_re.net_data_cost_fraction:4f}]") + + # Now show the subgoal image data + height = 1.25 * num_subgoals + 0 * 10 + 2 + bsp_ind = 1 + tsp_ind = 2 + if show_plot: + fig = plt.figure(dpi=300, figsize=(25 / 4, height / 4)) + else: + fig = plt.figure(dpi=300, figsize=(25, height)) + + # Initialize the plots + gspec_left = plt.GridSpec(ncols=4, + nrows=num_subgoals + 1, + hspace=0.4, + width_ratios=[1.0, 0.5, 0.5, 1.0]) + gspec_right = gspec_left + gspec_maps = plt.GridSpec(ncols=4, + nrows=num_subgoals + 1, + hspace=0.1, + wspace=0.1, + width_ratios=[1, 0.9, 0.9, 1]) + axs = [[[] for _ in range(4)] for _ in range(num_subgoals)] + + do_include_policy = True + + # Add the map plots + ax = fig.add_subplot(gspec_maps[:-1, 0]) + self._add_map_plot(ax, colors, 'base', do_include_policy) + ax = fig.add_subplot(gspec_maps[:-1, -1]) + self._add_map_plot(ax, colors, 'updated', do_include_policy) + # Base plots + for ii, ind in enumerate( + self.base_datum['backup_subgoal_policy']['policy']): + ax = fig.add_subplot(gspec_left[ii, bsp_ind]) + axs[ii][bsp_ind] = ax + self._fill_subgoal_subplot(ax, + ind, + ii, + f"{str(ii)}", + color=colors[ii], + data_src='base', + do_include_policy=do_include_policy) + + # Updated plots + for ii, ind in enumerate( + self.updated_datum['target_subgoal_policy']['policy']): + ax = fig.add_subplot(gspec_right[ii, tsp_ind]) + axs[ii][tsp_ind] = ax + self._fill_subgoal_subplot(ax, + ind, + ii, + f"{chr(ii+97)}", + color=colors[ii], + data_src='updated', + do_include_policy=do_include_policy) + + if do_include_policy: + self._draw_policy_annotations('base', bsp_ind, colors, fig, axs) + self._draw_policy_annotations('updated', tsp_ind, colors, fig, axs) + + # Now we draw lines between the different plots + # First, the lines across the different policies + for ii, ind in enumerate( + self.updated_datum['target_subgoal_policy']['policy']): + if not do_include_policy: + break + + p_ind = ind_p_ind_dict[ind] + ax_base = axs[p_ind][bsp_ind] + ax_upd = axs[ii][tsp_ind] + con = ConnectionPatch(xyA=(1.0, 0.5), + coordsA=ax_base.transAxes, + xyB=(0.0, 0.5), + coordsB=ax_upd.transAxes) + fig.add_artist(con) + + # == Generate plain text == + # Sort the subgoals by rank + ordered_subgoal_inds = [ + ind + for ind in self.updated_datum['target_subgoal_policy']['policy'] + ] + ordered_subgoal_inds.sort(key=lambda ind: min([ + self.delta_subgoal_data[(ind, 'prob_feasible')].rank, self. + delta_subgoal_data[(ind, 'exploration_cost')].rank, self. + delta_subgoal_data[(ind, 'delta_success_cost')].rank + ])) + + sc_dict = { + ind: self.updated_datum['target_subgoal_policy'] + ['success_distances'][ii] + for ii, ind in enumerate( + self.updated_datum['target_subgoal_policy']['policy']) + } + + p_base_ind = ind_p_ind_dict[self.base_datum['backup_subgoal_policy'] + ['policy'][0]] + p_target_ind = ind_p_ind_dict[self.base_datum['target_subgoal_policy'] + ['policy'][0]] + + explanation = [] + for ind in ordered_subgoal_inds: + p_ind = ind_p_ind_dict[ind] + # Prob Feasible + + dsd_ps = self.delta_subgoal_data[(ind, 'prob_feasible')] + dsd_rs = self.delta_subgoal_data[(ind, 'delta_success_cost')] + dsd_re = self.delta_subgoal_data[(ind, 'exploration_cost')] + + sp_base = self.base_subgoal_props[ind] + sp_updated = self.updated_subgoal_props[ind] + sp_changes = prop_changes[ind] + + ps_rank = self.delta_subgoal_data[(ind, 'prob_feasible')].rank + re_rank = self.delta_subgoal_data[(ind, 'exploration_cost')].rank + rs_rank = self.delta_subgoal_data[(ind, 'delta_success_cost')].rank + + if min([ps_rank, re_rank, rs_rank]) >= self.limit_num: + continue + + # Prob feasible + ps_base = sp_base.prob_feasible + ps_updated = sp_updated.prob_feasible + dps = sp_changes.prob_feasible_diff + if abs(dps) <= 0.1: + adj_str = "slightly " + elif abs(dps) >= 0.4: + adj_str = "significantly " + else: + adj_str = "" + change_str = "more likely" if dps > 0 else "less likely" + change_val_str = "up from" if dps > 0 else "down from" + ps_dat = [ + ps_rank, + (f"that Subgoal {p_ind} were {adj_str}{change_str} to lead to " + f"the goal ({100*ps_updated:2.0f}%, " + f"{change_val_str} {100*ps_base:2.0f}%)") + ] + + # Delta Success Cost + sc = sc_dict[ind] + rs_base = sp_base.delta_success_cost + sc + rs_updated = sp_updated.delta_success_cost + sc + drs = sp_changes.delta_success_cost_diff + if abs(dps) <= 10: + adj_str = "slightly " + elif abs(dps) >= 50: + adj_str = "significantly " + else: + adj_str = "" + change_str = "increased" if drs > 0 else "decreased" + change_val_str = "up from" if drs > 0 else "down from" + rs_dat = [ + rs_rank, + (f"that the cost of getting to the goal through " + f"Subgoal {p_ind} were {adj_str}{change_str} " + f"({rs_updated/10:.1f} meters, " + f"{change_val_str} {rs_base/10:.1f} meters)") + ] + + # Exploration Cost + re_base = sp_base.exploration_cost + re_updated = sp_updated.exploration_cost + dre = sp_changes.exploration_cost_diff + if abs(dps) <= 10: + adj_str = "slightly " + elif abs(dps) >= 50: + adj_str = "significantly " + else: + adj_str = "" + change_str = "increased" if dre > 0 else "decreased" + change_val_str = "up from" if dre > 0 else "down from" + re_dat = [ + re_rank, + (f"that the cost of revealing a dead end beyond " + f"Subgoal {p_ind} were {adj_str}{change_str} " + f"({re_updated/10:.1f} meters, " + f"{change_val_str} {re_base/10:.1f} meters)") + ] + + explain_components = [ps_dat, rs_dat, re_dat] + explain_components.sort(key=lambda ec: ec[0]) + explain_components = [ + ec[1] for ec in explain_components if ec[0] < self.limit_num + ] + explanation.append(" and ".join(explain_components)) + + explanation = (f"I would have prefered Subgoal {p_target_ind} " + + f"over Subgoal {p_base_ind} if I instead believed " + + "; and believed ".join(explanation) + ".") + ax = fig.add_subplot(gspec_maps[-1, :]) + ax.set_xlim([0, 1]) + ax.set_axis_off() + explanation = textwrap.fill(explanation.replace("%", "\\%"), width=120) + ax.text(0.1, + 0.9, + explanation, + ha='left', + va='top', + wrap=True, + fontsize=15) + + if plot_name is not None: + print(f"Saving figure: {plot_name}") + plt.savefig(plot_name) + elif show_plot: + plt.show() + + def _add_map_plot(self, ax, colors, policy_name, do_include_policy=True): + # Set up + ind_subgoal_dict = {ind: s for s, ind in self.subgoal_ind_dict.items()} + if policy_name == 'updated': + policy = self.updated_datum['target_subgoal_policy']['policy'] + subgoal_props = self.updated_subgoal_props + elif policy_name == 'base': + policy = self.base_datum['backup_subgoal_policy']['policy'] + subgoal_props = self.base_subgoal_props + else: + raise ValueError('policy_name not supported.') + + plotting_grid = np.zeros(self.partial_grid.shape) + plotting_grid[self.partial_grid == COLLISION_VAL] = 0.0 + plotting_grid[self.partial_grid == FREE_VAL] = 1.0 + plotting_grid[self.partial_grid == UNOBSERVED_VAL] = 0.7 + ax.imshow(plotting_grid, origin='lower', cmap='gray') + ax.set_title("The robot's partial map of the world\n" + "Robot (R), Goal (G), and Subgoals\n" + "Also includes the agent's plan.") + + # Plot the paths + planning_grid = self.inflated_partial_grid.copy() + planning_grid[self.partial_grid == UNOBSERVED_VAL] = COLLISION_VAL + for subgoal in self.subgoals: + planning_grid[subgoal.points[0, :], + subgoal.points[1, :]] = FREE_VAL + + poses = ( + [[self.robot_pose.x, self.robot_pose.y]] + + [ind_subgoal_dict[ind].get_frontier_point() for ind in policy]) + probs = [subgoal_props[ind].prob_feasible for ind in policy] + path_dat = [] + cpd = 1.0 + cpds = [] + for ii, (ps, pe, prob) in enumerate(zip(poses, poses[1:], probs)): + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [pe[0], pe[1]], use_soft_cost=True) + did_plan, path = get_path([ps[0], ps[1]], + do_sparsify=True, + do_flip=True) + path_dat.append([path, colors[ii], float(cpd)]) + cpd *= (1 - prob) + cpds.append(float(cpd)) + + # Plot in reverse to 'first' paths go 'on top' + if not do_include_policy: + path_dat = path_dat[:1] + path_dat[0][2] = 1.0 + + for path, color, cpd in path_dat[::-1]: + if len(path) < 2: + continue + + ax.plot(path[1, :] - 0.5, + path[0, :] - 0.5, + color=color, + alpha=0.8, + linewidth=self._get_linewidth_from_cpd(cpd)) + + # Plot the paths to the goal + planning_grid = self.inflated_partial_grid.copy() + planning_grid[self.partial_grid == FREE_VAL] = COLLISION_VAL + for subgoal in self.subgoals: + planning_grid[subgoal.points[0, :], + subgoal.points[1, :]] = FREE_VAL + + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [self.goal_pose.x, self.goal_pose.y], + use_soft_cost=True) + path_dat = [] + + for color, cpd, ps in zip(colors, cpds, poses[1:]): + did_plan, path = get_path([ps[0], ps[1]], + do_sparsify=True, + do_flip=False) + path_dat.append([path, color, cpd]) + + # Plot in reverse to 'first' paths go 'on top' + if not do_include_policy: + path_dat = path_dat[:1] + path_dat[0][2] = 1.0 + + for path, color, cpd in path_dat[::-1]: + if len(path) < 2: + continue + ax.plot(path[1, :] - 0.5, + path[0, :] - 0.5, + color=color, + alpha=0.6, + linestyle='dotted', + linewidth=self._get_linewidth_from_cpd(cpd)) + + # Plot the badges + ax.text(self.robot_pose.y, + self.robot_pose.x, + "R", + bbox={ + "boxstyle": "round", + "edgecolor": "black", + "facecolor": "white", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transData) + ax.text(self.goal_pose.y, + self.goal_pose.x, + "G", + bbox={ + "boxstyle": "round", + "edgecolor": "black", + "facecolor": "green", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transData) + for ii, ind in enumerate(policy): + subgoal = ind_subgoal_dict[ind] + s_cent = subgoal.get_frontier_point() + label = chr(ii + 97) if policy_name == 'updated' else str(ii) + ax.text(s_cent[1], + s_cent[0], + label, + bbox={"boxstyle": "round", + "edgecolor": colors[ii], + "facecolor": "white", + "linewidth": 2}, + transform=ax.transData) + + def _fill_subgoal_subplot(self, ax, ind, num, label, color, data_src, + do_include_policy): + ind_subgoal_dict = {ind: s for s, ind in self.subgoal_ind_dict.items()} + subgoal = ind_subgoal_dict[ind] + + # Add the image + ax.imshow(subgoal.nn_input_data['image']) + ax.axes.xaxis.set_visible(False) + ax.axes.yaxis.set_visible(False) + sp_changes = self.get_subgoal_prop_changes() + + if data_src == 'base': + offset = -0.55 + sp = self.base_subgoal_props[ind] + sc = self.base_datum['backup_subgoal_policy']['success_distances'][ + num] + elif data_src == 'updated': + offset = 1.05 + sp = self.updated_subgoal_props[ind] + sc = self.updated_datum['target_subgoal_policy'][ + 'success_distances'][num] + else: + raise ValueError("'data_src' must be either 'base' or 'updated'.") + + ax.plot([0.5, 0.5], [1.0, 0.0], + transform=ax.transAxes, + color=color, + alpha=0.3) + ax.text(0.5, + 0.95, + label, + bbox={ + "boxstyle": "round", + "edgecolor": color, + "facecolor": "white", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transAxes) + + if not do_include_policy: + return + + if self.limit_num > 0: + is_ps_diff = self.delta_subgoal_data[( + ind, 'prob_feasible')].rank < self.limit_num + is_rs_diff = self.delta_subgoal_data[( + ind, 'delta_success_cost')].rank < self.limit_num + is_re_diff = self.delta_subgoal_data[( + ind, 'exploration_cost')].rank < self.limit_num + else: + is_ps_diff = True + is_rs_diff = True + is_re_diff = True + + if is_ps_diff: + ps_diff = sp_changes[ind].prob_feasible_diff + ps_str = f"$\\mathbf{{ P_s = {sp.prob_feasible:0.3f} }}$" + if ps_diff >= 0 and data_src == 'base': + ps_str += f"\\ [$\\Delta\\uparrow${abs(ps_diff):0.3f}]" + elif ps_diff < 0 and data_src == 'base': + ps_str += f"\\ [$\\Delta\\downarrow${abs(ps_diff):0.3f}]" + else: + ps_str = f"$P_s = {sp.prob_feasible:0.3f}$" + + if is_rs_diff: + rs_diff = sp_changes[ind].delta_success_cost_diff + rs_str = f"$\\mathbf{{ R_s = {sp.delta_success_cost + sc:0.2f} }}$" + if rs_diff >= 0 and data_src == 'base': + rs_str += f"\\ [$\\Delta\\uparrow${abs(rs_diff):0.2f}]" + elif rs_diff < 0 and data_src == 'base': + rs_str += f"\\ [$\\Delta\\downarrow${abs(rs_diff):0.2f}]" + else: + rs_str = f"$R_s = {sp.delta_success_cost + sc:0.2f}$" + + if is_re_diff: + re_diff = sp_changes[ind].exploration_cost_diff + re_str = f"$\\mathbf{{ R_e = {sp.exploration_cost:0.2f} }}$" + if re_diff >= 0 and data_src == 'base': + re_str += f"\\ [$\\Delta\\uparrow${abs(re_diff):0.2f}]" + elif re_diff < 0 and data_src == 'base': + re_str += f"\\ [$\\Delta\\downarrow${abs(re_diff):0.2f}]" + else: + re_str = f"$R_e = {sp.exploration_cost:0.2f}$" + + head_str = f"Subgoal: $s_{label}$" + + plt.text(offset, 0.85, head_str, transform=ax.transAxes) + plt.text(offset, 0.6, ps_str, transform=ax.transAxes) + plt.text(offset, 0.4, rs_str, transform=ax.transAxes) + plt.text(offset, 0.2, re_str, transform=ax.transAxes) + + def _draw_policy_annotations(self, policy_name, policy_ind, colors, fig, + axs): + # Next draw the annotations between each set of plots + if policy_name == 'base': + policy_data = self.base_datum['backup_subgoal_policy'] + subgoal_props = self.base_subgoal_props + else: + policy_data = self.updated_datum['target_subgoal_policy'] + subgoal_props = self.updated_subgoal_props + + policy = policy_data['policy'] + probs = [subgoal_props[ind].prob_feasible for ind in policy] + + cpd = 1.0 + for ii, (cost, prob, color) in enumerate( + zip(policy_data['failure_distances'], probs, colors[1:])): + cpd *= (1 - prob) + # Add the line + ax_a = axs[ii][policy_ind] + ax_b = axs[ii + 1][policy_ind] + con = ConnectionPatch(xyA=(0.1, 0.0), + coordsA=ax_a.transAxes, + xyB=(0.1, 1.0), + coordsB=ax_b.transAxes, + arrowstyle='->', + linewidth=2 * + self._get_linewidth_from_cpd(cpd), + color=color) + fig.add_artist(con) + + # Now add the text + xy = 0.5 * (ax_a.transAxes.transform( + (0.12, 0.0)) + ax_b.transAxes.transform((0.12, 1.0))) + plt.text(xy[0], xy[1], f"Travel Cost: {cost:0.2f}", transform=None) + + @classmethod + def _get_linewidth_from_cpd(_, cpd): + return max(0.5, 2 + np.log10(float(cpd))) diff --git a/modules/lsp_xai/lsp_xai/planners/known_subgoal_planner.py b/modules/lsp_xai/lsp_xai/planners/known_subgoal_planner.py new file mode 100644 index 0000000..969f3c5 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/planners/known_subgoal_planner.py @@ -0,0 +1,86 @@ +import copy +import gridmap +import logging +import lsp +import time + +NUM_MAX_FRONTIERS = 7 + + +class KnownSubgoalPlanner(lsp.planners.KnownPlanner): + def __init__(self, goal, known_map, args): + super(KnownSubgoalPlanner, self).__init__(goal, known_map, args) + self.update_counter = 0 + + def update(self, observation, observed_map, subgoals, robot_pose, + visibility_mask): + """Updates the internal state with the new grid/pose/laser scan. + + This function also computes a few necessary items, like which + frontiers have recently been updated and computes their properties + from the known grid. + """ + self.update_counter += 1 + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=2.0 / self.args.base_resolution, + chosen_frontier=self.selected_subgoal) + + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, self.goal) + + # Update frontier properties using the known map + self._update_frontier_props_known(robot_pose, self.goal, + observation['image'], + visibility_mask) + + def _update_frontier_props_known(self, + robot_pose, + goal_pose, + image, + visibility_mask=None, + do_silence=False): + """Compute frontier properties using the known grid and write data + to a .tfrecords file.""" + logger = logging.getLogger("KnownSubgoalPlanner") + + f_gen = [f for f in self.subgoals if not f.props_set] + updated_frontiers = [] + stime = time.time() + lsp.core.update_frontiers_properties_known(self.inflated_known_grid, + self.inflated_grid, + self.subgoals, f_gen, + robot_pose, goal_pose, + self.downsample_factor) + logger.debug( + f" time to update (all) frontier properties: {time.time() - stime}" + ) + + for frontier in f_gen: + if frontier.is_obstructed: + continue + + updated_frontiers.append(frontier) + + if not do_silence: + lsp.utils.command_line.print_frontier_data( + frontier, num_leading_spaces=16) + + self.subgoal_data_list = lsp.utils.learning_vision.get_oriented_data_from_obs( + updated_frontiers, robot_pose, self.goal, image) + + self.updated_subgoals = updated_frontiers diff --git a/modules/lsp_xai/lsp_xai/planners/subgoal_planner.py b/modules/lsp_xai/lsp_xai/planners/subgoal_planner.py new file mode 100644 index 0000000..fa6ca9e --- /dev/null +++ b/modules/lsp_xai/lsp_xai/planners/subgoal_planner.py @@ -0,0 +1,467 @@ +import copy +from lsp.core import get_goal_distances, get_frontier_distances, get_robot_distances, get_top_n_frontiers +import lsp +import gridmap +import numpy as np +import logging +import time +import torch +from .explanation import Explanation +import lsp_xai +import lsp_xai.utils.plotting +from lsp_xai.learning.models import ExpNavVisLSP + +NUM_MAX_FRONTIERS = 12 + + +class SubgoalPlanner(lsp.planners.Planner): + def __init__(self, goal, args, device=None): + super(SubgoalPlanner, self).__init__(goal) + + self.subgoals = set() + self.selected_subgoal = None + self.observed_map = None + self.args = args + self.update_counter = 0 + + self.inflation_radius = args.inflation_radius_m / args.base_resolution + if self.inflation_radius >= np.sqrt(5): + self.downsample_factor = 2 + else: + self.downsample_factor = 1 + + if device is None: + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + self.device = device + + self.subgoal_property_net, self.model = ExpNavVisLSP.get_net_eval_fn( + args.network_file, device=self.device, do_return_model=True) + + def get_planner_state(self): + return { + 'args': self.args, + 'goal': self.goal, + 'observed_map': self.observed_map, + 'inflated_grid': self.inflated_grid, + 'subgoals': self.subgoals, + 'robot_pose': self.robot_pose, + 'update_counter': self.update_counter + } + + def update(self, observation, observed_map, subgoals, robot_pose, + visibility_mask): + """Updates the internal state with the new grid/pose/laser scan. + + This function also computes a few necessary items, like the new + set of frontiers from the inflated grid and their properties from + the trained network. + """ + self.update_counter += 1 + self.observation = observation + self.observed_map = observed_map + self.robot_pose = robot_pose + + # Store the inflated grid after ensuring that the unreachable 'free + # space' is set to 'unobserved'. This avoids trying to plan to + # unreachable space and avoids having to check for this everywhere. + inflated_grid = self._get_inflated_occupancy_grid() + self.inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, robot_pose) + + # Compute the new frontiers and update stored frontiers + new_subgoals = set([copy.copy(s) for s in subgoals]) + self.subgoals = lsp.core.update_frontier_set( + self.subgoals, + new_subgoals, + max_dist=20.0 / self.args.base_resolution, + chosen_frontier=self.selected_subgoal) + + # Also check that the goal is not inside the frontier + lsp.core.update_frontiers_goal_in_frontier(self.subgoals, self.goal) + + self._update_frontier_props_oriented(robot_pose=robot_pose, + goal_pose=self.goal, + image=observation['image'], + visibility_mask=visibility_mask) + + def _update_frontier_props_oriented(self, + robot_pose, + goal_pose, + image, + visibility_mask=None): + if image is None: + raise ValueError("argument 'image' must not be 'None'") + + image = image * 1.0 / 255.0 + + # Loop through subgoals and set properties + for subgoal in self.subgoals: + if subgoal.props_set: + continue + + # Compute the data that will be passed to the neural net + input_data = lsp.utils.learning_vision.get_oriented_input_data( + image, robot_pose, goal_pose, subgoal) + + # Store the input data alongside each subgoal + subgoal.nn_input_data = input_data + + # Compute subgoal properties from neural network + [prob_feasible, delta_success_cost, exploration_cost] = \ + self.subgoal_property_net( + image=input_data['image'], + goal_loc_x=input_data['goal_loc_x'], + goal_loc_y=input_data['goal_loc_y'], + subgoal_loc_x=input_data['subgoal_loc_x'], + subgoal_loc_y=input_data['subgoal_loc_y']) + subgoal.set_props(prob_feasible=prob_feasible, + delta_success_cost=delta_success_cost, + exploration_cost=exploration_cost, + last_observed_pose=robot_pose) + + for subgoal in self.subgoals: + if not self.args.silence and subgoal.prob_feasible > 0.0: + print(" " * 20 + "PLAN (%.2f %.2f) | %.6f | %7.2f | %7.2f" % + (subgoal.get_centroid()[0], subgoal.get_centroid()[1], + subgoal.prob_feasible, subgoal.delta_success_cost, + subgoal.exploration_cost)) + + def _recompute_all_subgoal_properties(self): + # Loop through subgoals and set properties + for subgoal in self.subgoals: + input_data = subgoal.nn_input_data + + # Compute subgoal properties from neural network + [prob_feasible, delta_success_cost, exploration_cost] = \ + self.subgoal_property_net( + image=input_data['image'], + goal_loc_x=input_data['goal_loc_x'], + goal_loc_y=input_data['goal_loc_y'], + subgoal_loc_x=input_data['subgoal_loc_x'], + subgoal_loc_y=input_data['subgoal_loc_y']) + subgoal.set_props(prob_feasible=prob_feasible, + delta_success_cost=delta_success_cost, + exploration_cost=exploration_cost, + last_observed_pose=subgoal.last_observed_pose) + + def compute_selected_subgoal(self): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + if is_goal_in_range: + print("Goal in Range") + return None + + # Compute chosen frontier + min_cost, frontier_ordering = ( + lsp.core.get_best_expected_cost_and_frontier_list( + self.inflated_grid, + self.robot_pose, + self.goal, + self.subgoals, + num_frontiers_max=NUM_MAX_FRONTIERS, + downsample_factor=self.downsample_factor, + do_correct_low_prob=True)) + if min_cost is None or min_cost > 1e8 or frontier_ordering is None: + raise ValueError("Problem with planning") + + self.latest_ordering = frontier_ordering + self.selected_subgoal = frontier_ordering[0] + return self.selected_subgoal + + def compute_backup_subgoal(self, selected_subgoal): + subgoals, distances = self.get_subgoals_and_distances() + return lsp.core.get_lowest_cost_ordering_not_beginning_with( + selected_subgoal, subgoals, distances)[1][0] + + def compute_subgoal_data(self, + chosen_subgoal, + num_frontiers_max=NUM_MAX_FRONTIERS, + do_return_ind_dict=False): + is_goal_in_range = lsp.core.goal_in_range(self.inflated_grid, + self.robot_pose, self.goal, + self.subgoals) + if is_goal_in_range: + return None + + # Compute chosen frontier + logger = logging.getLogger("SubgoalPlanner") + stime = time.time() + policy_data, subgoal_ind_dict = get_policy_data_for_frontiers( + self.inflated_grid, + self.robot_pose, + self.goal, + chosen_subgoal, + self.subgoals, + num_frontiers_max=num_frontiers_max, + downsample_factor=self.downsample_factor) + logger.debug(f"time to get policy data: {time.time() - stime}") + + if do_return_ind_dict: + return policy_data, subgoal_ind_dict + else: + return policy_data + + def get_subgoals_and_distances(self, subgoals_of_interest=[]): + """Helper function for getting data.""" + # Remove frontiers that are infeasible + subgoals = [s for s in self.subgoals if s.prob_feasible > 0] + subgoals = list(set(subgoals) | set(subgoals_of_interest)) + + # Calculate the distance to the goal and to the robot. + goal_distances = get_goal_distances( + self.inflated_grid, + self.goal, + frontiers=subgoals, + downsample_factor=self.downsample_factor) + + robot_distances = get_robot_distances( + self.inflated_grid, + self.robot_pose, + frontiers=subgoals, + downsample_factor=self.downsample_factor) + + # Get the most n probable frontiers to limit computational load + if NUM_MAX_FRONTIERS > 0 and NUM_MAX_FRONTIERS < len(subgoals): + subgoals = get_top_n_frontiers(subgoals, goal_distances, + robot_distances, NUM_MAX_FRONTIERS) + subgoals = list(set(subgoals) | set(subgoals_of_interest)) + + # Calculate robot and frontier distances + frontier_distances = get_frontier_distances( + self.inflated_grid, + frontiers=subgoals, + downsample_factor=self.downsample_factor) + + distances = { + 'frontier': frontier_distances, + 'robot': robot_distances, + 'goal': goal_distances, + } + + return subgoals, distances + + def generate_counterfactual_explanation(self, + query_subgoal, + limit_num=-1, + do_freeze_selected=True, + keep_changes=False, + margin=0, + learning_rate=1.0e-4): + # Initialize the datum + device = self.device + chosen_subgoal = self.compute_selected_subgoal() + datum, subgoal_ind_dict = self.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = self.model.update_datum(datum, device) + + # Now we want to rearrange things a bit: the new 'target' subgoal we set to + # our query_subgoal and we populate the 'backup' + # subgoal with the 'chosen' subgoal (the subgoal the agent actually chose). + datum['target_subgoal_ind'] = subgoal_ind_dict[query_subgoal] + if do_freeze_selected: + datum['backup_subgoal_ind'] = subgoal_ind_dict[chosen_subgoal] + + # We update the datum to reflect this change (and confirm it worked). + datum = self.model.update_datum(datum, device) + + # Compute the 'delta subgoal data'. This is how we determine the + # 'importance' of each of the subgoal properties. In practice, we will sever + # the gradient for all but a handful of these with an optional parameter + # (not set here). + base_model_state = self.model.state_dict(keep_vars=False) + base_model_state = copy.deepcopy(base_model_state) + base_model_state = {k: v.cpu() for k, v in base_model_state.items()} + + updated_datum, delta_subgoal_data, base_subgoal_props, updated_subgoal_props = ( + self.model.update_model_counterfactual(datum, limit_num, + margin, learning_rate, + self.device)) + + # Restore the model to its previous value + if not keep_changes: + print("Restoring Model") + self.model.load_state_dict(base_model_state) + self.model.eval() + self.model = self.model.to(device) + else: + print("Keeping model") + self._recompute_all_subgoal_properties() + + return Explanation(self.subgoals, subgoal_ind_dict, datum, + base_subgoal_props, updated_datum, updated_subgoal_props, + delta_subgoal_data, self.observed_map, + self.inflated_grid, self.goal, self.robot_pose, + limit_num) + + def plot_map_with_plan(self, ax=None, robot_poses=None, image=None, + query_subgoal=None, datum=None, subgoal_props=None, subgoal_ind_dict=None): + import matplotlib.pyplot as plt + ax_img = plt.subplot(121) + ax_img.axes.xaxis.set_visible(False) + ax_img.axes.yaxis.set_visible(False) + + # Initialize the datum + device = self.device + chosen_subgoal = self.compute_selected_subgoal() + + if chosen_subgoal is None: + lsp_xai.utils.plotting.plot_map( + ax_img, self, robot_poses=robot_poses) + return + + if datum is None or subgoal_props is None: + datum, subgoal_ind_dict = self.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = self.model.update_datum(datum, device) + delta_subgoal_data = self.model.get_subgoal_prop_impact( + datum, device, delta_cost_limit=-1e10) + + # Compute the subgoal props + nn_out, ind_mapping = self.model(datum, device) + is_feasibles = torch.nn.Sigmoid()(nn_out[:, 0]) + delta_success_costs = nn_out[:, 1] + exploration_costs = nn_out[:, 2] + subgoal_props, _, _ = self.model.compute_subgoal_props( + is_feasibles, + delta_success_costs, + exploration_costs, + datum['subgoal_data'], + ind_mapping, + device, + limit_subgoals_num=0, + delta_subgoal_data=delta_subgoal_data) + + policy = datum['target_subgoal_policy']['policy'] + + lsp_xai.utils.plotting.plot_map_with_plan( + ax_img, self, subgoal_ind_dict, policy, subgoal_props, + robot_poses=robot_poses) + + # Plot the onboard image + if image is not None: + ax = plt.subplot(3, 2, 2) + ax.imshow(image) + ax.set_title('Onboard Image') + ax.axes.xaxis.set_visible(False) + ax.axes.yaxis.set_visible(False) + + # Plt the chosen subgoal + ax = plt.subplot(3, 2, 4) + chosen_subgoal_ind = subgoal_ind_dict[chosen_subgoal] + ax.imshow(datum['subgoal_data'][chosen_subgoal_ind]['image']) + pf_chosen = subgoal_props[chosen_subgoal_ind].prob_feasible + ax.set_title(f'Subgoal 0: $P_S$ = {pf_chosen*100:.1f}\\%') + ax.axes.xaxis.set_visible(False) + ax.axes.yaxis.set_visible(False) + ax.plot([0.5, 0.5], [1.0, 0.0], + transform=ax.transAxes, + color=[0, 0, 1], + alpha=0.3) + + # Plot the query/backup subgoal + ax = plt.subplot(3, 2, 6) + if query_subgoal is None: + query_subgoal = self.compute_backup_subgoal(chosen_subgoal) + query_subgoal_ind = subgoal_ind_dict[query_subgoal] + ax.imshow(datum['subgoal_data'][query_subgoal_ind]['image']) + pf_query = subgoal_props[query_subgoal_ind].prob_feasible + ax.set_title(f'Subgoal 1: $P_S$ = {pf_query*100:.1f}\\%') + ax.axes.xaxis.set_visible(False) + ax.axes.yaxis.set_visible(False) + ax.plot([0.5, 0.5], [1.0, 0.0], + transform=ax.transAxes, + color=[0, 0, 1], + alpha=0.3) + + @classmethod + def create_with_state(cls, planner_state_datum, network_file): + # Initialize the planner + args = planner_state_datum['args'] + goal = planner_state_datum['goal'] + args.network_file = network_file + planner = cls(goal, args) + + planner.subgoals = planner_state_datum['subgoals'] + planner.observed_map = planner_state_datum['observed_map'] + planner.inflated_grid = planner_state_datum['inflated_grid'] + planner._recompute_all_subgoal_properties() + + return planner + + +# Alt versions of functions +def get_policy_data_for_frontiers(grid, + robot_pose, + goal_pose, + chosen_frontier, + all_frontiers, + num_frontiers_max=0, + downsample_factor=1): + """Compute the optimal orderings for each frontier of interest and return a data +structure containing all the information that would be necessary to compute the +expected cost for each. Also returns the mapping from 'frontiers' to 'inds'.""" + + # Remove frontiers that are infeasible + frontiers = [f for f in all_frontiers if f.prob_feasible != 0] + frontiers = list(set(frontiers) | set([chosen_frontier])) + + # Calculate the distance to the goal, if infeasible, remove frontier + goal_distances = get_goal_distances(grid, + goal_pose, + frontiers=frontiers, + downsample_factor=downsample_factor) + + robot_distances = get_robot_distances(grid, + robot_pose, + frontiers=frontiers, + downsample_factor=downsample_factor) + + # Get the most n probable frontiers to limit computational load + if num_frontiers_max > 0 and num_frontiers_max < len(frontiers): + frontiers = lsp.core.get_top_n_frontiers_distance( + frontiers, goal_distances, robot_distances, num_frontiers_max) + frontiers = list(set(frontiers) | set([chosen_frontier])) + + # Calculate robot and frontier distances + frontier_distances = get_frontier_distances( + grid, frontiers=frontiers, downsample_factor=downsample_factor) + + frontier_ind_dict = {f: ind for ind, f in enumerate(frontiers)} + robot_distances_ind = { + frontier_ind_dict[f]: robot_distances[f] + for f in frontiers + } + goal_distances_ind = { + frontier_ind_dict[f]: goal_distances[f] + for f in frontiers + } + frontier_distances_ind = {} + for ind, f1 in enumerate(frontiers[:-1]): + f1_ind = frontier_ind_dict[f1] + for f2 in frontiers[ind + 1:]: + f2_ind = frontier_ind_dict[f2] + frontier_distances_ind[frozenset( + [f1_ind, f2_ind])] = (frontier_distances[frozenset([f1, f2])]) + + if frontier_distances is not None: + assert len(frontier_distances.keys()) == len( + frontier_distances_ind.keys()) + + # Finally, store the data relevant for + # estimating the frontier properties + frontier_data = { + ind: f.nn_input_data + for f, ind in frontier_ind_dict.items() + } + + return { + 'subgoal_data': frontier_data, + 'distances': { + 'frontier': frontier_distances_ind, + 'robot': robot_distances_ind, + 'goal': goal_distances_ind, + }, + 'target_subgoal_ind': frontier_ind_dict[chosen_frontier] + }, frontier_ind_dict diff --git a/modules/lsp_xai/lsp_xai/scripts/__init__.py b/modules/lsp_xai/lsp_xai/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/lsp_xai/lsp_xai/scripts/explainability_results.py b/modules/lsp_xai/lsp_xai/scripts/explainability_results.py new file mode 100644 index 0000000..372c577 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/scripts/explainability_results.py @@ -0,0 +1,267 @@ +import argparse +import matplotlib.pyplot as plt +from matplotlib import cm +import numpy as np +import pandas as pd +import re +import scipy.stats + + +def process_results_data(args): + # Load data and loop through rows + datasets = [] + if args.do_intervene: + for data_file in args.data_file: + datasets.append(_process_data_file_intervene(data_file)) + else: + for data_file in args.data_file: + datasets.append(_process_data_file_base(data_file)) + + return datasets + + +def _process_data_file_base(data_file): + data = [] + for line in open(data_file).readlines(): + d = re.match( + r'\[Learn\] s: (.*?) . learned: (.*?) . baseline: (.*?)\n', line) + if d is not None: + d = d.groups() + data.append([int(d[0]), float(d[1]), float(d[2])]) + else: + d = re.match( + r'\[Learn\] \[ERR\] s: (.*?) . learned: (.*?) . baseline: (.*?)\n', + line) + if d is None: + continue + d = d.groups() + dm = min(float(d[1]), float(d[2])) + data.append([int(d[0]), float(dm), float(dm)]) + + return pd.DataFrame(data, + columns=['seed', 'learned_cost', 'baseline_cost']) + + +def _process_data_file_intervene(data_file): + data = [] + for line in open(data_file).readlines(): + d = re.match( + r'\[Learn\] s: (.*?) . learned: (.*?) . intervene: (.*?) . baseline: (.*?)\n', + line) + if d is not None: + d = d.groups() + data.append( + [int(d[0]), True, + float(d[1]), + float(d[2]), + float(d[3])]) + else: + d = re.match( + r'\[Learn\] \[ERR\] s: (.*?) . learned: (.*?) . intervene: (.*?) . baseline: (.*?)\n', + line) + if d is None: + continue + d = d.groups() + data.append( + [int(d[0]), False, + float(d[1]), + float(d[1]), + float(d[3])]) + + return pd.DataFrame(data, + columns=[ + 'seed', 'did_succeed', 'learned_cost', + 'intervene_cost', 'baseline_cost' + ]) + + +def build_plot(fig, data, args): + ax = plt.subplot(221) + ax.scatter(data['seed'], + data['learned_cost'] - data['baseline_cost'], + c=data['seed']) + ax.plot( + data['seed'], + pd.DataFrame(data['learned_cost'] - + data['baseline_cost']).rolling(25).mean().to_numpy(), 'y') + ax.plot( + data['seed'], + pd.DataFrame(data['learned_cost'] - + data['baseline_cost']).rolling(50).mean().to_numpy(), 'c') + ax.plot( + data['seed'], + pd.DataFrame(data['learned_cost'] - data['baseline_cost']).rolling( + 100, min_periods=1).mean().to_numpy(), 'b') + ax.plot(data['seed'], 0 * data['seed'], 'k') + ax = plt.subplot(223) + ax.scatter(data['seed'], + np.log(data['learned_cost']) - np.log(data['baseline_cost']), + c=data['seed']) + ax.plot(data['seed'], 0 * data['seed'], 'k') + ax = plt.subplot(122) + ax.scatter(data['baseline_cost'], data['learned_cost'], c=data['seed']) + ax.set_aspect('equal', adjustable='box') + cb = min(max(data['baseline_cost']), max(data['learned_cost'])) + ax.plot([0, cb], [0, cb], 'k') + + # Print some additional statistics + data['cost_diff'] = data['learned_cost'] - data['baseline_cost'] + data = data.sort_values(by='cost_diff', ascending=False) + print(data['seed'][:50].to_numpy()) + + +def build_density_scatterplot(ax, + data, + bounds=None, + cmap='viridis', + title=None): + xy = np.vstack([data['baseline_cost'], data['learned_cost']]) + z = scipy.stats.gaussian_kde(xy)(xy) + + data['zs'] = z + data = data.sort_values(by=['zs']) + z = data['zs'] + colors = cm.get_cmap(cmap)((z - z.min()) / (z.max() - z.min()) * 0.75 + + 0.25) + axins = ax.inset_axes([-0.02, 0.64, 0.38, 0.38]) + + def add_plot(ax, bounds, is_inset=False, sm_bounds=None): + if is_inset: + size = 4 + else: + size = 8 + + ax.scatter(data['baseline_cost'], + data['learned_cost'], + c=colors, + s=size) + ax.set_aspect('equal', adjustable='box') + + cb = max(bounds) * 1.1 + ax.plot([0, cb], [0, cb], 'k:') + ax.set_xlim([0, cb]) + ax.set_ylim([0, cb]) + if is_inset: + ax.set_xticks([max(bounds)]) + ax.set_yticks([max(bounds)]) + import matplotlib.patches + rect = matplotlib.patches.Rectangle((0, 0), + max(sm_bounds), + max(sm_bounds), + edgecolor='gray', + fill=False) + ax.add_patch(rect) + + else: + ax.set_yticks(range(0, 81, 20)) + ax.set_title(title) + + for axis in ['top', 'bottom', 'left', 'right']: + ax.spines[axis].set_linewidth(2.0) + ax.spines[axis].set_color('gray') + + add_plot(ax, bounds, is_inset=False) + add_plot(axins, [400], is_inset=True, sm_bounds=np.array(bounds) * 1.1) + + +def build_plot_comparison(fig, datasets, args): + ax1 = plt.subplot(211) + ax2 = plt.subplot(212) + + import itertools + marker = itertools.cycle(('o', '*', '.', 'x')) + + for data, name in zip(datasets, args.data_file): + d_cost = data['learned_cost'] - data['baseline_cost'] + + line = ax2.plot( + data['seed'], + pd.DataFrame(d_cost).rolling(100, min_periods=1).mean().to_numpy()) + ax2.plot(data['seed'], 0 * data['seed'], 'k') + + # print(line[-1].get_color()) + print(f"\nDataset: {name}") + print(data.describe()) + ax1.scatter(data['seed'], + d_cost, + color=line[-1].get_color(), + s=4, + marker=next(marker)) + print( + f" Ratio of Means: {data['learned_cost'].mean()/data['baseline_cost'].mean()}" + ) + print( + f" Mean of Ratios: {(data['learned_cost']/data['baseline_cost']).mean()}" + ) + + ax1.legend(args.data_file) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description='Generate a figure for results from the interpretability project.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--data_file', + type=str, + nargs='+', + required=False, + default=None) + parser.add_argument('--output_image_file', + type=str, + required=False, + default=None) + parser.add_argument('--xpassthrough', + type=str, + required=False, + default='false') + parser.add_argument('--do_intervene', action='store_true') + args = parser.parse_args() + data_all = process_results_data(args) + for d in data_all: + # Resolution is 0.1, so divide all costs by 10 + d['learned_cost'] /= 10 + d['baseline_cost'] /= 10 + try: + d['intervene_cost'] /= 10 + except KeyError: + pass + + if not args.do_intervene: + print("\nResults Overview:") + for d, name in zip(data_all, args.data_file): + print(name) + print(f" Mean Learned Cost: {d.learned_cost.mean()}") + print(f" Total Learned Cost: {d.learned_cost.sum()}") + print("Non-Learned") + print(f" Mean Non-Learned Cost: {d.baseline_cost.mean()}") + print(f" Total Non-Learned Cost: {d.baseline_cost.sum()}") + else: + for d, name in zip(data_all, args.data_file): + print("") + print(f"Dataset: {name}") + print(f" Num Successful: {sum(d.did_succeed.astype(int))}") + print(f" Learned Cost Total: {sum(d.learned_cost)}") + print(f" Intervene Cost Total: {sum(d.intervene_cost)}") + print(f" Baseline Cost Total: {sum(d.baseline_cost)}") + + if len(data_all) == 3: + num_files = 3 + fig = plt.figure(figsize=(3 * num_files, 3), dpi=300) + bounds = [ + max([d['baseline_cost'].max() for d in data_all]), + max([d['learned_cost'].max() for d in data_all]) + ] + bounds = [125] + + cmaps = ['Reds', 'Oranges', 'Blues'] + titles = ['All Subgoal Props', '4 Subgoal Props', 'No Subgoal Props'] + + for ii, (data, cmap, title) in enumerate(zip(data_all, cmaps, titles)): + ax = plt.subplot(1, num_files, ii + 1) + build_density_scatterplot(ax, + data, + bounds=bounds, + cmap=cmap, + title=title) + + plt.savefig(args.output_image_file) diff --git a/modules/lsp_xai/lsp_xai/scripts/explainability_train_eval.py b/modules/lsp_xai/lsp_xai/scripts/explainability_train_eval.py new file mode 100644 index 0000000..db685f8 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/scripts/explainability_train_eval.py @@ -0,0 +1,517 @@ +import glob +import matplotlib.pyplot as plt +import numpy as np +import os +import torch +from torch.utils.tensorboard import SummaryWriter + +import lsp_xai +import lsp +# from lsp import learning +import learning +from lsp_xai.learning.models import ExpNavVisLSP +from common import compute_path_length +from lsp.planners import DijkstraPlanner +from lsp_xai.planners import SubgoalPlanner, KnownSubgoalPlanner +import environments + +MODEL_CLASS = ExpNavVisLSP + + +def get_nn_model_name(model, args, extension): + """Get the name of the file to which network params will be saved.""" + return os.path.join(args.logdir, f"{model.name}.{extension}.pt") + + +def save_model(model, args, extension): + """Save the neural network model weights/params to file. + Returns the path where the network was saved.""" + net_path = get_nn_model_name(model, args, extension) + torch.save(model.state_dict(), net_path) + return net_path + + +def run_data_gen_eval(args, + do_eval, + do_explain=False, + do_intervene=False, + debug_seed=None, + logfile=None): + # Determine what 'seeds' will be looped through + do_generate_data = (not do_eval) + do_plan_with_naive = (not do_eval) + if debug_seed is not None: + do_generate_data = False + do_plan_with_naive = False + args.current_seed = debug_seed + + print(f"Seed: {args.current_seed}") + + args.cirriculum_fraction = 1.0 + + if do_explain: + explanation = run_single_seed_eval(args, do_plan_with_naive, + do_generate_data, do_explain, + do_intervene) + if explanation is not None: + env_type = "maze" if 'maze' in args.map_type else "floorplan" + plot_name = f"explain_{env_type}_{args.current_seed}_{args.explain_at}.png" + explanation.visualize(os.path.join(args.save_dir, plot_name)) + elif do_intervene: + did_succeed, dist_learned, dist_baseline, dist_intervene = run_single_seed_eval( + args, do_plan_with_naive, do_generate_data, do_explain, + do_intervene) + else: + did_succeed, dist_learned, dist_baseline = run_single_seed_eval( + args, do_plan_with_naive, do_generate_data, do_explain, + do_intervene) + + if logfile is not None: + if do_explain: + with open(logfile, 'a+') as f: + if explanation is None: + f.write(f"[ERR] s: {args.current_seed:4d}") + else: + f.write(f"[SUC] s: {args.current_seed:4d}") + return + + with open(logfile, 'a+') as f: + header = '' + if do_plan_with_naive: + header = 'Naive' + else: + header = 'Learn' + if debug_seed is not None: + header += '|dbg' + + err_str = '' if did_succeed else '[ERR]' + intervene_str = (f" | intervene: {dist_intervene:0.3f}" + if do_intervene else '') + + f.write(f"[{header}] {err_str} s: {args.current_seed:4d}" + f" | learned: {dist_learned:0.3f}" + f"{intervene_str}" + f" | baseline: {dist_baseline:0.3f}\n") + + return (lsp.planners.utils.get_csv_file_combined(args), + lsp.planners.utils.get_csv_file_supervised(args)) + + +def run_single_seed_eval(args, + do_plan_with_naive=False, + do_write_data=True, + do_explain=False, + do_intervene=False): + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + if do_plan_with_naive and (do_explain or do_intervene): + raise ValueError("Can only explain the behavior of the learned agent.") + + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution, + min_interlight_distance=3, + min_light_to_wall_distance=2) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_initialized_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + known_planner = KnownSubgoalPlanner(goal=goal, + known_map=known_map, + args=args) + if not do_write_data and not do_explain and not do_intervene: + known_planner = None + + if do_explain: + explanation = lsp_xai.planners.evaluate.run_model_eval( + args, + goal, + known_map, + simulator, + unity_bridge, + get_initialized_robot(), + eval_planner=SubgoalPlanner(goal=goal, args=args), + known_planner=known_planner, + do_write_data=do_write_data, + do_plan_with_naive=do_plan_with_naive, + do_explain=do_explain, + do_plan_with_known=False) + return explanation + + dat_learned = lsp_xai.planners.evaluate.run_model_eval( + args, + goal, + known_map, + simulator, + unity_bridge, + get_initialized_robot(), + eval_planner=SubgoalPlanner(goal=goal, args=args), + known_planner=known_planner, + do_write_data=do_write_data, + do_plan_with_naive=do_plan_with_naive, + do_explain=do_explain, + do_plan_with_known=False) + + # Run again with an intervention + if do_intervene: + # Compute where the intervention should occur. + dat_intervened = lsp_xai.planners.evaluate.run_model_eval( + args, + goal, + known_map, + simulator, + unity_bridge, + get_initialized_robot(), + eval_planner=SubgoalPlanner(goal=goal, args=args), + known_planner=known_planner, + do_write_data=do_write_data, + do_plan_with_naive=do_plan_with_naive, + do_explain=do_explain, + do_plan_with_known=False, + intervene_at=dat_learned['start_of_longest_disagreement']) + + if not do_plan_with_naive: + dat_baseline = lsp_xai.planners.evaluate.run_model_eval( + args, + goal, + known_map, + simulator, + unity_bridge, + get_initialized_robot(), + eval_planner=DijkstraPlanner(goal=goal, args=args), + do_write_data=False) + else: + dat_baseline = dat_learned + + # Write some plots to file + if do_intervene: + num_cols = 3 + else: + num_cols = 2 + + plt.figure(figsize=(16, 16), dpi=150) + plt.subplot(1, num_cols, 1) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(dat_learned['map'], known_map)) + xs = [p.x for p in dat_learned['path']] + ys = [p.y for p in dat_learned['path']] + p = dat_learned['path'][-1] + plt.plot(ys, xs, 'r') + plt.plot(p.y, p.x, 'go') + plt.subplot(1, num_cols, 2) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(dat_baseline['map'], known_map)) + xs = [p.x for p in dat_baseline['path']] + ys = [p.y for p in dat_baseline['path']] + p = dat_baseline['path'][-1] + plt.plot(ys, xs, 'r') + plt.plot(p.y, p.x, 'go') + + if do_intervene: + plt.subplot(1, num_cols, 3) + plt.imshow( + lsp.utils.plotting.make_plotting_grid(dat_intervened['map'], + known_map)) + xs = [p.x for p in dat_intervened['path']] + ys = [p.y for p in dat_intervened['path']] + p = dat_intervened['path'][-1] + plt.plot(ys, xs, 'r') + plt.plot(p.y, p.x, 'go') + if dat_intervened['intervene_pose'] is not None: + plt.plot(dat_intervened['intervene_pose'][1], + dat_intervened['intervene_pose'][0], 'mo') + + if do_write_data: + img_name = f'data_collect_plots/learned_planner_{args.current_seed}.png' + elif do_intervene: + if args.sp_limit_num < 0: + img_name = f'learned_planner_{args.current_seed}_intervened_allSG.png' + else: + img_name = f'learned_planner_{args.current_seed}_intervened_{args.sp_limit_num}SG.png' + else: + img_name = f'learned_planner_{args.current_seed}.png' + + plt.savefig(os.path.join(args.save_dir, img_name)) + plt.close() + + if do_intervene: + return (dat_learned['did_succeed'] and dat_baseline['did_succeed'] + and dat_intervened['did_succeed'], + compute_path_length(dat_learned['path']), + compute_path_length(dat_baseline['path']), + compute_path_length(dat_intervened['path'])) + else: + return (dat_learned['did_succeed'] and dat_baseline['did_succeed'], + compute_path_length(dat_learned['path']), + compute_path_length(dat_baseline['path'])) + + +def train_model(args, + checkpoint_file, + all_combined_data_files, + all_supervised_data_files, + init=False): + # Initialize the learning + torch.manual_seed(args.learning_seed) + np.random.seed(args.learning_seed) + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + print(f"PyTorch Device: {device}") + model = MODEL_CLASS(args=args) + tot_index = 0 + + # Define the optimizer + learning_rate = args.learning_rate + optimizer = torch.optim.SGD(model.parameters(), lr=learning_rate) + scheduler = torch.optim.lr_scheduler.StepLR(optimizer, + step_size=1, + gamma=0.5) + + # Set up logging + train_all_writer = SummaryWriter( + log_dir=os.path.join(args.logdir, "train_all")) + + if init: + args.network_file = save_model(model, args, 'init') + print(f"Writing Learning to File: {args.network_file}") + return None + + if checkpoint_file is not None: + checkpoint = torch.load(checkpoint_file) + model.load_state_dict(checkpoint['state_dict']) + model.eval() + model = model.to(device) + else: + model = model.to(device) + + # Create the datasets and loaders + preprocess_function = ExpNavVisLSP.preprocess_data + train_all_combined_dataset = learning.data.CSVPickleDataset( + all_combined_data_files) + train_all_combined_loader = torch.utils.data.DataLoader( + train_all_combined_dataset, batch_size=1, shuffle=True, num_workers=8) + train_all_combined_iter = iter(train_all_combined_loader) + + train_all_supervised_dataset = learning.data.CSVPickleDataset( + all_supervised_data_files, preprocess_function) + train_all_supervised_loader = torch.utils.data.DataLoader( + train_all_supervised_dataset, + batch_size=args.batch_size, + shuffle=True, + num_workers=8) + train_all_supervised_iter = iter(train_all_supervised_loader) + + loc_index = 0 + num_decay_steps = 8 + num_data_elements = len(train_all_combined_iter) / num_decay_steps + max_steps = num_decay_steps * num_data_elements + epoch_counter = 0 + + while loc_index < max_steps: + # Get the batches + try: + batch_all_combined = next(train_all_combined_iter) + except StopIteration: + train_all_combined_iter = iter(train_all_combined_loader) + batch_all_combined = next(train_all_combined_iter) + + try: + batch_all_supervised = next(train_all_supervised_iter) + except StopIteration: + train_all_supervised_iter = iter(train_all_supervised_loader) + batch_all_supervised = next(train_all_supervised_iter) + + # Update policies in traing data + print("Updating datum") + try: + batch_all_combined = model.update_datum(batch_all_combined, device) + except ValueError: + print("Not enough subgoals for comparision update.") + continue + + if batch_all_combined is None: + print("Datum is None") + continue + print( + f" Policy Length: {len(batch_all_combined['target_subgoal_policy']['policy'])}" + ) + + # Compute the 'delta subgoal data' for limiting subgoal num + delta_subgoal_data = model.get_subgoal_prop_impact( + batch_all_combined, device, delta_cost_limit=-1e10) + + # Compute loss for 'combined' data + # (requires re-passing through model due to way + # subgoal impact is computed) + # This will occasionally fail when there is only 1 datum + try: + out, ind_map = model(batch_all_combined, device) + except ValueError: + print("FAILING: combined") + continue + + loss_all_combined = model.loss(out, + batch_all_combined, + ind_map, + device=device, + writer=train_all_writer, + index=tot_index, + limit_subgoals_num=args.sp_limit_num, + delta_subgoal_data=delta_subgoal_data, + do_include_negative_costs=True, + do_include_limit_costs=False) + + # Compute loss for 'supervised' data + try: + out = model.forward_supervised(batch_all_supervised, device) + except ValueError: + # This will occasionally happen when there is only 1 datum. + # Skipping this step avoids the issue. + continue + + loss_all_supervised = model.loss_supervised(out, + batch_all_supervised, + device=device, + writer=train_all_writer, + index=tot_index, + positive_weight=2.0) + + if tot_index % args.summary_frequency == 0: + model.plot_data_supervised(train_all_writer, + 'image', + tot_index, + out=out.detach().cpu(), + data=batch_all_supervised) + + loss = (loss_all_combined + loss_all_supervised.to('cpu')) + + # Perform update + optimizer.zero_grad() + loss.backward() + optimizer.step() + tot_index += 1 + loc_index += 1 + + print(f"Step: {loc_index}/{max_steps} (total: {tot_index})") + + if np.floor(loc_index / num_data_elements) > epoch_counter: + epoch_counter += 1 + scheduler.step() + print("Stepping LR") + else: + print( + f" Epoch: {epoch_counter} | LR: {optimizer.param_groups[0]['lr']}" + ) + + # Save the state to file + args.network_file = save_model(model, args, 'final') + return None + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + + # Add some learning-specific arguments + parser.add_argument('--training_data_file', nargs='+', type=str) + parser.add_argument('--logdir', + help='Directory in which to store log files', + required=True, + type=str) + parser.add_argument('--summary_frequency', + default=1000, + help='Frequency (in steps) summary is logged to file', + type=int) + parser.add_argument('--num_epochs', + default=20, + help='Number of epochs to run training', + type=int) + parser.add_argument('--learning_rate', + help='Initial learning rate', + type=float) + parser.add_argument('--batch_size', + help='Number of data per training iteration batch', + type=int) + parser.add_argument('--relative_positive_weight', + default=2.0, + help='Positive data relative weight', + type=float) + + parser.add_argument('--data_file_base_name', type=str, default='lsp_data') + parser.add_argument('--debug_seeds', type=int, default=None) + parser.add_argument('--current_seed', type=int, default=None) + parser.add_argument('--sp_limit_num', type=int, default=-1) + parser.add_argument('--learning_seed', type=int, default=8616) + parser.add_argument('--xent_factor', type=float, default=1.0) + parser.add_argument('--logfile_name', type=str, default='logfile.txt') + parser.add_argument('--do_train', action='store_true') + parser.add_argument('--do_data_gen', action='store_true') + parser.add_argument('--do_eval', action='store_true') + parser.add_argument('--do_explain', action='store_true') + parser.add_argument('--explain_at', type=int, default=0) + parser.add_argument('--do_intervene', action='store_true') + parser.add_argument('--do_init_learning', action='store_true') + + # Parse args + args = parser.parse_args() + if args.debug_seeds is not None: + args.network_file = args.debug_network + + if not (args.do_init_learning or args.do_train): + # Create the log file + logfile = os.path.join(args.save_dir, args.logfile_name) + with open(logfile, "a") as f: + f.write(f"LOG: {args.current_seed}\n") + + if args.do_init_learning: + # Save the untrained neural network to file + checkpoint_file = train_model(args, None, [], [], init=True) + elif args.do_train: + args.network_file = get_nn_model_name(MODEL_CLASS, args, 'init') + all_combined_data_files = glob.glob( + os.path.join(args.save_dir, "*.combined.csv")) + all_supervised_data_files = glob.glob( + os.path.join(args.save_dir, "*.supervised.csv")) + train_model(args, None, all_combined_data_files, + all_supervised_data_files) + elif args.do_data_gen: + args.network_file = get_nn_model_name(MODEL_CLASS, args, 'init') + run_data_gen_eval(args, do_eval=False, logfile=logfile) + elif args.do_eval: + args.network_file = get_nn_model_name(MODEL_CLASS, args, 'final') + run_data_gen_eval(args, do_eval=True, logfile=logfile) + elif args.do_explain: + print("Explaining the agent's behavior.") + args.network_file = get_nn_model_name(MODEL_CLASS, args, 'final') + run_data_gen_eval(args, do_eval=True, do_explain=True, logfile=logfile) + elif args.do_intervene: + args.network_file = get_nn_model_name(MODEL_CLASS, args, 'final') + run_data_gen_eval(args, + do_eval=True, + do_intervene=True, + logfile=logfile) + else: + print("No operation selected. Ending without computation.") diff --git a/modules/lsp_xai/lsp_xai/scripts/interpret_datum.py b/modules/lsp_xai/lsp_xai/scripts/interpret_datum.py new file mode 100644 index 0000000..0de8521 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/scripts/interpret_datum.py @@ -0,0 +1,127 @@ +import os +import matplotlib.pyplot as plt +import numpy as np + +import lsp +import learning +from lsp_xai.learning.models import ExpNavVisLSP +import environments +import torch + +from captum.attr import IntegratedGradients + +MODEL_CLASS = ExpNavVisLSP + + +def get_nn_model_name(model, args, extension): + """Get the name of the file to which network params will be saved.""" + return os.path.join(args.logdir, f"{model.name}.{extension}.pt") + + +def explain_visuals_with_lime(args): + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + # Load the data + datum = learning.data.load_compressed_pickle( + os.path.join(args.save_dir, 'data', args.datum_name)) + + # Open the connection to Unity (if desired) + if args.unity_path is None: + raise ValueError('Unity Environment Required') + + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + + subgoal_property_net, model = ExpNavVisLSP.get_net_eval_fn( + args.network_file, device=device, do_return_model=True) + + for ind, input_data in datum['subgoal_data'].items(): + + def predict_fn(image): + out = [] + for img in image: + [prob_feasible, delta_success_cost, exploration_cost] = \ + subgoal_property_net( + image=img, + goal_loc_x=input_data['goal_loc_x'], + goal_loc_y=input_data['goal_loc_y'], + subgoal_loc_x=input_data['subgoal_loc_x'], + subgoal_loc_y=input_data['subgoal_loc_y']) + out.append([prob_feasible, 1 - prob_feasible]) + + return out + + class InterpVis(torch.nn.Module): + """Helper function. The IntegratedGradients function requires a + class with a 'forward' function.""" + + def __init__(self): + super(InterpVis, self).__init__() + + def forward(self, image): + # image = np.transpose(image, (2, 0, 1)) + goal_loc_x = input_data['goal_loc_x'] + goal_loc_y = input_data['goal_loc_y'] + subgoal_loc_x = input_data['subgoal_loc_x'] + subgoal_loc_y = input_data['subgoal_loc_y'] + num = image.shape[0] + + def rep(mat): + return torch.tensor(np.repeat(np.expand_dims(mat, axis=0), num, axis=0)).float() + + out = model.forward_supervised( + { + 'image': image, + 'goal_loc_x': rep(goal_loc_x), + 'goal_loc_y': rep(goal_loc_y), + 'subgoal_loc_x': rep(subgoal_loc_x), + 'subgoal_loc_y': rep(subgoal_loc_y), + }, device=device) + out = out.cpu() + return torch.sigmoid(out[:, :1]) + + interp_model = InterpVis() + image = np.transpose(input_data['image'], (2, 0, 1)) + input_image = torch.tensor(np.expand_dims(image, axis=0)).float() + baseline = torch.zeros(1, 3, 128, 512).float() + + ig = IntegratedGradients(interp_model) + attributions, delta = ig.attribute( + input_image, baseline, + target=0, return_convergence_delta=True) + attr_image = np.transpose(attributions.detach().cpu().numpy()[0], (1, 2, 0)) + attr_image = np.sum(attr_image, axis=2) + attr_image /= np.abs(attr_image).max() + likelihood = interp_model(input_image).detach().cpu().numpy()[0] + print(f"Likelihood: {likelihood}") + print(f"Total Attribution: {attr_image.sum().sum()}") + print(f"Min Attribution: {attr_image.min()}") + plt.subplot(211) + plt.imshow(input_data['image']) + plt.subplot(212) + plt.imshow(attr_image, vmin=-0.5, vmax=0.5, cmap='PiYG') + plt.title(f"Est. Likelihood: {likelihood}") + + img_name = f'{args.image_base_name}_{ind}.png' + plt.savefig(os.path.join(args.save_dir, img_name)) + plt.close() + + +if __name__ == "__main__": + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--current_seed', type=int, default=None) + parser.add_argument('--sp_limit_num', type=int, default=-1) + parser.add_argument('--logfile_name', type=str, default='logfile.txt') + parser.add_argument('--logdir', type=str, default='logs') + parser.add_argument('--explain_at', type=int, default=0) + parser.add_argument('--datum_name', type=str) + parser.add_argument('--network_file', type=str) + parser.add_argument('--image_base_name', type=str) + args = parser.parse_args() + + if args.network_file is None: + args.network_file = get_nn_model_name(MODEL_CLASS, args, 'final') + + explain_visuals_with_lime(args) diff --git a/modules/lsp_xai/lsp_xai/scripts/run.sh b/modules/lsp_xai/lsp_xai/scripts/run.sh new file mode 100755 index 0000000..66a96bd --- /dev/null +++ b/modules/lsp_xai/lsp_xai/scripts/run.sh @@ -0,0 +1,84 @@ +make build + +echo $DATA_BASE_DIR +echo $UNITY_DIR + +# Maze Experiments +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_0SG \ + XAI_LEARNING_SEED=8616 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=0 -j4 + +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_4SG \ + XAI_LEARNING_SEED=8616 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=4 -j4 +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_allSG \ + XAI_LEARNING_SEED=8616 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=-1 -j4 + +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_rs1_0SG \ + XAI_LEARNING_SEED=8617 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=0 -j4 +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_rs1_4SG \ + XAI_LEARNING_SEED=8617 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=4 -j4 +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_rs1_allSG \ + XAI_LEARNING_SEED=8617 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=-1 -j4 + + +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_rs2_0SG \ + XAI_LEARNING_SEED=8618 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=0 -j4 +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_rs2_4SG \ + XAI_LEARNING_SEED=8618 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=4 -j4 +make xai-maze \ + MAZE_XAI_BASENAME=lsp/maze_tmp \ + EXPERIMENT_NAME=postsub_1k_002xent_rs2_allSG \ + XAI_LEARNING_SEED=8618 \ + XAI_LEARNING_XENT_FACTOR=0.02 \ + SP_LIMIT_NUM=-1 -j4 + + +make xai-floorplan \ + FLOORPLAN_XAI_BASENAME=lsp/floorplan_interp_oriented \ + EXPERIMENT_NAME=postsub_1k_1xent_rs1_allSG \ + XAI_LEARNING_SEED=8617 \ + XAI_LEARNING_XENT_FACTOR=1.0 \ + SP_LIMIT_NUM=-1 -j4 +make xai-floorplan \ + FLOORPLAN_XAI_BASENAME=lsp/floorplan_interp_oriented \ + EXPERIMENT_NAME=postsub_1k_1xent_rs1_4SG \ + XAI_LEARNING_SEED=8617 \ + XAI_LEARNING_XENT_FACTOR=1.0 \ + SP_LIMIT_NUM=4 -j4 +make xai-floorplan \ + FLOORPLAN_XAI_BASENAME=lsp/floorplan_interp_oriented \ + EXPERIMENT_NAME=postsub_1k_1xent_rs1_0SG \ + XAI_LEARNING_SEED=8617 \ + XAI_LEARNING_XENT_FACTOR=1.0 \ + SP_LIMIT_NUM=0 -j4 diff --git a/modules/lsp_xai/lsp_xai/utils/__init__.py b/modules/lsp_xai/lsp_xai/utils/__init__.py new file mode 100644 index 0000000..c4476ad --- /dev/null +++ b/modules/lsp_xai/lsp_xai/utils/__init__.py @@ -0,0 +1,2 @@ +from . import data # noqa: F401 +from . import plotting # noqa: F401 diff --git a/modules/lsp_xai/lsp_xai/utils/data.py b/modules/lsp_xai/lsp_xai/utils/data.py new file mode 100644 index 0000000..b28d681 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/utils/data.py @@ -0,0 +1,132 @@ +import lsp + + +def _update_datum_single_policy(subgoal_props, + distances, + relevant_subgoal_inds, + target_subgoal_ind, + beginning_with=True): + """Helper function for update_datum_policies.""" + + selected_subgoal = subgoal_props[target_subgoal_ind] + + # Recompute the policy (using old policy as starting point) + subgoals = [subgoal_props[inds] for inds in relevant_subgoal_inds] + if beginning_with: + policy_sg = lsp.core.get_lowest_cost_ordering_beginning_with( + selected_subgoal, subgoals, distances, do_sort=True)[1] + else: + # Get the policy starting with the second-best subgoal + policy_sg = lsp.core.get_lowest_cost_ordering_not_beginning_with( + selected_subgoal, subgoals, distances, do_sort=True)[1] + + policy_inds = [s.id for s in policy_sg] + + # Compute the distances vectors + robot_distance = distances['robot'][policy_inds[0]] + success_distances = [] + failure_distances = [] + + # Loop through all concecutive pairs of frontiers + # specified by the policy and populate the distance + # arrays. + for fprev, fnext in zip(policy_inds, policy_inds[1:]): + success_distances.append(distances['goal'][fprev]) + failure_distances.append(distances['frontier'][frozenset( + [fprev, fnext])]) + + # Handle the final frontier + success_distances.append(distances['goal'][policy_inds[-1]]) + failure_distances.append(0) + + # Return a dictionary containing the data + return { + 'policy': policy_inds, + 'robot_distance': robot_distance, + 'success_distances': success_distances, + 'failure_distances': failure_distances + } + + +def update_datum_policies(subgoal_props, datum): + """Using the provided subgoal_props, recompute the subgoal ordering beginning +with the same subgoal that would minimize the expected cost. The datum itself is +updated and returned, as other data (in particular the distances) need to be +updated.""" + target_subgoal_ind = int(datum['target_subgoal_ind']) + if 'backup_subgoal_ind' in datum.keys(): + backup_subgoal_ind = datum['backup_subgoal_ind'] + else: + backup_subgoal_ind = None + + all_subgoals = [ + s for s in list(subgoal_props.values()) + if datum['distances']['goal'][s.id] < 1e8 + and datum['distances']['robot'][s.id] < 1e8 + ] + if target_subgoal_ind not in [s.id for s in all_subgoals]: + return None + + relevant_subgoal_inds = [ + s.id for s in lsp.core.get_top_n_frontiers( + all_subgoals, + datum['distances']['goal'], + datum['distances']['robot'], + n=lsp.planners.subgoal_planner.NUM_MAX_FRONTIERS) + ] + + # Ensure the citical subgoals are in the final set + if target_subgoal_ind not in relevant_subgoal_inds: + relevant_subgoal_inds.append(target_subgoal_ind) + if backup_subgoal_ind is not None: + if backup_subgoal_ind not in relevant_subgoal_inds: + relevant_subgoal_inds.append(backup_subgoal_ind) + + datum['target_subgoal_policy'] = _update_datum_single_policy( + subgoal_props, + datum['distances'], + relevant_subgoal_inds, + target_subgoal_ind, + beginning_with=True) + if backup_subgoal_ind is not None: + datum['backup_subgoal_policy'] = _update_datum_single_policy( + subgoal_props, + datum['distances'], + relevant_subgoal_inds, + backup_subgoal_ind, + beginning_with=True) + else: + datum['backup_subgoal_policy'] = _update_datum_single_policy( + subgoal_props, + datum['distances'], + relevant_subgoal_inds, + target_subgoal_ind, + beginning_with=False) + return datum + + +def compute_expected_cost_for_policy(subgoal_props, subgoal_policy_data): + + expected_cost = subgoal_policy_data['robot_distance'] + success_distances = subgoal_policy_data['success_distances'] + failure_distances = subgoal_policy_data['failure_distances'] + + ordered_subgoal_props = [ + subgoal_props[int(ind)] for ind in subgoal_policy_data['policy'] + ] + + expected_costs = [subgoal_policy_data['robot_distance']] + failure_probs = [1.0, 1.0] + for f, sd, fd in zip(ordered_subgoal_props, success_distances, + failure_distances): + sprob = f.prob_feasible + fprob = (1 - sprob) + fpXsc = sprob * (sd + f.delta_success_cost) + fnpXec = fprob * (f.exploration_cost + fd) + expected_costs.append(fpXsc + fnpXec) + failure_probs.append(failure_probs[-1] * fprob) + + expected_cost = sum( + [ec * fp for ec, fp in zip(expected_costs, failure_probs)]) + + return expected_cost diff --git a/modules/lsp_xai/lsp_xai/utils/plotting.py b/modules/lsp_xai/lsp_xai/utils/plotting.py new file mode 100644 index 0000000..6a4c5c2 --- /dev/null +++ b/modules/lsp_xai/lsp_xai/utils/plotting.py @@ -0,0 +1,198 @@ +import gridmap +from gridmap.constants import COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL +import numpy as np +import matplotlib.cm + + +def _get_linewidth_from_cpd(cpd): + return max(0.5, 2 + np.log10(float(cpd))) + + +def plot_map(ax, planner, robot_poses=None): + """Plots the partial map from the planner, including the robot pose and + goal. The optional argument 'robot_poses' should be a list of all robot + poses, used to plot the trajectory the robot has followed so far.""" + partial_grid = planner.observed_map + robot_pose = planner.robot_pose + goal_pose = planner.goal + + plotting_grid = np.zeros(partial_grid.shape) + plotting_grid[partial_grid == COLLISION_VAL] = 0.0 + plotting_grid[partial_grid == FREE_VAL] = 1.0 + plotting_grid[partial_grid == UNOBSERVED_VAL] = 0.7 + ax.imshow(plotting_grid, origin='lower', cmap='gray') + ax.set_title("The robot's partial map of the world\n" + "Robot (R), Goal (G), and Subgoals\n" + "Also includes the agent's plan.") + + if robot_poses is not None: + xs = [p.x for p in robot_poses] + ys = [p.y for p in robot_poses] + ax.plot(ys, xs, 'b') + + ax.text(goal_pose.y, + goal_pose.x, + "G", + bbox={ + "boxstyle": "round", + "edgecolor": "black", + "facecolor": "green", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transData) + + ax.text(robot_pose.y, + robot_pose.x, + "R", + bbox={ + "boxstyle": "round", + "edgecolor": "black", + "facecolor": "white", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transData) + + +def plot_map_with_plan(ax, planner, subgoal_ind_dict, policy, subgoal_props, do_include_policy=True, robot_poses=None): + partial_grid = planner.observed_map + inflated_partial_grid = planner.inflated_grid + robot_pose = planner.robot_pose + goal_pose = planner.goal + + plotting_grid = np.zeros(partial_grid.shape) + plotting_grid[partial_grid == COLLISION_VAL] = 0.0 + plotting_grid[partial_grid == FREE_VAL] = 1.0 + plotting_grid[partial_grid == UNOBSERVED_VAL] = 0.7 + ax.imshow(plotting_grid, origin='lower', cmap='gray') + ax.set_title("The robot's partial map of the world\n" + "Robot (R), Goal (G), and Subgoals\n" + "Also includes the agent's plan.") + + # Set up + ind_subgoal_dict = {ind: s for s, ind in subgoal_ind_dict.items()} + subgoals = [s for s in subgoal_ind_dict.keys()] + num_subgoals = len(subgoals) + + cmap = matplotlib.cm.get_cmap('viridis') + colors = [cmap(ii / num_subgoals) for ii in range(num_subgoals)] + + # Plot the paths + planning_grid = inflated_partial_grid.copy() + planning_grid[partial_grid == UNOBSERVED_VAL] = COLLISION_VAL + for subgoal in subgoals: + planning_grid[subgoal.points[0, :], + subgoal.points[1, :]] = FREE_VAL + + poses = ( + [[robot_pose.x, robot_pose.y]] + + [ind_subgoal_dict[ind].get_frontier_point() for ind in policy]) + probs = [subgoal_props[ind].prob_feasible for ind in policy] + path_dat = [] + cpd = 1.0 + cpds = [] + for ii, (ps, pe, prob) in enumerate(zip(poses, poses[1:], probs)): + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [pe[0], pe[1]], use_soft_cost=True) + did_plan, path = get_path([ps[0], ps[1]], + do_sparsify=True, + do_flip=True) + path_dat.append([path, colors[ii], float(cpd)]) + cpd *= (1 - prob) + cpds.append(float(cpd)) + + # Plot in reverse to 'first' paths go 'on top' + if not do_include_policy: + path_dat = path_dat[:1] + path_dat[0][2] = 1.0 + + for path, color, cpd in path_dat[::-1]: + if len(path) < 2: + continue + + ax.plot(path[1, :] - 0.5, + path[0, :] - 0.5, + color=color, + alpha=0.8, + linewidth=_get_linewidth_from_cpd(cpd)) + + # Plot the paths to the goal + planning_grid = inflated_partial_grid.copy() + planning_grid[partial_grid == FREE_VAL] = COLLISION_VAL + for subgoal in subgoals: + planning_grid[subgoal.points[0, :], + subgoal.points[1, :]] = FREE_VAL + + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal_pose.x, goal_pose.y], + use_soft_cost=True) + path_dat = [] + + for color, cpd, ps in zip(colors, cpds, poses[1:]): + did_plan, path = get_path([ps[0], ps[1]], + do_sparsify=True, + do_flip=False) + path_dat.append([path, color, cpd]) + + # Plot in reverse to 'first' paths go 'on top' + if not do_include_policy: + path_dat = path_dat[:1] + path_dat[0][2] = 1.0 + + if robot_poses is not None: + xs = [p.x for p in robot_poses] + ys = [p.y for p in robot_poses] + ax.plot(ys, xs, 'b') + + for path, color, cpd in path_dat[::-1]: + if len(path) < 2: + continue + ax.plot(path[1, :] - 0.5, + path[0, :] - 0.5, + color=color, + alpha=0.6, + linestyle='dotted', + linewidth=_get_linewidth_from_cpd(cpd)) + + # Plot the badges + for ii, ind in reversed(list(enumerate(policy))): + subgoal = ind_subgoal_dict[ind] + s_cent = subgoal.get_frontier_point() + label = str(ii) + ax.text(s_cent[1], + s_cent[0], + label, + bbox={"boxstyle": "round", + "edgecolor": colors[ii], + "facecolor": "white", + "linewidth": 2}, + transform=ax.transData) + + ax.text(goal_pose.y, + goal_pose.x, + "G", + bbox={ + "boxstyle": "round", + "edgecolor": "black", + "facecolor": "green", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transData) + + ax.text(robot_pose.y, + robot_pose.x, + "R", + bbox={ + "boxstyle": "round", + "edgecolor": "black", + "facecolor": "white", + "linewidth": 2 + }, + ha='center', + va='center', + transform=ax.transData) diff --git a/modules/lsp_xai/resources/xai-example-explanation.jpg b/modules/lsp_xai/resources/xai-example-explanation.jpg new file mode 100644 index 0000000000000000000000000000000000000000..c2bad5825fd4748cf2051e81d650f5050a0fb3b5 GIT binary patch literal 1188555 zcmd3N2UJttmVb~4L0TwE2_*^$ilFokMx=M?O+h*#^xg>wigXa9_fV8-=pZ1{rT5-@ z?;ZZ}z4_MnX4cHC@6DT8>%X&d&%WpEbMLA9?DM<(+>GAL0>HA8GLir+EUa5vx3mC& zoB3PDGUDQIlwT=H%E(J#5&(c(YF0)F2jDXR0AcND|4QlwR7+b2in{~=VSW?8~BmRtIOa%al0|0>Xra$A}#sL5oK>z^dn606`;oshajk(@3H3b0na{vHB zZ2*9*7XY}U`}a1(r2S3@WR3s;Y95%b>H+}b699mR7({LQG0ZLQFzJc8`XFjGX!|2?^zWN@`kKdU|>?iU*7j=oo3}=;?kx z1PhZD7YCOJ1R|m%Cn2Z%r|G5vKmx-3K?KIeA_3eY!NMlNy7>v9#SB&~AU4+T8vGl9 zfS5Ag!p8fZ>;MK}VPj)q3XXpV48q5`g^vZeg$=w-f`dzXp94e&Qz3s~Xy=D__Z|i3 zEA_~j^gf0c8un2cC8dr1lw7=gs%mc?9G#HSpS}&uGjj9rXQF@1F+CL5H1-e3%5K_~ zlrl1Le)n^a`6Y{lsY}^{S@R&~r4Y;<{X6|pBmma$m*U`J5@95miFykQ8xsKn;$Q)> zZetQjurZ|p!funPaK19MBftBA>xExrIu3V9BZKPOzPViyfdyL3Zri`0$00E}D zm@Fg!F~GPq=>JFJWJ|jK^5}ct4Io$<;fNVG{|iJ;joh;-9?!0tTmcU>ha?$SraUL= zS2h|KHy?LU)l;Yr9pXNENk-$u5qRY5Fa?e53?sTj(D+AJ{OjRuqO=dCYYuAw445r!~r ziL%h7p{jz9niD$uorP{6_Zof>d=D;-s>Twzt9DnpCMKedZeWcD?2-okI}Ih&*icg_ zPG_O3hE5)(`)CTSX23H;n?6rFBt{9x!;)6FRE&p)HS{-m3i45QQ!WI8e9mQE!mxSp z>j?1Q34WEibe&;E-oNN_X10s3!w3wrg=%ggK0L_a1iFX2kd$WVzyom({^NL}bs`g20)DznT1xrW!ZS*wvB2ngJ7Wp}YuulxYU_;| z@3O$a`h`)$Rnh&VOO+sK!x5hh+arm3+OQGZ8fo0%lX*~h*3yi-zopgn)x(^=*qTdp zSGJeqEmg8NwUD33vu08F>$h&*fi%w#m<0+Hp2$KR?ZxcE^K-2f97>XI&2!ok1Ig{y zr&yWS+!H!(0A+>mZvbfjlJP_Zw8=QKzi;Vl_!>-!{afFjcYOY)`~^Hf{3?qU*PI$m zQU~`}E%V!VN$w&p0($79WZ4wSQt-qRNXpa>}T9abjI|q+0%L zVUq8C`#zA;WCfwiTh6^>DZQQ|z!^o+p_D~96Oz_se*Uso{|JF6Q@tEfDZ=J6K!_iy9SP1S9-g(MD% zdjIzvVvr5*}Hi@;T@rfCKwBk(@a)iPO$0*jWU; zPNH8`UA_Gy6KcxpJ)Qls8*z^BS%hq5X9$A*M2qSmZP8zT%ilW2o%f6h*@H0Yo&(U4 zo-s}ZKado6wR5O4ixoa=(AYFWkW=r^Zm>B4%JuyTA~{NJT7{%U`fbI7gk5eqbm5F) zDxZ5iQtsg#Osc*4gZ14FfR0P%ms-`9w?NGa!$24nA+z~}>7X@rR1{@Vv1xvKBrmoE zg?b#gSET!x|74{DDT~lG=dDYzINc~DaMCwkY?YIvB6RG={=mGU!*9H|EU<+0rN53T zJ-<#uA(#7tB{$pECP20O_1pGYy?z`iHyY1(z`zfivAms-@nd0Jo-P3(-Am}A@4u1% z>kYP&RRpU`9$N2|o|5T45%?cg+oZjM1Iww8>Qvi0wRhN5ZgVXxf_H z?vh4$vs@oDo)4UeytVT}j?r#@-O*12~R-iP{QC_*a!jtD67ZN`b zsy|&XYcUdAdsNzszNB@JJ%Z&}sk?khobC{mwCPypuJnuG$LdKSlyF>Q%}jGhgqhb4 zleBjm+o3P5nU`TjM^9zgv~}xfqsDB|EwHAUgbz}mllXRI@dUEgE#Zy@sM4~zBh}uf zC*6bqiYnjAS^Ife{DfQoBO=hW5ZrD~+x%Yn`k_NsG#d&P9ui&Yj5R9MJ}U}EK1ATd z$2+yU7&$e+Pa*8~%=2ipCS63DT6}VXBB1T%E`0|oGi&LUGwbn28K2TOL%w;ZH|%%1 z;Qm)18Iz5SS;rJjek!mF-C`(dLc8sQVE3J$R-mRVEjFnKn+f#-IPpI| zH?|ilmKNYn*=uS8+Z@s>|5h)$Wn8RG19ALYKg-Jw?aPzG+VP2YdIIR&W!o7(?RB(r zN>-L_*){?lfG%l~`uK)Lr0aqq(rin`-d zbenA&nX+d2wOoUz8}-$1SDxBdj;?>i;MkT4XfrY0%3U7ayKl*gRT!w_mT4R*!>85C zvpv;A5&>f<1G>Y6d7pH3MX&ja628AgbP&{GVc~F~6^M;ToGaNzn$+$it*g0!eqlsY zY+Ja+F(m$34?DLKMZEG+UE10zGOtbGiE7JLeN{DC2515#jfW7}(in1KmQ1(Cb1$ZR zX2VH%H~8GS8yXnlr6iKr+$si!NflNL%zQmwV?8|Tiz}hiTQ?$B<=xr#d`sh*MC|Ma z?I&<7mZxbIePrYe0|s%2Hz>={g$n6Z=@pi&PAO@uS20=a-f7p5$20HII5-*uL@3cw zE=2lHR^I?#YVkDR7P))d2cyvAa~2(g`;>q%D1S6MR6u460HNGV*> zg%bcnpL1Hy7zs%QhN1L3@EgdZ7I#U_))g;`D9%iPzkV;mB!ZgjeV!v$C9gW`WK0c1 zM}=vHir?%3hR>QJEYPIl8OPm@bvx2(>#SG#_@7>WvO(VKiQ@=?>mJp9U`%1IbW@fV z;whXkttg$bNY6>n3W;hnFfgK)X>XuiT)O@C4+VG!e=B9gD~J;lV}W+{kjR3SfiQ~j-E#5@e*y=|LB0utFtF_n$a9rwNL!U#Mg*kbV zBlS!#Pw%J23KSTK6f!jhIV;Nt0I6BC9*z;EIG$_Db>0B*jhqX=+GhhjVo&OEQ-{ya zaB%xJOnAFIB;Mp6u}SEm`-Ui~@ac3+q6r<6Rt^|iXew8Pm8}xO!mGWb)wPSC_W@9U>VyxmQ!)+}5-EkT zrCN}b-)5_GtT1t(UrFbANg*hZ#U1XUtE-Sy?)vSg z(F|4;vEe=`NYR3!;`J8Rx5nE}xAhe4!pxf%A_H!5_CJ$iH)lAJBZQ#7CcGGPE*)KE z`x~3D2s&v9Cui z@PLfRI@0>wMIxc*?T2YdA<1D11w{Vir<#w5Xyh#BdOiZ5pMIr}IZld!h-X;8LmqkL z4Y|mgDo7!0gFl5^>#T?-3+2PS zF*@JDII}5hXWmo2AkOc2sT4XMlhn_dJAa*|bsQeW4&`jA=xm~&^{F&(Klo5dwZ(YA zcpUvRt@7VC$y<89aF8HS=~jC4p**(jrP;ty=1}|J71l(mrEj zdzvLCOXyU*yn}F%4?lMxo`VVY{x)3xkH}b8;7UW)EAs|Go;Hp#i2pZ;Cr*0q20)q{ zegohzJF4oZ7i+@Ptf6L}r
tO`n_Gi)EleC|oS2(sjXmpm7 zkVGJnRc4JA9tR#&&(?`qtzb#$uKRGG)IF%)1eB!pqDLl-xh_>w+nv5*N zyrnH&r=Wx^CgB}&~p5uQK z$f@j8)p+67Dy$G$PXdH4Nyx~FD~`KAHn&K(VVMiz$n52Z?!aVR^LHTDsY!l(QIGJE0<5sw zK$5<+!_4Tg<|{h}>0!CdeZWcl@+*UL>+|V#^VaErySaZh??1tD$I0XG_?lA-G1_CX z^?#+P5SCXVTsUdrCgA~2tS(q0a*U2OLZ}{(o>ze=+dV$eletKxV85h%rMhYX{aX!8yaFI)_ zA>f|pJ(p_}<0N>Tn8lu64~L7C4q0ZDPpn&m8=1A_`|H9Zxc6ou4adZ?ghl0EIl9hX z<^a(84iBLyp0pBy$H~Hb^V9ZOA!$O@Qo?T=UMlDs{iqeD+CGiCc}XdSY8?n9c|K`n z!^7SmZn;%rF2doQhn_4{Cn`eS{{|y`62``e9TGw9O463r;Djsl<%x1tIjzteRbE?K zt>d4KOHFbg4s2nbm`!@96dM22<#eJH4R@$-BdxGRdg9XAybSYXmx>2k}$^k@r>R7~VD%q&Rb z@Z)z~ZToUv6!O#7j8R5f07XS{U>pAX1K>SDk$S}APFp9Y^~aB^?t5?U4yhb*a)%lH zoN7D>fauCPzVG9M*hXE<@#-|#o`xtT2X%~a)Yi_DQxT?GU5M69KVsvZKp)+8isq%% zVp%e0w`-W!c_y68p0HyfC@!HPA(6|@2~+3RceLY7k-?9T;))F+f*!E&OzmWq$K-@b zj$4iBoIT$oNRMb)Sm{g>UAj%z#@n8EG(7ldi-#Lcu2Ip*`itXP)itX<=e}#w3Dz>K zz85~FS+0PE+UB`8zVWqmL{+%d{Lxy<{s@r~KVeTcPSxPl!`un%coceZ=kp5bBpvne znG2%``{mkb zeBNFw>!R|YMip%T$9aqbp6tSv$LQJFGa=A@90Ol}H3Xlv&KnsSrtecX0KzG%h}Ef1F@U))XN0!Sjj272~*wx zrr*NufR((W2&^jPh_6)?u2hvxe$RPsK6%VSMYd_ZUCHm0$?~8BZ>JO%8oOpQA8fOp z;LifXIlgeusYjTe>B{gY#7A+aFcZC$Y$;x-wZWx1Q+_STX(4k&)W60~{H_JrEuq(M z)VzVahUoD=rd_sxae*a?5}+Or2D-Pnqr&S!Jmrmn$D`c67`<(_qla{aLVq|%qqkVo z@3U16ok}!RaP$sDtcAIe3UIqAVi5lHr(TR@p$d9|Lx?hERk9;q8Ax^nF>5K-MTGyS z=qyxGPA<-dWtnE<_~`iRn^kA&vj}On_^n$_MO#n5err2j@%2-c;RO~)ck(X}_#*`t z>hI&|`0H6B%B_x@bXCMvoKjGQ@!Mfq7I`W2Bk0)*SKmpbP%pedrQeb+y>Bg4h*<~r za|G8HGBy7!>8cl2T&|C%Cmws^-l;Xx|0=MP)g*?`t`gp6PPirFOT>heH7vqdG@#EE zE~lHjhS;N}^`CV9^IiNvjb( z?Xu-m3b>31O{R)uz7(?LmcJ*d@cW<#`-@P>sc>N+@i;PUmE$RZ0i3~ z7*-%CNwDg!#MC0Tz6i@c6lg)0q-=zW9fiW4^!~XP{;QnwI`KYX)9I7?U}cM!f9$ya zn~+)xg)tHiZQx>;^J43!uoDyNx2al=2HC}G*62aroIE%B?2gBbPh8R)+&PhtHT%_+ zHPw`dey-*}T5^2VvW@Ui1Ra9?tq)a)MT<9rv>q=_rPumF>|Ht2Jp3;U+4iHR7fH9U zfck5yd5@jw%F0(+CCzrVsfHz+&P~*ksAm?@;WZ*{T!;dT1jPNm;4ex8)-{cZ3d6O; z157+5aW(z(UX(C0uzXlBqNO#r=lhqWt8>Cabo@N%Ohy3iFp0%bhdU+m4e@RLLYKYFJt{wp zI`Am6e8J(f$ZUvzW$#w6XXOF3rR)>V5U-hS4j=y1aB>vcpxVGl+bJW%=Xtj?np*@D zCdv1$)s7-2oLZLjA-jEVXbek#dQA5is2y)3t74*<=ik^zmf6s=PQLM3lov~+WQN>j0w6!OH@smuXu zeArhUx5YCvis120!XC4LoAVdLQ*A#O6tooqaNw|Imq!;lnf4zpi8QHbfS77jgH#7<@sxDt>(0^AcD+WIOQk6nLNRXtwJ7sAI<`UMVp zhH25RKP^m6$c>3wXqT&|#@Y|kn)8pkhtcW_!xPEpM+%x)M9(y3Mv%l$U216tris8d zB0*cFv_@K;IO&1Ztepq5`!7MkIoON_(bb!`?2_oZ7a_@5IOy^3qv+*8PGzoZ@>;(i zQ4|I*?V7&244+k|GFuXoXy=zt711)a3{G4+vNN_!=)Drhe||n(SIK@@8FSAak%4$4 zIjMWsYy5;D^8>1eW8a3DJClDu1lsuY?!grMP@G^yqln&4%Jas+9g*f%>>4KE$JJM2 z4M#FJfcaO~c*@dQ7!5!vI{jRTelYENpl5~$NC{&*r}O32)sjL?zw$}=fU^oCb=S2F z7MiZe`lehfJ0YxS+>ae$;%4C>^_eH_%w7m=P{YvoDPck9mCoFUmN33@oi#Vm9MHyY zM>r_v><-=(85KDqj5n~vm!|;R7drx$d#(#`mi3GS`CvzgFVY2%OR}l?SL1lIz|{O- zZz;ib;IOj8=r;Hcq{@Tf1p*>o-@X31@S6_H$w#WY0FJV{ z%BLq1qx)yRu(#z~T;})AUdEjN*q&thqfJlS#i zW6Sm{wqIjbWSi^o8q=>s6c5+DREHqZpY>(58Ymy*OUlvoHHc9`L$LiDoCA;l%a!Fn zCcr4qEtKj!2V!PQ2IOx5)ece@EDZB_Tcyy((kZs8&fx@`@GsWhj#RRk%{7Rr{8Sfb z_=t-dfK#_KcToh{PpjDcDZIrj?_~7!Xg-?GyDFDiF}GNUhbKi>WIsehxkKj-iAQ`C z5v)^M7_()nkmu zhS1C`-!cx~vv$avH{L(h=XZ<%8$@QdHZ)E{4QBUuKz!w>F=zk5PXi-UhlgB4-7ZCNbe7+<3=Y-H?D5TT;2zU z!f4zL*VjMmTlb+IMESEnHnF-W3O3fhM2O0l{R}UI<)4d<<{c3YKN)n2#Itzov2J3x z=w2SjO}AGI!C+dpX`x%KTTLwRJ9~~1exkrZN_oEc4TjkQ% zP3MmNn*516u>H1YU+WO3lt7n*Zj>#)v~c@rueidu(SmWfMMWYLib7mmfzeCe+Re?} z(aM?AUWtOvoOAmF!OVECOKruko#f2@w9hO&-u=!J>D$K_OIyQ1Qm(Nn7R_>xP3YC9 z82KwaTvAQJ;y_4{VU18Vg1Udz+9e@Dfz3MK4*WvWIJwKh8EY0~y%Pd!u@#7cI4|{0 zJXcc|yd&d81nEHst#RvFuw(BiPB!mIfsmC=6qqAlx z!LjMH-cq$5Kl&c_NN?ODKt}d zwHf)+mHdnVQ7&|{@O*FLwe&gq9Pz@DY{B>jP~aVV z&76Imm&^IvyNa3~<+9G%e)-nti#@0qY0&>n_uU0@9fI>&_IVTu&-PlXLd7B!(ajtV9DeURta)j*C(Fiv{A)4N;S7dOfLwE zob^^xbQ^B<5=k?rEJ94TO16^p%%|k9p2{f2&XuZ~GFNoQrZD%!kZ{4PA9~&Xx>72r z*(1NqYbi51N%g?x$r%ht&+DQ5rkeA$Wr40#@mRHlag18#~)PY%XjNe1)?<8u)8l_hpGV+xecR z5{m6WBnDkvi7RtosE2_8U^hRHw@DL$U~QGs$5prS0G|4)$Adg;hye5J)osnaNEzYh0;=9rSx58@4Kq|P6HVt*jv|3a8P zNWTaP+ST?UPwRjG7qBo41{OZtKX&Orf5ZiCbANVS8mm;1hcQ4SaZ=W7GQBK^o>_MA zm&iEnJ$}Z|o1U4vpTM;O54R*_P~t`(w5kBZ!nBg;TG6v*4T~g89e8u4UfTE2y|Eh$ za-R1$*VjiyOHFrO_su@Uy&Wsa-V(U_GI{D_qj2SEe*Z0AT%YbyQrb0{%9SCk z3@p+8nYz$DSwbqyBA@1w`TX6xD(GFuo)hTR7h9=`wBZYqlBV49oVVp_&BFs!zXrJX z*+R2VMa8Revw<71_lRi4=6qfow{lTlQA5SGwGZcGT6~HAV@XE8WI=RDokPjN{;5MY z_27K{GphrfpEB+1#_i^Z;JxJrSS5SeVR?;-LPxbmlbjqGDt;wer!UGIip1X%d;Pj> zIxV((K?Ry=9JVVcKNlgDf{mS65>gX?U;vHQr#MVz`)Ed9;qtsk&w94!N#$OE+XG(g zDZjcEJ6Kr{2@?6_u&CD=ep{U`2Q4*=S`y04LmAo8UGr5;?8q!cc2)$@1Sa)eIw6vL z24*o}yvQBc2selPRC|VT=(Yn4bl*oN|FI=)@f1TglApm-S*8jit{Y8eZ!4UBTT?=- z>A3j?#&M2WK`3aF0Y4}%lIo1uY9V^-A87)Pb4azlN)DmqUuPzDz!Ct`R z)va%J6nVU6N{)4-k2c`6s$8_J)4S3{4KyGS?{r)*wUE3X{TsvL0Tp#o2C^)8(!7>5 zqwCLOzddN52v_c-N897}rFYEVCS*_t${s(vbu~am#gM`m-r}#h`O*yTZtQaa>cAWK zS3OJ{zN_=*d3n@?&}?Citi=QaZ4l=(uKT$4(GFv^$R}3Y?Q~fq8gRz#2h<(qoUa77 z&DdMx0BNa?yUj{KTNvbRFmE77C?%meC4gv=S~vSBIHBVCs~NuM`4#Fs>8JBX(SFvR zb2)uWu)AzWPTY5UHC2ACT3Rexl}HaXhgq~S^n=}rQPy_T=%w;Ka1(3ZgIx1%VgqMU zM~rXXa9{qRS5!ieQT{sn2~B0kG&>Tjq0)ua6?@Ue97c02krP-tj>sR@f6M8(d$zJTm z3fp=rZh8T^x8{cds z@IA)JgasfLj?xC}8+sOiV0~cf>e}t&OaskIbeC3Et@|8D)~7Cb;Az+cY8O8myO0#^ z4t%C-#i%%QTI+;hR03adsS<2CF1^ z_SropU$lsFatcyU3Tp4KH#`2qz*1%s7511{U5(m(^ev@fWEVTUVUeqP)@~xKU)fw% z_QTraxi6?seM$tOQGDn^!pgc#j z`4CIP07qSn+|=V2;z|&sz?3Bwax3!&xGsY)zzs<-k@?*>eIy|zpS8BseGCRMO`x3C zF|}jlsiFz0Zm036S_0;To9W=ic!Q>B->#R0adX7kx469T_N?jv)%1&-4PO!FKVtfZ zD`i#Ha?*^Sq-W>>A~t9KU=z~MH7)g)09SHYaOTVAQJ0%xPGO+Jter0%9&Giu>HpUV z)HR^^X{*{IziXiK)a)bw7W}i_38vzBUBx;qEh-7@Rw)42tm-NAhq<4WbYkuM?IQ@C7DI-pIHI_kBW3d8_O??qQG5(aRYfiy^ z<@k(cq~$D@^h{in+uD&~aNO*r+=uI+tAQ8aaYmoq>)IP>S7)57OD{0p_U23LOJp24 z5==CYh3gCPCC)ubu$RL5`GaQP3!Ba!tn?BH&dh4U=NSlolw9lp47LR~*e z+*^P>1*^P))SDEVeMd!jt-)3-@f>=uN$5HszZU3p`qX+>8MFwiig?K$XXoUh8G3rf zIfnoJ4C6-9;w~Dp6|HD=+*JR?9k0a~Ipa|`w&~b{I&jRWXxdpfwK6y>bxj*SxsHGc zmD`lZ7M5=?D00ZiKWE-bt>##wg55ig%YEdeSY2&-N6^9|tsq9EL>lJcsZ3ZvKm`{I^kY@_W3&$9vW>o<{W#?@~3SJLD|tYSs7J~ zU|;D*NW_rM7}pp4De>EP4g+R0UvpSs0P~k|dp`*6ip4{V*XrkdHU)son6F#fnsO3~ z>%kqLEz->>WLTT1g%@{WMNUK$$985O8GJo@Oy=E71d__0J+nREVKn7uXjYBhB8~M4 z{qKd5F%g2y)X7sT$jvZ9X3B+$apYLB^Uju!0`a+l7?})A5UlMq>1F-CUZTf)LU|^P z8G5h=Y+FS&Oogk|%nT`d-vBV5Cr4m})#?ooChl7K8Wm>yt#r;~yr@c%GksZRh-!}> zmFuF%c%}bS*!Vxs_kRH<7rKiRtg>8w>bqv`HJ@U%%P+vKuBLAVG5z>!v-+<{{nH=L zr5)SFuEW@jZUBkj&f}Gh^(l#*Sxxt4RIWUFjVF}*dpFn!?Tg!}nG!_K%~HR{*J^o- z;A+}1<&nEnT^JN9?JGq6o)yoD>b^ZWAA2UDD|dq?7} zmsy4LC!WR&ZMO)FvQ9Q0d0e>LY%IX=!SdgOXTC1s?k0q9+#$?G5^U{f{%~%}W8D6- zemxgzvk3E9#Q>)8!{*5eDFK^Q7kb|qGFn`UvLd6;d$E-UVY~j_HA%N(m(*ps-kW+F ziAsU}-4CBeHmO>Ie1!@#LtDG)n|5O$s##l}Xb5dJFU7WCzO+R<-C->Su{6+K`NbgF ziiyaZvcTB&Fx?G_r}R(NCNEbxjWIh(>z(2n=I=*87rKV3fYyDfU+|yq1<()k;HI;H z?)S(ZTW@)%U99sHPe-1C1zEgn4sQSrE0@YhBPgocC;D-{o6md$0^EY!2 z*PMjKNM6U0D=}HGf;V&TaB@ctx!+A99_f zauNz;Sf9ud<)_tXTTH0h=0sG3l1U;2nzM`??S%0b{T*TD1trd_)fQ5F3QCLa`0Ulg z6S~9a&K`uV67n4~ldVFHh`U&0aQ{F&_ASt}FB+ZBK@JR!=yyX^{9P~gpPw#H!ML1l ztO~xFv(lm#TS`mA0$EJqdNkMxy&RDZX&d|)!q&*zCNsjQU9U&J5Q}-9K&u=j z*RRTn&i3l86CHYDz2(#5RzXmr0lTfpyc0L~J8^>R-bj? zFeq1g4iq|Lx!-{&)w`e~rGnaae{0bi@Jea!*|UT76o9j^Ula4z55iMlU*uSR;o&hM zk6oR*KtXVD`~l5zY>3|qGj_j!PjKE+ets+}eOU(O79~YzZ70CI0DB-vV_^|+qF|_c zZ&Nqrw)8?O<)YvVVShrZ3j?GKG^~!N{wEsa;4!c64T>=LO7Si_+}SJOJ1T&!lHR&S zEb7!wG(0lG7g?o7a=8#8P4_N!(M#^~0dccC-W`9U@owL81g@g{g!X+@{<{`gSyYAV zk4u9^XY_G6pE>CMcAuljf!WDvF8iy2?^0K<5-hb#^{{3)Jy1y}ev92;1S`=9Z#&Ei zQSEhKq}y2%a`)wNM;Q7{zxuh$PvI(iYokiFZwn6t zEHu%0DAA-vBr=X=Cz_R4v`Q~%+vQ^afEybS`E2WmmVK8`eZ;~Q0|eJ(U%mWsXonb58)^8SWqhEXDDu&85j8 z(ROBt*BQpNAg3P5nrr#F^IcQb=c^?0E;ME0fxwt`tk@;$vrncaLH6$%=ew41Y0)J@ z|NZNy88Y1d-#&9S_XWmGe@i9(mde9OVZI`!`7DU|x~NEdU*S}a%2hbmp*~zy-PsuNLGJ*zS?dbY7krPaw^4&cAoVyU8U#=8c@CaqI!tk*pc}QMtIB2Q zS1LvTPkN43K*uU6y?6^xJ|$=^y+Y?1Lp^{JVPd=M z{W&KS6_{{uV9>gi44Ycm)E*m2=+U=ngNRckJ{Rvf=SxeHX47dsVsN|05<9Ynt>pg) zT;U~MoYwKEsVHHPnB(ES*C8tq>wz12k)yk2!!g2WJD}VSu z!a-yKG_(v-mP8MoT>|KZ?lAMp@?gK7<Khi-dm0Qr{rF!jsOg-qda zMbvs=Z`;}wLo43nEM|IpzT`!rTqa9GlYYO^(XvI4wMVVz&g9@SV8?2{L&-Qj6XtVG zm@+~Q?4Kn;5F=zXND%oh!y;aY_&afEju;g~FETSz!p08~+gaz^5mt?BcA_Fg&kuT7 zO&s8h#|*Gz5#Fd#3+^n?H=rczKI1shMjzzQ?bfk0gk(x%uHru~<(-3H)2+dQ+ljJBJ2w7u-A1cgwg{jbRZV!z=3RD$zGa;VFP+*pke3F7PPcwPG4Y9NB>@oV%y1%ZYr;Nb`tZ9_;YH9 zf4IagoRPI!w8Qmdybxr<+O>TC)za@1$!`5fBS&R{vD0w_M!JxZ)jZ4U2RCCHztN-;lAy)?bkEX9yCpn~4 z61wC)4a+UREvq)z>RsVJHB}6f7#j6R2ZJOo3S=3Rtinbyixuf%RCa8f)yQ{-eg4M*(D^8%a<%PZ{Dx7`WG+$;kOC_TAKBUuqqQ ztwwy%&Vr4?agej5)RpFTUr8(0J}Gre^pYJG5Ih)HlagLLsK0$=uQoI&T-9T@)GCzb z%E0Cdk<=-Ar7W)ER)jK9`^5E3U@r*G&k=tDy@l1v6+`RATCaUxG#BB` z39|L?%NKTKl7&+|QMJ~Fwh#@jHVJ%`~GVw1DPVk!uJCB4Gin_)E^LEBr z0FwPMbv%^tETo^>Iaf_Zf+eaN#T6@ieDQhQLx-5ujTA=!I_&YJmoL;Kmmxjv!(N}{ zESweJQ<~~b&jT{C+z#VIcSTL*JmHR&Q@ceiD1E|U!|5TzjE<6Fu1%|ghSu?*aP(OL zF5vNs$d&cym$z{~_7;)AJqUuL+10j1Kj`@P8UulJuInyG)v;?&>%Yd&KspF-0KFNi zHTkp5zTDyTYkrqlz;IZh`}2*2I{frz{jbG(8_eW~-5z`ao_G#>6TbXz(zD7EU5S<* zk7@Ii*OQIrDEKE>vr;s#ROXhlcus{+WN>Le&$R(bokeOk>!vp_o2Bx!)O`-z5yXT^ zQ*5S3?ciPd&;DDYlgEbK1>s|mOm==8*+&hhC(lG!xN2yZhdk2|UI`0wZ)6wzo{-{J zh_up#N8WY^$@EKHVEpTtPi%>UK|k<&Ugm5g5CtcPWPE!{i?C-A%9a9&N;!q<#J2Fa zS)UeD8YpFng?i;)2RYzwwp2ga3)^97jc6u0SGLX~fuOLPj&o#ty_!+?QdgM7KH=Oi zwgBoH3@F+GsJo__>k8>V0asx}?wYM!y!Efvl-{57(^8CYFYE?EORdN>l~=nm2K3nj z$^*?)6@-0Bjo`)N#r#S4Le4mm>aWX7zD?+t4E0+kIw@nb1x6Wi7mE1uR51+r%>;mV zEXI)v>V?}0euqjKcf;Xh_*Vm3l*7fTkIZpv!hsOg^q7h2?h_oZsY zua`KY26Wyep?O!@)UK{_chj@&;SkPHxre5?NtKbq(BIv$0y7+E z61U*SNzZd@dRsPFGykDY_!`FH&fGD^E3P;kA@B69Y+5|RhXqz1A^tt~74DX^ssFh? z0ihU)*r(fxnID^Y2XgeJsiF+`8ljgM6z;D86MtQX;G>yXeuoVjV?IOl|5Qo1tzaC? znc$+WH*%Zv;}2_xs8~%bxCfuj4Ja(N4p)fj*$S^94{hD8&bCWjW)IH}^xu9=2+y{z zDad#GHokSQ!|F8DgI?Ibd;YnYJ;iX-oaZa=p|YcAr#3XHWe9C0nb6$S8-PyPWr!E6 z&lgv*d-a;T*UYPN<3U?r-n6y$r()vBj(mvcy+3&6dXN8>dvspmzbA$fV_lA4Q~jFv z`18}@M3a_829I1Kq_R+BXX0vWwnNXHr?YogNys(iUFtW-Xb+BY@8l7U5`E)>8McO$ z6j;p@;ITkGJxPRJLs4W`V=9qOho~kWktd(F{ z>dj}$<_dy#xooY~`A;!u)BGP2|3rudGa435>CCo@p0=p~nVTEX3767MHvr~kHnABC z=33((>hpIE?>0TzQRJ#-+1QSCv4Cg$OKPndX2FZc69W$xBU}QxeP?9s&oAHLC(JNi zhvzl#julPR_XX5v4G-$c>?SJj-w``0ya8a^nZjo1Qtac(Uu*owHDP@Bv zA4R!n6_-hc-xX4x26w+9nETF0dMOlqI^knwW8?0lFDm3YJ6^=-^WoR!2aaDY*N|x| z>>fXC)@AopiBw!4j)OX>%$}h7&r@pZA@OO*TAK%zGyxbNfj@~{(Erlk_8R}`d<^wp zSTu2ek}RO~hlAxL0!Qwuy;3`skFMtBCmjw9TwI8wusxt#q~d!ykxg*H7B<~csi4lL zmm%%aav>hJ%fI5E;w?VuZwLKRK9r^V_1MFi7>nda&EUE5eDP7BFIEInnnN(#&Jc>SY5hj~`icz7?6Pt6YBOAGWze{DN>4 zDRNlddvq6##=u2bk%N&(6o9_yp_M1mv<*?j5n&BT{!wf7d+;T~>4>Y>!RgVht$q$P zG+6t#Fi~y|RGHjZ@3ie8yaqTdDOPzcb18wKSWq{?MSHkoY7!&s~zzLg_bm z$t9ZHwWXVEg`P7rR|3JNLoi*Z%7KZ3!T#SClN7m1NY%E;duGXY?f`cNaplqd)$etIP6Q*X(V(NSLK3uqxkvVV2y`R-|^T^yMc=F8n$6< zLKDV70m!Jwdy%vdutzXKkcr33y3O-%A#54ijf9!7}(=Wx42oKyx73EfN{T4V9TZgvgr?-q$=0MG<;w(*2~YBm9fueq+q z%KdT-lZpVWfV6{VV9jcfCd~y~LK45tfL^wtwd-tI81Bw@V@M>>U@cP}a)gtT2~RK% zjMb*Wn#Z2(6$7UY3Ej^NjWl_(z7t!NLcMLRRxYkjiaEA2CoI8 z_!M0h8G6z%xT93YmZBv8nCdIr{QxuKB#s&TP5O8ojy&E2jNjS) ziqUxW+%Krel2Sp*?Ppa#0en*-DI&gU6NHRtQV^rP$a{t!xv9G<>V$M<6%A{`)M7YA zg!4MTmcmRzoo8FoZ6b{eSGe2UJtvvo8)(m9EmO0)kZOB>{{`@4XidJyhvkK|$$7 zKAgt_ML%Dgva-&}KG`Q{WhK8BSTFex^}q0a$v9UJoJMDZsGTd;ol7FN7MM%p>8B*K{laGjWrqAA@S@DJkbD%D?Q$~y+lWNr2!Z+s9T=bnYl+ufMdr!HnHU!zT$k$8MO{Q4{c@f01${`K+usw;?}4bp@#+k1=IDqa zIGL+Bwu{}FN0&A_T%}VpA?0j%KxvYE*#?Feh=%B|!Oq7|N`tr+0<+@)sX)K_C>NSr=aC% z%_96^NKIVlihVE}!!wdJ+`4E>Bcm}rDT2D`t;NE(=Lv%3DlE|tVAatN@Oj5C3UYM> z^J8n8B6pdo;|8Xd2V0<04C?MCg1vJmb*uDiv?b_Suey92^df_vASp?=B4L4yn{AA? zj8@5>hWLY?@sHGlEg^E4Z{|aOh5^Hf0xsP&G25^Si_DO)C|*}O=;xd4*fT&(<@ttk zdWzQ&31k~h?``*3w>NV?3f7j*(avp<4FX75E1Ra6c6YbeNsd}~C{KRmC~KxkLp8gO zS!Ry41hH|FGs&t66*dxe7NaWhkeg$grqS#~;3D1Y>zXx2$C1<;jBhIsw;c~225Xs~(^Cdi+wZ*Z=)&+loKC_}aAN=)=g7faqq@(fDTK zgY(e4!Q>U$rS%iyiEVK{iXpy*1re1yN5S1pKP2efg&czICuPtbh_Gs3oW!$X)z^Q3c#xv2uEM-Y#;sZxS-ACZc%@R8R8|&$X^t5Ockjm)@mOJo zv(-$H9s>WYngq5A%k`EIo(5JNnv*$DNE-@)^hvO$r0|hzO^2FdzbRL zfVy0s4Rx_)7_9FFxl@Fo(D0lnvm53hT@Vpxy+bUF-nNFCS2)9{g>X#f9^nK|IZoy} zGhR(**JE*sorht?cV-lu!8)Y!(=UBF=IDUn4B3(^Hq#u4Icp|?$kM{+8m(ZaFd?Y< zsi|t=*FiswMveGaX8q1@3`^Ci@sCrq%3rkR3V-O2F?HE7uQ!otkq z;dtCljL^x0*H%OhU1o0kZHUPB*4fo0Ob6Vo zb|bqYBc_<=R`w2abRWoi1x9Ld1up1>-$b0NL=P>h{pzN6O#6;v5}YXKv`o@KX6J-T zXv^x#Q{5iMGobG1UkQ?xX`QGKM43Bze}8qeBqu1?#F*=2%m(LMH=(Zu0H^mFckCW_M+-TAlIv-p&2*|oHLe89ZJLDbIBBC)5Wg|p zYISufaNXmyV?&~z;#On0fJ5!>&^She8idVY zNLJkZh%F-&tNW*C`)jgLo_ToKD=PY<%z@Lg?81|^nDl-vrXc4nB-~7xkTG|-cg)KwA|hgvG8rZ+L^3BqZ&!TZJ(L} z7C%Sj?>ISZzSb`Wd=jk>%n_dmqPC0;hxS|}Rx+n@064xs({=fc0h3A&WJLdzYH`XjD}{2&ntUPW-=VrYuO0ZO%+y@!rwo}&3St!Q z$4<0}Md2|;li?mulQWFjq&Y|1h;S%woI&^5q#J>9g})MObFZAhnLqx^Q;h$m3;&~< zbrdSL{<&kxcB_8nF89apBeWHwEckL4yj7ooOY~p34nQSlx@gn2sCSQ~%{EK&YbI(h z;`Sb$s2HbozFw_-;%x75C}{5YYv4+ck^-!+%omUp9_0e%i#W5O#hgUS)?OSb+Hwnr z-hEhH#zXIohgSlF@L=rscdTKukguOG)JKOL&z*E-OuFpPrOeggZGb1FEKi-*EH5Zi zPRbcQ8Um`jcE^qx>@un@MUMEdZeL81G^p4ncEkTe?( z+8dEg`tpZ}U*YReK(xwgBp(cfGB|qi3JW@2hJ|GsQjD zpQ`NI0&>sHlBx!af1#3_O24u>iEuFg_X~XyVmal2z$yJ&l#39?ZEMQndnhf&W$e3G z|A?vlmyhs__fRj`nb?#ZvUTjPvbFV#Rv(T)KOY}FVYsU*s_3@4`#oEH$fc%ANY zaAGEO)=GlCyu8^4!<*I}s#Qf)IMvw}%Zhz@y_wuNYk&h%dw7Q7l}d+kTU3+^k0Cu! zBNP|ZKcA98Ox==_*GeL!yD>L0sqXtUMC&JI=nc180!#NVYtR0{t~YnKYZH}h<)&8FV0dDv6h z>uE@@WBBn~e>nryuIW}M;$L^MX)~-Y>{K3PZwPMJvl(Y7Oj_lQ?o#f_uSZjQ|LE`# zOPA+oq0wk21eQKe2fjo23@!%Hu-BWkPcHk?BU`N_*B0N>mf=d(NPr%dj@A=Nk#|n6 zPYOknb4UBZn@*b(WnG)2pvgp!DP_*ZhRQ6xcTja9*VK22_r7;Ipsw_E*4sN$e)fr5 zZnR@waT+RiU6$BL{d|MFI-Qu5B)hR`A|*65B{J3|y+|DKrP+J61M2;w*JY#_aDWY#_U9)fKoZo*}w0fx96C)V6ej5bS zr3sbn_s-38@uX(o)s$(CdVZdT<44a}yK}KHed1ACz>P%@D@ZIi7wB_Z@INFPtfo&y z`(t+rHBn9&nDYJm3mpvN50){$5VYGUR&tnX=GLZ<{)~A38$(IjSn^e{*tDA5CbyKU15#%~%cS@L z)7aSav2nh+pU4i%*dI^uGQJ2%)Y#AN&>$VNDJu+-asqj5ojyCiUh_qsF5?U3`0z?M zFT)H7ntQ%rUfB^gTOk=*Y)~o?SJ2b)ip)F`+&SBMx>s1V$$02oXBI}+A3;a8s8r)x zl*#>%K5gZ2A|M?wriUPXT0yM8JCaV!BXi1Oqf=Rde@kI*xjWVgOA395nBUFxb#&2| z0qyDJ_rRlPMDHq5pLMsd%j*R#-}%ovT|AjtT|Kh5T=zi zU$WhV%#LM zmFzvszGZ(B>koT70*y|k*gqd2soRa5S@Wh|be}Yo??3pEw&%?7lsfp}Ev=^&h;YnD zvWcM9^7&MFDKSZy0qsQ3y-=9`?d4S$No6J^yZCz8;|0Haz5Op^^D3ao#0CazQt!7k zlxA*D^|PF;+b z*U(J8<+Tjn4=zs0Q66{wuygseDEAYg6Wod01H7cJ?x>Q6zCiKj*=|n}pk#Kl*;;$6 zoTbz0mY#OHMq}Jy@cHYYp|aAb@nqH2mktIw?rykbqE^2#^wMW7te5cx?IkGDaP$m9 zFJl%N97y;M&t;>_0ZwG1m$BgRYlU9Z&8&cV(+8oOfieOl;TyiNY)_s2POAE>t;*gM z#E6-JB-mZTbc2~{-orKHA<^5{L0uKwLNqDzQ~GG0xS9N7LZXt$yy0l~9hVMb+a=l? zJtM*^o27fe3OCiA=))CBlY_6vWHLnPM$XZcH~Y4C8b$X)jLbJKwJe%Ob=6^;Ytky} z{b?Av-1cwEv1^tzMyOWQogQaL*_aW2vybgVOx1Qh=-6j^OEze93`;b6TPrSmphg7x zWrdh>@>f2?tD%e9j`*pF`(^_vNGYoW10}G^a0Q42skg3|Nep|#DkyhusN25^(d%;UkMcFk(k4zLl(?kU3RNePnjmUH`-+yLt!*Qy9ZA(&g;KhHb41s z;_-fb{7iPsuIYk3$Crqp2t`ZZg223b5=A}I2tn04#2eQRXPpet!*p!(_C3DZOsk@) zZLMToX>oQwKjn9tm%U0YaFHk$ z<~PogD~FJV|8h9y-(Dzv9n-AZI$x_YqB5$hpk$F%=+76z++;`B)wB+db`yEiu^Qn# zK(svCC1>QeHo`q6p9S63v-8j%*CtzbY;fWWZps#(dL-oR&GSKe|UDfIx=>(RpA zX%(Gy`C0esn*{kjW%3{0gA{n+*vDGY@R zwK3likmm){Jolh1B6RF@bFTi5UdCHv^|>OPF9eFE`KMRNh>V1fBwXlin3nzEKCUaF z$EgaT=u%QpqkGaj`g&3*6Y~J)CtX#er9*%b=c~F2yTOOI2-WO8E{yW~PfW<|xf3Z3 zIZQ$c7l$H;VJ(XtWUH7S$3Km|U8*;?I)Tcn(R{ihH0pFHpXouPq#Ve)raf0z^sSOR-|ZLzq=rSz)5*o1R_R8Lr=uxf#}yfzgQd=>GKshqW=! z3aoBm#n%zYN%+FZbh_4o{62R`Iw-d%w&q3IoX07~Hk~&RK{YNn7DXNhB#jv*Q3zkr zhG(^EEmxsl%pKs^I5TK=kSq|a`soIC!w>yNK8zqU;*6(R0YUbq9Q2!*Vs6FyFT8Om zGMOi7Lm7W#=-iZ)V~d@8^MCsN@g}zdctORRP0>Vbq6OoWGd_>My@cE*_IsBbgAap< z_DS6(gsM1{C~lg#K=Mk}^(G`MN`GVA@p~zn(ny=`b+5&LSd7?4_-577zkCsM`7)r^ z#LB6enbwm8>0EHSA1B-rSq*`lzv+WE7%9&P3gX8{XNB_YYF|V&d+|SK5noX_vCs-4K%37 z{=SGf22;USI?c?dLr+hI#TGn5Z%l@#bMlWJlkU)(+)t?I=wnCcQ2SNOQ%y!cW`Bq$ z@1G@IaU#P?6kDZaU%w}(yfD_P!Q40J>;!hU!OD>Q#Wd?rBWx`hTRT|jeOKzAU$Kjm$V=S2WbIm+--8?-Lu@JnoqzIOs7pPk2s=9?iD%5i`kycV zw-N+rO3^LuyT{v< zM$>f0c70%M2EYmv`;k+l_P!Csn+u*g>r3wW6>IdgPuRB z0S?Mcegop&&A%e9*ct!*t})TB)!=}XKbM=Q*rN%ug(gQFlkG-WyC-$=n<}~apneAW zNAc-v3ERhvYkb#%8z(-z^FVfPTi;B({1w5ZzLb3Qj@*J-bj5&f0$QcsMo%wj=G8yiOgWDg5U!CE;AcXCX|;hq%qyI(%r$A+1f9xRDq zz4f~I1*m#|(D)zXI1+G(4S#)Qwy4ciQO@0o(ru|r&H_9l_q zf%hhUV`!dCg`R!7b{YHgx%&0W=opPzEzxSz%3Z)+SMoLqQ-Y2#3_{Q6JZIC{Iq<8! z`0CUw?0Nm)BI5r+{`^nZ|M#%)@6$TCE+wyb zaGsNzRb@uF;kD@|<%>40AVs1Rt5&Vq$4lwAjaW2mB%*8=7Gxn1pGagEyBJfa$F@Lq z*a*uPVC6c!1Dx^>6vYV)n)v_&<>%5dKqOad8Uq4PPv)M20?SK99(7M!ge4~++#Ng{ z=fJq~%Te2&nO{+eJxhZ{iS-pWG@zDEwkuA3NBY!mV1KH2`R8i@_P(4~=|_k6ZeZV< za6RJv^Y#tw=YWlCtXqD)y@CCnWnlGOz_S~T;#t)`y(jhHMxiuMn{A(E#Qaex|I_pT zPpEOf7R4=WB4}Bbeh@zoaFledPItrzygj@fC$=-TnS}9 zhMBkZ>rRa;Pg9R~wRecnZ>{~(+gbi88Q6V2$GvQiHmkm46Kp0i&)oF>igQ)+WjkP# z{wAEkd;f1pR({iQ&9u8pRdKr59_``RQxQS7&$d{#xJ_52KKD+IqWf=f#B|KIUC$VI zg8|5f+O(q->kTr3zh_j<1}NU(1usj=vfnvZ*ahOw2m6G(En{M3pW}M<*Y>R44z@+5$RM9(n1G-O zU)|vKck>yK48+C5{Ta5|joF3%hmqfSVd+XAT@Bep`jrUbY2rmhxL*Dwv%EPMPctXU;G4Arsy zWM2NJy1SpLtIL>Q;N-3Vnw@Lr)HKFWO-;vaSG;P9n_PI$@G;Z-#;jo?JmR;`{rDop zpXx?8C5WJ9;~p2Bk^Va6c;hM(0(9$Qqd~jFbP5ZiOyRB6=x;_YbTmiJq2wv=%Bcjmm7L^Df)WnP7K(RMSDVS_&79%XrWV+el5{80s)*N(mXOC5*w zsUoq=QKWWdX$}PTK6{#S=5=;6hPDx^35XFH3>%nBx&{N-n+d6DgQ{%eUaa*JpZDE* z4r!+Xa^Kq~o4Oo9f~6Mq7Z(JzZF;-X>bB4)EeD_iXTBW|Jm!r7qQ=Uy-0u!|2e}S9 z7d$zh(dsF+w$P^TwieVD;C+(?eIPvfi%dAx+TT$;!W>~B?v?41T-0WX49J@AMMnnN zEb&w3{?yD5txP$S7j{=TaVKTFB29M15K*vs#OkoEZG>pevgbO4txg$*O0s?N8)M+H z8vLHR#Rd?-_-8Ni;)0;Wv=edxIc&bj^?v4H!_hf~1ybjF-O*W_7v-5nA;pPSdoqG* z#89{wbMl?H|5#T0_amzG?}FFGZRet6O_M63eKU&!2G9B5S;3;dB2>Wl()UIv^!~5 zSLe?cj(h0^s(QYA+Ten>CeaAVI^mU7oNOH#^NG8yuNF@JmH#Uq@(bNnA4Eo>(!WZB zjEJE)BpnRpGbw;RJ;J?yPX5KsZNgJ5Cth<)o)ON&wPj}v+Ba(ohHWof_((rj92gL{ zoptFt2zG^}deFY*Hh^@`f>*{AD9Z z!EQu@!t=={&*yMQq9vD5vd~xHs$k}SMomcPVK>~dO;+f~Fu`kf$xy+F&|BaQQAscA z-L=RzU@{2()EjC;tCbIUx$BrzK(Ji zs-qON=$?KX=R-By@JpW8Ln(oEX++K=(>FuOfPn2CAkSRReWGBwTS1loN`U~UxFmI- z`Kl#kK|5p7E$k24qU%OyEsDrplHPZDIxq31o^e?xq|nPkBcUSP$|MHVjTH(F^!CTDIr@`m(V!Gh_goEY@I z^-5UKJzrt;HFW%J{?odaTKVE;mO0p%_dZ;{Ow&e3XZJrRroR_@80M~(53=~8A(VyE z`V#1&y;(9w|ET}D8m?#{d&y)P+2Eu&*|3QJs8)IHD4k03+rWO%?m#uih%!;~YX-jN z-2veDlHn4~bT7eD9$Lj|eBCqL%c-iDRlrT6J~$i`trE0tlyIxa8QHK~#J>{lV{s;S z>6aKZ*^)?Q&B_hYg$p{uq93%p(wR8p4(};Y9#fpF%8Pn1YY0@G2A8B8T*_9$=gKS5 zoDc>fQ2(L)UY=_4l=3Ta%|2o<{rqqp%M6CwzRZm2kH$BYsC} zW+PF5Xj!+Jdb=G$lb z;{sEqF?yj>kP5bm8)>34F_m(ZWWd~Zg;Q5m{rEBvDnPVKMpKJbwqGtjZP&bvHZZ?> zC{@e&CP1?NvHGoPS&xyiuqxVb&x$7$Tr*08=U{Kkxv`>K=fNzkorhxqN3{MifD*vrJt@QBGVhJ&u6HQIfwRqFQ# zyAm6ZuE*Mq95jBZ>0K#JnKI5nf5KJ&d?pc`IE|HmoN*k}B4A6#qh_HUeke!GhG=Kr zJgUx+8rqkT69b2#QvA6A;xn~wq zitYf`BdcbV&XjpCtE0c(pi=dV5&pr$cmTR%`Jk6$ll8%$7*lyua921FfkM2!*3kxyy7_#XZaZa}jo%xDa@aPb6cY71U3$IUQeA2*-?{h?Jagzj_h4V;o`wi5Ui;v+@w|DV$wiy{LfOr=d zDEo=a!qe~n1>KNqSZb#_N&?M~Z+_X=)`qw&i4y>dE-E)%J0#K-tAHwklnc_z1}M z0+5OxqfhVV(*KP?aU&Kwn?(RRD7XUu!1@NMzND1_lYjINz`3Iz@1jNb4Ws}p-ssu_ zd3|7BtmH-maGU_@lIVfO9MDmKl>eXh;F@>wRiFRB8h{|*zAXVyV9#F)0pRXlB?04( z=O1-pTI>c_QBC^NMVspm3YHU?Y(}dVyY*Bi61X9fgwsZQeu$vr*O&4QepHhbXWBNa z;+=y=l1il%dsh0}lfu8CQzS*TT7F|pg3xN8V-FAX-TjNBP~-yWmt6c}ozpJh%DE<& zRi`9LWsCh|Jg7+MQ2q{Il5etn=p4@IP*d5V(^o`L87@gZUt01kI8OQssxC((9oC@c z7Ws?)5&x}Q#KrL;_Zggz`y*@pS$AW>mK8xC$uh19wA(0DCTrZ|LQh3VR>?mkxS@mX z-Sn4fqYuN9#ND1w+XTM+%Xl13+R<4TJ2N`o5SURW9o5$zunph>x?D!_YybW7&W*Vd z&#f~;4zMwfk?gFunjd?UBZ2X|t^S>!&5a54TTpBQGa;WIzABI+<7W z8)zjv`;itqx0cp*T??3#@r~$cgomz3@0;nH_B3za=YBN0eS5CTzcHk41O+h4MHi|+ zNbYz-`J+Vmr%&YkA5X=OhHocp4oj^V-$;9bsoZn7kvs>ZP?u=D zcE8+}g6F3i$nCmVvHbFUQ1_C^2Rf{_09b+U+A_U(Q%MKHLu%%a{H6h>B;#M05=Q!5 zdvoi~8~IHDEDIxUY$a5Z@ShCCUv}p&K>}I<>E->aqgHM7>(Nv2KSY_H5z2V|mtiRa zB%A&L6nHD0p zE}KHyeXWLS@CDpFI?{2qXns(Fe{T2`?F-n!SkI$((27SFe6FY5whWtiBp2|%=o^EW zRL8YlIZUqvI5w6oM#KvR7tIB30anyR_5G4t&xZo{?@}WG4sKKrRIuzr*F(IF8=E_& z`u^v(ZhywX-v|Y8GpSMu0O0!BU#&}5Y}WAbzf3{NlvX}Fr&|w}{u-S2({5LrVl`+t z>GpO3mK!FjGhmF7?84qpF4Lb-YUq08*Ta&F^@xk3mI;`LH5W{bGsNVD%9`~G zl2;I9uy>2P@)rs{i2sf8@JcH8s#hu=m{UCyt)2ZSIAI~_K}oSs zJQFxT@+DJlbEXIV94 zDEq*LL4o8(`9+yl8opn=cXYb?2+)L;wwI31=Zt5TH~Lg35oAnG+Z+d_=APr!Tp7*@ z<`!1ng?HT7`^=VvMAZ($6D|>D0+8b!~~WtzE+8hNRyG^Ok+QL-nUJX2J`T? z);!liph3X6Z1kM{$V+t=9FepI;P$O(6wg*k zRBCDW+654fm1;s`*^f1@n~c%(f50fqLxPx$@dBzL+}L^(aprsnDXZ5)hz@5}k_q~* zbrbP=5Z_n{N=GekJMOg~{ql`gfScGY(l5&!2wd}Q2LL{!Y4M1%zejB4n`^FLe|$)Q zEW~kD0TVX{LL1OHevWaKfWxX2^T!2s_hDW{2x~5fdH(VHrc^(zp#ad)Sl{1ot;c8rU`L#jzx>Y|gTnZd!t5U!1+X?ZCNSg18`V+$bbiGQ#d-&L#sK&MSL5ZF z&dZu6$Na?4v&3{q%u(Q3?X54L9FPpjwNPBjhO5R4T}dm|3|>m8;6!Sa;NHky)P?rX z&y2j3qxlYap~2ul0CIY37Je;e{t?rcwi&;c+Y)>>{Tk@GZ6ud&%zXfG>L$}xucVcj zfjb9l`|)Rp)Fyt1!|simbFQ-|_i4+r#6Jy@p4cLdQj*4EV`ER`UY$>Y5;dEYT`GVv zl7XlNi*+o&7@$_(qs2Yurd|xe4+mP^Hh^qmuFlSPQF9U_948iOqD`xn$oemRfG8Uz zsD47bCq|HBtFrBc-I$rpo%^wx0|&Ih$zSCnycZ1;c=)P)*oR*fj$<&oFU!_^^8bvFnqfumxrqz#CbeqPBSxbJ?6l?6g#g- zbXD~z#J*Yyb6J7>GTXmhf%~1Iv0XIKhw^zbZFM)c@HM?}AzIX5&N2!JkYLjP*Kd>Zg zz>?+q&M3vY`$_xRJ}(8`)SZT(#&td#KH;*k5FgW)`re3bvGI0xM;8igS;*KP5ukl{ z2XGO>6ct-z?SyrO-c^n^=~5Cd$;KE&^E_qvNJEgdY!`*tN&~`%!QsYfo)Yt8%&3th zF?b$!?cbsZ5K12#5t{st>kGE%55FDF# zo)F$L&vQ`z`uX^<^?PXA*M-GUio+2G8xgDCrA-g5yy+;9KE^X;yu-{v^?xr~Al)iO zv8Omq70_>Iavi&h4Q$%>@4kS|0<^1rp$Y4A<6{}euLHEHc5-s8;spf}Q**p+Ky8XV zGNpSo^ifP!{4N+K2g{FYr8{BVEgqp_&?v z$l-!EB~_CMi^>RmAx0(knW6H51<`(Ktmq8vfaiCwV;m9B=GFxL`au8sfo&t3x8ZWW zMB~ZD>7x^-!Svd8MjE`7dqGQvCe7W}mADVS7Y2rIhI+~au7!&h4TySUDfq; z!GzRSrCu(F=P5aBkSJJr)M>QQyh(NmCp(Y2V4Emwl7CzbKMkGp8Y7SVFZL(?Zyk&@ z421l7fP(N7LWwg)JvZJ@8~f$bV^jD?C+V^D3QOyP z6`UQ6trT#S%ZW)m=$9J1U72Gb&Knl<=dnJX{)3DgpN})={t>PF6SiY_n)0;_n-D@A z7!i@*XQF=eae*)ubCo64oC#j%Uc<@Il8D|S;P^&y*4qUh4H4GdUrvlz$MUQpw&6ei zdnofC2NWm;XzeD5>l8M@RFYYU+Iq?B>RE40Ct4FE`r145{T1u6NwlopmcMX%j-Z>4 z;6rJ$ghPLIiH_8k_(9LmSnS;Cr>NZYl<3ppn1yFEf#) z`((`4SID^}QM;vy9B0ns=_j7R(S96lJeT4u)81{XBxk z_Y_Sve=}EVH6@+5Y2hLulGL!+%{}~Wg3uK{B`z1aIFkOPRI&L7yNO^rrGToy$rImO z!@BZN;lZMp+?XyN$R=pR98(5=`28i7Lzmcf1KXLehNylcFtWUcC0|Qsx zAMCf8`ARgq?e435ID|!#7sbm6I^|(uW`T2G9mx7cj10C!mkxuenP2uZ(tDErXBWUyldioL~IP zds-gct9P8!F4=;qYXckXxQefc_Pxrzw}_XKVmIg$sF{3gS)__q1huPWJ$ik7FWh#% ztgi5yt>ijytAb>Y@7Hp{pU=T}7xn0AmF8PPw?xxA+Ud8XzFGgA`nsNR!2b*N)nUqI zq`PI<&@;5Q3!H!ycT>YMCB`49icr%)D)W**=~ZK7q+V%SPP`Ob6++1|FwhtUVf4zq zDlCgk>7aWP1+kjU)fOatwRB&PAIeQlj2F8QT)0OUBTHKTMM+JNE|jc$RmPtXgCqC@ zs$)mp{b2Y>VR6A-4E;S)21Nc6+%Klxm9K?zIW9%7pP82|v=+Ji0nU;ZcjnQhL>R@! z#p1ghlvwKbIYvvA2w|#5G|bBO>h!UVMWSj`-n`ue_XW*-!cgok#v}%w&!CSs|AQcf z{^!U~5yTv5VR?iY2-D;d%ARCc0jJp3Bqc`-(gTR~0~~T0X8L7fXzXpuejJEJWXLnD zXkK<5@_gCq5283G`DrN&Z@T?#tL1pajteE@_)-%*BW(-0u;R{T2P!5Z$y2u+Z$3>Pi&K!Gdn=c~1sKwD2w8hO=VP*w|Ib z1ZV2xVrD$@?fblsi3^`o7#Uc~dbu@pwS^UA{p?-gP6=l0g*m}fcM^MOm0mbCFUfQ2 zcE?q7`aiL7fZ=Y?-8w=x?SN#uaLShW!QmVQZkg?##9At1vPP+*E2r3Wsb?ZF9lI*Y zZbxD(YCfEmv7+?b*$y)-vs9kM+a-&Fluyp#)S6?eMXWGYPld;|V{hZWo<^e9GWhS= z-6@t;BuG`*J!BbFvYIVRxH2xwDGrS6kKUG)ne=?s+5%Ju-ccv0?hDG(Xrx1!kmTNi z43OkBYKt!7eN`1>FJ}`|CnkBBv+PBTDdSJo$?`gex=BsQmwfP>jtuw^S1@jY#3!6$ zDqjDW#i!`uf_H~yQ9R{OCclvIhh6k}Mib)=Bnz)jh^1m;=Oqi1x&%GRTzK3s2Kz#a z+{)%&Qhi2tN3bhn7qxCy2j7No z92_vbK7R5WL*!CwKdfRay%Lu<}31kajVsr#yVJ@{v zueU{0#y)p%_8lnPehnsF=!!bt<}_m1@BiqsYfxLnNY!uHkDVEN(x3`|#o-mM4|l$F zednM+f2i4cPh^(*&FoTDu}2px^mRm&C`dZwPQCh`p16$yvJ7JT8`vUBqu4@FTp`kUW zoGbecz58o;)&sFz9&((a5 z%$Lp_{W9e1A?DnRKG6<6=@dgxk$O7XH9dv;X()`gMb)+MQH_&hT}^Wf4*6VP?&Q|+?YW- z0vKtJnaAb))ssz$jh`iqDl_<1Sm!>g$sAo%`T{Efeq*fhlq*PEUa=PP6iQ}>O9-^< z3QH}W1?sQRUjFl{@^7(8$1FsUrYT4V_qhYj89R9*$D{ZCE}$QAd4Box=mM zkf_g@EpL)U<6lokA%KcG6En}yr5>&1Dx>v^X>55ZoLO%^V&55v6KfcNps=J2#a28l z@jObVWp=}YjH1G)l8b3`iMFVTEPD_=Vpy~3SRW2oyh%0O{AP9>OMsoECNLvgy1#C) z5zY!>wxP>ys7SD)iOm_X=%hU|nR6sAs)(0T)RnQiqk4HNO=0Uvv546=s3J+hvm1GOfW7dS|}L_&Nm)0R|d?*?%)wTY>asy zJYB=u{Lck#GYra_URBTcJPCtQd~+H{K_qrWQe)2pds-y}(ZHTKkh7;S&gHrn1vTj- zh0KkcxCkemkw;*L*{^5jeQLLke$06-2lu^8(z3sF8hJPMSjaD7>9cNY77X4T@2wnw+KuN{4YS@ zs4-`CHJ3ShBTmybnTUgan-LbWc>7D~nboj;x2v^fX*<6!w?oUAF~7Mmz1SUuQ^a;e z$qVN;HEY=si7C98?p7&n;17GGXIgA>O{93$nHWmy)9*Thv3r_1H4|^u?4I-POw>I= z2VoU?)}!E&R)sY~Glg3d&9pun1XS>H8`p)c=$g22C478jny;{KwIjn^9nr8riQygU za=71lTOBU6O#%&0UW|eCJ-~*dbETGX)1;0K+UW~fh)1N1xif4TraVQDxSYVMHtbNDRI9ii* z;nkGX&NnWddZJm65|PM>Wq3xa?~(OtCapnl($sXaF;;s~Iko2O3_8Xn+ z2sTadOQc@AE=(!1OUGoFQcnEMs5h8H7l-JQB57{1e#xV zD(y5@bGXpsP*4^d71?$&5*f7%r;uWV)?zqpZpr6vM3nyQMt?*nObh!hAVQgd# z@@}hHwtl*Hc*1q839;u~HEH}XH$8Ec?XCF3qc=edep=nmop^MI!TwB4dCfWs(hlk6 zG#p{*hc8@h7vKgDb{!9}BwqzRbW3Qn^PRY!*^$X73KGqV(dho!T@m}Pi^s*bV?`9Y z45@NU&qew_im%Z$tn;-?4x^!h<|mwR;~a!wOp#3yvzVVU&H9Mv|CCI~DVfkduF=zz zU7wJ~!(Tdx!lMMmyTr%C*@bjeM}-(hg>o;{tWKT))#=K3%32i|^>@B+TRrh|SrOb`S> zB)`-xI>RREZwakas?;zeLi{UOXYMi53hJ;1$xv!;bpPoNn>WsmrCY)=HR} z)FSN-2i4EX+ro-9^swk2yh(}hdVp-(dcVUK%|a`sJy=Vh&DYkIE?Azy5~4HFw_#U| z-0Lz#tO+!DQv0=(oD;pKSA7}b44MdVp|F|UPNhnz zoqv=a9|14X3%`3`aO(<*SsV{AfeHI<>tJvyNgtPlMwquoDA-H^iWMSI$#lUtF#fkG97X>ztj_iGNUxBPTh zf9(AN_q{ZFj-WZSPDHy)MogX!z9VO!FV1ODn@W7*>NOI!0FvEca_NU8Zu7zfXRZ@Y zx87=K%-eo$XR()L*@oVT}g-`yWHL)M=8=Hxe@!8(xKQ6Rb;m|;yjv& zTqXYamLWeoAwX*3v)F;@jHH=XHfT;u566 zv2bv*Lv2K^3hbKFq%w#bE7&B@Gtx(3b}Wx>;XB~-=cr67B~OCNjN@rZ zd2vuC79Lbe@85u(@G}CU`6)STqhY3I>aTYJW5vV-<<$|vHueMjJD8ZiRm@sfW#bzy zo+>wl#Xd%*mc$9a)R6@SEGfsE-FSUNcId499VNxKm!O`d-mxA))qt#Kf;^7JiF zX{pTkDU7^O;2(fPdUi*4@68Nfqg)B>9{^kYpF!@uFTU5FYTgb~cgEn(Q@5~g0|3It z`N&!Pb4iJz;k~c0qG!$F3zF+-&%{fc7A*Hp%wof|4o|q<0odU)*u3LV2s5<8>G0a7 z$;LfaS#e>ctt*p(^=8aH*V>7-FlW};Y!8Apu+(THG>W_FPYb@r5LmLLgh(Bjoj(|D zMs|{hAAmXjT_1mGFQ{|R*R>G2K74uJ67nIJFxY1Zj9pTkQPOxxCz6w5q?aA1F+zw1 zn}3^R(#%clXNOW(MKgQYnRStR9>eDzTTJ&S~N8XAj=ENcIZ>4%(gyHMM zBTNk5qDpg7Cnq~Yx+ezy2SCKO*Kv4ymip>Z51@sF1pg-_`Bj{s-+WcQ9NZZUE^%^qc zYRAox(8Os8{=L@?vV_z_DOppmHLX;ISW$`joO?LygSmOAwd3xJkc4Z&7s8234tZCYn zqiRVaj4mcX1{8breguQ1pu~g(rBPVd4K4);5~d|CR<|0(z;V#%oAa~8Nf_GGGo)p^ zn|gOgwFUFT^9w6YY)nbuc4D9DI!}~&)w{H@P2&q*@%!jFY4gW;8hM%<%s6E#sn}Re*SR;sl%n_Opuv5m0me?EM3|vJPV2VOf+m9 zi~YhT&K(jR!d#Cp#xuCsY8v8VO)UmMdq2OSQtnk`p|m#7-+8;tcS$fgl_B8NT2Q8* z%G&_a>m%*`M;@gDsJVq4otWp$cU5+g4(Gjhn4V!zh84y_b}A9VsS`IzY!dRk){}E}06aE#$LXymh4lB(wOBuF3`&xh zyz->OmT;J^b=>nT+yXm8|1=4D*3p6!9i-qX2}@>TA+Pv7aIxz=`5fx7O_?`bsc~pc zy3;XxK9dvYl)TF^WMU<#pieQPK^c5On~qsh$lQ^M>sEcg((50EotijdT(nsdmyj+g zFkwGjY!qGwF$i{6jjx5?H{TE-ca-{qvD1B97c$j*{SjybB-28k22@x#kMb^;+ZEKn zW4xAcPVx|qligS-|Bfz~rPfE~#PO3$ihNoE(gAkpUu$b#ElmsNpqrzupO_1pO)?*r zpM|AV{8$IPh(sOxr2n!(GY*0$Je zGt!TpQKXQ3rc}rFUU&Qfk20pa8)D)1!?N<4KKqFT@Z9?D_Bx@oDTav2+xqh_3?_MT zxNRR$jlBM_=8CPP1``&~`6a=Sy}&9`l!_t%%doz22#bx_d(Lod^v!b+$Vn2i(Kfji zWzIPF%-`1*g)tu6jk2aD4|||BMS-Qb-&SW#u6r_w`U%zgZ*AkF_tC}$WpEA8HDUND zBxv$_Faf)cI9K&yr2LOX@kbXCR`2LK4ns{QKJ@EF7 z{`<(0@X)m6HiCWd@~QaGi}UMyX&)`#>f@v$5l6mIn!@Zd=u9_lE&f~xQ|(>G@4;vL z7p}Gp^v4(d7=)Q-WI(0*_EY!jxq7@fg&#dQn6-=fOHJ}-POL8|=rG<2SW_Cf_$tV+ z4(k8OU1(qeRt&%6(qCHe6YgwSgGiT8QZxRw}kK;A_d~$BnwFz zIyHS=KX!jqAL?s$IQuH{c@&$2j3m{8UT@I=J$Ap63Iqq^_*T2h=1sE$CLN3O_tCGc zhIfwsSybkWmB-_UsjeOMO_YmDjwJ>%X?+IphWv)1a(wGoQWm@Ga?CZ68-3?$oDb{I z^48JY!RKSBb`1v6n*7W4k~*NRBLB;k?Db937a4)}I;@&%4H}an!4|fyMXYq#XVM z0CZheT3*rr?A+G2Idl03@EW!3Btg-R-rA&Kj@pBRtm;jS`E2NwpB#w9?Yed_Mo@bA zl;(rxCFnA`U|~WkEdsu|~Z0!aStNirO4}=)lI5*P>SXKyx`AwMZbp@8+n2yeJ za?~Um?NPLBSBSg+%(mnnHQvV{U`|xGP9FQHR8tPH)v!7rXBzLRvpnFLpQ z2wTv{Rn&>*C0!zX++RsGeX~NRLnpHcCUQ@#8SWdlQa34fiI|=l#ETFnwD3Dv8f&>t zaKv~y1ioH?y)MNgm_${zq^E-ww|!Z4g@SZ5->u=)j^!I*od=C#rOGco_AIvSQO2S znzA?C)+4)E^!&5!uz!_PFD<`^X{%E!=x(ux*?$v3hC#3`F~{d^Paob?>=w!K$W_LJhAiAUWZ{**0DPWg7R)E}ewU)+L@ z@oa4(Qsr6=gocL`1#FKQqA2o&WA()xhCugi-D4l3kSQ-}QQAub$*hoAvc@Km(CxW2 z(czbU#Gf9Kfm@T`!wtJuS(FJ8X-9S+mU(mvpqdB7R zpYW@$90icT`F*&?KGV>2M!OOE5ZeksvbQ%PAWWjR;~WPliArF%Ffj98l?K81V;#;x z)4hpp-&7-1VrI5w_DpyWXy3AQ@V=(Pc74+}7aCC;8ZxwcypdjZ9Cgv#>q3;<60+lh zzb2FySF*UYpyjzp8^DXSM(6O2GV3&)Zw+r!c&)B|0c7U~6%~iZ*$yZhCknQD)X#n> zj9spL*mWj>Yr3lo@gSH2W)kEKFe+c6ZEo9tf2E-R`||tN@U|~OFnf8|Jfy@aK+i6;KzRe zk*HP7@jrn3@K!&?MQLN7Jkl-b3}f^zHOI?A!{Az& z#TW6GER{6RF`VM;sQf-35xL8$&iw!+_r&?|3ttA_5ha)rGb4Y)GhR^cr$)?QpJZ)& zC4!lhlQuM&6!M5U8ha3$_2tD|*`pmX!y2=}d{*C4Ps34aJ%{Ge`!?@LOcdRMLT9lf zb8#nbMBBrON0pUXTS)l13EI1njQ(=aIei#j`3cM@#}_e-Ht{2;c;ecWrZPNJx-w=` z&+$r?C-L6tMdnam;5v>`yq~;87$22GIw+L^2j^X3eqFEo0iUvIv8kts+#RoRR%Nuy ze_Fvf4Gd@u3=G6Hrh@A6075Yq6%BLXTxStC&#+V`Y`JTOWppugeXg@xJbQjNQAbk3 zFH1PfrZegylSXm5q-ZB-6%HMq=jWi9VpPXh87*IXEJADv(HO>|{UT)iAYyxKe0Adh zT=YP$XA-WW$AXFEzJC3yq=MdGpJEAt-WL3{501NZp(=b*L>wp9ZF<8PRRG1b ztU1}f^GmT3^V@>V#2zNy_HhYLmgs2oEpVP2?KjqGbBOks#l!ug7)xdBA04AOaU+C1 zUk5jF3uckVV$O`9+JRxQDN99xhmJ&x9Tjui`uYRWSL+CMw{W%jikVS|06r`!86gKB z@dF1JNHDj@KHYfjlcZi}_}<@&L7J>D=l=l6KO&L25uOjYUs1(su&RFmimCp0wM7p_ zpa@SwZ(XK|%~0=(P)vwaWI`H=CA3#zdUICs&)nyMv%;7xN9;DcyXcq*EY~T2Gmf?6 za=5xC`Eo@Ei?Z<9S+c~V+{r1a$UdJv3N3_FFwI1?n!RKKTr;;&$kil#l%zEttB7}w z#5Byw_KoQoX2=MNFd8>?NcYH(Q^>&j;>U2+J$;q9YGU0EA6Qs*D)QEwi@=s519XmS z?M8pWMXM=oIdWDnEM?N!leRjqZ&?}NU&VL;fb#{-yp!tp&NMs8ifOU_Yl+{iTj6|E z&)#dF7gow|VtC#tzRfERZ0H?+{z9~19?B=zGTL@1k&<{h)=66N$|sTli(K!(|d-?;4s z)?GO%V|N)iBProxatM(sSl{Z0K;s{82=fdUMNRy@=i8BxmzU6ubd)qq6; zH-F*@H=ONBRepVotNCS~z{N`jRuE}>mE8{|n;IB<=~{(nqs=o?;!x8U^tA^&4fcr~ z|JYy6F}L=c^CGL0+Lr9i5KU<)ESaLalG=Xj9D@}5%VXQFF8HVWkPok5b6S@DaiZ{p z_+B5XK^7D&LU(H2W)tXh@;NlR(-Nmb1%9l)<^e($w4>qYOa3ZXpQCoLCe8ED%o8UktYRx; z2EH0~AG2<2uQ|HI#Zs;Ns#}N+032nlEt6hf=ktlVXa^iuyML}ancjVYNe|>79 zp(U8xb_Oj#tt*SH=TiljBWa4S5|Zqu;cwA58d|dx(>)CwmPe^qfmqiDp+;yj)`UBLUlZMH~>ySv9qfSy4XlZ@@%LF7WuG-6;cJ8DWSwdS{@r8PSFR z_L?=@0f^-Rn~Gwqi8{1%?Q~`zd4elm%}uCGfvA|tC`JvaTkwBS8NR~*-|9XT`ce`O zt3jbJBZw5gyg)CSY;_FEOxVd?bK@?Gh6W5ZgDQi`xlFR)IlG>m0RYh-{R?3-Qk z9xY(K|MpJ%t6mj986&BC7*R1#9FC44{o;|e^N_z4#e6-_aDw5N*K^@_wbUr+|8kZT z!nxhXZ>Q9vtX#`!T?%Yg!1_vZts>EcNc56q%UFq9RHK5Bb@K~0TW{$ zCp4~N%q1b)Fi4;RLx`+PV1f-t@PX#YJ^xlKlFYUw4pk2_;Ko+dKR^se`yqPepYCih z>?gj$bWm|cLNfcCm)zWCm8F({ouh(`_Td@MZC>TARm)N7UFB~DiM)zPLMJG$jNrxQ z*I(cHTZJm=tF6}|*(-2U)>m|`bGK$f^!|3|n6C{mZv3#o7nfiPp07!)fhXSfy-Gsm zvn)|X-PG?`Q?ZGGFq0!+3m*taZ`(FqWJl%mhv#mG>YX7VHu$WhN z+@5JkcG!lxjmPLJ33nxaqNwnaBtOG@2`N^3)%;VnLBpA(v=tuPj?YJt;DlobU4Q>w zni?zzo9Txl3n9Vjn>1YyXI(DqY(MNFW+_jnuXaIg$OxARTUIh*N&09!ObLmT4E=i1 zIpmb?#t|rLMjKN{4x-HaCpMFSCV3UqlzjOkrgT|;@)V+Lp-@Lj`2E3cXxEaYAvRs0 z(izu4M*ypduFq~4i`|~$t>kg%w}WAvji?bReHAp$xw)Rj!UWhV@g4ygk`#x1wZYOH z=1{GIa4cwK);)|2GL{e@uSh^^lYxi>Aa%w9uKQ>sfhz_)9mnZ z`*Pj~zTe0wG*G564ienhIP@@c7`=(Q2PevoTqUne4PrcP#AlYCc7k%^smVRay_P-V z+p&Gv+N$Si&%Yz*z=lS-xWA9@mkAfyCp|@FY>Q?j)Xxd$FQY+lhEhy~3 z3M&0zM*AVEgUG;LhaV|y2iO`1a_sMF2hAjupJQ~c9&4Q z$AyS~dA{e(QP0mUn$~g{=v1$!s^)W<9*{>vZ$JvS)?{wKjm)sj?KN%urdz_0+i^&q z*r+w!>O+EAYY?v8o{lymJTAOI;4Zmv6Fci1x+rClSHH?9bk~(^^V{VN;gz;@zn8Hm!4Q-b}(=ja;G4>%_1m zAy`RfQWdMUXiW>c0PIy3CyrAIOH-lMP$Scr7|%C^OocEN6d7|)GlFi2El_gpV;vMZ=fl-y5IRg)jPovN3YDdlF1tf!o#%ny z-~4VE!SZY6U36(cmoO#+7RuxN3C#|3AyUiLpxv!JR zmkL9*WBV&Cq*w=q&)n?-$bw+J3Z{$4oT}G|W(2+Qc7wI?zJV)}qs^8dFVkcfTr)}J zVLKu@LkGM8OkmC}D&>T!+=Nu+@4 zq78 zBhJAR^-;bzcmtMP)Yo3g@Kas6yhX=PjzK}k``Dkn$Fz@yG28oIDJKY;)^%TZyj zN#t7*@{LgY*97II2xHuB0f$_#Gkp4#RaRkzpOk}Ky3L0VktB7)Bke>s!IC%A-;?ly z2LAz6!mP=Gc8F(q26>I~4XUQYRz}W-knod5xQvLA`fO$wl@=-dc#ERV-Jv%Ihf}xU zcv*XKsh7O+!asPX#TN6p#KKHtJUQ^^n z%4X7sM{hct&4yi$GF}}VEL_Yti}!Ze(YS1M*&l;Dc=hvamcGjbB&}N5&rFma_UXOW zqX1an*aC0u1b{U|SdB|j?d^w8dCJGV-{v}^-YU%KFy}Z^$=Dm>+iuSR9HMCb1RU^l z3T{ktxvx6}wRAVRF;CVH^ARq5OzeXEqYw7*CXL-_t-ria-A!V=={vz2Lxo=HQC zx;EoMOdl$Lf7^dJ0jo{XE3SwU+z1{hVAY8#kKO>j6Up{67Z3$p(+H8 z8eo5jh4BQQ^l2s>O`3ma;_#{!ELMheYGv7!PABe@YqkJqW{$%&TAOqxabOU(Gk>t9 zg9^ggp+S?^+qvBFCWTp70=nl?BPmalkkJhz1GZUS;_%%}IlC8L&%VlQ`|cgsNJA-N zfJ+R92~Y-@R9}MMT3%}f|6EpOp9_`&ylcRVewPqGjV-r5R)p4~w{Apcx;%wPyhG(r>4#yi@8I=O980XH8yoo8tNiY8aRt|nLC}hN zq!7MZs#VaeuKEvO--!}&pUx{&l$Pz2$sbqiIlY2Hn%Rw?sa?{e*hY3khfzM_qfEP~Vv(?6*NeTvg@6Q%~ z$bLWM(gIiGX|^cU88WbYn#4CFyP*Dp&sAgtZ8gw((0cAqLxGpAHg#%Do;)sWyjLH^ z3gK8@B9dd)wGtU#l(EZ;k&;t=@gWpdU$TyaVos4mQBP!7r>G~g|JbU$6$K%8mH*nR z26&I^O>aC4lONP1co5Ak@phfz+7ULA8%tOc1aOH2ERkBubYz?b|xKI{?C#0fZh`2lu=#)6$jOElk?jS5Pt72%`1)-Y8m^k0cw3t&?+nBCw7 zC~8ST{ZKB#>Uo~b>fwj-+FsG^Ga{$huqd4^06#!cxkCc)7R2Ex)Xu|=FJtDt-4c9zpp^F!86ybdIuPF&|Kkv~RTD<39T z`0*TQTK({=j27oY>X*M^@+LP7kr{7C7Z)1V%IvtO<3b9sLJqL=vBpjl+pTi8Ju~V? z_w%E$f7XmdZa@**m1v7LY{2Gh#3SRZ)f|*~)qBO#VHiFfvOE-5k8Gt9i$FEnapwOg zwnRYDJ}V=YAS>q+V}lZvk6=%(SF2|ih}kyQ93#P_skukhx+83BB$1EAXr zW}C%^VI{@(x}2}4>UM}`w5=dSa)`^Dj+D*G=?aD7VEt9V%N3|>dpeS>m1kHwC{;R< zCxPQ^>w3tzjivQ?j|M^h3xbtok_5bm8!a^7+J^R5^rnlu68to7pp28&TAe3eaX6OY zZgmP}EHEY&%h+~SR;8x+a-ZXo2jCOttCmJ^uHh}ePl{37ush?k+LXFt9i153*L?P5!Q|^*OhKX&y@Tor{L%m z6~~NY--#jA!mo=DB2tCs)5Y12MLc%Bc713ZBqlo*r8T z)5H6suY!liV`8eK%9mvHDCU6uSPu_Z>Ap>o>))4ew#4jFFeAFH57tyvAJT`o?U870 zV{@+(GR!JY97$duM@Gkq*SSYW9J8!gC^P82z|Z|YZvyfnYVSn#BXUJwqB;Vv9u(HZ z**n!9752+N$jl(qBX!NW;>Q5j^V%vx$Q|-B&9W&70ej5vg9|y~fTQI$^oPn^;tIrG& zY+F(7l3v0biKT>JgdPI`6fgdti7Bg^a;FZoC4(2|f9r1V|Jnrps{ryrzVGe{Qy|(Z zwW9_HY0BtbwyH~`tVnHMK|}c2i6EgW+BWr56Y>{W8$d1arU|2A*35gl2$}oNe;ZkwU+J7p|W_gL40al^wx6MCj(|F4>Qx(M@IoJ7-7aHwl%5C4J=c@0v`I_I_G4*tO<+Ptm z!hlOar) zoQ^ghYc-c+$~~fzB1IqR{s!r#I-_lkww3#^I%bA9B1sibX>Er9G_N~!4HLLv;Ln5j z6W1@VvNsR-GNSb2b%n4_-yc6HQOf@&u0y`nI_;jf9}w?3cxrUBY_(g%bF4CRr(fh)Zh0 zynSnhm)+n?fOBCyVxr|PA>`42`7(R+&wYGuzpgT!oMu7fLS&oH?#(^%O}Nm!A$yQ@V9I=ZoZRe}ZMn@zKh^rk$0)aEAR1`y5^= zxS)!ELHp%TEcY?4Bk=Wl$Moj6kC~-OpGN;DdS$^F`E^yBedQ*}U{9yWYkYQ!g)ImI zhF&1g<3xGNn}q9x?mP}@ZEp$g5}lzQ98li9;+SX}DK&@!Mm3Znd?#?6fb1v1z-c<` zq10*`MCIc+I}n1pPvM0s&Y)!F`wtfF^bHmxBzAD;g|%1ah9NdjHdOuT7dI9_&&5D) zcYjh?g1wV-=5Zi42wgiOBI|u#c5po~E9KjAEePj4NCd|}EmO=dYrD|<|^ z!o~e5NV~nCJ58H;m0t6j7qzMM15QdKM3P6Kr4)~Og@?NlVb!*C{OkOX9Y+{tjXgYT zkw*#=Ej{OBE1?NHqnDb=OMSHSl*s^ASn5V}eG+Wv;M1*W(J^#z_&$f;huv1P|`+L-U>{z8Cp`pu4t(|lU~XM#3rcJ*9(RYi9Y zwEirOdPqLRN!?NXsO)KG-FtRN@ZG$+mIzpP#+T)nx<9h1$zFI^=ly6Yl=%s4A#*Um zSM5~-%W{5wZ!vdL2E9hE2G$C)pUlTh$L?$HPb;(b8@)aw)sLu&Jv;xSd|AF|@qK7f zUxtOax+RXM%XUy;voOi}LM)kU)Ik8e)YXMRA1`}1VDBGl3-WorbTISha$9(q;kL%d zc1XCHIp4!#!JYp;UY(}d?stN6tACEb2-cVICWZ+$msU`w=60!&){2l1hzhO>XLtQ1 z3rVk9Hn=gka=DBC{NMQ6tpCE-^00$d73f4{ImYlJS>puAf%Em37*rS^UkucnJyGXh z9Z#fo7qT>_7}B<1sl5EM_iBQ!0weowl`=oAI4aLNsWyB{fDcXVZGcH<`6^-}iQ!|& z{~rtYM~sa@e;H(F{WIU?K@`UnMKM6>donpuFJ4vdsWYLB9X-!pckx*KiFEMi%WerW3v&C`ubCa zl8lv+8n*%gwz~xy z+v9W^QQ(%LL8iPddF_#{&#TAiex@%z3+(J}rsA*jKO+)082zc}4EY{zbXapWYH9Zq z-nLFKDRh?q+71lu?YPiE(qPlSc+Z#`oVHboFDTMygA(mI|u%9Tr0!XW5A8^S^S@`5& zP7X?u@`V0of%Qphp`;BZUoJ@abECv)@?xvt9r(d(2;~R)9h$HvIZYM;8P2!3M zkRRoEu12OQE@bWox7Volt(=35s{XLtO-gZ-7A|}+q+p&U^kTPC#oI#ck4TIwnq~$$ zo8`|WReau`P{IV|TSULVZLb8m`eUzRkP*tg_3j@NMogV2=7`jA(%@zpXpJ{{clO+l;y1@eyjr^-L`<=%d-wP2R&^_Bb1l^NYxFT{>It232LH zJC%4Yi4JP4o85DaACX8Lp1=7E1QXWFr}_D1^|D(Thf?E6ui3|5DsTWfjioky%kg|S z+f|c3es-cAP!<1Yn1)fe0~nAw5C^; zkM7WVO_8Xjp9szeo|2o9jLO6v34G!BYsFgAbW(nlQ0VpEuOj}8YXwZHG=um^5{DD@BIzr^legYju{i;_8?a{l48mkHO$ ze*=W~+lT0zF0S=W*8zuZ=jZX-MVl%ogMxAJ%Zvq=zXxMxFk6v9IxQT3vv{F`-w4q` z6O+C@9*oumKgleL7J+Ii(u z%SUzVy#Coee>n%S{_jQsw3d4IAVs!WdN^Z;&=nMcQNpjE2Ea95pXydE=NSxBi zO;n)KnXfy~oOvS}G#k%DZhUVN8{1L%d|+l{6uZwI-Nnt|6X_|qBan_k;Ps^cjW4!^ z)*MPUBm{x~*Tnn3$qTHq1LcRYl}`cF|H)N&;&mz|b#A>x{UK}uFkTWC>>X9SJvaOm z{T|oE($uOkAqT1 zYSq9dVK6~|_ZRK&FuqMg1x5WyA)=VsX!1n5B0Ad$gMa@>>8KKMa{K(AOIhf!ln}Y?`2E$L)D{DspOHBS%D zNq~x4zWeuRT*mC)#t>X8Si6UUxlZ1aGq+c!?pYTbeWR28C29C`eK(#26$#*xkRI@_ zIqW?(&!$11-z#bfQgFL#t*l0UI0w=HEu=2MLV_!xGTIwe3#&Wupi}s@>P!A7i-1UM zRG158+wgT{w)$LuXwr=0TcsTIVk3L?+ffHJ?xyhf|1P#5*xpsJ*#QV>GyBNr9vd@g zBrSc-1SH1rMIAvB2wFNyuX zUg<`TE*mU7P3|9*iZzLh+hY^H$93}qS-p$&mTnx_NQ7S7V8h>mKTiHy){ZV;v@Wr6 zDlAxgE&nMND{NouSpS+r=-}t4SF2aqs}z>-R~A-TYKz4y19J^y#RY5Ih9)2O>OirX zquCK|20ACyhP9|*JASX1z)53I`VHRd9pl)wFsg2sWF zJ$5R)(MP56=L>j9(o`1nS{KSvG^O6rxMus!6Ij^_gDLwl7tye)4htQ!_u`w5qHu#eUh4|M%-lzTD8WjOx^|q@=NR`k#rw1x!X*%?n>lGWUBT_!3w!7^_4PA`!3IP7lJqNUUWPDRUjIM z(?OAKLcNyx-1If0VP?+OtsI_(mq`n@NbsSRx8-6%Wn6zxji7wHk^9D{8B@Wtut zhzMZx7rbo?s}d@7gNcbG#n0HA*|QMOWGi}=6M=`0BKhwNi>!t`1Yt4}_DE|ibidK< zyOwQ%?089@IfS$On^w5O>#1rzQ*dIC*cjsBy?aJ9xcd}Li7Ff@n^8?{Pu52w^QLRn zppY)G#jeYFpy=&f!#EktRiqirX=b*bUl5j<`aujs7B7mI58vQ(7r+@0bOI)EGiJwk zGX4$JwOpkiWBwaYtSnwrbMS(T6kuTr0uXf1HefDd{5mKQQy{sN*U=aVJ!ISsk{~du zX$frkYd6TJ*Qd?wEK~RuaWr=~`1oB|KMjXFOYY;v-}JvP__i7_d>2m-u~Fztl4)<1 z8B{_oqerW~LPm1$HzhuhgQMNwg$(x*)#VFHdSfg>k{ibFEn_4^KEZC<^Su70L7^^` zfhRC^cVJT*N-sfgcevJdfA+`i8UAuLc}W?sP~lEGzes)IyY^F!TaHeyFZd$UvfjPq zrvCt@_Wl@y5NQlWMr@;weH=d66)NNWq?`Lon_irXx(z%Q6-(B8wm*AIOm~v0nKg9p ziNvgYbZq9Ha>$P`{pTNp{bc?U92WN2%0RN(kZT1P;ns~yS@V{zdt+V!-nITOm&QKK z@J1JI)N~qKHG~{4DlP>hvVS`UwKT7;yYgp`xe4z-B15N0-lU-{a7?sS9_NjWe7zc) zq}?L-7BQ9q|CdepH~f@m2NpiJsFkLf!?xp=afLxsE4$FM?Sm!@d+}2|!uQ1wbI8_k z7q8dUw2^U=I>O2mKAV+I%5Gua&%?WSi;pyJ`Z$pSA}iSDbrkN2gN<@}wBcR}f%n2% z;-?$mzb!55%5mp3a7-tglO6{LUs8_P5B4Xvo-8+9@OOHmG$mN(+9&gI-8PFM*~M1E){u5O!wK|9*ZSsrLc%ge5T=1jV5jD}x9 z%!XVu0uzCmA6uNU9QM>phw={+PqZ;}YT5*T%K}}tJhnE!dKMQ}A=s?M$Op~^j2$jf zyNi^);%Hkj+?ZxNq2*4_;g;0kFE?LrB!L$~&uf+KR6Ml&0j!+2=<%~>)dC*;NlJyPYdpdh>!q;bC1a)w>+5i`rsE6s6V{Eh)*UW1YDQ@@~d-t5-divJ$ zqr>0>AUERG{HWyp^^jfu1;ih~E9ecR zp`shJ4JKS%ZhvW$_&kqJnDsD!U6LmCC`w-QSKjNduY!oDN22N42iz>$uih*6h!$>) zM$NQ%;)YjG`Ap6W6A1x!>t@vp1z-xV2*fXI24BU9;LgfP481q397htGTR9ea;?X|( zo-@}^m(4*vPu9CcaAz{uEE{{Y$db4);&zNBq$nA}Y57E*c-xuEtOx^DT3Rb#a{0G% zx>qMI;?k8DK39_<{b7O!VPlKpR0Q*3cT)tpYw^=N)J9!?nS)C)Q`3j6Sf9Ey4<75S z1?#${d*3eZU$wW`8H8U)H(qPY=oVKkS+BY_jxLrko276onC;GUQ%Bg-R96k|MfNgB z-gs#XTMOuzZ`Tg`_!BN0Erku$%Bkw>bNvd@I(%<^e*0Y{Fv9dAiJwsV^q{82ev5u~ zd3wu!XF#EB)afDVK+~#Vx!yJy0Ehr?4R%r-R^DI!Ia4*apOfI$8Nsn@Dps$qV+qk?rq&D$ACsy#VX z#pn5PvOn;67Sy&gnD~?%pBK)s*T3rSYZ6e?El5RnNXW>&BTi1$5dhk0E=y+?zlp+V zZA(XC!lK@E2zT~@>{oY{c-Lu6y|GM&b6Yn|cQp{$EgA_!T>^XW@`CNjon#bbZ-S*1 zC_+w6*DJ?Fd7nGi1;|;u1A5X5;}cXA;~+Y_=nFHeJPnOaFRhzCNNhQ!{3-i>I;>em z7&9gJikiieSaQ!0V7ITf!zA@9mvK9?@+{;Qumcm&nES)mS=J#~YDQxL?dn41T{F#W zt5c+pL-!nmglO8OD|?3Q`33SbCqtW0E#)V?Tz!I8Tg&l;x>cM+7T4#Z-}Qvu&z$nP z?1_{{M_5pF`Nw4=4}*koE&?6XJe_g6L2jshmmI4T3z=bE^~=QsC%OI(i>H=ombD?$ zZMbUkOv|@sgvRi0M=IYZl=ro+m-=CNraLX}3DdALxuKlk2Wp{HZp7ox7wuANkq?R! zxM69~!BDL-V@+ij;+!?$wy;PQzZw3fS+T{^bQ{?8qPSIs+fQ&nAm1ce(P3ny zb_M91y$gq*&F@swuTnAHOL%aEzGp+2x(jee{nWKYBwJ5A%qVUf40xNwu%6cpCcC3F zqW8<*{;>b>&dT`iT0I8Y4C3%4Ed7Oe+C1~U=V~y1fjJK3&3=g-Q~P57`u~_`86wPG z5NW~n-C%UekLZshYW8PyqH2lVxDhWY9JXJC*KHI<03eFX>wzt|R0*%~Hu-D#+Q*6hZbvIWq>EX0^B6m&rn-FwPNxt;x6}=wiokkmgTPR*#yX z3p}r9)&*fHriaT!hOf4UHxeAJ8HY;z=z}w%;t>2RWEsWSTcBCXas5(e^@pR+%|Y2SUYME zXFV++YPt#G_1~8(lF7Llb``BQ(#xMdVy))sLuP7hbZf@KAFPfe*Ljd${5!0g;Yr{1 znQ077JonInA_7V*MsG&k8FK*7bX=MzQ~hWXP}2R_C^q9H zJNj-#K@H;aK!S9(&t!@j?EB6W`SZLfEp9z1T~}HC^+rVzvG_*tCl}i*T4<<2wMs*; z08KRTOsV*U_y>M>Z)Xkovce*re5)@$C`(36L3CxkG9iCw;Nm3dkL)ObQlWLz1qLclVTpv(3GXy`hB=*i1R#bSg? z3>};|pBsFfvVxy{z$MrRb&}BxcF+&l{LwL4KYREG(Db&2!v|dpJH;cijhJ5)M-RC8 z-k|%`hMW5^Dl;J;*-gQ*GMQGG;ly1nxe`ru8?bs|W?dW@gK{;Ow$-fY;3CzGJl-fU zNis&NRHQj#HSt^X$27DEah183zIW33i0=X5;zuB`gWblamCZxS7*}qq)89li$94;{ zHMT4FHpGeV1%Cs1JHJs~4%LBs{1WQ<()upyOPAEvT7X>ZRy1UlyX?JHKhkv2!T}Ms zzA!R`xcUi(m03{65fWx#JCM%fMLeKp<4`tFGbuGE$u!H^^c{S3&L5#VE7y-Nhg>7z zD=-^^5ipHf$;5{n^;}CaYtstt9G|Cc#^7ot{~yxcGpMOHT+{~X2muwTp(ss2kP;uOcS!29p$$#rzXC2Lvd*177mfJzPeqDz{UcZczL5E*z z)O07r(z((GJQx{|e#{!noMcLVunKp)kH-m7otfdRlUe&Vot-nTRU$wqPOxV4%ynmn zoXno)^0F4pcOF<^h(n#M0Fx{~L2`^AYZLL)xtZyE(uqIIytIO)nbxxohN3-$^*jM@ zdmH!7Eyp^Q5rzuga#;+fFO7T4S~jU&)_~O*~*YP+VYv7 zostp%Ze6Ji3^(9rHPv`__+zRKGdlGBzmx=E|5*}v zH`CnSl?xf4#WBymHW+zkz>tg-um#0(ghbq>B3`BbyVO5 z%WS=t3RZ<~5Tct%*XMa=YGX;GDxH6i=-88tlH2Br45{$}JWeel#Pe)Uw!?fldh6ih zAY@YUi7a-y_A(sME(3kAd|jDHNLVH}q<+B>x%jv_fPEn!_1c;b=e(PXG|_vee@%+d z;O!9DZTJ%pU=TUo#f4j?lh^bnid30~abO^Jb`|K?$)?QF`QBKgsR~#BVZemw170qX zKw7ukRu1}`P`m6TE@*L>)2*I-Db3uV;Z-V{fRVlLLe`*v!4>}T-=Rj={`K?tCDQaiMdrU!I64--@DWh=g{#wa0 zt*pGBMaC*Tpe>U7L+pYoe0rAG!WCwsXWl$yts~X(%*k(D#0g$j zR=+p@mPt3!XeSS6rTWkjG$puvw7OkA8JKtht{Pmjs&o_b(2mn3IsrhXr zgTKx4Tz`PB7TxaVj4=yMn=edeMO&ejJYO~0cpDDLQiW((yPZl7R{I^ z7NuGlnQP@|mi2&sF)n>+S0IAL0jWGT;^!hC`z}bh2aY$7%_G0&C(IN~Q8r?Uv|1?@ zV9}OjJdO!lVPRX;ZCMflw!faQ2BCx8LmM=mPGMalgCJUJchqtF^3Z-I$Xrp?zIhPS>cP4(XeKuf%q3Cg;))19&3?Z?E z7M9`Z8aN$UNJ(*7^N@}_nZZNgH&-~Rqu~1pkkxdx^RCzD-ogT z&t)%`+0+&a5J?oB7$B~lkQvk6=QoealsCUA+(UAvzbET6T^A)~BlUxE;1;am4d7V5 zS9XmAv$E)d?@ZqJL)KeA+>up$M65c|05PZz%F}sJ#N$1M@sXsI*sS+!I=S#0fo*be zq~5Tbn$~63oBw{OU86=7%9qY16g$!3E$baYh$QyxSB&T2hz=6NL$vCjt!i&o67mbV)_Z*3EhQGU`ZQ0zII@dZ0#Nx-? z8^AtMlkzi%h70EW9#qwh_n9dOJc-XA5$o@X6c+jvls60&e7dHT(G)71MC)-l`v-g> z;;+2D!Ok3n5_g(FU^G2*TNg*#70OOa<*$L z_hMg|*>+6nDH@nT?;9{os+;kgGj>XbsgnsFqCqTLF6qjc83C2Efmfb@)+jzE)(4LR zkUQ-!Xze5kSl7^Uv}(xMh6Q<+3dcqqJ9$oaVZ(sltW4$+*zyevzJun4sb5ygjqf#h zN+Pm+#--2rm9`~kT2}BO#@s*HKa|#4H?7 z?jHbq9MC>}*PEccU5dTWO5({e!ZB-?rMB%`J?yHqVEJN8?nM%v4%OWPEhBJvrJiTY z(LEjdT|um~)XH-aDPTY2S|X9R^NaE5deA}8l;(6$ou zEP>>{p1=&r3qF0VXuN&reRlkIBfRUVIzS4RwKw0O&bU@(;eCtNSppyFD-SwZy)@r= z)hxV1w;C2K7L&DnHc?~X%=_xip+j;5<-5URNp&{cWuQf?lpPGNLTo^fHL1+ZMf(QP zCHs!-DDyhW8yNyP1@Xm%6Ed<|U-;WcrRneHv6zL0i6TCy(W5scX1M&fM_oI+gH#Mo zm)Eh?&%bLqAzUIa&Ux<7TDv^<_Rwk>DD5X%Wy7B#FnEx+d4Aph@f&Z`57P9cmSffPD=(iu@V9DtdqGfg};|aKeD$K@(E3Gf~wK%JGZH$h89u zJ4A@hl~+{H3@K5_8@fBgb21+EfMf}WM?Iwc0a6?bYI#CYX;o-QR);13*6N_CGwCn+ z<^2@``pf6R)Whbyx31w$u=$*|D!z57yTjiEXw>N$T3FM5%B2vYF(& z^`{JFJ`K)U&P-}#Vpv*9&(Aw;gZnhrLYd0Z7a(R9&HC7*2Uz~NH_#$p9t}MQJ=Tf- z_j;oG@7lN}Tz!Iq-#~=PtPiWcKg^BQmK%~Q2Wkaz){(aE9@gQ4WZitzr|TZ5f#Z0h zD*JXKWjA~YW!rLFBDZ3QvtkbuCHlKl8p%M{p`p|`%EjphH-_e0nSt-#p}$OTe7hOU z*Oe>AqQme|mVvJVKHua zKAH10*_TD$0LEWoLd*QVrfcL&87~)nT<^?3Yc5@Kf*wMFT6C!u8TEqSswjUi(EZ~j z-`(iR&ZM|f;)6`Xz)=oa&1hv@{Kj2vcmH@vmN{y&6t%uk4hx|p)S~H(P)_M(-R#bc z^sUm_qrl#t4W@qQQT#9;cge+e$wOYfrFpB>{2Y(D0-gzOc_wC>aNsGx${VWV+W0#~&9u?@Z zynHhY3xmtGhQzyIOBYCh^|$wCTmmjeo}xlmSn}<3<%kpIsK>_xJ80MM#MvwgrmIQd zCo2o>;3cn29D_QK$(c7&B?IbuPN5e7jFR|t^NN-^7 z$)g`$P8_z(=N6Vwx6GoAj>%b(d4swhYVylH_d8S%In`YDlMd?zN>F8X4kijW&bA&l z91k`?06X8T4i{N@>c71f_D!mGd8J<_Gzq)94#_Ivwu7|F?{8mJNN|^tY)55Yg0z>x zF7qtk_2jsIe-Sy-6CwkuDoPDfH@w~B%q=cl*l!~l#lB|Qs7m805!g#SUW!|X%O5lLjR(T;Xz-?uN2Ig=O^c#f{N5Po`o0o2t?>Mo zRC2uMAA;Vy`vD~jA16Ms>=6mWCWd#^W+~&azVKQ{ByrSXYQ>mOnk@3Z{?? zC5KFS>ibT>qOOt-v4Jaxq zTS(bK@o%|0?67bZ2uT4FI8cN4@w{ z|LU}X9JKN>0%Yh?e_t}1kDN`xVQh_@3qdW88T|cFC^Ssx<*d#d{~}x4&l#4cXtD<( zJwF$N0ZYGV?OSLjc2r!?qUQBS7Ji)@S!^b++II{Pmi^Tv?`=r;aY$Y?>Z|AZHaz{b z>2)g{AoQr`h7E}CND#_sdA;IFCy8Jr!(DKjk^rbgq-$GroCU3dwoy2{jXZKa4B!>bWd!056$k)xbJk~At zSX+rqyzLj;Dt+X(jHENnjrtwpW!kS9D^bJ77Ei}PEUV-)>c76%w53kYK- zbJO#rs(EWJeIwvln}RDKUE-%GE@j0?(J=fHq;}7sqc8vJ*4HPLyP~7}Vp908GUJMp zKy8kqbdtLox;?JI*_ z%EfM$2m1m7-&r=PPZ53MEv3ApS{+|$-DG=5L&sc^Tizv6iSW$yvmwsPnYdeD->fKk z25!6Gu1Kd*Gj2gG1az3;4y{%m?QbVMOW~?;<+`DnJ-tX#Sl?FG*u!n;^3@BX={Pt8 z$9U%5CHW*5(kq12*b097i#TM~9LXvG$t^>sO;ZcESoq+L9wLybqmZ^QsfwgV&60W`1mfnlBax`kj~gW z|9HGu<}>Mbqk(9BXbxN{T<<{+^h}EOBPF>(b@84zV4={=2a2Mri_0$U@1*v%<=WX- zd^CSV&VvKo@9)nEtZplfjTQ3B@E`yVDBhP~aZELZY!~ClWxWcW_8l7sgpTi6UNiOu zP(a7h@`;-j6tmykoAH!juD}=CLiX+1CnNB_L6!)1o^yh~uPK)!5h*DhFSQD=oGccu zna8gF>$`TcT`S&}G`Vf0hj{o>k#9$dkfhcUi||C!$8HnC=+6ey`kiVq8o&&TJ%Sjh z2j1tT;EG^naIeS73-Qud+EX5{r6Bx#_m;!MgY}wYG^K4 z>9o5vCVuUj`!jLKTzOX9>x01o57#!k;R1-fo?nVc^TDsv?;_-4T=xR<50%QB&$>{% z%s51U5&Th%{o+|GX~QT?jpm8sqgvLax#iee(}ruTie^7@?Q)E$?**H_+A>0SN5^iq^XC8RVGvH^1;1%tduc(8wFWAyGi~L*oG8%$`gvG`F?1D_Dhz z9)N&6#so>AuqWp!50I;?fPfH134{^?h#|-K0pNuJ|Mq&|kDp<87Tx#V3qMA0|9Kh8 z?^ovt>F7HiC>&`rm!Tqd~yPio2NCEgy6i zs(W3PsimyO)$uW|rvkzo)I2ZOmyJPuQOW>#98usWCzPbY(asrYpI{PFn@4Ec)%|!C;r^hPwE50YWVF`sae66 zk-8N+@;RLEe#_l&yS7fmQeM1K=IY09Pdy`lQ@vA*ajY$Qjq!`;{H39P4SR+JBi&AUrF1T*y{`$-egd^kqR-imSCJrh|r1!#@M+w)PxsRz|^-j z43vsZ5xOUFLahDOanWTS&xAG+lBjzcckTCW9S*W=)R&3h8)dd~ALaWHC!{_{=4iL9 zv~WD#^VQ*27W_mWgJMkhMc~*!zn9U0uhgF7N%X-CeSvAUJW-qa4 zoaxXYDgRdGmqN+HMMgjn6IMh))~)LOwG6KxZ4bYvJuXkxF_JF7kDiY47{Cj&1p;eQ zpI$+I;}8ywKkWi?Bbo#ZqWauHZM6+nwYTEcTCOC=UZ}!*gI;r91K=F7bN;hK0Y_U{ zd-(zUx#Y7na1QTqIh~B^JgeeK80VSiIL)K2)w~~qn~RSlwC7bNo!7U9YX!a4WHWtq zZ0Z?Os^RHGa>}+*%@IcCt}?#iIq=+yC?=>_rOzb_+i`1=+1aDeckkMm4Nl3o=i>SUhN;Vbfw2FE7kTKCfm# za|vPn1bJCMTZ#@*6&TF7dhS*CF<9wvb8BVCdu|4x-`{>j?V!KI9ixv=J$1F;=i0bd zK+Mk_>D(LUN>-5zI}B0$bHi04=rlKSFRukcf*me<$L|=Zm(`YR)A@Vr=ipY9um6pZ zMEZ$C>MyR9#b+;Y?d)a$5Ugyj-84k+>rFswSHeIY13Z7{Ul^U-y8r!$fb-IwVdi_z zhI0q0^T$M;+v*P`Yd0&mf7Niy&&t5D#SpLsg!`oCwWZmrhwKM_eq$dG@t=KHM;cz0 zdJGR@GHkiu`^i6JC!3E`qbb-}`z`XxK#}WM&}NiWb<@9dh-62|_48Z^y)Q=N&?LCaO9JgtBarM2Pv z81&vdC12Eyy8S~y1%eKa79Twyz^hrLg_tNWrt0)K;HLfY!2x9Nt9fRvo}WGy`V`XI z9jxbctX${qen$bUM+GI9YWke#v9plVRZ75c6k{*T86TUU2K;R_C26Tdz;!~R;~dzi z(Y4sp1UxI4QDg8!_Yx&iYHmy^T+=XCdTflC!7WO%G!nnkmMmY9faZu_!f?xuvku&>aSMnxX7S^KbQ8!tO z!%Ub3=ErudPBc3bHLE?v54F@AE+2^wvJesbvu$<1keTYk2lxh9@1o4nlw$SnOtg0f zNKk{R#e+U|O5F}&%Na*~gvW;oa(U7hsLGkp$NSNG&@EgPr|GI5`K4qO%xYyueJC(7 zXl?O7_Cn~fzf5zvwuH%wGGbFsNIW4IcV-#9&iG}SVF(RpHpRKf-vUyZ-RmJp&AG&8 z1>#d`w$IEkJ0R&%42*cexhH-d)*`D$EXRjqZF$fyhtSL9T3F044n^{Y$&Gj{$0Qurunv=YkV|kI(09ExThgw+yMDA{pTIP1)c-@J^#BX zjm(YF#)X0L&Xvp?9CJ--c-2|GLChVo9P<3Ym3xknBG(Nh98puAkSnw?RAnVrXJLxPuAS$FuSk;1QT%XP zjEMm+Mo3C4xeO0cp9?`iAb zr!Ed>ivC;vmm~zmcsy!gpw)g92cQa&IkAN@Vdac{F05|f@HBI2V4Ia=rzcEy(lxnz)C8VjA6Rfj^f#!Ww@Ju+40O04!b4yfZU(Q4U8ZNm9T- zoU`vw+`Dc2tVCJ=l3bTa$fWj6xboqdw5Rb~7t2kV5>QzztW~N`?)nw^2>rKr0inm46tUGta zQA{uHx6%GeUby9j1RlmSSkbS{*-_~BbsJpnP{iW}hzwuj$Tg?wHa zpblTvlD?jlMz@P}x!67^FP$`fa+}aa9-g847AkTXIO<<9WH+JHszoxw+#Juh5cnYA)Ydswfr`BoyQe(6cdBQ-`#NVnXws>Y8AHg4~?EbT%1;X=*Eh~X-Ke^cB{7E zOd6`KnnWffaiWqxNd2UjG}~_B%SStra7*qb##NDpg4pH_?h!0N$cE{;GUm{wQK{)s zLT(TAXVfikx4ib|#xL0LKLl#C7lD&<@7=$(xn5i1f`|eySG1N^RAkee1cX_EBi9vg zSJ%$rKNwn4BLJ4~z2elK(F1GDRF~bgf(pWeAc~?ZFg(ZecAE*Puz6t8}q))YxR-*{ky;!m#AhID^?{f zeildw-YCmPl0WK|L3l_I11F0hnT#IyINh3-{p*(TAtD-n>F*+C8(3ZcWWn+pNFb|u zx%KsjW%VgrY4x{}8L)GXy&xwCuMp9fWBHOZ>yq>fxJCNv`Ps7ek!Bd<7|>R3HeJ^u zFsau~VUXD;shcpDU!Yvo7Ql=3btDidL(=o-a$Ty)aoSdr`r{cfZ7ui#?QkG0@U#6J z{>>FZ@ZI!opk}iK%3C>!<=Sg;OKV=P_+99eqHa=iX(FZ{QAGvC$%)|+FN%1hB^&>^ z9Jx1xYpSNVr2)TLn^rQ4vdxHNq0XX6v#uv5P+O}<*e;?ke7SbvPoOiJGg5G%M|qM9 z^Y2(zmdpp(4n8LjqDVPWsgiM@r_&}kD3wUQn?yZHD7$D4bV|9Dd&o&o9(2PXCbF_G7dFJ?QdNEjlpXX@6 z1BYa9cTkDY){q}jG29#DcCv{3ETRmR9?Gr)+mtN$iWG1w8a>jx@clJ(%<6cjHB$*h!VrHl%8GokfgQX%{HprNBG47gI1!GIJ^vlNAiLkkMEp7SnG=UB zP(iLQh>%PNLj4ddDez(^t248 zDT_139S~W-FLv3nV`LrNO^QDGC{+F@B`sooWoc0f(%ScT08@C)1YK<%F>{oY16uHk z3@_eUn5m1U1}mA95)ct^-28uM@h`3|RM2~rb3W)xTTTf2_L1Ua?`c79x40V0VpD#m zRazS@Mvq&;w%up6N>ukESEHo9NsGtgqiC{sG?CAduUo@=}9$V_fZA zsbXVo)p%-ch=F)AVju^tA`=OjHr>~FxdD==_vDwB`a5~o6_>+4O{jo$qnzfs+!(#s z#ueH0_01n)%#E3o3;=1>Xz3kJr+0wonM+x%B4xHjjN^D3AVDV~85cfwJ|Lh1JY+Ks@Le1yKq2T&n* z?aY4Qb*WCE)t?QnJJVVnP<-GZmU$Lw>SO24BX{q3`_w;Gt&w zije(-88vH{hVDQ{!)hA3bKmoy9!H8miQF3bLhy*KL81L*?N{oA7&yNdG9ou7eXA20 zb{nDORWE&oux$QUA6J8+e_m>pU3IyD)S-=JDrm+ZA z>C+Qi!@=0?)wheoYiKUp{xD^TnvEpk`$W7@@g`h(N8RCsL2FuucSrj3pWrbLb@baK z$};H^34C|?m#+-0bk9g)yB*T9E2NGCSet`5pBpj>Qlr2(1E;Yj&|HjfqL(0d>352> zrfZTlv{!@^%$GfWPX*$1TB~0~Z`| zi+1CSuNLIb5?2qOX@El$zZb#DEH}O;T53Q&(9ek&4-_+yF-MK+s2HC{mXuKXub z`I?bebyg1)>5)@6l*jM$P&b+KI=s_dwgJpqp0gldU<@&nYIY+;z+!Q$#`I#bHuIqZ z4(BE*z2Jab65d9$h$>Yr==Jyo57ygf9W;~nK?UTsP#yLMjyxd^5a*Cly*Widf z;EhHo{V`+u9=Dt|`qVrYreVO-ea7%g9Es|T!dahD|Va!sMJSm!voVf!X2xob-@wj*ikFJ>k65kYxAJm1ER zjPV-aI6#|r|3=u*bW9VvB_hL@qjX+kxDcdJ)MPl-yz{YqptL;RH>q{I()W&E((oSz z(oX!+zpNHC@|YEMxqZa&xjBDgfa}%Z+*YVDhqXcaQ>27N;dr*|bK#X$yPV6$-P(dEu{KfstM1yNo_fLc+@ z>j|9BJryPO?UssiRI>bJVK;P@>^ajJ$0)7pZIi3avDdV9+b-gXeN^dP}C!~L;BiL0ZjySk9Di4ua1Cr61sYCn6bz3gU`R*WP$05Jn zviI(JV{@+rY#SKt%S#L0b{$h$!8N|Z(XT~@m791>u zt|{EI>cB$FjfaH243+dIPfrN8MEx zcEM)6u`iF!jzccI&8$wiTx{9!My|z&RT$4g$jle=D@`w2Z`|N@;ru1Z7{Bg$rq%80 zCrcZx7D(Rh?J$w~?S#7B%x8MGbq#`XeF#S?8GoAQfYw`VFyUO-V+F<7LrJX~GpB%* zOz$6L)2dXj6XFM$SGSWkhg1X86j{A>zb=-Kxru{r-cQUZilI%rpNbj`su8TE-dTAO z1sx#{pI?%hs4wF8X@k%upT}EhY0$cQk1(yZjr3eyQF$CI21E93)y$?@l~DQN$TLP3 z(Cf@OT=1sX+=-Ok2?x~%lcHkHt$m%~GeznMZZq}eYMqIGxtO{+cB_OT zxE>t?R{J&&LW&iHhxULz=j8eLB&SlOb1NsXd(Ws2A8mRKY#`r~f@?;Y9L8^gQUXA_ z*yR<3v#?#-&n~aH%}rXnNb)Dg#)B*)1;x{zD2NKTp@Xz7j2HCx&9ispV;|>`Z4>V! zX4{Y^?bTB7w@;I+rYhMW9=^<{KZ9^o^^;}w7aX8u7PZJnm{8C|Z_Xkyr z`rcvA((zQoA?#x)g5Siw+o5i&GSw}fs(jQc)TjT^yg)S&{b9HhMeS!~K;~&*?rW^o%?{+ zr`uO9;pWIpGZ>Z15eDq_HM z*#EIQuM^3*y0lcF-Ms}0#hhA57&w5VZ3^vP#j0js=xYy8{ymZeM2^cjyZ{2s6}Qj? z!3$Kg3p0D_a|h|dt%@d3IurK<_|_tS?>P2(u+9-@?a%iOZPwv5F6%4G;m5@;8P;!D zpd=Eicw{ee<}#C1=PH>q)$dnEON9{8sRcpOV^hrd;4A$(*qH)v&=M*Bc~1Ocku7`y zK5<-|%HaH7%M$eUR@*~n2bh<*t`!|FeZq)-M|G?)1JTo)D`Wo9;&_p4cmY+@cFDoZ znmO?hPg5^EOIOY#44gF?0G%t9!IaJZrd9@-0o5q$e_B;>h?~y zUa199*Ro3e9--p(@C0jXTZ#kX(cV4(n3`=1OQkO6RhcESwU>S1IK16WPF5F^-smZEE{bWG9UkiGXr`QbDx}lckvq`ilaC#j*~rEQO7;f&``sic}cd{ zfm9A328&lbE$6ZWuolA=)8y1>i}7r8Dg7X@$S{D9WA%z^gEvYbI=yAiBP+XccJkHB zo&J+?QV&G!B4rzxiS4L3@xG+hQU9u1f?340%-<;f_r(j_p!?Su=bke;ZqvAwoOZsu zH#^dsw&-ONek_4I7)wrR3Tk{#!->$7K zP)qZ<_YFZkYVe7S)2+`HDI;44ZTjawaXyBxYqly+7aWyT~{eWejc3zDosv=3RmBCYxy<0Zu=csQ62s&r}8 z`VNLZ7cOyM~M{u>=nU%;4w=r(y8Ic{MroYU!X~r#{H`*3&-)<#td_rFCxQL=!ic0ie9Omla<4N2w)ngx&nvB&VoiFQ;ck; zvqWJTYv9W`wua(kc?WuT-4!zz$*}ixo`I-c%MOc^+hHNy3-a2cXMs3#*Mbac!m72TUJdgPEaB; zxqy?#y-c*3+p25?lXTan(HE8Aoz5Ko2C7(F={~QeqK0M0b*U?X zyv697`bzn^E-A9XOmUf?a4O}`>&$y0m7+gGOui)1c=gO>dK-Zk?Cy+?f_ zy}5DXv65u!Gr{ZQ&@IK&Ghy41jk&P>Otw8PAhI(Q?!0&xcwk5PH37^DF~H@C$^Gmw zC$qURzUW)J={vTwDav0=NF_jWAQ??mSIo^~GLX|CX?IXd03#bdpW83TM#e<~QuCs6 z`(UXm`*j)&JyRg$^-EZKpwYPAUu;hWniy!_=n0Dvcx-;qr05mE@?{A-YbPNVss=SS z9n-OJf%ti$GUVZ2)w%)3^@t!aClIE3$JNtUdQF9q<#ObSEWxuFVOf^;O&E6xiiv~R zEoBqNcIk`ojZ#G@PzgO7i&T52*^ZsGTB4Q#uVley0V)*3~_+Vm24)L0-xw%<_;b=|UIoSu(F*#jASe z6mdp(yAUbFtFg9k{Lycg&NE8?W7TfQATmHIP*;_ivHa1W9X@r>pZG@|aAA)okm`?qXg(pC zisPQ+aM);jvI5)J%iy!6{J+^H(tcoefq=V29^*=(>xY&@4SF0J%0Xb@4nxzte4(r) zvk2TJcaP(I{WV4fcmT07^qzC3K3(aKOF9u$E=gx;7FHE5c~G4VTUfphiNKOt<{^94Pmm+iSMwivH zfgO>ZU_XMo$;WOBO%r~u&`KujzOYv2$?m9RJ8QmjADz@c+_8y5on4`F`}C??B_rHH zAk1@euA%-eMh*GI6`wO%It(Vw>=g@}?!G5LwBhUmJ+g4gnG2UBk3v9F*c-h=v^;c#UqlJzb~ZI9)BJ zTg*>NRllNO#e2wfauQFO60wG?NAGLmzNi;di~bm*<`W|F39CUgo4304Jl>%7QXFHu zSdhUvda)d_M6j8z$4{;%!+o_X2~4_BMqm#61!SrFWqC|P1P2|acRtrw6c%W(9MjB2 z#(nr`zVk=A%i!v6u(KDOs3loN+*TuG1n42Qs}D!elG|{4C(Mq+(i`5tZFQre$> zc;V{uCUWhNf8V`+(qcjTg<)z!K+}zE>cFLSP3n~OEox$Y>r(pc*GZ{u_>ssa(7%G^ zbKw1|;bpAgIluE|MQrDTcsjas`B>j`#j`DD)AH%Dl!~tT^~!+qvj*Ol%=XbFP6Yzn zhnH2gto&QLdjVajl z0Jg>eof_XsjkNVbPJI2BU@G)7$*WZ47!=_S^%#SiA2Q9%pcnZaZRG^YJ{kjn8%dwb zZkcAMXX);#V*3&g*c=hAlMU2ZEcGg#$-Pj&Ix;XhIAbPrrqSk?(L8E2F9hi*_a{oz zbW2T((W{2yDLRH_#Kr$8`Ls4aFUBUw$*ivEVagX);5J1b>j7CBrCIy-MSG)L4L33w zk1ekH$yJwU8}&KJM{V}LhKZv(aCQq{9yeSbaqe9Oc`?aHmS;br!OCai_z|UBe`y$f z|74cQsU?HyA;yZDgHFL4LkaqeUu&y^ml9V*o$Wm#(g%+^p*lQE(J(Fb53EatM|is@ zl=m!0nt&`i^ktDHm0&kq1e=Jk!Vi3CyAUD99XvWcj?N3)zD`VFEjyWbjVXrGpFKF| zNdgPb$PQ~~*0CIiAfNAEbA^oEEv;^vLvOSX5hLZLIH;g5Qy7SEb{V`Vt8()yxC-iG zSNdoJsbHW3S)qB&bg8g@gx_1ry;=zDRawXheexyY*x%Xd)S&v>qi`kRk1lSoaACr& z@T4G=6SkMR?9(BpjW6)en6993$YCj&%sI~C8o9baft&xqe1>=W{$C%DHnuM_>M(GSr(Q?z)ckNZ#+l!g~W@$v2Ku~R`ri~ zR1WMv`sejy`SZjf9n#6pwPPI`W=YT+jTZxsk|f`5%7&-`nzp4t!ds z8J=<4{t+@8gxJ1Cc>D<+htAa$)Hf`FE=gS7T*oDa4v8X7%q6Ncax-76 zhI|px;zlY~z%ua(&Do~q)xQtjinWX;H3#xT;th0_(09~a(gx(jV;crH1sljhzF8_T z-jykHlg+A`X(URxClB97NEFe#V6Gyx?!|bKN$Vz+Epn$k#$eY2qnvPNx%JGHxwFr&5l?9Ou zK0)A3z((s)4-WKOws^?g`3;5iMk@`z?PZk0@!q;$Sl-zEQO!#wqkb*E4A5jhGgZT)H_v8S!iQpscq8z*8)nrix_!P)H_u=i z1QOA-V&i8b^^>v^bs5<8JvCQ^z+bCnX~S{1>jU!4yHxvo8) zs04~OlJ@O@nnwCLQ}9yBn2^Tjd)-TGh8X1A%a=QMD30|{AA&Gqz5BvMvM=*3YHyW& zL=AO_6XSXOhJKyA2%(?e+wqSG#8(wAs=nRe*+>2$xJLfs<^hbXai`x71dQdsg1&Fw$bD?F z*i0M!@OyyEL)w~J>Yy;QCDVG9v+7M3UB$Z^?fd7_7Y98EiLMz zf=cP`o{HkQL-iXxf69!@j=Q~anhj{FKDMeOH1onNue>-=yKzeAE(Jh{lLWie^6(^c zzgdURe8G#A+rr#xxQ#~xQ$M}CI0;?7JfI>%5eZ>H|q2R)&}!t zCoyDN?oT=FHlaEy3rLx(o%?-PEw#3ZnY^#tmvn3!-Z}G|PL(W4+}|dXQIq6^%hFBM z{Xm2=`!@6v*V;&3Wo_?vNfDeJnwg*{83;5we@$vNSk`J6o;o^t(MTjy7ur=Tp-Z4| zd8On+XXY*VcUN=|6*E3oMnif+n!8F&Fn0Xze zJ~-vCjp0mP8n92k)H&oyT5V_ z=-fuztbLu5EpqYUqRJqf(3Om2SrWdJDJz+;(Qe+jU6jSE3rG1p#LT`{FDSK*JX+0^ zu`VmI;-ZShH0x}`1O0hoo0nW1;yg2R<6@Kgi?-gpt&iyV;E)=;x;pC#j_{m{S?H1I zV6=bOK#h*$UA=2slW2Y*`6n9kmxg`)bHVHXA3@HzP&qn!{HE(4f+vdf5GTFTCzQG|a;XJLw4YvAAH@A$D^0C=@o{SGZ2SC|jz6dqP@H+tX z2n!=snscAJd{j=i@089b>Dmbm{0?*G1aL5@A&;4n7Pr!YXlWlH)Rz>Q1Y z?X&U_j+#FuRfT761*Gkpm!)vDm^!2YCxP!<`!fFA{N=3-xYV(JpsVgsbeQ580iDs0 zK2Cc~#)i-sLBNS|)!FDrhk8q5v@UG1^-Rua(OvA*S@TQG;0MB%rXxxOQNf9$_(WYN zC_Y^cl70_Um85>kSrc>K_gc`1@mvfsD;p59Ub6x|Kou5*R=?z;4otAwyb@IQ!P=5e zOCRFK2)C72d@6K@%^X8|N1lR-)DKAn%&oc`S$-9i@6#Pq4|!l% zyD0M-rzT~7YiZ7N{V&GeI;`oo{~HHMl~O>7f#5(wx?2%x2S_tQkQ}3Hq!*!-Fktiu z=@=nh0|bH5-7&gjl%#PzyYBn@+}|gT=XdSLr2Y!F(jN4Rp zaN(yu3brPJ4n%%!e2d&m(FbMm*t-Yvk*W^3^@{;Z>x+JN!)JKr2s;w_sd!6b0 zVoA1zy9G)wNfDr{NoC6h8C?W9s9BoX?G;WZ;|9r6?4=&r;1FtOl`=49S(8VXyYdmd z{RM4Pl^?(x!Q*q4pUnV=m~ptOY*+m|8!vqYSH_`)!rnMmUO&2a#&#uQf#s3Cjw3MQ z*^+%>d;jxvN^W49j}%?Y$Hkia0(n^#o>>4chE5XABpJsI)=YGo8A49m3H44eaX8R#h=#8mc9sR770lEqLf zraL~cr6pEhEo9c);gqXK=Z5dSrI`aF`}`nBy^d`>Q|tS8{UYj4){=IMbywV@{bgXo zV(~a?cD-Ex84ZokNqX%*kyJNp?Nl#u;3<1=SoE1B(>#xjAnR_7<(H=>@^G9uGL&J1 zF*h>=`>}?3@<{v-mV+*h!4QPg&D-b?z^T-Mg7Oq^LR?25ZaQebmrq0SzH?NM&!3Zb}vC;s-cag zUxT_D!wrI2kN+mX9RGFs*RP(2hv9>_nmSNyzVkaBh=k$LaF#h|ZedzCbpP3d4wcIT z3rR4JN($pX#J0P8Raf?B3}nm)VX@dCI6!b`rjYie^%3G zG; zCXSAjK#lG4T#=K_GmF^euNHpdo0G8W|4e42!j%`Cv)cHWUPDCl{^Ox1DHD%E9tp>; z`<{+c5cTCu#2=j-n0sT(w3Vz1YHCai#FE{I%*BR>a^qaIb|KsHBRcB;;#}w+{{->l zCdF&2FZe>uu^Za5xqp$7QOFlO==Pyw;J53RfSJmop7STyi=wfb{1{l%O~3#B%Jli{ z)XC(jX`c|!;K_&9kxO=7N^EdG0j%85c)Q5|no#+X*;{%JHN)>zA!TR~EAEJ2K&E#y zq>Bq6`sEen{W_L!`-AwTmzZ(>8pB5sRZBKra6aj-Fan1|`2sh^HZk!agIQ%`TyjrQ zWeryQtu)k4a)sIKkZOb@rxh>s!mo~oxcXS0Tmi3{L39~cSyt}0jB(h|8;;-|8#sWP zFmY2c9V|eHNAUPZR%Go9P*F8qKtJh9MiTrz{y&RC)*R~CCbW>+lmB(rm?!VRrnJZ= zNX?kr_&ex#}zhBWKoSEI~&43OzZ?da0wJ_v3pR2PXSOnZE{ycLil;0ldQA{HjQM_vDi}s zQ;uuwh$O5Zd!;J1)74CJgWngVlI0itL1ATdGFs=Sb|#Ksxz-?nsI==FU!B1%(vkP>NgfKe{$b?fSO5#UGCfi>oEZ`3F2O zgZkS;zz4!h!K<(=xYVk&`$mUExwccah{}%l5fvlDs*dNs27blax9s@f=GPt?#uG;v zism^$L{iS=qUxe;mwFe&hY<9nx{g|?=I42UOYaM}cL)(F8@Ay~#lO(|S%j`rkDDN? zsB#fGRigV~2G-SO;>14tFOC$=|Jn2Z{~qA$0;Rv!RZQA{tzHlmo4%Ns!91Z8=#MSu zXhNeSi6%nF$KRPloTUq0QpzsYkyzQX)~5=s@vO5dGbd8LcSf^_5yeQ}Xy1J{Uj&aa zYcG`+1TTJk|DWCR|9)`qId%qX)1c{zHdInpeI(Og=)<%WKc2Y7L5;V>Peka?*Q>PV zr}UcBd-L-XS$U0b*0r|b*jShDOg$vC$#^vZa~3Rirdi&T_Yo8NzAvJdSZ-q}WeHc< zyrprn`G+62q06!@@s+9t zMQs{qAOisdRBe^kE^8Pef~&MN)@(FwyI8gjgpW_{U~40AiE5808#BwVXX-Lc?Z3_C zx;r(JgTZbp`V&XWM!r?ED%SMlQml+76G!v5t(`!unxa75QgdsjT=bDx+v{`o-#i_# zGTGD`B&y=aj(45tAhw0RM%yc8R!JZ+@sCDXuYe*bx``_=mh;D%DqOMC{KM11w;n~d z(9Nu#+;%py)GW^d$ym?uQ>fRcY`U?-Gd;~l9#=!(PQi+(e1yZ|k@)(wu?&iL&J66a zO8vg2v_8;dvL5~2_}WiDzEV&G#OCB0Tipc6JUz35uvF_{X2N371dktd7sWRBE7Q)m zY>S=XK+Jj#lWNT9DIuy8qPQ0iXsCVx}E zenN?1-#_Qdrbe*`^p12V)vBTC4a=;2Sh^+P5%^tQkC=Y4Ahshg?S+$(izKVXVftCC zQ0i*yC6#8;lKxrqdDccaI+&1*scC_C_ZG7?yxdjW*-WmymQWu9aVH#JU(smqld6i4 z{TzHdEhe+r4#ON=pUDrzs2Xc6jdi}Axp2+Aqat;_o!7IFZ6|`1%9oC5q+}^&Hy1p3 zYIh0)_V=~;F!p&q4YX-q&AL2e^#bvBA>a4X&b^|_lG)z26R%lA$YR_&6kf)c6&e}H zSs^5S?Pc434@`MjdTO0eZp`H==%>`A|HLg3!2=SEkNPG)C%%axbsiE!*V!`lSa8Mk z+*(rg-jPLczE#v&h{VkMr zuwmm$G$!-%vM{QVnv7PoA|XeeQMT!DAbJ`(KN5O-#Yol!pk{-`(eKq>zDQh&{r#y3 zk=KxyB%c&sy0w%`mLgZyQ?fQy8NTRKvc#eZ$zsP^+m5KK-#6mr7YEK^rVZB(Pvze^ zR?Aktg`il*?4c+Cbqnlg@>y1L(u_Zok4xtpjO0HfMDw6)xFU|of{@Y;fIso>!5_a| z@4ruBl}{yizKDmkVIt4e#*`L3dqeOWPTA?l55>yTTgtA|J&bq5YcV1oUteB1IT!t(5^t`n4J&;een0bgXI3nXUW zm~a|fn-P-4u=0SAUaHo4(ayIHEybsduF3Xo(Aop%`fBy|!H=Um>rE8T#ybA@TSRpn>Ii zX8S^8Aidy<&zT3`tVUwyedmqK>m8~e3-cPK6#Of6$MGAHj?;FTU@mjZR6j zPkin8pw0DzDybk@f# zKM&d;SX|B#w#jNU-so0fhaV>bzB?>r&7iE=-9tWR+lry}^yl_0ejlAP-~fpQ3(=;k zdb(r%OqZ>`!RJ!jweDpidYzOIr1^q6`~DfxvYZi5*<+NEsB`+%k;n^FA`!;k6;rrm z;#1M6qe}mVwyg&P?Cecj`{Z^u@`15iSGJ5*Xuo4nZM%)xFUvJ~l$3vL#?_u(7GAoJ z?>pcn4hyP;xa@AfdfGnA40^6jRo)02-ZZ4w*OU@^kxIC&<1Lk4^{9F=KZK~BeaR{NLw%z+yR zOe4${S85O=jT03Ql`B^HNFIyrno~lG2^pJE_9|hGnnqM(FKL7WzjUr zx@=v|-pp?Y0$kmq4L4&CseJXl-xXwhSfRsb>!4Jw;_;A2tB9nV!-!EtRNesz61%9XWpk&_c`PUbJ2Cd@;gjV+oCz;N2^i z=zG#e4$SxGICE72Z>QSSW5fFJEa(jRlBR#(wOfZg z${`6UOraIuL@`RGd=kIbrPY#B|Nu2IcL~_$y_*%xp4jN%@pW`FQ?O@b@zUW*DG}3 z0dC!;GOL2Zz_p@RgG4_n8T@2Q4b zL-XfkMh=<6jEw_Taeqitk)(s>P>_BE8P;tbPxll*28TV*n68D%36HWGIDtwRIY!ct zgY-YjN?{p<7ygOW$vcRc5ZJASEuSJSadRPbtlhZoIlCT&_V? zg}~4%Su;iWVzd}L@>4}`YwL&1DYG0fB+cVUJ2iFepht=RjgVRPb(K=vvTQ&~^+tbY z^V8-=<81N=>f7KOpW1Wamr6H`oWtgN`FiO&+hQii1}gbos#eqOK>@*sWG>>}Vl%Ky zJw;PD)9_`LY%k>KULd+Kz2`yU3u7t1A2YYr-YtS{xinN*v*rPC~-X-$@;<3?YZ zRu2N-D+1>?SBpP+`}eQ)?(65S?)bbCB4pV=5^GhQT0Y0wNBsGNO$)3SV_d43X$HDp7yj`8Jbqn~|W<@k{L6CL{`oOr(PP8Gj; z-PgDjiB}w!f+StRhb(&mwCFqtuemJ6D}gevV&Czhb?<43+ z?Eivw6zTp8>##-#MAbS4=n8kS>AK$Ho5jvQGG*kxye%q+x#d5ZWkaa_KgebFRP|dO ziCK>aKT(mTOM$=jO#k%ZAylC;GRyDOCI9_P>=n!D<$GFl`7VUhLalLfNAABki3k2q zI#`je#rEaQ!B5ajR;8gTv7a4l}j~gyHOy4=+{SSQo zwT|BMykE+^?%X29>Pt?ia)=ZV!(6!$a|&o;n`?PLtX^DqL4pYTtFt7>NjNpLDOmao z&vxkMznD1koocYvpsBOV8b$d5Pr zZrpU9vc+@%^Rk|9mw%o&(nNvpNap6Fg59pFFr02L2B^q6nf^5iQqijQSq0VrgkuHV zafHO+-9ixOvEyuox~K|!F+yoE>RDpM5NoLZzu*eCG5O~gBe|2)kIFcs5BS^az0NfC zcirXzl3`$?=ElTknlKLss8d4_vwed$a4Q=Lf2MJT(EQRO8TC(Vq?!=+ZLK_esW(WV z0KK>(?=9rOkQA=Qr|%`cuEQnEX=csACeQXz6zB( z+%Y(KKC|SM@>{j!IrI(vFVh)xzyF=l^JOpD)jr`|*`oEV9)Kq6*Izt@@ED>&c zebvYhJ?%(X5dHW7?J^rwxx3&feNbN^my~=Q2y$*uuaf?h!y15IQoO=ON*JktTNZvN zj?b9!?(^<*mS(n?YzhXndPpU9pDEVr;IWo}FP)YA7LY?Jd{9pt zk>BC$j@e8cCI$a%-{saNRa}XU#fe#w^}ZcPXK|2?GAJ&OF^$ax6EG0?;N6t}UZDy{ zEw#{FBkhc(mVscM7N3syxdjj8(H*PD(gl~+VQ3u-8Q_w@V|hlu^5$6s!zr0<#gsfF zwT+8sK23=W_>|>;t&YpJug~T$;kGk~sAO+%ddi}Znw>J}XS1UnYvLHO6JlEuQaspY zQYXve)yT^LftGMWIlKtJ^ALsbvprOkqf*hfI#R3|`=9U3f4;jRq_+O;_pI+?C!;1Q z#K=aQw0v*nZLR5kh1m?AMSPWOnT71f|7{(uvqv_&EkS%F)7t~J}*c9ji3`p+wu-c zNB9%(YzI!=J9ww95P!p;hTDkicGqrhpj~G^bf?wTnlOP%LHD90x!Q&P($T2l9;ylG zx6Y(R-|{rP{ld8r!PP@i@9YMoi3wTK7%5K1>JIy*VXh`8X$~ndgB?4K&t=R}yU(-4 zWzE6YxdGK#ll`C|gSnpuR^@`uBZ{nlX?A=!)+i5Ze=HQW_^s<(bhV&2e5c^3=<%pF zFjs0Lor-z{Sv2EN@uU1N{rM2iIS4+K^o+YLd1x}EH)yJ}t8Rn4Eh}MfNh(OOoOt82 zL6lbks;D%#L|(Z)7iZ5^ok^XbQS;Ty;ODqlzowiG6&qYxS>JyR)S?bOUs9zv@%BG> z^JKk;D>c-?TYovbSo8w&ipAMI_AhNW08>OKhYt!0)ax zsbRqqsKt>l%Q_eV*h$Cg=u%3n^uzK)7Q3IYw36!CML7$U6UwW#n@UW&2~8oosOS=`6~*FAwRDGwjfZ^HS)KR zjU=iq`tDvLl!Z)wE2$*W|`UTSHh@L5~s?jab&Y){A=% ziM@B$T?0Lx`AoZmGX0Pi6Cq9;g8=jYIMLJubzGd8I8Vsy_3=#uCeWgBQcrh-JTJ85xjxW z>suAtPkp^>Mg+#|Dy+^p$t1Ym>=ONQTXDy3=@@_2e?6tdmR7xLSx4<7o8%~?R6zTv zK{AGl7=91V7Qb_6i6&?q5brat40urMUL3-)F%tRnyhAruAkGmE z`=v_~M=2G6@gL?9xey)8R3@;W;M#d-JFXTM2q&=l3YyhE3po99GW(|p{>3}Dx~l2A ziDBT(Q4WjEG8426xNj!?@sR&yQn#N6bz+j2-qFbQrMtGNrLw4DjVKMX?tt;QI^l{= zsm$^=FbIgV*ENa%P_j}1LYn5H$`kL%^bW!q*|^)1W__PO-)l+#@@#h_<%C^-%7mM( zX{^ttUQ=9g1hDLP_MA`ixp@67)7-+sfmfB3n9acGV};lCvX#T367JSaqDwU1)9O=_ zKT`WIbIqewr|v~&uiPnNWLTg6>@!nW*ITm3ta~fXQ{;4d!jB*NDjGFl0VSK~R$}>; zG%l$Uk|#TzAl^{a_DofC-8A*G6tvOT29NO7x2#b1O`|LFP@Y@vvN(H!<&MfkfAhjd zeVk?IVs}Wgm$NEAr4ygLxm-x=$@uUC`;1wQS%$o5|DeeT`CkM^HL&vNo}%|&&ZT8# zL2u=RTVaYu1HLv1lfq$?4tGnOCmckdXWlHW`i5U|y^+`}3D>G9O7)(DJ>eZeF78EJ zZifnemvizY0WtIBM?0SbZSYaQ2N--~y}C0@Nn1IQ!s;WO!xMa%H8sn7U$3RXpy62* z6@#?R?ZfVcai0k{2JBl^xf5K>g*(M@Af#|%kp+3h%)({(goc$H*sJhK%=u-PhfP?Q z!!IUDSxUiG4Wx-d9>KPh2ux+8?_;$}m*~^eeRH0^ZBoOgog>k#L!5PtC1Qsj+j)WG ztVj%57omZv35hWGa2NaDW?;6Z<7B8>BuG1kf_*(+p<#_`4h(pg^Ce$;6Trrn%$?xm zwcd2C-$$!Q3c_iY4E@R;2UIXMp1R4RNz7g8Cn(vI5(B+X{(IQ~NO4hgL2tYxHT!7j zMkekk+&tNxsmbwnet*-;KF;vvcTC;#W!XvTyL2WdZOc&-aZryrG3;*5LQ7DuH9!BA zlu=Pe+}G$5wE-8D557ox2D227Pm>eYOe9~-dJ#6ZfV8mi?-$W_C9QzIIfiIgt(@^U zUd#OzP51D>WgILE4kM$-e|4-}(oui=?0A8|D> zX12xHY9-K>XebnGL}}n~QmZL!-N8@c;vq|iHhGUke7c~&^LVj1s`<**vO^u~oSksGwH?9Q|UV;3! zOUn0gLhy=Y!AQa`fF7ifw$g~3^T6btxFs1?Yz2URzNAEQ@Bo{(#}g(induRUi{1oD z9F4#sD{XBT3Tgrk89nqmo`FnYD~45D7tw8SWLfl@Gt!fYcik(i;vSW^Q*h+M^=-$- zMO&Kgp54;3qL_qdzhae`lGKlD6HiZ!x< z|7ARJN!#jY_27)b+Uq#EOJM)X7iN#(tdxA*4jv5T^GuHlR|8zror$P!rP;aNn^xNh zo2A$xYO?{0i;H>FZ6%9s8()PrGA~Q>1WJCy6&B^^L=yt7VuPs^1ZfH;gRrL!*^1%v z#o_LoTHoO{$do*HiXS!de z%k!nF`9hRqORnw-@A9nF4yxl+A8W2UU(h7OrDEew#UMwYG-dq|U%pYk9FDS^B5IwX z?SD7ScPnB_GO{y$Ek7`?yU`Z%Z0C*~3MY!{TMJDeriM%PrspbyE5m$HsxCWya)a|d zmloMCYRa5l)a*m_g9c8wEQ0u9%sui&h2?m4MR`_t{oK)!N&I4SYP27ze=~S_2o5Ps z9-X~s?-6yQ@VZJ*+da+~*D3d@wF_KZXo4!JC@*z>t?%ujSLa&}m7-lP51(~#a9p7Y zDDC6$07e=W>@VhNI_tOx@L=1PN$)`(wd^dtPwiY(*SGkaz{9P4!qogy{)K`0v*#{U zPt2#qPS5FWHHI82>ZYp0l~@U+*FAe=nLSGKy*@RiVF=gB932)zimXMMSyDIH==nbL zdnwZ!hY3RcJEZ&!y($%RM*5aH0g|7qyN1fgvDhh{-e;#vR4~HCVQ8)VKnt%x?s0lT zeJn&k3UFs85&HVpZq`(bMV0*{`m>GI=$f9XK|JJVou`b9q&kr4PZ9b(g%7YUFxQ`ZA{|_RE?GLP(13m_y9AqBohWw<(@wf!gtbUW}(S z=Yv_`OBXW7dk)r}?!a(ApcZz$gLLmZrwC0=XXI{&daVT;{!a>(lN*C3*SzDZ!Z1ge+eU^x8-*FR!~op=-d@x zgG~GD?B*V&^w@q4e9>{ni0L-6v^0nAD-yyIUY!H#PI?@qJ|V-sm9`hlW8j|uIi#Y* zFE;%cODV9VkX@uz^w~S)I8}UKvB-a{{*JxDnOUVD8tvrmouubIo{-H!H75H~nx#(y zEl@oJ*|Ferww)Q*&;Jr;>9_!VmuRZ;exWR znd}QCC13T0uZQuCF)Ox1iIhz=a}G+Krj=JtK2BGY*5?D+v-i4yfIAf5^o*9A8z5!; zhJLQ}Z}{;&lXl%Zp)Wb`>NpC#(nH&{vDBfSV6q;3=ahc6Z*Eb2wyL#xj-QAK?m^?6 zC2s!Cqh@ku=|}|3TevKkk1*`p?Qka&aHV1++8nq~H7@bFxK8tF_!`Hw5mU@PXwY-m zPEuk>R~2m+*B3h-6O)q5MsqF4-8vFfI1nQRtxQiJJ`0Z#yP@V_xOjxka+p%6I=Zhh zy|<9fm>zdvOt`r&j97WD8SkRO)Z(}=1?5IPEh$P5In`tiLtbXTelWx~bNkiB|GxIj z^q9Jyxv8o8^R*NveFQ4YDAi{Ga8dK!E7*Xh=tZOxX$$L1B=r1L_K_h zFPoc)0S^_tX#EHYNg~Yl7g=Mf+mC}#`<7Hov9Zh(8t47xu8^Au(cm!pMn`A-^+IaS z=dUvAoR^;aWBu6dRIFT1sSyalj=FR6T{%}c@&o;f8V@R{Ir+r3DMD*j^q;|1-ByW$ zk2lp6UNZxY_MrlawKB&a%EaoN1FTmbNN+ZsF*tBllNL?0aMV@M2{?x?ntOk#o`C1E z?@7a!Z*^P(lr<0d#k>(!svIXGs$#5^0uCI3yTbCG_417Q0u~JxI9d^O*~5zmdh$D7 zJ7jDwm#k9^?U9Q?k7^fK9wBSyx!`cSfj!=R8%kda>r5fcraPPGKcPT=#7eDVR4FlJ zhoMC0RXJERXi+>)%?xXko0t95-xXb0C-__cAp;yPE17;Vl7-jiaoA05*+xUQc6j7vYZO$4i2S0x- zBkHFeGo}K*8A4O+;G_PuIHSd_7mgo=h*kTqsJ(_g>hmT?|a=TWk|8EgOPI ze%K9(mqRz5<&;dCv-$kxUf+;+WFn6&aYJN-{Wv$4XH_Q1&sXsw`ZB7J7A`~VZ^-0T z#LV=COH$R_p$;Ztgk~DSwrqfoO=?+T%b-*Cj(2%998P+y&R5w%boPZyB+T5jA-PoC zdgWQjxUP|@@!62Gb~?6zV7;BZo#7?vz}|NtZc60CpmWc`0TF6{ibB$FGp2eq^Qgl5dG0cA z<$d7|orMjNw7&@g0~9H5MiWR0gBC06s`}=?1_+@VCz^s;$+{l6ImK0H4PH(B;PrcT+HET{260){pVgB4M z$!Fd;S1W#Np$SzhIU19d`m(JsgSU_)_q?LU{&%A6g{ZtzT4f&3Fb@$j0<}>9e3RLm zkOZx3QPJYlujhxJV)AD)jL>AW{?c-nz|Dc<6j+V_G;QM$i^cD2_=+1^JC3e7kGzdz zYsEjzarg5OGC~dPis)GId%g$E8W*3Z5Mb=!7OF66lqV@JE8{=YpEWd`(73h@&rY6y zC>C$p`g?rHlZ;&2X%uSs+uZS+#X%{s27IJtd0_v=w@FG0fg>R5u%tLYQVe%gNTAob zNSvz!*(x_z$|g^1dolt8PMF-Nllue~#rFuUryAAxAEN`x>l0f=7-g1g$ePX|K7JviQFHi`hY8+!93t;_^P#<5i9_3*@^bW)n=l#_Q`(p`R5w&N;%m z38dM&TMU;L6>DUW=4Z1@yt%~=EKM-uAck0y#r&+21)mo-))CXZX}67;o(BN4l{T!R zd0lLQ@ec#O?{>rPO*I0I9T3tVvG(8M&tku{C6H66$2Q?#$~+sx=6l9lWg7{5<)p32B{j%r$A`1~E;q`&@uyT1ilBfEn1ZP0 zy7djEn_{atrg5@GCOxio=D}Mb1#0#C{{1^Ink_f>q*(QtCSN))2btIT^GlK<>FT_- z67r0u9&2D{q&vHq7B|DL47P(tp$yjjG!!u@VubSx!v;_k-m5fkkB* zUqv4N-mZ^z=)jJsZ)7WzI@d3z*BP#iD**XCcM|L-Z@~Ekq z3sp+S%Q;Lgf-7ySB5<9FJ5xG@{kIT&Y$#;m6$NQmLzbrNf*4rVVsAj^u3d=@WlF-x zZMq*be0_(kZquFETHy^FwvqRi*_Qc0Ks@P(*LY03$tH!hYEm}&Q>{5~!^~+@&w3+~ zEkFvsHCa*IaO1NiGkf4i3Y$0vI8pRn#v+N_JaO@x6ixcI>FKZ5*-Qf_;IWw)gxPk; zc}~lLy!rbH!@mjcx6Y6chU`N&Tz*Z`NQDczD|}F@`^fY+feqTuXH0w;1iw!m^0pU$ ztljqddB!qZ-7Z8xn1vf!y-Z^E!^<(fvohYuFgYf^HSs9Lx5_uZRh^j{35)?m;NWD* zq|MVZ=gu^*ZwD=g){63DQd!&I-A$_cur65_w%Mte;-q9T<4p8sYN@QkDJMInWKvG$ z417ge-yN)Cii^0TK~byw&Y8($l7Hsv9VI>B!@fGT=p4beIu4)%4ZyW6m|KeOVl%Wk z?`Nc;1U$%B*siczKg|da`$yAB`4t;M@5MA&o}VOt2RzMy56JY6KPB%pq2e|(Z{iX=a|U7Yf}g(qRNTFT)n?Zf56 z*h@?D@;Y<0ko0Ko1T#>FPuksbd(uiS(*1wvADM~^O_dsC!R|Q6oEIO+wiIo59bf!r zF*jd<`Tk9y^pJA(UsOcsVkw_ttg1uGWI%3oL$sOe>tE-9NMIze6_B$x0e;_AaP*-8 z^3zLStZ)klRd>g;P&*IJe5q_n*8aaGr(__0etvG>!lH13tH-S>9oQXKn~ikErGFD3 zVH=T9O?(eXKljrsm9(}5=SH1llpOD-{v*(RIaIlLAOlsW?70UZXR1Ck76zHU?8F48TMj7sB;k zPpmS|t<8O^9)Jdk)x2KNNTcw(ExT%p6KMgJ6&5yp-(44GgxyHzv-wS`Oh3gcadc)J zi9GQjj^N~wI4G}C!#qwuO-zZ9B^t^SJNRtMP3Ue5(qtO(vp&O1`IWq;#ow@>Ou0%{ z4?C#o<7 zKp{#T57P?yV0T59cnaqR0^AwAs76F8BlPm?#CwJM2)5mjpe7T1T4D5#nZtT~%E>YS z|Igbk&4;$0N_XR;L$>X7dy>Z)Jb6|`hm}67z$mPJZ$i~f4H=)iPGFyKRXD>JFo0CV z-L39ldy{xItAN*LKqQmGyo^?{Rb>HE1!Jn^A#%T&3nY_|E(`pGzMwk^=@Xvs(@HE| z=F?aGpu}uG#*qn zGkLv7u$KE&1oY;}f6_?|l)$6g$z z6NI=I{*F8AesDzZLCDcs*N!1q&98N$t}63Z;Z0U=ufghx1UhF5;;;>=WYxQaS**+e z7d)`MSrq;P#cr!v3fuH@4t)!Rk;0Y;nVWFyg;3@~WmzT&lYeJIm)ALn8KYKlhfZlss z_AO;@df>R7r>+(9PDkTnlPpFgI={`R?5?a|CUlKO8AwDHMYj}=@(agfJEU(6q5=g@ z<-eGXQTg$!m=!rBbO`5rU9oCBx7e37=<)Uv^QzX`k(CPQ>tEh%lRW&33;m?3|L9G2 z(F*Z&-B7s4Qd?Lgopq^Teu-3Ldt+%tOp@_-X|Mu*QVZ+)wyr{7TNXkxK*jUKiK;4{s^ zi>ATP?uG{}57nvH)vJ7quDP+1ZUN$}9 ze3mnzH^7c4&3h%<;#ZU_;?+<5Fm!hM4z(p7qq1_Af=~*73F;JcK9P8Ng6U-jVm$lr z6_qtELwS%3ej9~uKALl|8ri0@i7ZVopZx)ii00{Gub)jm=Dq8hcQs6)1yrPO86mwf zLidnR#{r(!C;VT_J~m22&%1AE)oau^OOq!T%QApeWJYtcBX|WkNY4R9zwQ%iN1gm0gY@2#)s z6=R|8d15?Q__^YUil3MyS;q*X8RVNho(O<%Z)d9xeFYW$=*59OY6kDyBbuj$9*1YG z5|Tg}ZS9{o-pPpz(*C*yKL_A`_D54PtOr@ z`}xIMYg3c5FV04{cGPT|Jw{ZCRg?>vl{taP?N^SHBe-)F?Lxb&iqZQOquP42;n8Uw z4%KITzz>8*8@w|H(?!lnV3PYl~Ffq-yRX3m)7h0x|F6! zo9MZO#-fXT4CR^{2SY0-L9qJ23Czr0>ibPzykkUYRa|4VDax_+^ZXLbf0P^kCLoJD zeHHq@XheUiF^(CHuIhf^B`*mzgNSDFL*#$x{9#k{e5p8Ya%*zVc0OBB`ImC{VqwR6 z>Qc;?38v6JBefgLkwaWUt7(dLw8H|D!69-vg)G%W!7J==42)E<{16yo{%p!~%os=S zJ`riLhg51*l%rLd#s7ULd@<*u6jX(jv5%*4AuHj4p$w=(CbZ^^yr|AJ z>v`D8o(%)T*)xRET&29}Ag^V(bOf4tDcb9+Ub|+NprOZ{`J9SJ7MH$HZLj^5xjI1g z0EuI}Ni53JnmeMK2H7C`=9fn+$?i^gE65D0(-o<_UTQtXf|$M4U-kAe(lduKEm(~Dn}9UANLFcCb79tviy)g*%sIYcUW@7{WCMcnU=l&f zq=2I>_x~oi8^liaX;XN_kKmSWqN%ovS0ElA+f___TtyK5?FziBTEX(DI#JJR-Q9QP? zQ>oPG)auo2--&6AA9%LJn@(#ooshNB)mK_`&lgArb8B8&%4^pZ$(Z%UHeV<*68`RL zHn|@l_)2X-e#{+g)jdon^zeQZK|GlV5-|6tB}q=W@`!K%>R8aMuOP#PN4+(rR^2rh zXb0v&Jmm%SRLgefHB4(^pVHUR0cZ-gp$X{+>+o)g!Wf1F@Fa6404JLt9$4a|KczRg z_Mdc%^9Jjtg|0$ml#H=$pv0|F=w)xvnIJ+3yEl%sr{5$FWt^#Ry0sKwhgr%k-n~mxE zE>W=im9m((v?hs}lT+gOtDWp1<7K_qmHa_Y8Q*zDj-Nst;j4>Nd@IF`P44|Hdj$*0 z$3ZruBE9@#u|&Sots}CJYok95PWJv~CperNXze?t@#j!TkUwF20eR#Sii&CRwaF-3 zC$y&*<9BPB1(NdYQ1(KFkP=5uhG(nR;bw59d(RKO+5%cql%F$cPg5NO@K?wINo##> z^(c@@R`SkF`o7N~9o^VPGQDZO)L_%I+?KuDkNN&G4dHm#!PD>*0bSv4gd$JA6$Gle z8ue)&^YVMN4AVTogdl>XX?c15-c-zyT}h4EI@UX=Pd#ism1U))GWIYq`LOH(BP=We zO%!Zm6lhl|oxxYH)1sgak&EzmsDG;iIe-E4o9Yon2UhPWJRb21 z?0HS&rAeC?h0!j%;~Oke7+qLevsigYn2#SC(M;6y>u$woPQyr4$T2c{jm>iXsT;%f zWKotT+lQx+wZtx#!P>+mF2cEO)jN@;pDJi#w)8y+NE3%is^jjon6JBc5#3iflD!`W zr&9GOIV9>KaA#Z(Ef2;iAzDD~Y6Moj?~^_|%YBsIL>xA4^yO=HvEu`!?&TL22k2C} z5=C2I_v5k$O938IdC%)k3nUfSKvr>XKda-ZNkpKJ%=v40TU3Qq8DhIa9EW?I-_+$d z8Xp-hRLphxU&Y{>=efpeCkq>0=x5nMy0;ET)9{XwU+%W0^`_fjr-lD&YBkOGC{0-S=F+I_xv~9ioENL#_CB1o_>GrqMm%x);si7!`bZC z)X7toTHnIFTaJnl#H`=2sKoa(Ho#m^h&Y0`&w0|+79ruv*ujAy$_maB+yCt3b19WF ztzTUM@R+sX$#)DZ;@P*Nj?Td)theR3ftU?UoJ1FM_iZW>MZ!4nY2WjF7bXni#d}F3 zGM6S@H8;PX2qY3zRr&dEf(_WWpD+HrA5>Se{mogzhlc)!cuSsoeF-5B+^sLjoi@1g z!P*8kfF<Dgrim z&~qP{Q(l8|1z(-}gxs5_O{%mo z{{7ENNO?v#)|WI;$^r|PI(WR#Z*k!AfjmoR-BY%W2+|k(Bj=e?_D#eOTO>rJ76Hx_ z)&$Uh3K`lyyer$!aoV?^Q$k9r z22Skj^jSKy<@NDLL|kKUcbJzZ@M+Xp-zrA9aKv4X05CwwQZ;BfW2!hMYtZ!FoOwS> z8$!*x73^{x9H1m=ntk?zIlyQ+XA)_#6;uKV^b#9Qs{%ZZmy(=tlgDdDRJiSC0<_zq zn!k!F+Yu6NpSpUS5XWLPvP9rn0$IW{w!{+gcj|3ipb{TvBTpyL$xm63zKC_4;fpsA z`Nd`hpN|aGO2g**x5(d&MxtMc-iv!F_Wq~=5XZ7AwX(zk(PPe330~v+hpswzfmFgh zfLQsQ216Ph$e$>%Mau2Z!XRury^^AsR&jp(Hmx+-ex*H^bPj=NrYqgU;A(gb#(3hp zq$b`qe#jOP#4Xl_);xO1=yW21$X?Unjd>e8QvCSA-YAa?hnX!q1DkU47wnRly0p8T4)R0Qpq40`IJ?XH zEC{lsM&Lvkw<6W8@uaeLeJKl_v%R?zMI4r)|1{%E8#(827CHqf5irM~@PqBAcX4#( zq8aA6rWan#Sm})nZ&kMQNh$Y)`>$JJIpI_eItp081vj%{CxL%iK^2lP+2L zDe-jo+Xu%Zf5Wu0pTeV0`G2Ma#lkYhh+-VTe8(pC8VfebrX0v+Xa8JLMV)Cu!E^CP zCWKlFW3dnM6^17k2ryXdzN%q1R;Q)v;ny~^_+RshlL-n|hP7bLB?oR^1GK3#sd{K~ z^2?t8VBH)`yMB2NQ#zY?W6pGA{AZDGP_b^0L=wgFOVi z3YVe|t>X2>l=H;}pddh_$j`ci)^cHuFR zD>mnN!z0+}FFSf-(yR*g`~{CsIoDoPox=_eYE9OYsdujP^ubf#_HOcI#JZrL`yZZW!8N57f-}zr-;_p z*Hb$Ex4rE^xxbSGj$ zdjLjK!m_Rh69+Zm5c*=5h49)?nabLt)Ya8~Qn(eq^nqeg724i`U(-G)vBnG%BAXXw zRT&Ekqd|7MkrP3(bb%LVBdG((oZ^$zpnp=M-Dru zU97n3(1K%D8>x`>jQ*$}LtH}6Ns!cQWDv?2-`VNnJ(G^&yxJMv-f%Bw~?0j<+cuv3=Xgx=gJllO$`Qx7GbCUWkpub5a| zndLlO_r|sqi}0hDcqbNxsc#Rb!=|;=?(Z@ED=a@`C>_?K5;ScmZekjB`gK2d7}Az* zeQBYRn;@N{>Q(5zvv1oV=O8?t{$v;2d-x4yQ`~VO39sOTHF(9~A&&yKt!tw~Rzj&`mrM2Qy<@-T!E-y`b zd&S8%l*iH7dg`{NfPc0HLXgA^FQwvW~SVDWN z&}s_e1$7fo){`(K=w8QlAZ&BJvV&$dY&j7^U3VsOycYtk{gMm)GScDf0XZrM-$bk` z8z9T-=)#(sVO2$-=BiYm32r~`1vBb!>6J`o&7rd)HGr&hLj83T1;?eNw-CB7g^9YQ zkDecN2`)vySZs3m{t$$@9%L&B$0YBsf58ZCfzgfM%B-g7`SwcfpcW9T5$)y;WfsXw z*P`A}f(Wx~JCxo^)jUJNhw$>YwL`{*J-4j^6S$IVJ3(g@c^`^!7aZk;QTw54?6|+< z|0cN{qickrfxEMRZE(j6ciF#Y#!kyhPQ(hMMKXLwEvNZB;}u6^;swPb7+PXcZGQBA zLyt*=1&@#5W}Zc@j)W=7iZ1?jeW%WDmXwMYdp^Fg%7s)hAIT*u3X!=p)sK`QZ7&^c zj&aAR6l6AX!gCYCvEv7pxo_n~P1m_)6;-9k>~xaRF0A7mVbT{Qs>~S+Mx8BvcYK&L zd~0_b(@XXRlagXdBGX+W3+R^#fUId1O^Lgc|x7J z8%9N-*}sb#5uRv?xME0Y#gspr(`*@LAHhgGDht~wHHqYrkV4Te)m3_Iz$l-9@J zz_|?dC4JkzY-v-Mh9@)%mjO_lvCqHUHXZ|;d@fFi*?C`aAd|WFGQKBO;$EJHo;8#6 zb?zke6AQmw5RsW_^cbScs&H;HFdVtxika(ENhEia_@(MhO8ZBHB^@G@;UW>qaV*Q^+BfCD!wDcdDNd9G~ zQRP5D9`fT-)Kx2Orkyig`<+m_{1Pv-O{XL|{o35SN#PDOtCjmt9*a=FUeG?;WLslEYl0fcBxFyRUSj{V0)n1E-<&(rT?~G&)y3 z`5g)E)*xfoNT$6f^W1OkrN$Z0B2t)v!?%EVo|GGROB zRWoVDB2GYHz$Ylh`RZ#wO!&Io{`ErGJ7$iUkm_>TukT zA#828k7%>Yz7>WvX3aaMA4YtPdeNTvlIX@dhep^2Gw_5YyI1tY)T?b8GHPe#iQ=Qu zHKUzmwD1*u2XdFf#c^i~b9_vR(1VVa&&pSRocKf^Oj4Yi^v5hg1G8~my?b)(?(Tq} zea5{JT#U&@{ppSx7M*o@eusx4oYtZ4VSOHft9Vtelt z#4=gk@gL0#Dm3*$fIba5qWlQS`janatFI2YnHLF`SoGP97K^hD|Q(auFo!XEx;$a4H2^oB++L?LsysSlj<|S-5>*$hK<$8-$3%LI^>_a@CSazCS zay9r(za$r6Xpf)!!tSxmPuJ94L~`3I_H z^Z@wWIR6$C@wP04aB?13j`{ZF!0n*0DB^N2QKt3Yltp` zm^?|}%saXL4SRW*W-4Os2uldfngdbgaCL%BC%+jw@>)SU<_`hiD%fpJ0hB9H04?tz z85v$M>9E6#ESOU~?KLtc_-Ou(~aH;AS>98we|NX|?;GwNVbcHqMy^yf^tjYvbwvu8n+>vdf}l zt{2mX5j$Dmhrf!%)hU%YNU5^hGlicI41hUAVHI3njd6uD&tH40XJFxQz|=xWPr9aS z>}~K9(r8?Q6n#et>9_c-N?0(9qp~vx^=rQ?J&-j^K`b5{9|%uMh4`dlHUGp!I#281 z?&g!%l`2Wu{z3Ml>Q^LgyA48e#e08i?~)zLZIe0$Vfue#i)*(5GI?Y5DCJu22Qw0#~7Gb0|aa4 z*Ll>{1LV1qm6f`D+&RAff~)%6=KjJ~eg{z^qS0)&0b55ny;CZu#qp_eaX(n@G`fh~ z)1(yKN3n;jt7?%()KbHxg{#o0JQ-ha))&lQ+`!hu1t5@mi> z=qwspZ{Y}eeLYL{Bzyy^aBqztztidJzP09aKj8{k9Yc;nv-jNMCa2%wx4^ZwIy1Z|&9Gl2 zK>n%V(-f2m<>p8?Lo1tIBsY+|_~PRbJw@oB^jn;$gpR9v73WKs3>%8+t@Yg$$r#`C}BzbWe- zGKe@hNB(@43NSUHcie-n(9a9Luy-$vI}LS%brCG*?;L3#lF_-N9RW$|emQP1X8%2Q zVSz%-V8U?9BZQ;bD{kj&Awxqwd39Ah()eMvCX+s-O(HD=+24OS4HDv@hFS zwz~@jD>6G8Axt7RNcV_nUb}swaKI=$Qc@EK0bEX=zWG@^ ztZZzBQnqe1P_d3|tg1RMa}$btRzKSi<1f}04XzVqG5^%!)Hvw&W2U3HBcF5N;KONV z4_njYzZ!?63ECFU=+DEtKCQEY$&qOpmjkDuQyg;kgihSvMEYAm=!9s56ZL~fBN>x* zPBgFDgx3w~^?2(lyQpaP7<;yFH<^0_nGmY#(StKszJcd=8%$r2h-l~{tZg$b;^zo2 zXIMfQ{!`QGgmik*dn%hB{p z{!EG%Z{EaUe^Ne8^B)+i%NJ7QeXQ%(|G&sezCC6(Qll*)|T)OUukCIOcFhr%)Ssq-r5+H}%?0oT*TE0)>K<>nI6p8^Z zM%hYO%^E`0>dan3o#%FMqAr@$wsD>}R}Lmj%X?AXB% zumg3Tbycg}f|7qYk3!2e#Cx!~Yk;>*Ht%V^g4}$wn|0Avadf$JVysQ?z0ua%WPfno z%h|dK-P2g^bPef4M}SV3qPF_8CT`~FwlNU?)G1efv$8ZeI6GBsL(r@z_W5MHOp~g1 zN43desLD_nTus%zr@q$s>+*}Y1;r<%?nc#<{FHMF?g=?nh9>GKl{PYL2si%e5PEn^ zVJ8I+TtVrI2PCR9A;8TZMb1M$lvd*WEHE3q<#rLNqc4rlFPwfydie}32p^J1#T!+N zxU@|FWLvwxik=YEI}jcH@2R~QZz*K_?Q`sqLuY1UH2EJ+NR;s2Plq9+R#<7|i*7pR zSn^8&?4V6&Mq7(kEhFd@FZsb+v`JB$ft&D&P{*E|I4AD=yMXxo+_<)hDNTD1p^}%X zoL|YmhxrVdzpC>d;n{#$5KFE|ns!OYne7e&)nP@vZ-Bq4fVPoEMXl2y@+l%5eTM66 zFM{u`p=UcQgwo@2%H>d1#tOIrgmwu540Xfdy|X9!dC5@`nNOVair5{mDa?@~+G*qT zoEI1lo|{83UyvYuSx?rmP)|Zmfl-)-?-h@V@v@_zlryE2Vkoj981Jrm$H4J|K|mn6 zrJqhljI~_6ha3|~j!#Z^rdq^VkkU1-uV-}WivfWhT55g>Vl95En0Wr$1fMcF5yT;~ zilwMCs2N01ioE}Nzq+=zwyTAF&}CD0xo|(($SYa;+>X*EUI6~3#dMZu4-KpvT*NOR z#RJcxsdOKg;hcsBjY4Q>9gOuo1>0N4sR1qHNuPKVh|mF{=BiHNBBSiV8rYqkg>+kE zS(bfvRM4jUiC>*ZX9Am_N2xXagHrm&)UTy}9PzzcQHZHWy{@{({;-)K{}w}ts7hhO zQrW)Qz=jnJ=%%`6rr4J?)TXRTl0CJbPQmO};`z-eGO0-%J?4a0AMC8J>1S_uWYiT# z3dCpKWp)7MMFAxVsqLXs$C27n0R`!6&+1Hzig&=I!dL>Qhw3@5H+3^gupD6YbYQ=t zY&)X!z8b<&$jy3M?b0|QNxnV^8NlB$ms=`o5Z-C+CXBl+D{!R0H-1pl7O3V#`na8_ zzHmv9+Za*A1HRjgc;X1~FDQU*y+rfno>Ag4n#U~^N6$-??$b`0^(5oqjrjhWJrJ!m z+ll0gif*A11NB%EJ@M2({HB-WlJA!TT=ik&7;^#rO5P>CX#tGFio9)H4mJR25T}}I zk}W+RVQ|@Hb9=W2PPOkZfztu*1BhdJXL?fW&ewC-k3XS3Cw)C&c4zW%k;02(p7?oD zDHpqjmbs` zQwE_0JQ${V?{R5sKyj$zkMi>mz?em1138pt0XMNKonuuK2cJ zlA=G}VYGCJQIg5(npAR{Tj`2GYv?-{u(kpE<=JH4f4}o~jiU{rMzS^Jk`wy6*6cty zuYzMaKGvzOAIDUqRRaFkz*V#KztJ3{#!#WWH$OUG{`WqZD>r!ww5PNf6M)Y&iz1l) ze-vEf9kCapE~$2$VKl8>V6wf3cLu(y*lvY3S_ znjZ9EPMEv6xGGsA87f|HQl2ZZ4^9-hd%@$doOvyD3e*=V>RAg+H*cQmWDTrSRApf@ z$3E&^g5=-*+5JJpDP@r^+N8$KefZd!&L`&1J~Ew2N-*E3X9QeD*3alLmTCTKM17ED z`$|PIK=T6!$!Z54Lb>bVj1_FCG-yuvJ12UAf+Dlbif-&*tY1;fahSb`6v23`q&%Kx4$zZG#=c)t zHD~5zr#X8WUFB7r(MLH;EU-BH2n$lH85J_W@iypy3oMWc5LT(ll)>D@%DX2PGUtRr zh^;-I>)ykP(Dc&e@7mKH@C`~ZUZ5^FyRviTR#lC1va-fJKUF`SSwI%G$D%{dvsw*$ z_i-S#`YZ!){30nwyDsp6g3@PGuMyiX?7?I4OpKE!2?K@_h_>qLE;IHANgIE@Bb(^z zvdHVkl%TiZFJTM|;EgbynPJtXuA`9G0meR1;G*iF_=ekeJ@e|P#%vK^v+g$R$+#Dm zRz-+IU!Zx6&y_B+w+KDbLuYCgUs23LE@hiw9X^Z`@qF_pCZCJyWQ@@5yFi9ZkA|O) zYo*(`!?h45Ya%%Q1#mXRun&M2soiM&|TRvU_2YI)Fp4S3{cHB(L@_N9Nt;X<1=yRJ9IqO6u@-};2G!k z=Zoe9F~^rQ$cFb#AgV-7qWr=>9{P3Et8r!OzR!$w8%Ju$%)n+a zH*$ZWH(|QBYsGv}*x6;iJ8Mbsl<8+5^1YZ}kFw6avB`S=Kb-s3v%lm2a8g?&ILK12 zlXL4%zK0I}pTrGe;lB3YH|2lV63*3v6`1GDx!9vKXxdQ!ZO3O-UfmqO4SY^R9@aPr z5%n^6PZsPlcXJQV`EE@=w};K6sn2E;ss z7TYLo(L7zsMb}m6E;%B7d7KzO+I6^?)GyTtnMB$z%HAUpvWInxHb_tJ>bl zA&NZA0l4E4(%y{F7pKkQx={ud|Mj+r^koVEC= z^FvYK-^4=&rrm|Jq5r#Q({o!?zsxt`bTMg88mp(<+>u^RDYnI#iWw~lRgCojGr6`i zpneu>KB-x8a0&PjHC8RFDe51z#`U|9CS2rp-rLzNH1tN=#~$r0GT9DecaVZx_+U=V zyYMR~B;qp+9e#V~7gjQ^4!g(>Hd$5@J^V-x z4#^2*-qSl-f|###f3~3_$v6IobKN-3i~kSjI5$;^m3M!ysNqZhHTENOiV`ua%n(-N z=9ybjRuc0mJ$=vIm<5>Ld4Q+6Dvp>6R(4iYjke9>`{bjtP*fI0YXg5dfJNxas0C8Q zCQ=>QECt`xLT_vfOc$YL&SFGjhbJ)sm2oY&CvF?(iu~k0e7H8g*GUCi7AOu$irM4AU6t%To55p-(nD1Fi7s&^+6=R-(NG=1yct6cpzjC~-kp zoP=lQ(F=LeZK-`XdAYtgxcI%`7ZUby$K~CU@+9LAa!-ZiDLtKIkqYZXH_qS~XM4Lw z^StFeBwCsKRT)-^TFp$7mhJ2&bI_r|_@2_?)w*JPfNe(iG4%|bjfr+uQ#{!J7hVlf z-T?26q{>p?SaqD~_o=y|KC8a?!|p$~_8B%ZqT+$F;o#Q|S%(?g2Nhnoan&{=Gbd@4 za8Vm~$R#3fAME)KOe^7#bKg^<_~+?|eqynXL2_@?q92jmKgu0RKCdA~-IE z1x1GR`T=IxntE9Odyn{%8zn8AE*%S*w~i=EWomVuLiinL?%6(=zQvpRhod(`C-I1Q zv1-S==HP>U9Z38-Ii*+3x9QMXs4YkQLNk>)4mGQHEetcz9~t1@u!=Wkbej_0{~Bg-i!M?DvFOxpgsLzG1PX3 zvPPPcNbJR+*NHivl4(!XZ461r%ucr~czNkj3d3Vh>(3Rm;MX?OaSPstvU>YHj@5;8 zYNu1v-2%HSIKKwLHD@XGQ0e5xBcqe0Par0#usdD|=Q(ps*3%P_7tWfcs2wP1U=K`p zEU0u^_g<<8ej01n{_1pVwa&K`5gxx|NDacd=#;j)_DQ|Y{Wa;Tf;Fu)zY!sIuSO&5 z--y2s1l>5fx{1HJY9};q{MKJ-$~z;5%W23Ngr?0D4;#D@jXQAT;@1efjd`>6T%RNVgNo9)Br z73;%o=Vu&A?c)jk@Ubm~hG%biI{K!lVV0XbS)`2X4||p&Q?0Z2B~P!dQvd3Zj4S$yRkpI$$!$hBVnpJB*3ytQ z*R|7__oNiXUZdv+8Ps|4E&1iu%GnbE6VbV(4>s5f40W+Bv7aM>5lUqEv#c4?Ji;8X zC(=D3(Wq-}>?%B+FCo1r1J(zfeKS#FObA4%d4d|-Zv$k@cvK6s8*6L4kh^d|2j)PK z^jEBtdBY*(`ZluKw!Xi0W?FS)l<2xqBxFj>4*^I>82wq0Ml8}V`|4eo#)mi6*u7J^ zt@iO^3Dic{ON^B&+DboYX!AgDxIdm z<|)h{>(A^@sjxLle1V$9eb+x6hrEVdUuWXij~HItC-g9}-D$=q2l}Uhg=pt$qpj(& zvuYed9EJg2`f1Hc$LKd7K7Nn>9$Nl%Lg|iTcRq#-B=eQZF#o5mdXtmea+`M~+V^1B zVN1#&<>HD4cKJ)omO&8p{H%3JxIqV``;#biWO8ua9Y&YK5A8T099T^5SiH%xzXj-} zmrs+<%uv?Z(ZStc?!Vdlov&qsTyhzg^*I7?6a7t`3g&mRs7jP(;R>m^n@7PE;=Teb) zEEYd|Mr#4?Iy4bHm)dS%Vv8inQ2@NA$%;2EHwMVvy%^LN3fwxQMg4eYBI5}F6NVmS z_AxM6$D&%dHr{!I0jK&}Z?GlcaAJ`d9K*y<Rt*}+ZLwxLds0b zQ6r6)$nLi3_FE58Kk52=k`lSy)8oizXBGBuK}>Ok%h+eWnr`iHk19Kyqea#Boe^i( zZLlDvLUsB&=9B3i`g_k)GE|KzZ^vj|#f!ksg>_?P26Nd9j52#PIeYesJ>I}0(i41< z1Id!yX;a+*c~mw9bswRju;NyzlG(#bb6h%4d>ukz(ZPkBud<}6>-qN88z*P-UtQorw5=mgq@Qz++Plkz@|B13SPC>L zGrw=0ng0o~s72?=#Im=1Nq(qk&8P~Gh2p%#d-H^gmh>^-U>g?*VsM9W&d%z00&^DOYGhzK@QiC$f@T%-%_si5iElYFmFUA=q zXEXnB=1>IR@|upIu)m;$hg2;?PZVly#oJ`@fc6(1_ydF5iNpBJokjN<{~MywL|X6O z#y!h=hzhS*xpirg7l}lv<5tulpn&KnIbI*WJrEZtN$IluvU>6XovdQ2{t(=zP6yqz z=~PBC*feZ^ zk?Q)T^>LL{@js0Y$%YmBx05KsUtls(SLdP@&lF^2HH|89n}L$iW~|yr!=|vTJp5sB z*(bw^F5Nnb$TC)FQDH@>QnqhRiVM)UC)OBEFO`K0k4gw#eT>)oKlkdI1F?*yE0LuQ z>7(E`j^&3c*-0XB)r_E~1;k4?Jm3EEkk)926Zf=H9C$3^lS3Ive^8M>feEJW0Aq5rnAI`>zgvJ@z zZIIyTHF$r=dIaHJhuOjFImcm?XO_7L@J+hm=bZx1sbEP@gHUJrhAQ1Eo`sFedCO<9 zOj03xL<6*nsk!l`Y;ZO7?y$!+jjqr~%ctYqY%F;{qoFaeE-i%f6SoC^@!#~!4x&60 z&l@Glo>%?Dp$Wrzydufr)4$Y&m*zocJ*}`!K$BVD6cKM+Zr-1~4>i3wliUL5IGv7& z5OmDKzK8vNvkcja{Q3T3Yk+oQ(vbNCR=b6Fs>o;`X!PmBsy~I@bz>jZ54Z1@Zhv}k z-G86-(q(rachnr`cggKyvuONfiHv?z2`?!!d??CfsJ3zJp9KRDWUnx$&^ z-PY<&!^Gl!aVs!nn2ZES{0X*&vlN7kyFYIoA45=#=v{-Oxp65jES=_!qMcNVAU9Sc*8I?FM` zi0jLy8hpBEtkKcDHcn7wK4vjI_U#-QpIjsZe|cf^Aun$+*Xj?gjbEQ~ebI)fxV@=) ze+PEn$aS*fVOhr#99cz8ASvEj?f)d6V}5^X9<37XDY=EJVzrVukq*%?qhs6Ci%iX= zT6adn=TBb}7X%Y;ghV5`mT3DL+#K+5@M-=iTIc0*nMSXv-ZKx`@_Y3Ig7T`a#4?p57j-x?)Y%9 zX-{G7u3UMlLQ8bKZn5gv*I9naPFDzchr8~3W!3s)2n^ppu(?UFF|ZTQRW<1`Wx=C6 zA~(IuKuiSpOsySri5l^q$Vd-0aw+{8hOxW_04{O|C1jRZK&zu;=t&!Yh8~T~TS+eI&8BkChkFYg%hAO>mwuVCc2}`#CR% zNV3(b)3;`NhR#jAP6+1R_xi6;ql_=IvGOUS4bpo3X{))z!K2zulqm2ojN3<{$Z02)hfIgi|Xz zQ77d;x}8-a_hZx@I1b%(_hFvX>}jgxLb$wmA=P)-68`qT_mPW!%+}J@6>s{DH;H0g z#7t0ZbiN-B1x6S9^YU-S){@plMxdmwW7eUo4z@Y!NRo$qt2|P081ULciptN zVxVpPWj-CXg@uLHFjvw|u_6y@_1CUC6Kc9DivWCiT*6xPzQ_Y=oHzNGGO zxA9rlh`m&T14dnFJN!(s*#t9i#So$`Yt1sNNxpGLBAu<(x?XcTUNhvJ=9yOw|2A^| zDSDeh*VpWkF^ zJ;uX~zYyXdGA2;d5)E@-(oRZmuTj?LIy`?z*R@-q+mrM>z!>s+0J4!y_T62{O{Q4T zZwQq`!l5;4u3&<*IXs58-V}6C=65iY#j9mu^YPe7^HKA!X!rx*C<<4Z`w`I0q4D-r z7N6*S8I&zLuP8n$6pI>hm7Gdl{uuaE1Dd187Asyz8U}PXI*Nw$cQH_Z(7Ou*HRC1U zm6*)?$B9bB;e2)V&a9Zff0-OD{{o>qEUY0p%50e#^iyES#A5QBp6aVqytOTccm*H6 zCD_`WU&K$LmfvxUJ35uR2BB!eV5QAo)_x$a4l!ps={i{Kb7^_D zE{_nZvQPaj!W0M5xdDkrOMdtM*jIFy-HnZSko_Q+-Cyjd*;`HF^WP(?@%rH+ z?QF3TxlIw{Sp>Qtqi}z&5Ha!;?7Xuqafc$^f+J%UH=?>g-3i_6e0}w7h*)pAxik`= zP0`4#IRbfU?}Hd#%#Kdn%v^L=@1;E5i>Ipf2Vm6__t!#UXFK(hTSM__e3g+{nYjH} zLu5JNdajfSkKUsHS%?Ag;xkw;O_G)_(($?Gm5 zw)mN+nLy_5##rUxZ!*8u1NnTLBCY?|&>cGU|Dv6P2fv4Uirn3!zZ|XvbLJ+eGw;bS zj0d1|9vc5gTd`mH=k>2x-^HoCvu{P}W^v7^6I*V4Ak_^`MNDD`%{pmSX-TH0?(1kG zgxRH`J*R|YdA;a)vB~TlXAT*ld=%89De5CzDH1IwM815|X2L z`Cs3EDZoFF?mD>r8?qdCoEJgafFB_yy~gEmg2At(v6#+ZiB*0ge5DQ&!Ke*uLB=Pd z2Zb^$EUB2K_#{oei31?qXNUN#5CnnXQoW-m=q~Gox&8M<ILtG|d-SrkzwGn^ z8wyF55@>d@22#nEe-|REQ)b;^8+*v0cRxwmg}VT05+Rv;)B6QRRvcEuKY70w3iZdII2NNpdVpr=@!z zC|f0e0kZP@+6%Yj5$lv6u0ngtz1jU1)rR|tvN5|Ko85J`^Y)5lv#t`bCoCoN3ioB6 z-aPQpff+-l+vZP|TCft(lB22%79mcn>?h*iG9!H{KSWp@a2$kLhCrnyl!JD%*W7R&If6A5yS6Cz3{ybL^6!m)fL?n zKc-4Oo967-#E@--eJ<^_FaW7rr_(Jim z@w1uP#D;>aDxE?`I3orW@;9A4vt&c@YGAL%pj!}bQ-a)54zA0=y{d$ zVPgd;qGub0wA`XSRcDjZE%ipz{8Smt0(@v6#slhpKNmizE`n}C!(Y48b$YbhSb2#& zYnfuW6!Rbi@ztxDH8$!!OL-RWK}EB#BruxIDBjhdM6E$TNg5=~(E$3=+U?RS8 zas7JF@Ac*Qu63`5lM9(RP?K@C5ANy|a%P?D_JxwJpFoVxIPIAfJI)nytE5%mySeeL zsV%c@R|`;^b=E$p6;l=4zBo=p)(ww731X(uK$#P26#c_My-L?h1@~sgA$K1R8c5@>;#nxBAX1 zdLI||h~f<`!AIc)qp5Z84fFwFHy*h%+gPj~_!)_yYMp;+(#o8iQ17;{KF$4|l%P|* zCIM#>Y!w10dJb%oRrOPO(pVc*kVCC~sXkU26zmtPEhjyvyjy6<_uaRLd~+o@>U>6^ z7k+21;R`?G?l?Mb_0kR_=j+chFrP`PZq$!Veaz_@EPgJJ9IBW#|9oT0#4hy?x4NH? z*bnVklx;6}kbOWd-n@qe4q#6r#B7W_NdcL-yrpbNp%p~lcG~tF9Ax3a_ z1Jct+;C>aGebE$BG)->4I@Q*9M`eA;qk0Eu?Rjga>v-B|TNCT%?-Al18biYF#!Y3g znWlWaYV!VZNpLJJhri1SFK8%x=*YHvlk0VWUN8BtC&AODJcpzCbwb*F2O+-*`iXw> zd?3^0LH=)Rf9o(&^uv@%a90xq-;a5wnv*V{_kMsW3IEG}ef6<~!jX5=`e7UStJJSO zS{FB>;u-$|{e*sur;vldJZ!B?HiaVYEBiSbglbh;MX6_FZU{AJkeO&dykP1p4cB71ojhDc zK2~o|1ol>iuQq$Vb4O28Ol_-^ZVX?A@B&F)t_rgaYIEV+iO(fub(g%%JD}0=#yngF zSrejg1*1h(_xO<2^M{S}z}x#!E>m6{{n0DXX78BolY9(|@`EEz7~nBvge5 z0eXfgnBEfy)VF523^ex7tQU9+$n8zeTNR$Y-y)7{$FRg)1_s+r&P>lu$r~z5!KOz# z@3*77M*TEdiFYZXYq3j>2^vn9o9{TFr*H>zMQo5DKzr4471jxK!vp9CGdnq=gHbN|N_I_}| znLarcCdt0{8b+@cZ0v0YW=tRkgBb4vc5W_iq=m!%KPQ6x(#;&R~M#v^J@@ zhR<^JoJDKj%7U?M!h*n#_+nArxnwbEv#O2x)&bMdz4n4O<{?q0#$^VBoZ{NU!`tOk zVRzzXL#<48mSjPnmyj{Jfr`%P=?^YCn+**#i*lD^SAzv`X5Vq< z;Fr#huWrbv4i9hmLz{FWnrW}XJE?mNif{~E_+YLsFB63_&Y&%A z(_cy3(5jEh-s$Qkw_(_A8rxh!SRN;6s1}KO+1Ki!s>*_&9`u;Uvip5o5n2x3k|t*R zq4vsIUS`svS|g%6y?U*$PNVx)yleFOQO|#cfN@(tg{dWk;&Rr}D7A>w^V)uWb*U4Z zC_fWCBtuja8#9ua8uc8J3Y!t9mAH+V`ddZ@-1ZBEY4_O3YA%AhHr4D6E@d}`* z$BaZRP~UA#N)E2e0^?}mgttk0Mqy?4FL#z%4QNvaKtah;x`aL6Pc!v7fUz-OLPflM z7lfo;WgCwr&FKt&29ur8 zOnbv;gGWEuLH*iT3UhZ5~7dROb`-<1$ zM*rtGZ_WH59*hwBUQv`=klxss&*SJ|^x<_~vq+`GuCi3Dg7b@#L(%%CCx2Xdh2tPg zDt$`*?Iq7{-u+*EomW&-?Yr%RAfQqekdh!uM?iW9i6|ZEy-0@;2qpA@QWO;FRRTnM zFVZ0hf|SrpLJfr8dq=T+C*S{^v-cV2Vy~NZwZ>Ruy<@%Qna})9DJiO}LkjseF8{Y| z0foNC_3qAp@pM}XV!ZvVG8Z0c@BW63Yn&1@*3Z?aS^YR|YEPeO#Cj)j=Ihw}@XO@5M*obl39tfX1k-5&L>{(*n zC(fi`Xbxi7Hqn9%#oBOmD4CM zkAr_%SDMm>|0|U;Cr)l=6uP5>%U3udZk6uGfgsV{>yw88Z>d=KRA(C@8E?=n1mf}@G(Xh-G}M3U zc{k#BScKsDC`ua229gOBQ}cu`ERKU70{-j}yWivD)aU#Si-EXAp~Pk^E6Hz4p`1rs zPD*`#cTfj}?E>4=49!l8(MT)b$2n1iva;r{{v$7c2T>-vY=R%ry;wxvbupTKc-3Ga zzxMj+BkH5tpJZ*1v4;?{JI3;XL7b$g9E0O@&kwSf4opUq(NRaGFp&vm0cf{V&a7*I znKJD4B%Q)6_-j>)@xk5d$B}EvS!!Jz$w+=?OYW%yS@#5rk9K4?rcqBg?sbP#^VWG7 zJ12OeKN}KBZW2kdX*M)F;%oOFTTDv>H5SMKGO2e>bqU3-_|HD&O-Az%g}vXU$=pSA zkh50IULJR0Ku-OW%QNQIW`NZpX#x!; z*J0|nkFkXq->9!p3)o#C3O)M-2Wd zG^?liPlCof5e8{n`nsC3`03=2V3R4JE(IHucNDqHu0*y`heClbm1 zGm8}#uM0HjWU1iM)T>?rYCtN71i)BB7mL$9U<`Gx4tZFD>#Mi?0-0^lH zfu*1sR!cQpzsh@BFJSX#qG(4_%j+Go_}rq1s3=rSx+sw0M2hc|tYj54=_;i}v$kbL znJ;70Bqj=ZeXx}f(vR18;JZnzfwyr_nUo9V?2O13Kk_&|qKbWIov$FY> zFjYRzOT(*4`TJb8ezu`V_-Y^K0S>g(*6E*p3}(NafQPs9R{2<;-MrZmOr8nq^s^gD zY&!rW>Nokg!RZevY#eRhOC#O{!Vb?y5s8rbs;YVGnRCAa<$ z+kJq=^}z74FqpQjt=Hjq%7lsXJ)I)|?pN*|V<3q}Q5}_Ot?qkGCOKGL!9$s#mp5)1 z2De)Xrs`Ii zb@6RkrtVum831rhf+V&DhzS1H#zI^zuJi23<^UrRtYUq_G2ixR%74T(&m%3>SYIiy zER)gd;i7~=W3CMS7|SZH>q81y{*1{-Kd<`vfSQ20rQ znia8@H_;u9NnmS1-{DesT44vPoq{E5t{ZBi+5WlRa!;WjnR4cI6r1j6MdhNJ>~5BS zjy+Rfm3}?d0?0rCNEae@nvl?(kB+88Q>W!}ap1sR2)FN>B7+_qT79P14S@ZW-kxLx zfTkk>Sw7=F=TtldiMxseOQa~CGc15u#9Al@*S<@UM`fcz!%&n@K!UK2=6$55R0f3= z^ij#m!mY%A045YgH!}(jE51PfB+v8NrY?A<`7zQmp%s+!j`k?oy7$QUECO=EDBP$C zu;g-!+d+@Z=5&m<@y_p({o>+&td8$fg(1A?{tXO$&!#9(c+9Tmar%`Ad5n0KyIoxt z6%!LYn8^kdQQdJw#FJVOla6yaVy*91UIbW&`cL6h*>rX9&9%pqL#(rD#Z~IJK-)s? zB4ymskW{~yP;~i6;!_GApzCC`(xf}!ua~;cSkrdo&R!DkQu6~>?uUAHS9@-3V_wYw zMsc&1+?YKTdyW+`KY{ul{Rs5v;C{|;T>sD zy%$PCCWcRI*=0|;~wHuG7e`vX{Dc z+-XI=H|Ef9M-Be~W<<%KjE`N=2K^QL2QX-V=ar78hV_f$$9>xR8isdTylA{)6EcZj zE|(nU!wIWPF!Zf9W=wepQtYZ=9-SfaU|qIU%7^k7PPLq8*7t%w(XY-}i_Zl{%ocgd z7C|*%K)d(Y=~r;V-a5FRj?Q3V&y|n=ZL>gma3B}Lo+f9d3ZCu7hRNhw1C>hlRn4k~ zebW`vHZo?4$$WVdN|hBmhL>SVP^Ofm84p%itYku0G{zi&@VA{aUy-iv7E_UO#dFDo zW9s|m>6~-uCH+=UJlo8K(+o}2lsVIp=2ljllD(bvy!9OP1WfHsPwfm^DAWO=vnu{K z%CqR^P`+bjilcXJ36I27E~CFSJ_Z_(q`het z6+Wp!fI%FizN3x!DeQojc$33RZlqLeqXEI3%!QM{{Qe2(#~>}*&}nKacx-NZyke(1 zpg0}rrsr-n34mH0N z?{xIqN?Z!oaP9=l)!+c z7MmOU_*~&@zxO3GDOzg$TxhLs2ueXzxQ+}i`X<23PVseaM*gIZ% zU!>)XAgJ(*@(|ocM+c=zRb#u~7XK51xpwC04QBrQ<8z3oUsuT=W^jkzbLu1o_SD#b z(80AcjNGl)k>Gp!;t1lwq^xYs z-K(dwf0h_7PYR%YMmd3f9pGkN1<7H%iD#1 zUKQyV8udq2*c>FLs4$h$$Hs_Qeq>bUQtjWSQ zzO0+3EJbYeNFjlHYYiOw?_eX zamqR^8rP?>4nZM^$O_90?9V(n8^Y7GoHYt3mfw;)dyzsP}@u2=8@XyR|X zmX_KUgu!~rbUsA3Rxv*aCv)G4v=+jc?6iw&Y8AN)XTZO7xI{@Sz52I>A+9`LKD0VH zf{x60ypD-vVLI&TjobgpLb0{<_~UUwdlItrUhjE(j*$v!#anEh;$bEATI{c)uPlS& zZVV z{dj?>#|jhUG;6W7jVi-YZ32a*9}>vgTQI?GI(!?g-}xi$;9Mz)g=nf3t>p94ox>;4 z1rQVM!(I)OuBnz31e{aW)H$20$~|Qu%Dc1Q&^agBw00z}t&mQJXGB)b2FF$)#8J_J zTQ>y^*9Ux9z6UMn?ty1F9G>YQUFIbw^~SN2x8`_&hc~Nu6KkUEo{VSjCSQrNu+0WKKix@(y4_*N)PnugeEsR_Dg-8{&0z)+G3gb;8 zRKAu=T2I|o#hW^HI*TWKkQz<@Wpp4>OW(uvHm!p3Vv78Bz$Y{AL>lVFK7&c@7-)2* zWqSlbbF^gW0nr=WjqVxW4gHQ=$}Yxf4hn1`cZ1kFJ7>HPv@||)CzxAu&^pGJ1^@$V z?{zsqv1N7Ekm{qPW4~B;+h~d}&B!eLo>rlb-RmRsbQ*=$^7t+0N6u&61e7xTITmH6 zaww5ZF)sI&{nr@*V7V_JxJO_BfY^<)hvR1S!bpIqxg2i=27&`P961 zK*o?8=_;$Bqydd-k?ys)<=i1+yLKS)zPC0o~lW{cv09G3VFVD;>&^8`5;Un?o z6mqiS;T&AYI>nU+Qfn^-_-45v!ezG0)qh5w7)wr$MfhMEEAVh2J@BFOF?M3%=cEOIqw`oleIZeAH!fY z>J8~)F}&ksRr^E^Rn|zSfW2X{2>2}UH3Myz;Dn^sF@vRv2g>*ZMa1JfTM=mAOMl%m zXkpFWrkuQ%fdQZhYD?F}5ug5L>XxPU3<_|vURma?x7+qdYnzLHBKkgTopi(E`(Lb6 zg7ag^eKod_NB31X;~#d29Zhawn~j!AHw%M64l)4gSxbD0!SE}$YF|~U&y?@mlGxVx zTarzE;m>!(fLK~@oqe46c$&T#K^{CHMjF=YvhmeHta<9$b#dQj^Lf5jOm9Vr(_l5v zL^Op&;C#W&mp#bp3LQU@EWa^l5ua6MQ>XZ>DSTXYTop=~Z0iZ>ZP;D2pG>*+U`?C7 zcT&fF$9rnnEIGF*4;>fxqc_zIy=}8AkAp%W9YZCz55OLNKjWkFrNdv+Qjm7@^W)|Q zcPbC`yC0ZNeQlcZ_A)K%qNWlz9s1meeiGL3NmrqG+P>YQG40+KN1ZM+IaM=R zwori9M|wQt&kQxJGXKJ8Rn4ky8uUh=z|0NRXWQNFl@NrkeL<6nWVcr`1&!to(2aG8 zB8b?*JL$r3;*fsCn4U&7-vUfHv$cC#_n!yIcm^fZYtbR<;698xsWM8`@l!$h46^_kVeid;fZK5wZ6?nk!S9>e9J#v z2H!&Km# zvvYO7d)Bw>eI2CDxzk4CE88sZ-m0x|Oa`NO``i%wNZCGWUJsO+buU}lHKUg|Ax$pX zey5_Up{2_dcU<-FjUW*!zF?zJqSi*fO{VUHeIL{T}F#%UV2#x zTxHMk0~W_XhZ^-SH>b7jL_eJ@_+&{8RH4)3mvnSM>WM9?cbb`B$_QGt3vV|n-W+XA z{UVl^tkrqH$3lGUKXdUOa{8NKN+0k0KCf~C7N8LDltPK0Ud!rHS#Fk>VyqCy5skpd zoc8e4iHyiYW#-lQTYRy#$AdFWPctbJekD%m+%wyk`~3MHj$BlEKa`F=g`n2boiy1gewtOFm?Ql$C~<9ZYpXsT3%i;`fsi7|8hI zsWGQ;CBo`-M&d}s=d9GT?u1Rvbd2Nd^f5hd>LP3Yh&Gm;`upP!CK!N|By(+3)hI&* zzV=l1fJAfhG%xjiW>_E%4qtdY<&D5!hg>)vLN?O$Ev7qvwnR@-A}Ym86vG^G}bUC#yLnz!t3~&DHoGE zsjf|YxaR8$4Db(3S4|CIL_nQc zi)eByqPup8BJq>X@BZfU=xr!VbjC3znCS_<4yo%r=Swrh1j9^F!3~P7a4*pBDa@b< zl;BIhuzRP_R>of}cxk@@nW6)W^4zuBj5^y?wgC}Z7EBT8rKRc9r+96N z#_X{)zrnvlD48pVW{|F_V5&RAh%2-o^XBIF8S{_C#>MFY&1tbzPm$9xiS`d4Q<2HF zla;ZZSd0C)c;8lyGJ#jBcgk4VX$33li{8qeDLMPScocJPm+E#Z+{R!xf;C1U_#S0NTyP~{;{`4A{X5q1K%(pXlAX|!L1 zw@$p!B>wU*l1E7cy%h&xJmvGSb_@J6Z*_@7eJ9H^_bERUH>kq9cg?qLShhG3v^m^1 zX_8|G7EZN&4wdglkJCw`BQFN(9E>@Q=lRQQW?ByurBm3luXsk&V)kk(S0^DuZgPvY zZQW%u02%+{fsbhw7J3SHu^HaD_D-~zjGbZ8eC36cLX%s|YB3^H|BjYbV5m>s!}Md}=|F zM33PG4Uxu_fq*SOo=@9U_EjNfEs55Qb(o=6o94 z0dDO!!5G%yzvcI+Y7+zMKy!=5(-^sm4S7;qlQ=+bDHFrc8uflvBEDorRWzkHW%$OU zMc_vf9umvf@6ovEhA_l!58sM-v+OSPNyI&f{fByyVdeGP!Z{6fwGA7G%-4B+GR4?7 zvMLXAcIC3_!A!SD4nO|gKzm3OqPFfwihhwz{-!`YsNBfl{#3eC{RHCW`}|%f|6@}| z&}og-U~OyX_oGgO#l8&Kf9v1t+yBwOBjf9F4Hh*z#%96>x*%?oEel&OXg?JH+cC29 zaQWvgaP)4~`~B-bI#fE1a#LJ_RF2bElnWN*Wb$pH%<^Ht8#Lz(83>P?iv&sZjvBQS z*9ak*#R51(D@Lt`*j~%4aI==AHpb7+yy@>1f5m*}+0b^BXuPwSfV@4YhmV=?{wiC@ zR9EfA$^2)C)JNfMVkA`G0H<$&(NNQ6R8-I*#PfY(ou*l)07SNux9o5-HhCmk&wF#x zPa&-*GFYzqmPvbC>SHpjW+2g6tBshlY=t zr85$Sfjez_Qn%Y!hzLttMCywN{mMS}6z_K;ca0>Ol;^`CBiy2Ggju8N_&0s~P+En> zOfAVFCN9*Z3V?Mw{dp<=0wDt>t>-iI?g?x)q1;%rkI~*loB5Zj$*TNj+(eyuu{*ug zLoV$7{^N0StF_)ynN@@)m5R;&H%+3zcwg(cq|X@D4RXrzJFKk0Egw*;H+W2IAKzPC zzT@0rx?~rVngZf)9o&T{g2}}K)Ym@CQFTf=zD4GSj4?+4S+InK+^!IH)s?;6kTIHxzM!dS~oK5$VVP%o3h z=flJzvdrA0RozBjC|+LZnhQA|IJ{~#Fk2vkp#ecR?x5nwr9$~l<_;vAQB}3fSvrc} zHEgL@2I6JN9HM=w8cE1+HBhJS=y>=#P4DBkE9ThjJzhv^I7C`#04ar*iR9uLo%+2I zLG9vVyiFy;Fk4$4`W6>v9<7jDjgyzfO>5z5>R9)BH@ewdthV+xUH^;$rq2|@4#A&t z>!6B{?WZmSERH4x%OmB719*FmLNIXRu4e*VPM9cpfy_Ax_(lmw)l_{{a=&nu@=u&V z258JVHq5%RX^?eZj4cW$6Z7h}*m(zL<>~Au;TND%Qj>sG+ z#R;Mgk-GCaD!SG_l@3K>o-@XBLFCHJGyy=bjSW80$T}TraZmCUSC8+AMk`|RoRLDT zcFfzK)2qvt4a0oCLC*F>wTfXERht1l_ew!kYSCj7?>)dqI=NcY7B?7EM9c~ehmSI+ z2mHWkU5+W}W`%*m$<-r)c=j)K+c~n_tCw4!w9ut1ad~5z>vvhl)q&w#-6Z6RIQd7- z2g2}5fvSm}$3hNpHL#~_x_-)q+Wi}Sq_eDxPi3hR&Lv#4-=zD|ym=k{i;LNL#-HLv zv2WVTTwJroVAAu&x_nfPZ-%&n)rvgMub*O~| zg{WefKe6^n_!Fa757K2eKAdRwbx1cfj(GKZDRfava-S9Sg|%8)o06a{Ev`J}Zkx|f z{ZyufzCQ6n76>4aYBfSzQoBL?Gokow@g+&+C55O@C zQlLDTF;DsCd~YZiz)}t~=s%?p=GwTqr@6m5R9pdZ6EbBxdsNgPpL8YrKsSQ2D>er! zvo#hG@zL5nMPu*IT!(2^n$U0*?XALcK`#O`1Q0>OyiY0Ho$KjU`$Zgrtm(o_dtE8- zi2hnhP)fZ|&09~9FM%a5K60||JK^ieV2j-hj*t&mVEdg&=Tu6`=h-xSc$s;Cot!qP zvn5GShBH)kQS=6`$~q7YLN~kZ@T?m~Zq=x-3j&nXVv`GnNk4#58iRM5GUjrkb&L&$ zTw7k{#$;|xV6(ELvbSXaGmWHzK4$OHxvAR@8A=}+S4y$<4sJpd2VE>ZH!M})X{z7?8Z$&cv5f4gsdn+PP__@5OBFW zXb4Z6+>#x2;3Z-~&vHlf=%DW}Mf2lZE2q+o>ZWxKML&1BcuDN1X1C6_tfizx-xUj) zrH-ABYLLt&4-cc@hTmoBG39 zXZh>6!Z`Q&t7Z{2UG&H<-0; zVTTO>UHbMO6gN36k_rzS6|_{osGliwTVwiZbr~q%t%cwB6iKEfMK78u&^fZYbvfgR zJ0*AjZ9a(kMUpfdrX7=&kh-3W@&8oVybb_H(6~xgPe?r}xX2mRYE-UhwsOK)Dspz-P3jhghLinNy-kahwzpt= zX@oJmHa}uavc(8>ttt=ubOWeY<`UJxbzuNoDl#VOT!_}|2JDpF>kY06uq^a#Vj??6 zva2&TLSE^Sp5>)qecY2gNPzpK<%K76dQ*s!%TMtHh9Fh|_!GxW8+eXAWBNKj{ZCMG ziw4;vmWL6_)7sO?s#jF;j$WKmbi_;>r;agL6aiWg6`xGs2GkdkB=%FjNxLakft$|J zcR-CG3O#gy-F*-lAvJI5f7zkP{{>~AVpEHL0c%m+iGE`>_OS_Ek5 z1+sr`G@K9#@3@Q|;E}gF>s?HaY&P53r8X{x`u-Vy+684npMEDrg8xMZvyhQ)gPrC& zMkV?p3kB=3ECP$7Lhe6&$4*_?`A(^58n5{+)HrRR*$ z(g2#-ML5Z1e)r3t3%|z&3oI@B-+@0A{@;t+2K?t|qA3IbPX0G{H?pSso0(LC_e@ip z_P=(CblL5wM$tzOUW+#%J?}`dL_H z-JhVZ9zNJ#Oo@f%O*{CMwpWPC_w`k=Kq8)0+9ipX^wR3>h3R@=BemI_1A?g6O*kliRTl`c0RqTaol*dsoW;9|a zS8`;?g0PMv6z^{PE_mM^dguB6x?~-|>C)c!@=`b8Mx;DA`XE7@+Pc1?F)wzpY!|(2 z^S2cxu2#a<;lelHJ>RY~pcIQVeP{#J5Wgt%}1 zT$)$gH_KVRjnW7&>OsD6czz)B-7uwwF!A{3E{)`#wK)xtUl$SSgfd~@%b_WGG6T7C z<^EkS04;Qk3N@XQy#=ImlACv9HGMh$)o=lFc%>GYI(>bM45xl7bA$Ee_UUKUmp7=y z?byW86R+GF|2D-2|1!H8(j|?zCP|S$3V^@oBAFG(dy)RT_7ykm$Ho5)ZJsYgP{qdQ z`_~?N20~VY{5hhtcqUDDsawX~*xso?_+DA+T@CPe#%d0*-croAq0=6sz8ra79IBJN zqvjnYeW;`f$>OxwcOi>cBjcC}6)0So-GIMwEDQhknsyyr6U++*N!xu{teP2`0yUXV ziMjq3&}Xy3j^H8!?@9*+J)<6LROHrZpr+7=xDVe|XVX`aS)J}D>ifU2wFSFq6 zUI+p#ufDz@C&8-dE)~?zH#%2UL2DSN6t#Ut9+c{JvRZLcWaXqJAD**}sm28r@%h75 zY+GOPZNun{G$*K4uI_X%T48T3!`t7oO_7k7?CAPPwP$uKz;3{OOLmEozj$j7B349b zLS7k*uN%4feaXMjF~L?0rzLJFD0~1#z6@kvRI9z&44Hra#Y|ArXtMFkLXD)T9P8sy z&bM^~oKfT!3q%reLI4$tQb-Xf6>6L>Q8*=Sa%c^Em#lk#U(i)PR_PUU%7)DT;O*)p zyh*e1{%AgOj`rWj+|BZl{@>FW(Dwn45}1ufY@F#7>L6(9y>I1K>No#YMAEb;<$; zUQW3tcQ+v7(D_@6qm2>#Zo3oKie6`%?9prfg1{6h|z zVMG7)@qo~#h&shX^0*y@nsvaGh4T!wptP#u*nDx;Hnx4;Q#uj&x*>O^PN+>E@(U!K zG0lWWzOgJ|I5FxRPMkibPKqX@lW}wzrgOJzf-c zMc+ti!X0(1YJ8YBatzISMHh6}IuW6~94TJ3BWvqxI|a!i#yQXfhXcp5S14R}B#Wh6 zcINwzUY`g3c4T97ZqvZYU9*HbpCsW&F7id_!>=b zH=BEx1iX571tj5MCh)d)a}IP~a*Vg#nyGj1CZ@^iIB6NGsOSry4JYO7nuqmW9*NBW z$W?=G$Z#an%mfQHt$4}R4J?UaS zXz)G}jqJ$)jMLh(C>_m zw1%|1)H8Q)8q0UFjd*W$Mt%+vLFjq@lA0I7=c~@2!?N0~h3ljhjVc}Wx_^~9EvokWL2VHEv&K1-*VVCQGA0^a!lh7v}o_rTL?K9l3QJ!-Xw))4Vvft#H``% z1+0zrKHw8uX1&<)og%H>Y^(cT0rEnbCX3Kil<5vDx_V&3}(|!Q~q{wqMUlL|c z6ovSru03^3Sfr|N_B7h2*?G!eEA%v?sl%=1lWj?64MO_C*VScNhX5c#&;HLn$*7z! z_@ky@8>{j7pS(mbvUa{yzqGmxZzE^cpQ3)MO;MP4JhVv97rVPpgct5Cx1x#~EQnsYhu=j2k zDl~fGQ(f{&a`1L8l?zX875ooZYwr5ls-6_1 z|Kv`J2tD+NgFTdtN*2qCA*N<6h)WSIzLUxrNBxR}O1<)goyzyoV6 z`OorokfUBxelc&-VK4?pG>o?d(`ho$9UzfUClvKdA0J#yRYvSccoY|Ytjzpl31UE0 zt)#3rto7?@S_=`u-FLOTzD{&O3zNbOEziEmKMi=?MIigt7a5O5+z^KjK>eMtve&5M zD09Az%1}qAf*Y4=SQxkW<7=%kD)4e9FfXklCy7LPWm0ZBZsr?C{ziaD9oi{XqCf|bNc75 zd`{GP37m5nsGCR5HbFkIY$;uaR-pbB2VcM?RK}9icF=;+dcLNkkWx1Ri|=O)F9Tf< zI(aD{(W)tGNq%#kVGFNasL9ZJClUK0HT*04Pu45hjUMvmX!QPhZrZg|GZ71(?4iO< zSB})V1Z(12Uk+1=hnxg$YJHJGnSmK$jRDk2zTp*ZMiWDl42@!gtN>7`M9*gi6btON z)LI1f=1A-QWuTeR#njd90ht#sbUf2=?ThC(#>IEQp*Z2GtD#iswjq#hQ*Vkc1Ona6 z;E3CeUL!@Ru=TI;M$x&xOqqf;c?=H0Q50H?l0t$bwksXe+Na9r5s^L?_FoTJ&0zO` zS-;5Ae*Qf55*>Nrb_J)+riC-_Cp4TWh|ocD8Wx{h^YHQd-PGwy|GVp}? zb;f~Gjt9}ld0Llh>cGzn9lB|>%&xRuoB|so&7PF#s57AK z?2^^FjYL3|$;R}4$L4G$S4RuP*l94MP-%7QfnJ?YSu+|QWi}cYo;1@v4Y?(p-)4`5 zcTE<);p4$jvJ-m&KZ^$V6W#7_e`wqA+C9g$Vxk2f*A9g#ZBSrrKl{+q2!N6Mr|Q4i z^OC9V2HxAY%&3K#zieR-)nk_E_pgTHG|2uv6t%RalcOB`59K6f%(X zPNI_QV=E05YVQri80CzP_Wub^D*6ke6C`GPB0tRokHlkYC=4vCkAvnhZP4t77q~Eayxjz`-zD;gF=qSp(9no-8eFb7bBM zbkMYkvNtHPItweTYoZX?C{b?>LFMxhNdaul^=i#OE#eO{E8=WfX< z4#O@Z@$Y|5Gl~4j^x7Y!*>3NW!Q|*eYrKw=x}(I?Mt^!fxNV}u$+__R-mJO>)|9+u zh==v?f!OWAfR?)$8DiP>c}SDo6KjEf&Noz}wCozUTL-1Zj+bS;2Mc0po)7}P0B}G> zp{;be1w`^*35r~6ZHPqr0% zeFuKsz5%1^O4?lS(8h*x$2;1FR&KE_^0{A+U#580zj#FrAHI@H9<3^B30gcyO-XWN zG0*+3u4)g8S`NwEgr3+5o2r*xjG2z1b?{8BEr3t;L|%8ir1LL*Gsxk6HH|2TV5W3O zp|!i^{H{fXaW(PxC;LN8@5?9j89sV~hSU#Ow?O2YTU)nM`>w=tvYguZDqFDK3Ny@k zpPFM|WMWDl%eoN01|FvRwgD4$9)@0$ehs?dUEQn|^UNFG4|bNs%#^;u)ZIHT6PxgI z2>8SAhD$+OR{d5HW$XUU(nCM?S$G_67jGUAA7uU{xUZ2~GUhSo5^Pd`+PJl|=?Miq z(9z|?sc_55MjXL@LvYgeY?N86B$`=1uRGr4vM+u9tM8d%+d@k-sjt5`5m=xFE#iW8 z)5)#|1g^;6wy1aw-rX#XO$ail?t(f#Ha|X|ttQnaF(g$pI!pv*<^eY{IQ_HR5Y_uzB z{L1Dg{oA=>`3fCNH~!7^)Ls@ElKIXpZckc%`-96*o_9vt$Jhm*LsNJ3 z-l77_mO@0D{Ss;STv9((87rP>2I47N=VWK7CskZ-Xi8O(-6q?30+0Nx; zq%n5e16&GO3TVP<2q`EZ(et?u1*UyOH1j%(-9gW=z7M#gChV4wXlyu1p_sWGcqIMc zordPRT*iHvY|-q#tj?uG2@1u7BMwO8Tc^QT7Yjp`n~I!kaaHi4=J&uKH<6P%*8dHP zuPbA8{s(a1GxO%K4;V5XDJOR+e{e>08?4jwlhw@q9DP^&=6=_Y@S7+97ZpEhlfEFQ zYnmv2A!qa8Lg-m-OoKB-rYQ2 zODjVZ+ptV+5_BxOIn7y8_N-LBs?__+g&G^C;zGGSwAiPQ;f2DkinC@oOFQXrHt+BS zRV~kUsG^@5DCqW;!0Y0l+I-lJbJtmv{Uc1;mZj9$4$IW;Ufw%4iU8s%@Hdag4w`LiEJN( zN;B78kRsV#ro#xC_zkx5yq4)?(PVjj&_qgWQcApnL6AVctaKh`**JsQ#@st$_tUTo zCvfs(*n?Y`n=Y=>Mr%E`-$$GJleb3&3QN23bO$K@ZV0kRg z2RYxE{w#g6AO5w|a_(1}9}66nuJOoSe@L7az9u=#FKKdVXn=Qn9;USAP2&n+8dWw~ zyXV=M+9*1@srJg-n`SkH<2O_;=3r#;z698-l76l4WMC}EZ8a;vq|0a5KGCX#YEShC zd|)MhbR&z)oG^YppDn2qliXor#-nG&h&6SW7P6Qfk*==wb37Auc_5d=v*ae=r;+dS zc9Dh4KwU=c5m2<#d$46S%>x+&Hswmz5IpSkTJjHELA3ns#`Ru0aOF$hJYnIxLv9)Q zl~!`4@p~U0i)X4guy9Pf5G)MKna+?#aQQnZIaQuc;$-YP4)Hm0Mz>3wkMyJi;*X48 zD?u|1Yg8KNfr;%!&9isZ_uu{zuxhJOb1ME-Un=Ok2=Z>1Or0ZeHyrxYD#<)HJCdKv zF3~>h`+ZL{`AXinPg;%q$KxMqGaD|U+1ItGgHSI-mOS2qH-RfUJf3Bx%l9{M@}3eZ z@Fa2JxNG_4J?HdKRg-n9r`w#~Oa9VXX^+qw&8pMn4Xx4574oI>4Sz`2S|tCn7Ylug^DzRDF<{j|l`qbpR^CoMqj;FGxVuJS_sTUubKe8@&6Ji?RaJP?Q zY9qT3gTI`Y^lh{`@SSY>!5Jl0TU`FcM-(GKpbsf5^pGcrTdkfhIHn2h*990@&1qlr z9x6$H3k~n2(?#Fv7^vPY-6&ubDu9AI7Q0w5eOVy6Y-0^~lnj5s>@?t2qIBTt_ck3- zKBpzSARvOodbWB(c6Wf25^1W!5hCQpaf9&~$-+SsNFjq^{Ads5o&xU&h=QWzgM@;`I~2;9jr<%2)M? zc3E>)S4URD_6^j(>q@mT>-nic6YYxYN`sykNyuC;Za!ctFC*^o(->z5&AW%~%f0am z_SH$Ve4COKudD6v1lnN)wvE9a4$8w*v@0ncr-ooditsO5I_h)mhZJNIzuj!cWBiRx zQu-Dw^q4;Bp|f!EN;OiIcG|71|W#eR2Q3rK1oh8K7>hrbQFtk`XIAdkEE#J)@aq z$YDA6ut^^0foAJQt@vhqclxkK^WjrBYe>rgXFY=WZpi=n)oxI>)ti%-?!1Dxp+vDd z#*and>9y@Dv^^Gjnq2?q%luC_hK9@Q+isjHx-WDX`4@);-;;w@wZ7_!_N084yTdWg z%4{5{H*v|{CcAjiAsqUHu(bhB>g!WubBH5CaRE>Z5x^k{1s5699wB}R@$So_2g7}4 zywCKMVUzNb)UgcMz1dZf5mxGdDO+WLSmZVFAK)92jF zTTKQZ6&Jn3X`T&KxpIAe&oP|?bQdhf%?Md?vq9V>x!u!}dMI{`ejSQ_36g2~`5xS; zM;8MANbnEHt4@1aUX4x9bO{<-KlX1NRa}pCy7|4UsDThZ8k*b-Yi{qR300Ig+oF9O zHUJI+Ynj5Drv~TTwjpj@t^}HNrj~F*GM(2&{#0Aro)eQiI_eLleChTM-|VJ7w(I2# zu;m4_E$`PA3Ow4vtp#0P9_Yq78sKE>HTL@U?Ev!w8rWWyFL!%iPRnn~$N$9(mdv#! zS%^UHxHl0XzuC7u3#+3q<=$IzzUI9_XE1lZm{TwRdcv-8o`C5qE_8HBNXzA@swgO^ zq-OL@G$IE!XfgZmoH|ixRbFN|1kXJ49+Eg%Ipe5S2G8h|Nz%))zIQ-M!yWKI+T2{s zB32x5tUi4Qdy-LeohZ+pR~44=);e->8;4_Z1knG+P6 zt~I#dpp(WMS{Fon)>P>&8ItOFU5&f*>SV+Cp*zaJKvSx_kX{VVR7TTiIoXD`3- z%+bRu1($d_i=$vIEt{?5j~zLUrX#-u&tnmPw_|fF>&*|CEa18>jT4qDyxgf@qi7Cnkm_WrFP+w$wq=$1sVG=n?3-Bc%Q!yn>pLd7IDcv|n?r|rsj!es z%kg{G(ghr$R@@+&R|Sxu0uX!Kc5kz_ z=i>sy!2V78R*!(0hNMoe=l_eb_l|1vd(*u^6i}MdODIZHAan?jfFjaFdT#=T7CM9; zKm`Rs2oNMdXbRGs^w66SdhdkZTPV`R@_q9=GxMIAGqcV*`;TNLYo)B`**j16eP7r0 zkz=G%%$ag5ICfR7LN3#}`HsrUW~)3=o-_9RT>MGfP?h+T!SUtv+00#V)ze!tt>GA` zj0}^sB$|+dW3X5QS5b(PQdqiOL}DB2itlRnJ;=;{dJ~O!mYr|0V{Oc>z=MA?c^eOwxh<;tF-FvMl=^ z%b@+Dx9>-Sq@K0j-Me~JG8uAMi$ay?J|)`0q!XU&Uy5J;5~iLWDT0Z8x_*RpRaiwu zz5c*djillgdjPvUX<~cO-H`vjoaVR24gTwLa{0IAR1hzZPk!4){9E{FC~I_!kZyh3 z)4RZt=y>X#?VX)ncQxyI^REPMa5$~TBM<-m(BTY2d?BpF&b8~i-#uBiC|dQK(EAj= zcZuez7|Jw8_mydh&!k(V6q1tSK|J+l2h3mweh2iJiig|qa)RNL*~^ij_Ot2jG_Eg6a~`EIxV%}+nR_t_=qq0}y- zWDa?6-VF)|-}M_E9n({p937h&|E^TU+Qo5llXF}GrM9!-`Vx0zMy87=Vvv!suF1M; ziX?o-yNPXvJFZj3G3!)17X7J~Jg_4+0A1QG#fay-WlGyh zeRg#VORG^zS(&AXC~q&ehhh(bmsI>&t2SC*6}4l=#$za0KAO4Zgki)tk$4uu-&p{k z9`EkuqY!@pDq zR}nWBJoh~dUw_;pa?2jj?vIA5QxhS$8CVRwEa*<3FO zV11tbfe@KbY--GG7SzNFWs&#Mo}8@rDP28c_os0Bz&l(%2am0RU=s&wnfj&@WR>sw z|LE-{fuH3d#1zzUev{|Oysx?Zhj!kvShAB%S58FUaZZ7EFAQDZnv`VXu< zyUhEVZr1Nl`Tg$CP^F#FN7oY*OY^$Zvqzm>N(1KrKix$SLP5>Sm38kVMZ()lXKA>I-g#a zy8C`@YN)ahTINWPdP?9O%>Tu8a4Xi;$NT#aq5isCWv*NnBz)eTZV_Yw%I$(=F(@RH z8RPh$A`_H?y9X3F>M-PC1~z){0ET?6Up#kbYOQ<4ll)z-5^vI2i=Y0*r=6{`Tk^s) zYI6%1`wDYWR~={Q=XU0B$yer9O#QGnNj1;rW6l?RNCy z=#yb}PyQnF${|$hF1Oz7$4xR3iu&GKw(|bqZ6&#_;@FC=1EUA zjjnG#w-1yPU+_a|b!EfHJ}n5#^yHR=K1?GZH5VH>!o9q7pD!;&RdCyS#}V2DOZI*&#B6HyH-_f!5$J@CSBTVblQZMM2_)LSt~`QRN7n z68tqF2WAL)pZE>*p?xIyK~AT-{(YDz$9CGGYVk}E5uAFh(BETD`;~0#cE9Sz&^9R{Jd3%TkT=%yKAsOi_TDqnNSYqxukOJd zxY?{L4mSD-rJsDsK7Yc`@WojYx)(R%a^~%~~3Jpc1#Vhi2sDvc+z;O#Ay3HZSZt+B3AODdOJj;o&E@zM4t~X5aI-upp2@ zm|*}8{>S!XPH0e%@kigIOYN0|RqG1}UA<{7J%Eo63B_Oo;c&tN*~LH+*Mwu`_g!Fz z->Yp_2_p6g6t~{kNMS zQ-&LdO7?rY$HT__g@ms5dEK?}W8pK+%-4ZpnMz_&St&%&)lUkh>{nGOrhU{yAs#`F zMsB?r+=qV+~dB>_7rJ zmadE!lU@3=?PeSIxze~uW8;8I@uO!fvf^^J9Y{|K=?mN6TKU|}+npB^@*(g^hb^_3 zdGf@R7rG3&@U4ObbS1u*mu(obe{@Y}qi7=QFprx&ds!D89WdV`VQC;_)xPs8woZJo z5=+5Z(40(Yeyu){CX(`8HYSJ<%E`vZBHt{9tM#dVX_4Y$o^48gg5O^_|I&OXW*=Ec zF?bd5(cY8ghJ3KmY+ua)FN&hqV#W?XqogaE8u;?XM>dakkLaiT7Tv)x-Dz}S*94JEWz097NXE1P)okyYj{QI*W(5$H7np{jK=n7cYcw7NDS>$Z%SuD!ZT-HRCQGU z`q&)!X(p=mJZ)4kMFS!@g{8OlHp&crL`by?n|lB4z- z%uBLr-d)Q@s2=Ll&yIi6{$AV?Z@32r*?Z2^*Dm{9J>`Vgcl|y{`>D0o%T6|aj)(w_ z$MhbU7)y_w5XOVJnqfZB$2VJoRB=EA*PEkbmhi_6#U;8= zOv~}N9rxKBoSf^mJo8SnxPAzyw{J(995G%vI$1NxI;JBW+@JY8-zKDjXuV^PoKV|= zrHAZk-HizSFTjL}I;n?Cx3FvS{y`~_ytv_gKX-=IxtDv<9YCc=5Q;C)B@TV~?&=@O zF`wXQA>qc+dEb^#f%R9A*D=h-4@#HU4u9}8AT@x&%}$z26rt4rkW4k))KC`o_l18x zc-{W$w;nOcDpUuWH6mLBQU?clg%G=Bm%N zWS>7xp*?i2%NM}VtdzXj#<0>ll5#yBdfT6&Fr6WFak}4f>M-XUbXz_p?8+*p~G- zvoAj*1vZBSd5Ew0^ar-PX7kbR%;E^l-)6aG?>(VVbaazYd&qi4gaZG0{Fp_0FWxi% z95e}?5_IA)8J5uoy1}U+X(Ysymg=VA7VgR|(_C{Q4I|(2w0L1)DK;R))@`yW3 zmGhY&N4u?J6fJD)j+<>t9a&%z9GmqmA%Et%_B0Cxb1YKT$lGHVafv-y$)BIdrUfvk z>5Va8ubQnRX#t^BKw*We>Ih+}iw^6m#Ca)YSiYrm`2xz=FR?xdTnIclVgX#qph#t6RiGi0j(17*zPc3cMBJN7IV2KAk@IT0zHO@(&1uC-M>E zf0U~mulHLVph6G!3%pa+8*sEE)SKFwinG88O=4k=lNl*UV=ozFg&b^fuChWM{KunA(0jDlF)M>cu#r zZV~XUuZ49*Qycw=K(8bxh*D=(XI-KNz<0Fsvw=);zN8DkhJds;Bj!ts95ZJ~+qCa{ zEjjM;1>{ewfwc@diXxzn`xbJf?GLB?C!%^+vs9wx4~QWHS=<_zsSgnK7`eCj55>`k z_j<4Tw%g^+kc^_s4QiVH7rQIEH*Fja2}|Jj*j^LKuO)%@Z83d`p$5^U*s zBfVReN{b5EJ12B`Bbsin1Ql7tdUk?l4-oko&|1ya5^(E~TtR-QK9@L&ZS2OTY)pSp zZe|l9kT;w6y+6ixda8Xtj>K0xG2fQ;z()>ZfD$|IzXjGh#b<>XefSKH!^*sk=aFtg zD7N&ghBW()k7~fQZgzbTWg{ESH#KyPJ<3<~a2QrouxQO!C;NwlZ*jC?=p~^ZUR`c+ zJ)4Jm?W|Y+Ui)WB%;3-g0L|Nu134(42GA(Y&^{eYkbz43MghUGj;g{ySI(6n* z=S)S0>B**sk(QH{0>T`AmYleO%2T$*t|DSAe=(&PQkGp@7>pf#pKT|``(cx_bYlo% zgM^;fYq!VBA&900AF%|~bTs86M^{u@P@DOWFgme);!n0>ZdvW=x7t!5+a|L8e_a^= zgzkkUcJAKCjt*#@Z4yO zn4eG)h%AGAHq5cO{2HV1;69hDxDY>~Y+I234^lu5ZGM2$&{g`(Ms zRzG@RF?y;)ng$J`pNXyS=6!^?c;S)BC?k_(qQGLY8FLpOt<^!%hjbb4Zt^#l+%@EJ zZyD{e2s|(AeXM{Y5P*2YJt29AFZtm)UN|Lxhp|}O?Mfg)bHTL?h_bLyDwZ$a`)${} zO}|F^==IGk)7#S8@G_5zdJ8fPH!)m}AtGrcCI!J~kIrN@VFrr zku`bLQd>S)KMTaf+=%iV8PW`P{e10_?RUCc+7(*mik1)CkIl(K`aLow z#tyRgsuXJ~__Df#i@r3X!?22z@te3P#zh%Uown(~5Wl+}ygFOEp0A0|FzK``It+aI z8g?Sj=G9}^P&g>7U2;zI(MX}j@EJ}a^JGgoK~g=Xw;mU7Jmn-ju_P8y(0b{G-t;X* z!8QWn9~2`Ju2Nnnf8_L2xs}5n?XX;eBqwhe619`(q37soLv^oJcM&t~l==x}Q@VMu zy<;t`y#pL;4z86+lqTRxqr>rLzMBsVSmrs_e^2Z%Yjy=3fp z+PGY^>U%2#rt%*A?|<-D_Uc20b+X}SxbOD#`3ESv-wXaz=>5;|vr~P?< z1SnW9=P5@%C6@-jju!os=F7n`ZD>m++!Oc@Nv!(7Q1ZZI{oNCMKX!9O{B(aB!8++* zCgxX>B{4anuO)SbBrW5+s1SI3Z*@R4nsB;$avKfj6c78~X4Ui79KE^Mnl4mTbcK}v zHh8TU>=u*@r$AbX)6CZj;P+bFMOg~bsoNCvf!|1IrD9p2oP|;?GQM+>xSFEcdIJMp zrAu>zR|(qskf=y4w#>0v(ss_@{WK{B1h1E+zMvTAE##eff1_t}7VO6}HFEYhyu1*j zrvKXX|7%=r6T4F1$={+hSMGYpXl%x6GR7q$H?}e&c9n;Sz_m@uIXUZJ^)e8GVJEbL+_=__2dVoEc^ehWk6e8DOKdi z*q!5pqa0|UfJPD-cg1!0tJuzNZPlH7HFtTJ78mS+pzmtLSt#U=7?Mz9vv=LU{;P+; z$R3`*uI^Y|RI{Ku+$igKM+I!RZ@t(`pgH>-kI-A-n)Jn==$Y)M`)8taB(E}dZy652 zW5YQcMw*EcZI7@s))(+s4fs7yeRE^AImb_Ls4@^k!UIU;dozARgJ`iiqS75|LMsAe?WiuC>vJi`hB z77y3{{J-YF|9I2w=P@c>_o-EHUhMLos*IZsTAphh>I}ohsyB=Pyl`aQ3+Uu)2HKXoKlo<%nXV+96|-I!NM8XNIMZCXXW8Y~<@z@6 zx|Sm`clI^m*h4DgC$>%2nY=3n2r6p^d;cFxE1`Yf8}e_rJ8AH5{@+H#2Lu(q{UQZ) zYlz~*h{)%Se}7rTDi3wio4X-U%mqbd2hpy{vvD^9^`Bd2mayc z8xx_1gKStkj&6tW8A#4NwQhbi%enmizV-Nc+|abf)!)fg%h^mk>>;Hn{nQ9pce-Wn zcHA;*NYv=lSkKTblx&c>GF{7e@WLs?KdnvO8VDA6zwTqZ`W@7_X|1GPnU;~v>t3I( zJ#XezYaG2P;Yp55SOH@z1Ol}d9`4%@aN1Dk#87>&co6)#{fUTM8ee@q>S`(fTFdWo z_4;-87;xrVltC>-fVH<^(bb0()^}thEK<4b)H`5#uvb)wx((%2*~CE5l)V7DFyl0{ zk--@!bxX!1NswXc;v=zC#L{Rb+T^lac3=sst;_N*eAJ4BOM+Lhm#Onb6>5=n6=|;N zk-9iLW`Hkw8ub1#{nGG4AviCoy0R>-#-L6iIDF)>$e&5>eROY4OHXuM*%U9!oaiWg_uFoq;9`M|`Ji4rkax}0L(J;5v@|rxTsDg(j`7M(0gc&K)w-QUucZ=oqg*P;x!%xy3N}9w zZ6DB2@wjB2JHm@3`1x)MMcCl5O^IC2yetZ<&oXJXtlkRJ26yo1j*2(D1mu3*=qY!{ z>R-{lo3Kik5_B>LAeMHUu_7;*hK{O=k!!m-G)RH!z`&sZ&*Z1l^%|HypdVWIPGVwI zC4r9Q=rQf)mUcDNW}z0?{M61**WxdK_iqi;k{4&ic8!*zUeKTd?}b^#Lt@y{t4221 z7UoXMB#vwK^8`XX_!wXS5PpPH+A>a&qzR_4y3H*9+O>!b4Tks2L(NXxF zVdXc8E3)qOck?jiLMQsM+Ia7i%*dcSt#*WJmMwwW*z0_6u1lUHu|!Dmwjl?%MsIS^vm}YhQ=`a{K1Rdr|A?m__)sgnq0x8!Tv8 zc?)3@&_*ROAv8Bs_0ilwHt)ytY0Pk0Q^8^2@BO*5)!$iogxy@0sk2Z&tBQ*UiN4koJfT(oKe%B3$crG77!`Ke0Wk&+LsG z*2>3Eb7b;rTUuQCw4bz>BU*GYnW7RfEw!J8jQZzMNUuh%dN7lp{|Sxw-bM(JcVCxZ zvN2MsxKw=BWp9tVwFUnc5M?HDMQ>e(7X4;Xa^HEW4E^#4Z&k5d!<`+TZn>z}fQ_3G zCn5`ZNiJGUoPG#<^xh6$G2LQC*kNl)YuGe@H|hxfa7zcoVC1 zn~(0w-OC20h5SQevx~ht-s@BX^(fNOu>eMpE=8Ng@8qlH2k#xlb5MX6_t)FN#p_Hx z0)sp6ZKmv3K%{r}Ds(*v>7Vk>??u~4kx|lk2f#X2d;AUYMGs2DEfhXbB25S>UTdMp zr`s|69YcX|VnenWP#>jKv{+P&9uoC+TdI!UU!o2Ed=ah|L`?46YE$10lRySowPXj3 z|2E{(D%TlQ2y|UdJd=_Bp>`5EM75Byaw1b&}R;Mkzb z?Alp2Sm2ZB$H{7RP;6VB=ch5p=F#S&nIVyB)WH<#bA z!X}89zkWwJZ$i9J#8=nrgiQ?aTgzO##~V{Jl|?-k$`CM(&SvSk4!nyReO|^A5|Px>}b)O9vT0j(#jSkzqVLxZ*T$P4KF0b z3-$Y_fc)af>ceY}4|2kJh8BA^TUIIDj#c^PX`#Aytjg`RiO)#h zH;_f$N;96IMClFIfZ}}$e<~{Rtx!NtD1~>AiQ#j_pz`iBzX-jZpge5nh3=}TbCw7N zX;-9%Y56*WQ*wAORIBP&hNRqFhU+WeVSBHdw>)G>O*yJM$oS7!C(DiumY!J4l1we@ z+mRZJO*{}>l5lC$5#V5)nBKWK#(PRf!j$_ip~|B%C!ecfF)n~}_5DX&+{Me{nO_>w zl^xGkR-@#vJmh^|hP_bm-G4v-pO9L8H8It%Kh_V1Z^`r2?ImVP_;H>YhTT`bm+-s{ zld;3Wef*H<<)D85@5<5eJBN>d|2q6_p;V^T-NpOc3jWf@@>gt|VES~}x>%pE;Prdq z`qZVo!9_2p8@h>MHpOkgnZi8GH#D1I4hr;aaaQXCKQ2p7ILqXsbUWL4>LR2loW-!7 z1dEORmd(g8A2N`IFGT~{V}vMQM!SFmZ#W=ap*+?b(a? zGHH9$9t?x;G%Ya8#7$kMm_C2qq4E)XRS-3t==vr6Xjt9gnmsI8zn^k%V_%^UWSw2A zSzPaZa`DqDfOxU>Oi&baPHK98i-SW^#abGLO>Aj}&n7j_6}TSyax4rN#4BFCXkuvc z-z_V^yH7Hn`7!D#ysxYSQNE?)p{8}Bs$EUt8r0DewuLPg!Z4}bkW(W|GP$E(c+1Ah zoy`<-{f2>BA1mc^~em152=?->C8dxDEu^=z8doW-rR9| zZDJgE82r5O?AB>>-Q6C;Zy88xMQGsf-I_{HcMEhR{Y;#sIR0-_&Hq_6Kr9Ik|mTYtaE zYl#a8DMibUKi_E?g>@VZGw$JK7C(-$X<73X1hfo7Bn@n6rb3BymAl>Ad`%m_5`r46 zs|#3*bJ6M;pI7m$+uxg-gTztjhb69GVxC+4khk~lmmKRoh8Rq+83%CMXfoW?hbWm+ zV`;TH_oeuEEd{4SjW|QTpk#6vrQVQDbUP6tyhEr(=i12p^VB|GvNZ(WA~064uEZd~ zZN3FF@a(cNyf!j(9b9z+NAz`~V5Rx9$;1HX#g{ufhohMB;{#?dTE*t$eCyw$ip@nW zugdEU)HS_xe5GVQqvdXdc~BYrF{^ZIHdwp=fl5*yN+rKghuvtJUu4dx#q%Pc$H*o{(tHm^ zcu6X0S813@b9Jqaz9BU&uO9&reP9?2DLp%Eo?2Ycg?t*!UlbG%Cx&|&asaLJvdn3- ztD9#0DLJOPsJb%mZ)Uw#xU?&eGYx|TS59fH^$rcA)RojfBpL z%ldO>wKavH-al7}cXXN(C-EZg+kaR!v~bgO?!meye}l$}tJ=OT96z70eHWk5g2R!& z6ucGYaSX&;)Nv5Rx;8$zP+9jKKzqZl{MYo3n?$KPS zu*l^;RfMQClXTvQqG2B`UB~v?c5j<<*GQC-qS?!lrtZFYQ7MS%TKL*dx3t#~2hXRL z5lQB|ySI;o&FvI3^NnFien&lIJ>JRv1HwK{XNS`IOKTxeuZ(TZW){f4Sq~J5$@-F3 z6jv>cyuU7-{+!pTPEW25gO=;NL_|=rIh58cu@c-vb8}-fEOvJLZo+#^@)nq3=XJsT z#TQ+w&v&iJPe`C-Z#ML9)gV*XsS}5QH@5}v-?L`0 z2vFPUWbzDW{o`LeKzhlqwOP1sD#ZbQaQ9eVFr0RG&2^w&WL~ugdizYaM;U%Vnc5Y-U5F#VKjnD#*GO@3&4&*Udcxo;y%eoM+=mk*4Y1>SUS62|;K=N< z#JSsGGz^|s0OehbBjX+=u% zS$zsu_Tz|6r)%IQu3%&(T9M@+lAfd27q5SJUvL}$pF&~A86kGzOzIjCyN1xNBP)t6 zl?xZUeUpmVgudkkd zrv&4@I$7G4vA0)u1OB7vH2vqnfkl$O+nNQ9)U>9a5F5WL#ADI-_|3t$fD@oUI3Sc# z#F|;Ur*y)?e`iSj=9%v~gT$n75;xmB3ePrf3r_U$pW%?z2BPThe;O`j4Tt2e)E9@` zuL|$kR7m3PW>8=8>4t5aBWD;AAm1>D4<6#*N=M_m2ts+LZ-{OFr}o|sui$;@#!^md$n z9v=Po?`{XynRm>X`z;|$aB(axv1vS76Rzw)QSZ-!~l5qTMWW0Nq{Vh>gYG0A(HBr+B0Ejzi|Z zRM-Ch2R9ve3)@98jxW4@nP>zDcm96jsDSbYII!EkKAqKFddKGTuWA*wA&i}v1mG;} zD`Pt6v|PB%II6-1-vahLIbdA^XaYu!+!l=0%cMgEawDV9yr-1(db5t#$oSxr8e~}n zJ$vW-t%kTU`wWpxLy;kOW8Pe=pbn*EZ@uhCi(*4;34>>MAdwZ#&cZWAtYdDxf{d$&lRb}`!BK+wOz}*yb0r!T; zUt1b$tE$U5*q=;Hbawu9NbD$sKI!AjQYL>p9s0lp=DKt!QEW&o%vrcA0nU&xq{ zlliO~v3Zgb#!=RAs=fP-ji<=BJ;X9HU&%qeN!Lt=edz*ep8H6gvw)sOq7gV%Ny5g$J3Nb`0_>U(NH0W zu7)}9jiW_X-RJk|{b00?5Y2_*YnlXdr#w2+)93{yk5Gt>iTIsrjuzv>!ngjpnf{q89`LtEt zWuB44Bzx4P+TE+WVt_sDIfXxOZf=Rh*a5 zXKv#ew&4b262#N%-p2`D&Nv497hosmi}%fb>mfi=%;U-tNQMcW)ka?V`%a>evSaKf zZ!7!l;7F8Z0@1rS?(LB8;k~Tu5o7wQ;mBSGHewn_u#(SPt;s+sq^nQ^k(3St7D{bt zRIi29g7;Pp9(}RbWqgZ-s%T;4vrcQpQ!gDiUDNseRjRDBo}5~_yO)>D^;XSaRq>Z}Ey>~8pt=a-60qp##Wv|8&^HyV~Z3g)#zrqsC5x8aTlT& zvg7)%#T!+3rJa3JkCoL}|BbJQ47%ttD3t>Z0%WG6d;q(eDA5|)kAdmkoJ7XgqLx-#vW!)&JV0ZaBmJ8jXz1 zS5wv}TkP&W9Hz_euXcBNRgpXM$|at{D+0HM^B$mcu_W%%!~c|h*`Fu3c;!7}+_&^n zSnkjzJlol)HAmK1R(*n2%$FC(i653k+t?F@j1`|tB3aUp#P8B1+y&1q@DKS9}<|-OQC((>g>;>+EG6tU$cXPNH1!A!yc%Ot6pj@lm19QL4D{OTM^JWL! zuLj8xhTa;gHnj~63Y!$S7LG>Z^L!u|o8ihRVp3e($UlI*8TVOBT$ zJy?gVEBC{O%8yyd%(arv8z7M1jHwrv0mdwxw*&L?_r0l*6fvDXCK+c{*1lnRp;FdN z<@tI#%B!&ch6E|DVtMx<9uiLeO*;0!y`Z0ZWq1H0g`OJY| zkYq~UxZd&<1OMVEW1@u-l~3_>ZFFV193uG~Gp<`2Fdq8SUzOGF*jAhXZYqeROCej= zmO=PeZpmix0TK>iTGc&j)@}woZxGNXs2VF9e5yhQtn)z8tO&Kcl zEZKW|5J0_>l8wI?%A9|~`<&+7%jYQ~tP5xp=N40Auf-S^sHfCnw*5ObT80HEN0ETiBQS#RnZ5Z-mu$UyGH3XEEgjo-!pd6B!i z!OQ@M*$Uo1u{~mL+hoVE?%`LjqP;vCc~;iNJ22V3xVT&;26bv3z@^+3t`{?Y*nAVLPyhZAC{(Q_v|Jk+E_&lOF{)aSJVeI3}0OE8*0aZpcLlOO_!o z-hi2Nl#aLGl#f!7y)h_$dghPO@Rd>9pO-QqP&7F9O%&%Cis_r7iSC}Ph< z7N`8DcK7|J-{FFD3o-|?2C4~-_~1F%pH?F(E<2K_Nwrqz6Up#?8T{19P0iwG!LO%fD8 z`cN@&iCvnX_#q#VQtzDKhR@5(%1Uo{5t>~t-r|vJmM2TvG)ps=sb@>6E|}rAVgq>A z4oPuJDSses;pXE1{hH#{v*}+7F53BxabvP9evBht13}W;@sA%`%Uw0dhkZX@<}TRW z_{9)xu~*~}H~NtnpaRb%98jQ@{I1JyPvDU9q1+X#Xzz8gaawn<>u$Cl>m2#9>(}8Q zS8!Hq&bn`|f51$8apyXms&3kN7}v_%Sp>p3c4-F}^rbj*-N7v+ZO3x~?s z(&T454kAQ`5z_#5>2cDd`uXQ<8M~lkd`9d=Nfh(TEpr^g*+HIygm$W=%gxaVuw6Gg zF(C4(`i0g>Ry}|g60_dLN3gmyHv0CYU$D-?e{lP*3QhvqUN2YBr093SrZNixVWuxc z6EO!NNKp^-k)}%hX?w3v-#H_?fD|z!jTLpFnnATHD>bIKKflXBfBT{I2@BOsj%m>? z6`gTsvMF#8vd3hV#S!C-7OQDt?L-x5rq|{gW+5Mt(q;5mOX6JnACfykAGvl5dPcrC zFJ>ACv?wyl(BxH48&xH4(Cp=a{+`)sf|k;aO?E$)R*E>HlS1B3d)SVEVjwgV(QpTYeK4|H|2S zq-2k10*G~cAMdDh83vY^El)Jot`Yjez$>A6;w=V`ibKiM%5|cg%k%dis;bxk)Jb!B zekg?rTNdT@7ntFu!u!-s8#;0qZxmR+Oa?Yt4l$lg4Dc!xc%jrC#3sjEL;XCLx&Sk+ zvY8XJA#Yt_<9o%E%v(mP=BxS|YvOFUps$zyc3NTYVz&3kbhb_k59}XrM+RaE^mF@^eGG zUyiLr7T)$$Q>?+a79rMc)RUo@*iYmR#9cyu(me?HIMBnXWA$v=LPXz{2^TSQ+szx*#T83D}+fw zjRsh=t&Y?`x?j77=}=*OGTFyznMH|^^cg<5rdO_#mC|;r+?O@QQQALE+fu)fCjI_1 zyav~=I%?GAox|jdx_Uv!<`zdVFDo?nMBQ1p@Q^X+?tOB&*p;njG)^RLl`qmsfZqaL z0TgsXcZ9n!GyYHxYZbsk6mXfdRaK@<;H=K7rX_VE#zpH%KK#lr0V#5NqOFl-GV9Ak zHrKMs@^DFKM-;!lxl!SZ?Z=hKI(Q@ZE+?kdW>uPB)?9rLzR@FBpKJnhs`uu|u+R6R zShW8`1@{P2#c1=s4)Ku{V%uE2MdWVqzi2k@aVhj&ifS7ue84nmFm4!$`pF#&2T&wC z#a9PiI7;Wnw)@wR%qew^cLTMjYb7EWje-)K_6or6fmpvGt@=P~BvusGQ zl?H?dRWMECg_A{$YkXu<*f>mers@04!V1ULXyIKAA=w{%POS3Tj_SvbmBfZR(D08* zp-mURHJSta-f!dI%w=EOai$*Fu!v^<9f{idsSsSD`(8>&NU%`))7kj>&+FV{5FC%u z)?8|O)u7FwQJf<#^*SI3A4R8t(bifW3V*1a57m0F^3C#mPBFKd^5vhYs_`iFxB9&` zsT8S{e@HMA!VLrzyW^cePL4>>{0b2i`VWcBa@3@ccWCgN^@VwiOu?N_t*U=-YGq7{BA);T#-p1D;DUusUy^(O)7^$7Junfo3yUa;@6 z?n+!zZz$JlvQb%1vMmJKxQ;^#0VRCUUB|O+Rs6x5qI(!@;_f2M zMglOkA8wN8b9?9dPaf#5-`H7Y|8dhSRU0ePb zB7TpSWaH+kteAR%eA6>J+QolJZYCYqYROJ&IE_fhC)7Ewdr^e`4g?MCm=h+5$Rn36 z537Y+M)dVG!+{{qtf$P5n=hxL_sUXtKYj!}diy2u{V=BqnQp=cmsTC5L02>YY0`jo zTf5ZNm~S$V*(Ccag8z_taXbQe15ODEs;t*BMGhYb>}px77|Q^yAqgWaANf4Eq;!3D zMYqPb?mYjObSXns@r zL1ETI0YtVG8Q$_u3bkkIi&8($TYP5+@rCZ-^{p*dwFh$gpr}TTgK+ibsMP4nyKs8`1>N5!zkz8o*qVBf9$hah!qhdY8Uu z0%KpllfsK}>(?3O7EcSwhH2&ZxdRfPI6Y6F0nFYYL{FR3y(;;H_*dl;oY2)u$Ng7u zRr%p)h&K%k{(*!Vg}CebYkIEE6NXiYEHF^zE0qf>h}2A7-jw*ttxSxF2Tm^r*Qvm3 zrd7<<835 zJg>O(CAFb6p=XQUVr`tsD z(7@Zb8|AZ~QW;0U6zG4M%?rOQs2?)8^r#Y)>)FoQihA3!qm2GnGoaq40*#>Ij(l0} zi@v(ONLTntoB=O2_%i`&)MPd{q-`3ZT2hwtg0Q8|40`OgLNOd66=}8=outCc7q=o` zVMk8y5hL&!&I9-;2D{Ut~$mxTWWSz^go=0R$yT#qu1rEtg`#l50Uk zLvkZalOM7ut#lc3O#G-D)L}EVz-+61RVIOwdIg`u={oh)u6Qpo5^iPX)QH5yzJDdB zFs8UBw@y60-p}(>WD*G@z&5CD&pxqgE~pK@cMAU{6!98;88OswiAZl#pq?J_ty_9% zZtYT$U!M260exF#J|vB^^%>KL2TJ2Ed_}u9FXp(m>x8=-1<3l!ICV*P`L6Y}-Z2Be zOkrrq3SBKTcYw)~Ai(JZZ%S#wr=JylCbt2>7|*T;x5eK?Fixhcjb8hIIhzU9Qof}^ z%T4vtA+Z2k`zCRh@?mL{#oW-6W0!jIPC74=eg4grB%-yDJp$w!fdPzD^70^6DJGd+ zhl?iAE`^Uo1B%&QFwsO9xsv|0;&&ngU@b6lHlo^K56qmN>+W#9ujTn3=U1M#!jiRx zwEvmlHQt!jRqSkINtBq+OjQ1g_YLAG@9|P5iFkK!IsfD9b*`*{P`=zF+;~LjK{=Ur zwW0)7Bw#^X_Lv|bfQsOM@}rkwLtBcahI|w1SxKX02Q3z79c>8 zqJ`k@?(RW~2bbWI;10pPbl-gEo^kH|an}EgWJK0lne%<0C-J=a=pum(;L2vaN52Dc z_BDIuI@>yV7n|2ro*Eudn;j7fW;^`pNq6|-lxYy>9yhkvyH_Pkm=j<0;{4qIMevMB z&`X&NaBsU1Xfw(;gVQ5MuBq@@_%69HW-9Wdg-YuG<`=nM(f2WQMTq{;e#>LIL}7}0 zYQ>Y<^M^}0^GcU8lZ8Ic?7T~*mRm$qThOtGp^#XK1s9tC5MdVUfftZzTycou%=vU= z?C@Tyg2zSrkbEVB=!0tU?%-Tm8Uh2bluc4ulk_6@P3y+*L$8^Fc?c&xz3O=YU# zKj%#BbsF!!I?d`R(~@8T+ur^}3`C2<=0XMq_N9K3KnLkei#qHt0$*3aC;|cB05O<% zR6apiE10GN2G(`^_%J;3`nV{I_!|u(583V(SN&TU3 zAALxa_KQ-C(|Ea)i|<9#x@@(^|6b+clmTz5nx-d4jNTN7P0F~gVw;~joo1ubc<0|C zR7|>xZH`Z8rY6O(1>vG9z%xTb(m_#L!V|!tY#VNq_kTMe=nhDVD^IYGF~xDEZmoyV zYnjjMB>bjLu9Oi!fe0CJPTqoXZkZ!pYaoMxzC`n&V3d=@7?j`1AK60Wgxd_M3Z83g zb&(}du4J6{)0w;TB|RHi#g7e?JNlugS|W`6zK~DBSP%N5W*@Wh$9#d3ueII3c@3lP zDBEF?m!BFo&5!C~pVtM$P#VKQhQm7&~^9!y@!SLy}r{>tjKC|k+t5Y ztZ0~`yik?({{Ou=*;ArNjVrS&8n`jf=uHrj|L$l$xOD&hsDLW{9zDV0{340(r*zTV z#FOzH9;r`rT8HC$a@sHZ;Us(XY#&|w#uDSar|3x=$H*DrsyTwR(NB5OKkmAaN9p$dRQ2lJpVm+@xn-pU3#`i>Cvj8 z7x+-Ft%nrl8C!YHP9_|ul7C}1aGl<~(kdmvhTzmZ*S6KLvB!*`C?JKep5ITF`~1L! z+eC7!D(MY8(mAKOPyA{hr7kpnnfOC7t7ykEsH?G6QjK-Cg>Hx9AMd89xJRDH6(p&RU4 z){!v>cJ^BCC7(6{nVtK+jOoB3d)CWwvW~gBOb^KK+9g=x;W2S09LyDwGg#EH!ok2sD$?KFKD_B*ol zSX<0$I5Ie{9A@oDJKeR9Res(V&%31VcD@!71@aQx+%x`Ke^K}??eLB=bg=T>y)RE_ zLEDsar|qTl$Ej$;kt}tpiyz8sbw|=gdu^|LIapg~`1Kq#XHb$&uowMwP?u4+jm@4| z2l^%xXCyGV2yWI&T`XvjVlOm88(`VfX6u^&?ikc#;=vUN`nm# zR7?h%MVRV?(;c3{F+dtg9|vj~B%@@zLt#^g(@*2ZFXk1^DOUUDIS~Pqfc{Rv}$1--*zj8!J#m0ue8DK7Uyo;b=-nqM`?) zbG**1e%{|23TgQnrhnib)V{o;3Z|;f{rB{eV_4B%VoZWYvJT03+2%BKV;;Z6Ta}$^ z%`?ZTfa)Hrl~X+1qm#@T#dqwegn1Rd)%$6+2jFJ=rQ7M)@ zpK8l^V}dUH3m|3OPa7$TV5Xj{yy}sQE!RuFqbj;GfpT1ECT6F3Xgn7Hhe*!soEumj zbevN(9vp?fPkFY&l|Fh~lGa8<0ub9+4o1Jce1|S}FkpF?_K#lc!Oh9-%w&@tYhzYr zOz^WrXUw6DGU-D{ZApBMMpzn@n$Bo$1Io_aqLyOa&c^_=ha2praD^p$`7v(8 zMY~i49qjjgq-;YYv_)L~jGUb%!y0tPtr|xN7(R3p&zU`N+AvHzFH}5lD!Z(RNld5V z8)J!5Qf!#PxsPbXDhjN3knFFG1sa~!g4a_j_;$jMM4heOnARz^pD zkJ~3#7e>`b7hV=xU(r|hJ(Ue?Pv{f4<;fiJ_LBb$&p9{^^z*d_t>JdUY+98RKZiLE zNOsnvbDKMqx5MZOb7~1fk*49sF+-VauI3*dO7g=B+QbLWd?m~G?<;h0Znxb(dNru0 z8$HVvifJ070t=b_U7a$(a>r0QqoA@V2f!Gkt%9#doHIo>9G-av380r^EcFsswYF z@Gl^5-wbDnt2sKw-M&R}Y;}2xAa0Ymm(Uac;eFmrC^$ig5Ia2I@W-)`m24c|HtXuj zGlO3`j!f|YI`GhVC)(D0rH|(colu&34HZGy_vkK9v2mML*FTV`%9nh?UY@0!+;~Zi z8uV@I?o=q(tqY&*vclq`(5cY*Rdi>6^D$Aq<7$DBY2bck{mHP#d}qF-;ev;xw{jKa zwlqaso0a8-tUiOFRs@aU4s@`W=Z|k$8XQ7*>E!j-7cdp9#z^lh6yd}A@l>I!Z?c}6 zU?sNc?nm+c*zXFdPk%)~ez+Y@k`1D;wg4j_r~a!a*rUwnhfD+b)Ir;gO&Q_IMZ3FM zk`a@_NVFM3E^Ru_1@tuixMlD0)yd$%TJ6v^8)b5r}Q_v9w2>DPMGk0uG}Bub=ht+VL^)m0(Cu&R{Y z&etCi{F5OReOHb{mJvg+-*U+GaX|dFo3eR`du>@+I9%&cG8T`?2kN}CI&)V8Zk%v^ zsB;$nWYd(^IkkonNn+uNi+Y!ib>`)kYfx!-wMblKE|A#SA6fqc1#a>*pA2sO8iWv6 zHtQ`P7<1cJC5*eDr*A~Aw<@uRNZ2{ziRH`_oK!HeK|W@fsHBQwPsKFAJkNfYc^BZ6 zAN^+=!!qV=@7;b&9gH%R?HAuJmP#vs2-`_Pi)#0MF_)@dUwMpVn5e_f-gAQRN3Emd zL9?fvWk3IJFtn`Jaqc?2?vn2Swo<1^@Rmw%^sN@8{gTWFfebAMbJ)Ct6`Hy;f!k4G z7E5$-c0tNRhE|21#SwjsN{-UJaZQ8i9N3Ow_xS1ReUj4e1-22-20r6FecN#02f`DT z5?3YL#XZ+N!T1L^DFLThdl|xvzW|Jbhhcmv3AgJgf2(u)lYWNn6b1z4JBjA<`y+?o z(7hrh(4#UH>69AEQnm4tGXl4CX(96~i*fgj|Fd0tk}GfUyKiY*)&+=@jR)K6Zgixo z_q~1dghZvbCnM9~M<8XlhS|VlaV{AZX|tzbYky=>WSgKAva(>cE9u8CxXSQ>c^g3K z!t=psg+h}pb!h&mDmQ?7`ZukaU;4AHv#KE*%+&DN+#UlpENDm+K!r-5=$=Q1ZP7Z4 z-6S@|pC87#fSvL?G?y@Q>Y6XROXjIG)9aX4i8Fh)u^g;-g}=7QeZ~r6dURD*?diwu zPieOTctx+yO~yg{XRAXSKA0-d0q#=lvxVw^G|O=&_N|Sd292CKSy}fD zxxkRJ?!$%V#0NG;uF`(uM_9f0mUCqsNw4^}FItB{a?hSz8cC+OZp1f?sYDvJsLN4A>++mNYSKKj%E=-}q&r8g}my*BNe zVTeT|$zIB*A?VURaU^q|7~{9hzNKHYrWvzhwi{b(+lY-JJuZ)hi25lc72+858s=;u z`BP%Ft86N&cqMr+iMow1EiruBRp>ju9JflwNH=O#+PuxvseJjJL6x9By^((sCx>;W zf+4Ft38@Q*w?NrTCmlRz^eSrubW+my$p`Pf6}EN>NX5Jfs-LW7 z7i%*V?>{-OG%#F_Vc3eC9>r7ojS%sZJPBA?Bl0TA$k_cD@HX^rE++cNlPL*Y7}s5Z z(zIY~PwZ6Z<=>a5`Y-ZrV@By~=N_z(tgdN3KJTbrG(rjZ5|Ezg9Z607GMzd@3)pT3 zkWjEXcEWj%>?v-j`!3$qCfrG?0yVA30v8?liY5R`hF=Ug*y^k8-O((r6~{hfsXT3S zR&ZJ9vb5XXv*9hZ(+DJClx<)r9tCIDr23;z zthK#2iZ1?fVVIj38tQ>P<`o#!Nd4(QkqTdO-wPiABTHIqEvHoJ*Im9_u`c0IszDY~ z+L|I$;P9!EVz%r6(nsAfsDaM_b&ZE9peY)^HB(dt86Wv+%j~^b2)S#pLaY*d-9SxY z7O92*h^;#M+c@KF_S%|$aDD%shs_&yZYOpaBb-!f#(3@WIkN2pZyArWYTSub>rMQq z%ulJyXM()$O=2X9yE%!^Z&?z>7Po%~7SIxp1`)gY^qp!S>*{o=Uw)X_k-$rbWr>e@ zZiIMOCU0)`L@}0Q6Ym}4p9F_(;WS4qkpvW?tDqd02lih@Wo30yd+7{P#@cGL%e#x< zSru-T;gHZ(g3oJ9F@2U79k1E}4>D6eH$9h9leISD(G#yo$Tw)7tL?7po4ooGlqmuH z@^YgCokGf961zH>m*`#-NnbNCA-Yl5?#<{BdbV7pI_>L{wZ437?!}YWNavM8ueEbo zE5{OqjohGkKW04WDdt(bHDsQYG=9lg#N)l~i8+pwo;B>!wl5Cq3UrGl1A2N?8gF_2 zhX+|K-QCVE%6+EQdz_RT|ST{OJy70~1e8J|S%56+o|a88@-l`DeuQ zf8>M|@n_MnR-lm?U!=*whil~BXjY@skKe^!Z-XRn#t3TU^wCRPST=VL99TxdX3!6K}hh`0Rm&)wPd&F|v4BMBxu zFz_2Z`$kZDTlVHjR*}~)q3OPxtdhD8n-<89U9B*`WwgT8B`+m~bOKyPcNn=ux7Bmt z1A19UR$o|L8rxd-vVIDvNETqRiYtYZ&LB^vKUvgbuTH!zv)~ZvgJi~M&ZfO}Vlf_- zFgo6;Zd8{nS+(njOv@# zg&A|3y-)FPo#b2apdDPpAWVaX7t(8Eetx-XWafd-D3g8xkO`c4u)wnMk&k8_AB>LQ zPgWkM#@@OwUv}3ToW^4C?02$Q7r*hH0|<@>*bCby*`?AErr`MhNR-2F%aJWwVaT)Wm*m8R`>{-_3zWHK}dA(xd($oEISLhk-W|`@G}vK ze6EsgI}g6GDdvtw?ZDQ{o9-mUK!d(bDyOkJIh?0q+>y1C$;~o^Xh-af3#Mc(fmV=Z zB{sp-_ab$~3c7mJ6+R3SpAg2QMptbse(H>q0=Olb{4lSPl9HMO=bs7(u$QSb1}eJb z9|fbRa5Q%~OPk~E4ZChXmTu`u$6;kaRcWeUEitc|ydt#c?-DHLoTo1Hz6HZ^I6HTg zy1#F;YZ)6(7w+Eb8IjN9GQT$L@sxT;aH#I=Fr0H(bukUvedNZQLUBMA(SLfzvm)@S z3=SgQfvA)EB10w+|juvCE zb8VtNb$%yadhyH1^r?>DD{L>4f?&`OVS36lS1J@$bw2YFWgTu~xIGmfwokGSz?qtz zckYH|tN{-a5|TXJ4GZ(@lMvV!HiD10)`ZtztE4X5>d?rGOz-6NeAUY@%1ssq9SO?xZrwEB_>L7a!5_7czd?Eaqj+A zW3h_Hl|eBhG&?V{=+Tk&>X&GR(~b3=CO?Zb9TastI2TKOH>7ARVU4*nXd=4cZ^*9? z9M9rg3{93WQlaJB zdd$zQRFmOWRr;#bjrA-RzM*0Gy^*@*s4zsP;5g9l1D2RQWj)}-GURRfY}i2=tDO`T zkWGovlP?k=!z)|dX#c9=pdG1a<0U7YkzXu$1u^U4-K3;5pdZ9`5x_sNb~?+}U{fU& zbil@s+*9hr6NMRx;JmaG5|056IYdFbG4}Zti$n##HK&rTIo9~J6_nlx55IO%PzMGh z;Z`i|#vcXiYiD!@=5vCAl^8d=DhODzcx4OgRj;aSQ*-xNl@hb$mw@vdxz^k#w-k;R z%wbjptm$nQfthc4+TR=@YywT8Y{PcBfo1y(|IV*LNLg3tTa$sJmZFD`9<}CCHQw9K zFHiLVElLrU%Hg#8%i9XHhW*6Af1pZ`j83PEEh1J_luF}Dp4Iy%ScCcOgAnYifY?$r z2oQ;NVGeaPb)LO$ZHosGC8u6HEbt^xcnK2i(`WqdVK4UVvAZ}IZ5uhCSGzg@NfTZ% zl`RnUSJKg#h(G9i6(Rn;12FSE6N?qL6f25hXU1Q4restU`S+j4*C;uQMniHMrN%@7*^F0r0gV;RSV&X@R+q8*9IpxSra>YzszGcAUu>fWf^HgfYH- z^_S~~DuwmsRnsD2o&00BXfoS}5!-L{W?qqRph>3=Bh?W1ybxfraCjcdm=Stm7L*GUWBhqRhRc(1qWm-+ku` zZt^3HaAf((K(94#5s$FmN3@IBn-?Ats>MDd2o3)}p|+9gOyp_y^=xO52rzN4x6A;o zoV?T?6na)9q?3ak*V=B$8Fg@cy@2#Mi>F@#@6o$g1R$dxcr@DI|gP)t-`;e2ZBXx0R|gC9N4b0d$ja@eJ$=34Lg@qi8I=bdC9) z-y@JyPyoDZPMu1pICFN2ryI6UqinD~5|J)M#p>|WeG)IlfuSP1KdhKWF#-mOB?Zs{ zfG;0a^}l#biExp3TeAx%^;=`kW8Xwekd3>jP)LR_go?!eL(0}Xt>dMxZ1nyT$*1+v z2#^k7^biUhGWu|ljcTRLEnloSTdQ1%kg-i3=mdm3Gs!cZPW(E{E(aM}6;3WiVRbV)5JcUqbM%=k0%bq}0&*n+# z&;n2Vg!Jxq42Nq_mJWeOG`PJd>Z@$KRPM3Nc}a1{e|YyFsqGwUS{sTKF!r%WY!8M* z%77v_$=0RV;OdN?OS#SsU^JvM%Ii&?p{|K({tOK%Nxm76ONl@V^w$kgtgYreJNlk? zp+YaRT?bb)a2vbZE4d2>>9)}`8Uc;_u!E-`ZYI8>UkispleDyLmq63BkkU=~6GX5K z1x38yd|(Lm`J-N^bz(2_yt)VcB0;-MItd>_ex2YzDYJ5lM9Ym|zoMQB3{c=ds)Nw; zRzn~Ra`IGC+-nhRiM7H+zr6{9+oD{%J)U}6GKZ71PR?0f8;g{#Pb>yoGuUUksJyUn zR|VcO3BK|&UXK}g{`hD>5e+G@yQ>Z0q>t3?f1Ky}`Pf%KX+Qm;dgRg}IKM__2sW{`^(J;>Ypn#XQZ%Ij{t=|B`|FED}WRJS(=; z!-GV0?qqsLo7~Cljw%(pQvDq@yf)--q8CK$VO5Dcw64 zZSaHBbQ9^tWjr>1Sl@qUZ60k!jOR)8)XrFg#l}T$!g{vCSl~*+&>**JtH(kzIKk^EL z5?62XV9QrdKn=M_aA85-QYh*iQ+B}OGn7hf#OiCwrdEX#mN{3Z{9=+nSzK0iF9Abs#@(IFHDtGJesr!wXW7B6{iO)$FbokOTGCn!=8 zawOj%ZeMA!RBFgpWD6g*_$4jK4_!SOmwf7(ogmJxF=^AzaBA-b`Y#5|)o^nCty^f&3$B@= zSH&;$o`c0D8yU?72Y1mDnq_nw_d0eSb&)pIeM>TaU4O*ql3nJuK0UNOD4C(Qv3KqL z)rjAj1lUb_tVEuVuF&UHr7Ym|N=twkau$8-jUkSv?Z@HTx7B$c_wxsu*&hFE;Odh| z=fUwhb#*&rR&M~kXBi&_=tIH<(g|txl~l6~u#1eXnwpccs_u=Txy#8W*Wstq62@?E zepyLpi7;99No}J!8&wH|Z>`hPg|#!y-%~;6Xa63qKKD$FiMW0m$hjmhT-7|eU`MA_ zS{vDLxlSLcD&TEpJ*;-#RFinyFS_cUeV8-F_8v(f_R#+*mvOKWMkAHj^ZcF9>;F`t9vb*i3DPR04N{Ct6I$^J*ZZ!wT)!96O? zN^d}D7RBPTXxJonbq`wxtEf^d5-L!TNP6xB3&aKrw%MjxLd8K-!v%J@@_1)#qIAL0 zS-^XumO!V7a33am=<0x|;5EBvt%NoXRBB01;VCz^eW}73o zuKYd`lfBQzaQY)BNy+)QLd2l5%N@ldXKn$>F*|N!?OljsvOu ze<)IC)wzL_+G-p--uAZ6iNu%o%z;hnl8mB9vM&%C*1swON{98`W|HXt%sl+K8I}W3 z?C4`@SEyQ64hdq(#w{g)G!-Nkhzy64w|{tIVs9j0tc#wB2|}5c5u~c1{EKBhD=Zb1 z9NCU7E_J_%;t^Z-4kVZeV4GXsKYU=p(vbS#H|v3XitVI?{~m*xGq)RB4%b%$eML;` z>B4`QxQ7{Qd$)bUhrLOen9`=4Ux%ncL7tMHSJ|`lzVi)b%6oJBk$mq?QQGa1Wd$ks z_c>$akmL;{`srh_o%EA#vg2Hf@~YpvcL%Ct1(yPbY^L91c6jzpC=Qe)PYhQjlNmw< z9!hQQd?<6v9BPA=B=F#g?2OMxj-6LT_`UtIXJPo&qZNOctrpSi#|GSTc}?;%kyH}k zuD+W47^L4?4^(nY!|n)F_>L}kina3Crm&+^9s=$!E!UN`B(z%oN znj5uB{oT23nhy2;PUwO^kL4bZj#&-><6>I>=V;isleL_3pEG)|JBjL~IDj@IK<+}3 zK%}A$(7nri&Mm5bP>H+n ztUt-)T@}XG4_1NvY6hS9AnpB<{!Olx^{V&f^IFm}E@ACD`-6E1x$^=TqbPzIez8`2+O6P8P$*;zZ%q7}E+;Ur*VX39^uxZjwjvrO4X zYy(0W3T-I1|L`;+=FQ@Tin(ER0RGvHes))6y>&H9hTdJ@uIJ=BAHLStBK`($`I%$O9&_Q)d3VX%rr7ESho2L+flR(v8x}vp zVvXnpRnwfJUknz^i#cHrk7OH`GA7&bMA!eJEauDjR#hJylPp{8;Has#+Z*|_VLZA% z7N6XT9YE;y^t-r=-JOHh!LV;)jmDf#c#|aE;D^XabmaJe^>9=R66hjZQ z0(rC#T&WnmFbfEO{z@yj!|K+S(ZlnIzk&1?n)XC}5#9L=GZJCSI&wo6( zC97vC*rOcYbCQ2^-+MCbyNR-*Kh&|8Dbi&ulA5Q_e-%k&SI1puZRd5ZwUnP4yWW2+ z4$miQgQHL+6pZ%F^@MvkFL|zyd4H+qW=RY)qqHWn%XlKO@9O|bMj0z z`Gv!Yzh*W19yo2YKDw*27ACbH+ZD>#8_Nkm5Dh*$T5Aqy6C#K=5l$S0(m^^I$^ zm}#iCHoTtlag8c5HIa$MC&otGNu}FSsvazIu-EFe*LCA(#=2vNsXd?b%Q9*x{;$Mk zoef(38!EBR`S)^8PSGIwikNE%01W}rykdIHJLn!#UY2cVpSEB=i}3I9jMLMXSG;bj z4jnTN9DO7mzhoY~@k1P{3C8`|URIj9)NS6szNi1)LwIF|=gjMoy%@@D`RTrZrE03N zm@_-k!&sC1kFxi7S$gychDMyP%7a;vj?sm>K`~N7r)ofbkJ>!cwXpo zlf_e<_J&ZtWoKxXO`4mT($G`~gC$)rCKSvP_0xqS30UIh@nkF9s4?zt){%cHT`~_O zJmonAKZg%uXx3JIn4o8xdF>0sx$ujS0xW(P+z#SGZv-Q)CiULR#ywl2Se2;>lK6k@PthPR3dP5Ks$c3=0r~sJ zD!v_EDq3{FuVmh_U(X~e2(xRfxU1%c8f%l(Kkt@(a?wHb+mAF1Rcl#EqdZ6*LH<19^A(ubj9fS zb2Ex)k+zzy-$6v{C`9mN$ze6-T|#+Teo|aoXZ=+}=P3n4-=mpFX?iv=iulH~$iF*} z$bfRtG2_?$j^Lp<}2vV;c(Zy*@ z&O=-ud>U&jH3`jYNs?LEX`w{XlFhR57eRQ35Y51Q0?Io*rnwA?eU3dri@eg(R8gkz zimF&8Al*?S0HLd>@Tqi)irhJcR9> zJ%20s`{RRpVSVSc*2=L?;06@31#H_?>i+UwE0uxEI`WI^TXZV$4CCO` zwNApQ1NfJesD4%)3Yusvy>~Phi~Gr2PczJiH6?yA;z{I@-D~6aw=I!vX3<^6H8a$2 zb-ye^;B&mskf}Z zUDIXLv`pVQ4is47MT(l%RWDz7k!LGS{)x>cBXTzGeT3w)e%kb1xs+s*2#<-khvgAV zx}z4DWAQ#MOHf@D^L0dxc^U6d#7%M%op#4!AL;-l2P)-h;4#Roe{mZ!52+U?$!AX7Ek<><2lk%e28{dA{_eIZ^E+lgQ&~cHvyFfh zXYl9Y1_Lgh8E2#XMi5PaPBk_}QB)CgwUfNl$36UH3;~+~ZwL=*Efk8y%=>3=671Ye zUma^f!N)Gz)5#n=Ww|NU%~DtaywmYu;;h)Zcll>=Tv0(fuOq`Ih(-mqMV1jv6Z8YC zaF&Xl;ol6YIA5ai*wnd(s$26^NQ%)J!#Yx>S!8jtXFL#7AttM~3D3!Av2E1^_t_{sMqTlSZ5{%ufi@vg3v-i zQZPB)$Z=g1FCfhuQ4pQX^hUB_95T4VMfK3VcfKi-H79bhdT z7%he9bf-Qeo5sd$HaDAXMx5g7EN+lQj<`m`75z7n6iiU2-Gmwh-{Y{>Bi0c}*rNp< z*WQUiCuTVyc*8+75*1pWU(8?UhzzMe#Y*c^=_?!UC*CxRZHk_#=+O*>7$U31#;nIc zmKmQSz9$k7%#XxUhd|+Gp7FoFqczpIez7^h45!*8O<02ROPlwiOqA?5?eR9=iVZRn z>-0;d5W|lN8LB%0pFU6UJ3{MXpX$iX3iN&x^`QSF(OlyF%q}BFd}D678y7;itmE2q zyxwphZr1g9QN{g^+y0#57_@KuR()AiQsDv)|P9!qls9E?gW(LG z%TbYc)yZdZ)G>{y3w>|I)olWn`;w|YPAbx6s~{T4hXpcZcEv5$ImeBn%;S4HluNgV zr)x#cB2|{ptX2=A>8b9$(Uixf0M- z$eqDNeNX8|G3((s$s~DB4+0JC^T6<|G!b02RLU5b)9)3Y{CWF6Ed2xbE6AYmr=qZz zCz@?2q1$cClE+SiVzMmUu3>o*yCQD0PsF_u z!1P;z5$;nbj1j^z^{A^SNrt6|QV8u*Sdh=-8jl*D^XTnYGxT2QzN7sky@um%zS5=) z+zCG08B)68xLf0jB$xl{8WPmTn$pwoyb~ELRBjWa}*^7LChe)q=QE$0orl=g+`wm++WkW zC3r2K!fDYwBed1R=fA!)ns9OR;QLwCpsDrMm%*wF+ zN?Lp`ry-N`p0+xU=6ih8u@8jqe$LbhiWZnu?U(ix#Du2(7mqS3G(}g7MXvU z6I6#h^4=)xM}uaA+!5MZMl0lkwt~7K^8SwyPVD8T=^ur<+X4+5KhKHTAA*5NRb&J~ zR1W8g;-&9Dq4De8zV0*%E&~_b;y2ubi%{J!Cu=T~*va}7CMdbrW&b?!OT9S!5vU!t zm6by==G?e_bMt9FWAOv=D_WJ0al0+#W`_S1dWC&#F7-WV^>kVrwAd@*GDE(wgaA~T zS(2bUmZtyVxxx~fRB&|ju<67Nfu-iF!2l?M$O6V`A#*0By|PtwR(alRe;#@B`kLhw zlCeCsShPVoI)+x#J3H#+1nz;mWoR3k*B$EyN0A}6wNr^k$=}=(La(P3F#9lyr1DPg z%)*lFov3g?CMnRQC@M(;F5+cM;Vs6Ud@n-L^JAcKW%cy$Tayr-|Bv@v&=#@C1@e*1 z3fGX^d>&=CBOzY<_w?_iY&;XwZu!Hz+h|#ze1yftMI$1^|17KoYN#%A;@H;F^n;n( zb839Q>C71g>fFCWG#52%3s2KZ7hXv=*YCsyR{!${7wd!coC9o39@5L~q3%ZV>;ZCu z3d||5rA)!SPM*kc?_UNEaER?rb6FTlXJH<&8g%5e!n<}OCfeCOZk*h*Qk&m_W@|*M zvE)0!f6!F+)6)mzVWd*n{nYOEO~Ke(Id#45yESbs5l5qIfrGSpzCrOy<9%?GuDrJ| zF;^RBnzL=_dg_N|cn>Cj8J)nhby!f3R97WZjEb_BJ|#IdMI9%7j-X6S@?vIZPA5d z3oyN!CejwyY~jVXyN0JM?_=eX8aYIIypbtiplg3yCC_d>uYHb#|H#F~@kHP{K~yT+ z%_MuPv9TN+Bc2$-gKk3b43-C4zaSf^rXxomuNQKv{!%i8l0Ai zO;V=+n^cFk8!2j+2NeD4N1H-P2%4J+6WH{iL9w@=OI)vlYK)muQ!``P2BdTMIE`>~ z)9s|EROu-TXmP%T#6`BoQNg3!Q9<*c0{~haVUZJTi=7MKy=)$5fz^f4lEeWv#ZJ!( zYFQFio)tMI5`+8i7a8y)Vs|1Q91qu)`cxL*&3wPtDJh_rK-4}i^j{!%W+cAl!Vvni{wySO6`m59RQ*ZEvg>Hz*$ z%tKhOfR*|~m9cIz^R-s|hhcGEltfUvv#9g&XM4`Y+wb&CQLs9MiUKG{XEChM5Ei%3 z$?THSvVOi^CSjD9$gye9kss9a3nSYTq#5v5L~k?;fPXiC2sV`HLyynG4= zhL#3rgLo}gU4Ww0>DbIIDjg#%IX52kD)+vu)ReN(@8mG?gyb-3Xz~*ahRpFFVL1K{ z?#2dDmTqHoLy)ev%aXY2#95f(sB!u76#1Ct;}QDWh51RoZUXkYS?Xl;NuRSZKi>#1gur(?3pNT55mciIH@4Zt7X#W@ir(W#i)&CQ*@7 zz$Xqh85Mo6XZ*#t@#EL*mX->39tv__UtT>2Mlnx=gvhMyhJtHt-NtZ3IwwNzktv7h z!>gx!K|44?+>LvWM3Tk##oRr#@~3Eb0E_*BdWz>Y1FVcWtm1*kVwK|g3v76uRc>)J zsvT}NsgCdv>+0AUE1WY-bJwCBB}s^DbQd+R6a}1}7&I=6L_y!(a(8bb(Tblf!jbBeQj^~A4>m#N-mAs791qnMH|CyglW33rgC3-HdL+HzJZD~B3_<<-s=bO^&8v3q|L}qU zkS_-6%6C3%FBp|FWE=d7qT+b_8~;dV*E_!WUoD3v%icmY%6mD* zFi?a__30)W_)MgEYwdLT&HieHqChK$M~~kz9?M~(HR^kAc4&_-bKx(Tudq~3)Yqea zu{+(f_WeT6S^W>@1&PJ{&k1sEKQzO~K@>I~7Q<0Vv;Tfem_kh<@#4*~@7c%G&p5EZ zgLI#WW_;u{k3>CAS1}}c)OnlqJ8Eq?MJdTne`e!Grg*d8yrnePT*vk30KgJ|G3G=h zQtvbcv0*Lo|*53CN+)a zhQ<8&{1Q6)5tiVf?_eymNduiG?b*xu*WM{We1d{UkBwN{|LPy_zY8r6oEnOuo z(=QEY#1VmKkKpty{~Cs}s zzgKhn4{E4>-DF7l#&E-7PG+K^>~C$t$zuwDB|*>uGKuW(=u(H+M$$s7E0Wpd&^$%@ za>1D1u`(ty_3d3P5X;o+H=bd!@@-~Lm!_FuX4A!SWA~T@{keRa3cL{9a(XKw`-iI+ z3wksrd93SJG&CWDC)+#jY5gA_b&=!4$-`s#?3^Bw@uI#BCdaS4Se)C^tfTtgfBNaV zD3Q6vHFKMZ#4bc8RY%HW<1e#86eil4CfFBMF@CJ5kHjR?xyTy~H?qv{2V>91sl)Sc zy&9+%AqQrF@Q4VPl>uEKSkudKO$G0~?cuS6!9iZyrCO!H0>b6?d1T~dX5tpxG#zW{ zfx)U)lHgi1{pjY0?ZQP|hQlU8tt456H}cjLFzngJ=O^J@c+XXvIL8q)UL00ovC;Om zQ%;eQV@xb_i+gdP2oBY!)em)&{%FOBuzDjJzy{{4qvC4b8k=Uf^`<=b!*o_-WP<5voNbTWJD{|tDJ?P?|G zz2I}cYlfvfG z8qOkw-97{yi;0<}I}f|t>mnzwYiG%eakHJ0%I)w}04L-2sjZMQ#N@rRMFgnbTds$Ta#b0gQ-#orN`d^0-+neS5bxCzs)W zc+LaYJ)j?d1I}E|&EsdK>4$%bvCi1SviHeZCa2V{>m&+l&ej&&ZXHN?Bpec5_cu6a zzBdcI7#j$2ElFy{H1qGYj-Uzw`<~bxWELdBpb@hVwXM>cM(AnNEZX2vN>s6zLBqjY zCY7Yl+ucjY45u?&{l{o>@%R7XMPmNLJH+X(e_c9E6p$xfBxa+G1>VPXS=a2%!w+?} zq)WXSVaX6s8jsTjA$^)<<3RZ$^&sTuxB3e{!CPYlX;gl!&s#1xA;sLOB=K%Xro2Qg zSkq_qO<6{98gPNzxCT1H?Bl@qBFO#n4$V{PP490+2TKf7vvx@~;-~C-R})G=d#rb$ zQ%8C;)0EG%Lv0*gzh$h_Oq6vC?7=gzfeA(kyvZnSK3kBh`bo9*D^zY^$V%2fuaEWkI8AW5A(f4&K{t;Q^ z%{9|HqrfhhBJ59E1xD-`=|yImb6JkEU9a7|^4q_=PRzXGtFXF1x}dR-_X@k>PSinl zuCuo)FEW8lAM<#gQ`a}$D!v2bl{SBFG?$YzMbUsG-AuD|g+7kjar2zF4<0Z=(?tk8 zYATPq$qMrXo6p}nofb%I;hlY5BkKQuxO&T|Homa! zm;RwZi?yYAkQOWMkdOeSI4N#L0;RaSOOcjR3c;bcyR=A<;7|xs++Bi8aF@P$o^{T9 z);jZL=F5DUnLT^&`?~Jm74jxK1jrN>D@P|o-6Mvj8?@t)O5?fi6u5)NlXQV*yOWw^ zjdo<{>;*rbDixdY*eRnAqn-_jc%9gPIBa5X;m>b>&V~gqJvn$Ihy{SqPUkQ0u?C)w ze=e5|CEhl@&ms&LVP8b6C9>V9Yg!< zhK2Q7YZ%C5Qs*yl`D=>~5FMGE9s_h^BI6`V2wX^Z8aFI(KLDq7H^fzX-mQiUE68eO zlr>)(T1xrYcurCEEVz}8{Q8-V>Q~3^ zVXgXBTDN0ywF11KZ>95)<~oClBjju9j2RSW*PK$qR}eZ>5E+E z)hm5vOp0} zv^)3LL3pViu^1$vqi-!lZsgAu_6;dGwF2i*;O5}S?C_h@yS=ps$?ShPeb{IC=~n;V z4xx4|r+2O@oi9%DIl)8WP}tLr-3BszAqPFe zW1Mehs5z+ohqEH3?#DT+*|~&jiHvFZ%<(5X?Kd{r6NL8Y&W>GBm*pw>(|4nZB#5kr zB5;i$Uw?1lwZE0761RFN-Ir=Nx&QR!Reld9skR;&_WUyVF*Xwu@7;8s1otQU%lXd_ z%1?Yl1kOgw6Q>6yoR++F=!I*{em4%`N|6V;)0KVtk8MBxeR#`oki6Qw=iRk*3e!k{ z(DtXmges#S1TYe}Y|{GyG%qtclBvo4ZDuYkX#yqc+u#^i4Y(caU3mMTm2sTC&`T&H zru+|QDx~PjoG~&aK9>UGVqa-v0I|Wiwru_F5%%xEUza9C6a)l(RutbY{ji#ZKz@-^ z?dyBqIQo}{+7pPmsvzhMQIhkRSI4awo6|wnd$t_hsB7-ZANZ-;%ts|TfC_eUe-*@~ z9EzL(Yb6Tuqp5xlsT&|A_KP&O={7pId@Je|`%8@rsD0KTFR&dOB9tS|#Sd4v=&PgFA+*EeO8183NyJRHx#GPsLEm31Y*o;S1ckdm9>HpWWkWT5$8rZBLF5H7O<~PMku}J{6*9jdu#%3=ut> z{)a<7mSv-NWh&j^`5I@IHwAa)YWQ!cpft(m*Mvn*Sr_jL@tn#tL=sm{8|^bF=>i;rIS82%pf;;n5=35*eR)Tvmhv(@#bIj3(K>I+>CW$1!hy z-1EHZ+IobayRGpcP>RBEND=pPireb`or4KE+WZle%(a4F3d>L34SDs1wwa2|s~62? zR7-$AjUzlOc91EYoF;%F3AfAoAmF7w?l*3x;WUr=SJdKK?}abZejHytvjb1{)PQD_$`DQPYGfzcp^9I@w$ORtwOik!mrEe6(n-=K-it?g3X@e)Qe#7WhPa=| zn#UlBj27?6UI_`a2jLfi|8NQqF6WRoyoI)@2A`?b8?htoL<+)i5#U1~JnQ5r)Q#uf zM&!Q8ZB>dPgniX_;s!3G~ZBH*$o{-61bD z&FfN;O~J3oWyRYCg){6f`Lo{oUhHw$#7-0oS?sQB zZ`FIkSm<8jo^b4De(K~{_YUkT?TjI&-@w0@rWFb8sn~I{ty>)qnP%Z$9oXd&YC8N* z$buxi{@gNgAmwO+lc{W->-)8JJVI*LWa~{(yHYpAT9>!+(h4`-phQh ze5uVQozw+*zZ93V++bz6xhmiOzV%8u9c#!Qq$y(zbCXeNW4Ag!A(hB~by12P4gjfu|)cUhs7!}uZ{7v8h@A<}K zyiYsPHg)qDT1VffPi^&vDP+v~|4ccB{p=kg061YSJv}qLQMvK5`XcoAQOJe$eCvD< zsLZSa&MMt&8)~N?A+X3ewU;!T<)b%l+6MXc#tz!!*soyv{G-zI9O}9xn4E6}_acod0~j&;cGlb<37-Zi;}p6&H9j9DFS} zAowd&byytH@y4SRFWR$T~ZbdTWcA6bed7of^vFu#fps^G2 zq12|pex#T2)q3JcUu8m&4w$Tl^&MFvqu^V{H}C5lBka6$<281P;`J9I(@!ZHqYiR#kb zieH!hhm8CqCM$^ht=2~f1^B)1D*dL;?{ldBHrV3eSl$q(cJ3X%WbMsbEfy`%OqPQm zxf5+wH_}~Lx^2x-V(wSUj9rN7w@MbuI|I?tJ?bW&T-nx$%&;2c^K!P<)KpwG+w5hx zS7B@oq0B+dK8MaMTVc4~OarxYwge z&g2v7_BRhc=T?t*xd*&g^-$;KV?BvN$N9Oc>)&u&FY*+-Q*_o{o8~lV3vOSfupAQr z`Q@IY(sX6 z#&}jsM}pWD${q9HRs-BTd$6)bU-Wa1UD=!BSNZjZALBg7+efC7UBG$$SPGrGb!L?I zIX0$6uf?r|<*2`(?e`zR^7A;QX8dhPs6i*relKK1DS_6oz%jC*X*=0A!kd;?H+Sq3 z(JCB6g|nG?KPL0dlYS{=a+KUad!Yi6D!B?uytw*vCO0(jg=O{csc;hdpsE*-?)uT= zG;MtzDlp8svQA?Hsccn?{6M>9<_7MIG2KOw~Z$3=dWdB*4XSm7kvRX-1KQ;{Wim`9PCG*Dy98H_vV zF!`&ZIL#}VuDjeZZ~_;8q6Mq-c$kJ-s9^t7rO=~2Ef;~h4V3QF|Lw+mWr%33oE-Lf;0 zAs_Nm2EmbhHr6a~iIU2B)wa2vvH2PYaJr@)56a+ijxK?OeYdc7dz?#EM=X$feSXe~K3Lls#~X)+wi8E|*6p zpeDI@*XB*Px)nbIDlCq`hwN;{>&+t4>E5KYM0hiApb>G~j^+WWij$MX^&m7w?J|y(rg`C_Iy8Z7M5I7QoW4(w<&-B++L1YGy+q|?* zTP6Een#>bjzO=Za;4HCI*>}pWi?~9xR*rEuIGD-qHd*9URf9N5`Yn5=z-MhGR2T6r zv2)&q-}|_ecgyDwpcXTmMgM^e8|lozgFS)8L(IKNypXhI%h+vH;ZP}+0T}WAaC|~j zK}(_~okmXpPpF*vyPb^E;<^%jKhJ=Y2nj`k`uM2efNH-%7$zJ-krPF|zKO;SnTC=l z!8}jG?_Zy_)GOOGXL zHzk`2kns42@&w%-Hfwu$2-DaK>DxEV(<+RUY?%)PeCRK9;7>P#aSj63lLj$$r`}~b z-$#@*+c!1eeh_cSbz)m>=<88p#WyXlwal3Gv~ftbvw%eTDZ(|VU%cCQcBB9MEQHJ5 zFY}k$!4!OE)?aTxLq;7$5H#%>P(vF)$a-+IrD9Pv4ck+CIiY=6oQ%uvQNe;9=)iN> zzT1t;IY`|q7r|ZBU?rBf^-lLnBg#COnUivzI>cfW2l29{scy{lSF_+NXo@tG=jnQ@SPyqR{qV0_NvA)2 zvsthLx!Y-98>aj)alO%Js5(87d?9C&)ey<1wkm(f$#(atkK>0y@e~~`H@AbMR$Knf z7vn2IhtC8R=@(H5w|K5wZq?>rYPXz~ybYT32NN&)cc*})2+YlopCkA}Un`*rafWvp zjnxAHm!9PdqY_6Fs+pBtPK%-l%5ya=`34*gV$LExpC?s4UED^m$H&<^%JuB1$nktO zW-fN$x9+e!#vSeR*!*dcxcv{ODX@qXa(e8E(3`6`C=sLdOee`|F9s9sc`xArI^wFXH<2f}st5_Y~$*cc{m z>H&H9byGNWBZRADT1ath1r$YpX@T?P1b|$N^(gaRsVS(4ex6UaKsgqa8K&uE# zkAc520bC`BG;J@-XSI8{U}GG6-wdq65Bbl*`DT|At%oj*NL~;Ogq*a?tWS!W`d|!!+JEp;pC@wcB{pr zd(5m2hCv^xqZXUJGl@Ws+?Z*B$p6GZ98dRY7LQXwmleNPHW_MTT)|C~jISd_hFL3k zA>NNgfk?`4|4E~`NtH;zbd#sglU;f}eSBVAeaN2@dQw>Xrwi?EsP&*m-gmP zv#7!jGoY(xrKe!?g-H7GIqCI69hV>eBQdl+y#^PtG1~LWGpSRx1j6KzT(y;pBeWkR zMra;u2iQSVN6@JHH^De&?nlbR14d6ama)&nc+gBto8pBm=l8`f+$R6MJ?Dpm=7-@E z?Vg9$fRyg(HSJM*BPj6XsOOHS2O${Nzn@fT)D7 zIH$jzMiO>)gzxldj?DG$P^xr&vk7s{r?uA@Aa8>3;}IO{PbK`~Afgp~qmj_Fd1s`& z>ehcd%ZBej#(Za?i#fX5gKW zOQzlaH1+bkQ5ckYlbyhuG9-VhFKXG!p|udCKT(%tDc^II){bbSr4-L6aXd6OOUb^9 z=3B&h(Eec-`6A*w{i9;OlSk>%uigz}ix(F+KJ2_<#S)S1!Cq0DAQ(S-Kw@upJUUtu zc6RIKDeY{x=1-DW>Yvu|cr=Do0Y|x~EK99*vG$obh&_(_Qn2HJ4D37&BtN{a96fO!}4b7nJLxv@rE1^kuJss+~8TQ={ zfSGsTwpYv}Y?LFT_ilvpbjEJPOzt8}9YpvDv$U0vbSoldiQ%xu)1HVfw(v3a8StGx zB;RHaS<>H1wu8BCtPdbcQ%Bu0vntG(;fl@9+cSWzYXLYBaF)-DV;u4u8t=qEFx@-5 zv#w0VDLAuL?;Uq31^1sdQ5*MV3{;vuSUF2tJdvmW zU|C%Dr_#p^?)LSZW!h>yPH9%R-}|PbCys7_W(|>ZK_COj7ir~(C_yx>)s0dF+@qKN z6I>1YZ)1QD>g}U}iF^d-`r_`78=dkZPMDZN@I&EGk-y-a)%&}9vVYcEX`%ZxB8SN$ZNpjt_XV^GPjGUYy%Hf+I+qB^W9 zn)RFk&4a?nKiQh!cz=mNy^lyW5RYhJE-i_aZVT%%B3kZB0$n?2h4>X$o~llD8){4h zD+|1YJX-E!?mk#eXh0{4(P4(X-xrqUw(j_u>8~J&m(qTGQ5OsKp*#Xmq0T=OHyS2U zUF-Fpn~)71a$`v}_(3}*I(niRW3jraGW^9QZjs~!_jUp?5`CR*PuGT{A)8v;ZKT*K zm%FN8^y2@zeN1f5H8}?#c$Woa-Mm25r`mPeBx<^7XRr%B=H)NE0H=3dD6RpDh^KPHx^&S&4?tYZEj%P8?xB^t^ z!-ZO$ERS2WBM2v&gG<5?IZicf0pV?E%@h~azuftGaI$0R;!HFA8kp#3{P$M8B2k-y zTwAMKPYcSe3UWV==}15700KMX>HP{za|;a}9NvrWCL`ZYxi|+2{964B^tz_3Y%N*h zInS+*5K^(LH0L%O@M8O(7j%+oClNoKC{dVMS+~LdZCXjAC8>w`3-$bMuEOJzvQpnl|o8&{;Rjn0~Qv*SD})sc3O~v13mho z)9Tbco@{N=yk8lUFFrn^``(9ghCl|q-CRw*qTJUu*0HRihAUYCBJi;=rO5efLXHby;S}c95B~&(Wh>alqaCLi3*Jxc6V<5I$g6P$EqU%`C40HMjYHR zzxfQ-^_#Rih069PGyi#%fH0y9g^CEY&{77;o=o&?Hjj6ZzQz6Sm7yeA<}_;1d6g&B zjQAQV$y}ci+V#jlo&!OPG>9T{5k8`x*-l-MK!KKR`i5->lcB8#`0cp&DBM$S-i*IP zmko49%@sXdU!r);yc7u#`WoG%oAQnAAD!33vMj=Zx9L7jT9#piVS=6eZZ@3o-Tp8I z(-KoWZ#eZCN7PLU_CqM2Kw0N5Sl){NhOHCvl$r9lEjG4#sY)|53RckvM<3#=!VuoL7}zs=B6)%zOnmg18l5=Y+h@gbj8s3KK4wUlzIQL*uUEQ znw`F{3PuWO%vb%0QPY{p4A$e=^+GCuTAirG7>&4nvYiv zs1tnA{tZIaT2*;p3-10>rQQ|%mi)rl0BYb8GC6b^)nw`Yas&Pm z+m{JV8CICAeL8W~EZ(DQouhajZ%^T2Y1M=4SH-56svn8l4_V&Wl_6u}Cz>(i6Wt_2 zjcu=04x^89&+cJr-{ThMcDTN~zo&5yq>1JSa=FEWMCxq@`vfKsIxo+)s*XEtc1@Rf z$X?~SUsG}=PF;Q|%q?m;uZ*nrs-s+u3-86d|HZn$G7!ByFy7@oMWAhzK2GD8snF=+ zv~FB7-!)mT1l?7PP|Bh^MrRBKe)X~ufdJ>%o(t4yr7+SB8G8XK-0N=j+)ov_bJF4k zBI(+bo;^A({ky+cQnZ&r%_7L{BrfxZ*wa@B#ZZb3rP67w+;Pk&dj>izu~Rg)`))n# zrtPi6cq9?-si^aWqXBxS(^v4@yt5;3ahIpf|cf!HT;y zx**T_M1{HF3PNa9;Spbx3m|BT{MgIfi=ZjZBU1QiIL;Imx~K4`Fvi`X=Pk`C>xZ4h zC?2L-SB%ktd+bG=C}G!IB9{n^Kv?{S!I;B&BwYtVpFCuM=E9EQAar!jvZIzAST#II zoQ;2xUcYu)?$9EZP^;rUNf+BV-g&eoDt5%})^JF5daSep#v;@{1#&0Gbx}Z^s~fZO z>nr0Ff`s5eGzy^WvfpTuSJ&7y5lAG>!c&+^2|8&a*&`Esc6eC^Hs0~8_-$mHqIfad zO1)A5j;)oQ2BBj*delVL&Lu+`oG6FALMLuG2EZ_|J+_C5oOU37$I{OGURUGg*Cly$ z_;qr}##wr^n5U#@U{+elxdn}3K}i0DMi&p4Wf@I+M9jmln3d%p-yU!6o^n6z@E&9| zJ@A(8VUBbaRA)-)Wyfaqxl+fGI313J2V03gf;*{pY1~!&JLHqFG#+9>HF;d3v zXdl$dho2ix&=*!2JO6Mj90t!vet0~V4XfnF6)sp*vJ{96`o-Gs+27=5Wq|_xy5-f~ z3-Y)g6@QxYDk{oeP$d7ixl7-A09P9$_ih^I?AUcU4ebImfy&>0FE;nU&;IBn=F{#A z;yFQw=^IDi{*navY|X(cM3U0{IHN3vKt<&#J)$afO2mxV+}p=LB6|XtJtb9NI3>3j z?iJHR#e$|6U~1&|gE9ropGPx^1``H|5yr-8ALSmx5PBCvT~D1!A&Z zE9}#8DE-5|xvB1lrStrwn}QxhB(v0qc4M_3n&a$&3vx?`X!DDw#^u#YC11500bT{i zSJ$CIXH0`5^1R8X-hoZyx}wb@oj;q{<9%nn+#aIvzD-ayi6&Lk?zPyvyT{ZD6f8jD zK#>Y85n+blB`sqYQhoBA@u?5}*RE3BHM~1(v83U& z_lu8<=H*v*UF-{=Kc8DFX^?h9E?DzuznEUwW6CQCw^S~%B4_aPWs2~qnW*uzu+J6x2*m;SJbaR)8^ z)t$%F{UO)N!$<*b*81heV?2r3w0}7FB{KKtYfW3^SUp_iml6tpU-gD;TKp$jg8b*# z#C$n^!Q-^S8M$>r$2Ir8VkiHRNRN#j>)6k_+1MCg_@WKzg)41P6PHFOLL1z;^m%W@ zk*`NJq^oy0cP{C*bYQPaoG;(j;!I_+0srB=xy+uuDN{FaA55}CY*y5sjYhhxZDF-- z1u@_SP6)TV%)Lj!19#dnTAJ^f%pi>Y9}dFaX_!Y&;Z%}^oCKevjtbxYmp1tk?CsUe zI}*l`s;=n@#ienzN4Hz|Z&>F3Bas@b9_K+@kqVFey>_S(ZAhx&5eWM5Ao=$GP)Heh zP`ez!4-Zcrf`^G8FzOn!mzGipo92PnYel8k+wIg)3vu@KN|ZMj0tnSzPO?zHa-qee zo27GKe|EjBj=ws!6DR_mH-ZYS0K>KDR}#B+bwiam9&#>lMUIV^=S*sBEBFw~;~v-o zMZ@Ko$3=KlEo~BNEcjd&)X8=5iitQL`Dx>rgIV_iy82=Hi9P-MS$CKtHj;qA)9>y( zRuiba`DAF&@OwW^9Xg>ctmaS>`QKm4dzCI;%+s@YJ`%2xwTjwAWTAqf5>8Q(=f1-L z9B|z3s~ztJO`Mo}|FkeQGp{sRLQlV?X${>Z@gO_xP^1^|O0q4iOzt4l?*~(+D9Y7g z2+Iym?lIrPxjI>vhKjgXV;lr|e8a-FEU0|n?6MX3VZF-s{^oW;O!aN4Es`{QCk?bo zSNcV}8@N|P}(-3txy<8I?5-&=?07is+TZ(yRNbY3~YgOwRwLuh!}EVGRf zQ!&E}MQiR$YMSGwB&2_h;8GU7Ympg?f2X2BpRB&0K=Ycjz`AOhKfBSTykp7``-hp? z86J!j;M=yo150gWWSX)8ThxIcqYP2%W_kz_!LyKUtSN-au7q|eakT%0c51o!340I@ zwRd*%HuKi|3MmZ@n;Kh1>MaHN%W>@$D|e~KaEUIaXmAK|Xs%;k*j~+NeHgFp0lB!C zaC&A5hR^iWyx}t|K3ba5*J5GSqp+iB%_qQUQnh5)K=5E>tS8+E8qV-3)M6hD9n7z@ zvBQ>MMyDhSb4%cxeGIOKcd=nN&n&kIMHr!Cj{9)w!?J9~$j`4y;o(k8v+pa08yf#E zH%C5b(?#L&&YxE{DIMh2ZII*2$;t3)NAnyTDUnK%ceS0VLo?`#9d620G)x@g>J&N6 zNSPS8y{7pupSeCWe&#Rz>_*in%WM8^&6Kth2?^21A}rW0L>_VI%{Z`i8xvwUsx>|~ z+NA=eV=jsit!Cplt+1xX@!=1ZKWmxLjm@_?8?gP7te}HZ-`4-rO>Gxu99Yj1Nos*F zH>!1>k^4X)g-)PWct1}evsPuRn8zE!a|2qC{GATU3`O59ZVOgMAUjjfv(e) z7HM#Z$rF~Uu4ZD)H9vU7Q5f%eQDIq)Nx}Rgh0@hulXoQDzo(t-f4tASAyW9GD4og_ z=9MD7qdZIPWBXH~8!Rm?gl&kH$E0G8&(i$9nm**T%37o29R+|FF5UJckhpcPIC6 z1XX_;1p0;js5h}e^PQLG45r~Opx)p#jcoq*Rd+voH<^&=tDC1dEJOp7;o1rjYVRZJ zWr3dnRQ=(EVx45+lG*>4s)KEmXLb~v7X<~x5nzHbxeR|neeGkpaiD-Dna5+geZ zpU?Oudg|5Gf7yrC&?hGuE_BaxM&&xsFip3R@d%9VKeX)b7|%M!(iM^C^dTKuuI`pLskj{3HpfLN z3(QfidcdF%@iT*h$|eUl^<|8!sBNk@s}R;UAY2_8I2bzzJBsVIhKW?WKF3aQu#7sFMb6bYsKfw>m8NVPn`%8hx5?4;HBokPTDFm?p zWbppEc6z|1oTF4~LiW$z*IDnYC9(_%oGQ$2W}hkDl1i9mqxkTnkKa9=cy^h$^6U&- zxOH|iG#Gwsp7rj@7pzW2LhnCMnmr-Db0cJ#)X$lcx+QS=wDWx+uh$aJddDH$Z3Y+_ z234x5&~p7=ZF^8)Qp)18||?cxj(G+Qw-T*UAnlqb)(hjqb`eqCy7T%|6V6O@5r0e zQ6t0r;zfX;(<+@dI*A!`EVSj9ORO8781g_`HOCkv9hNij!lmH{qSU*hE+wXk*d3ou z=|D8wz0yJeA+wY$;d!Y*#@N%G$8o-ma>AmyMc`Kyg z*@)mR+xW^u!khfXTZad!SovAYK6i?_otgojp=cZ0+%V3Fk8;97xGz7jP}VZMeTH?o z^bC36^WT@)Rzu*CjL{yCt7m^liK&&EP9QFu4u;SaP|o_TREVT}1CYuz1@iVlI&-f= z!yda?Ed7V$;f4&yAu$tZ;~K`VYCK>+$^1i`rf3^gdZ5WsW}is8$ok2=@Rim?%9am6 z(eaYNjG3K8I&M)Erh2R5q4N(%&o*tnqR6kFy+Ir(O~U@g9@U*do1BxTP?I*$Bv-?@ zqkqOUch3p9*mqo^>6?7H`r!DRvGYG-!ykp@B?H z?Z|h}L`91G?khVU62nDM?>Z$cC-Uk$neOzmW5SskRrn=*$E^S=!f2`fPbBDSV){fI zm%qM~s#2q0sIHOydVN|gkbTcRLm~tIAz-gT#x2OAnP;Hoj>3+&oZX4B0>9t^|1&ky z)IHI+JA(<*!}7?0Rq3`7IZP^^AL}@}zJ2}9IW*9|?ELpw+n z{>L}vWXMFk$ob<0doNAufa#E+!0CXdWl?nnc;t=iFO4O>XBxX{-64t};qM$yFdkjr zkw8y$7-R$g+Hy#Q+?(Y89jcV`4}VG!Ou@)_BikQ&Oe{UKtUvy+)AW3BNynojkh5v> zj2qWZ4V)u5M~>SR^kx>dq!2 zYfx6&&K>S;Dq3EA!H8$!!4{?hkydbmN5fgRHK2inT{aVN{KIQxhn!8}a`;r6=j#td zb_3O;y_t|HL>S2U7iszj(=c6&&jp^^@8@-f#E}MJ;^A1!cw8+N;6HESW3JJzo$8@; zmqj(q!8b}1QLC@_S;O|CA^&iArj|u>vLp7GIZc{pE?L|Nex5Lg-1zuQeFItQwN37C zoPB^TE=~r_tM}{zxg0$We(vU3>8s%`nZIE8z>Rv0;`@3rO=(z#N*?u0CKKA-vTW5^ z;xyUgL9(}0EP>BDpI_ws;maD>zCIer;payBcvQB=a04Bdcrez3~1Sw}&V z8qwc)afy;3J{xmDQ`A7FCsqec6_@B^E6Hh4VxKIE_&O9dcoN(-R?xH844r43JAh5- zj0+r(6IGS?|GY^Kc65r44mzm}D6%&?U)C%?pLmJz^8LBHtYt5JTghXgm2OG!`%&cQ z7TDi_l!=UHNsUo$lpch%oL{52qv58b^)2X<74`Fkwf}lNJ!3Byo>VvqW41YDXc$)< zZDo|)k!UwhXXG5xhpt8-^ zsK{2KOU&vG35WR={_~UI0C%5M)aq$S=KM-UH<6P?Om!i}nkx@Z*@SkxqZ3_GIzBPy z{Gusvx>Ks)<^|%_lG;}Knx*#$-opGM^VNzaJ363sJ3v*_2Q#c@ft#VCrMqKe2oaR{ z+I0JMFcOW2JKqgsfK((ydE622%>^Zng2pWTua>-=!qpzTjQwqLEIXK*n%{`4M&?tk zgw=_9=g}7d#`e1CbuVI7^b8%#v*TKWApKjEkd_`^W0~P0Y{rK*k0bb1zNMY*@Q?@7>gS&749XxCiNBYFW;vMwrvbQS} zOfdtIj_hFq-Bx@=T>se_$$#+Qu;jsP^_~t>6k4A^+fk3^p1I;e=!4-SrINy+2R1?Q zguxZHSs=p-WZ_+1oP)!}2&LqxkTh=q)Fn%KsEPNs^ao&V?2?$2i6R40BwD+&?h0C| z9GzR?2jU1M7TN{jWbCh8k}B2yiX#Yt`n$TMr<-aFUNezJ$@#}G5R)?Zhi_0(f_w1L zTToqb$CpghMX^JC5P1;y;!cU>g2CX{Ih;YvQP;^c-|Kl7gmSj>BbB01WP)X@W5yO0 z10bYHVVWF?|L75cBid-D!ScV_`osHfq{&SjH}~i&*fZX zYhjXjy%s3SWx)oZXF!F=#)6dhdhi$L@vxqlR>=+Ke4;-o5 zyWYc3Z#Z(vL>?$vO^ZIh>Zt9=zwt}{krpaRH=geQ@L8=7TO~9DEza#)Ld8s8Y6xbu zzZfTE$-Ju+*-8#b)KH_7EPE6owslq$mW&4l+m_fdC#|8b++AdcT&h9xYRRu4yizr* zD#Yg$JpK$s+-#yNKuE*$Yb^&m*s^sACuebA!{0tHSW;CaG3rn95l`F&94V^PZDi`V zv-YUb6kNfo#yZv1;LXfSAxXw^{^_095K-z9fdA=~=rGCO8*sM_m=6`R4P#!R-S&4v%IzMk z>hM%P*<<7~x&YG*T{9J?Tqh~Ox`QWj-|W!d|HavQ28Co7&Y_O;UOUjql7?}>1 z)RG@V7;T_>5;Uo=6evXAGJ8kX(_lJ{2gLjvB@KR>#u-%ido`~77L{%{YdT?NtC(;r zEvjo0af+ExU=A!x5uAb_FX&eFqy5-G7W>_{4zb8W{fZjIS-ao2bn?yq3+I~@GF#E~d4;DK^RjLoW*emg`UXz$sCW?-nb@}RErN-m0{oXC}wDr*l8c3pDxDG*)UyQH7$;$LaS!-m@y3QU#jgRbQj!?`qtmydsXDs)HrpQ{&NC= zlJE9*c0?|1C>OOf36PiIq=dW7GF>0A=mOsIqQBBdA#SVC8usaSiYXBPhX4zhu*JQR@tsDbY&5$h z)_Qi+Wj-R|C5Qzi6^iiaYJPC6e^PI~Vd9ABiF6#>-V0lw z$Hd5+A1gAi8M$UD=<9d${B4=>ATk;`I667l%t`@AILP2SiYXhU`FH+sRsCHn=I0j- zxNd`}j1`MepFF@%6OW^DL)YQUD7{Wtf@Ue;maqt)ou0i|aD0a9% zC~+T|luEge7d@M+o%j_l=(CwI%tLL{#f(dz>5(p&G>hqOIMf<&u@}4h;qXAlxb}5K zu}ti$$-kG^ERHmFHI)P9?|4V}YV3(b6*?mg+X3YF`5gW~z|8*#vB6WSvT`rJ&9?W2 zE?zV9H&%1I1Gsda_#U2IKd4ES-47{|mpm$g|L9!(DO#|aNzKZS*^(5n`b?^C5|?^v zcIu-7o2)am+aV@J=uTmyUy6%)9)3*!=&D+A1@}>z&E0WG5^ul=r-lisGmP1w zo#Fg`NA&O^W`t_v;YNDCr>?HiY?B0q@Y2g8>2z(X?%O=L%n6%V4SmvO)#-fZEy4rh z6rpl5ni_O~k>fD-;tmZ;g(SEbdjcScoB&Sa_-Qvi`|xMlLOq!>rhJX(4J8wt4Lg zu65B8>X4hme}eg#0GW< zx!v%RPtCEHi(a1pN~LuA?U+Q$*t8D=`UtMJc-MDhNk_@XTmgmEVpEc-il@96UTJLC zC$1(=V|QAB!bV7&%#I`nT&pPQQcv90z8M7X?d2ssZcRLQso_0o{oAkKuy00d`nX1% z4UBjY;IiE*&IHn(OKgFu`=Xi3m$tq(rk&KLh_?&D%`I5wsuqjtbhnYSEM7QMLAU}a zZ;m{N*9(nHeEdGVcJ=%K95OG8+5lb&V_dh)fbHmtUIv+^QuU3>E`R$A3pqxj`ELNT zzCmq|=}tC;PQwc?Gj^bU#_rOnL-iAS%R)R%DD}aySq%zSn*Xhw=FQA~~z`UBCmF1Z3*{$znHNf}`8t*gvbcg>8W8 zO4JiQiN|J*lM74NzOyAei)~3EE(>J7=)S~GFZa&(WdSzxgL3AQ#Je&r)O{?DE2OJm zH&Pt7YoJBnL=_ZbnVEf#{k3AZ=pzPdr!uOgD$G*x_tLujyg+BX{tI65M3G3BbAVnN ze3iE@*Zk8gkt~}^pE30E1nTW+6?e7JMl?)wE9NwOdPf#-*opavBS)foZuCAP$@|B! zT}fBfjAhtMj~rYAaU&EjOkc!j>bct90Y0o z!BgGM^~3iaY#&Vk4`FmDC=&5x8gW7ywUf*7ve=%p33`1L8+qd-IM#u?OrB196wmU4 zV63&RpzSCR<7<4US>6A^ZrSLQhm8JveY7wt832ES&+lh_(oofg&A_5|{7@Z>9oEX!>-}6Vy;qA`*u_c5$De#^?| za~}rWqKb&?!5l=$aPbDZ=Jti~%Ol;|x%8G=v@dKM1p(dOK^99Q7soX{Jk5L~_C#Q2 zDa05DusjY<4FtH(*Rp*t2{dimI1k{%>!P1sv=6bh{Cy~Igz0K+`SmHOu#{4#niuOp z8FBk6UU-J|m{552c_J$~{kA+8?4|Umk`C2eK~}z4#Es9cJfuo@1w{D{(myj?^AP@( zl#gQ8|2abwbDF8YZ^TD(;gK@z^0u;${I(X&y7c9@X55<5m;_hk z$=rMXC1%7~h|b(Hjn?l6O4`jOmBzQtGa^V7$W$GJ%mSMvt2?0YB`1$oS!61&b-JAq8x;5#xWpU= zyo7UQ@qSR9wKMrav%n@**EnCkw(Yyi-owVT^e7(Zk{He6MzrBOWTKX^gQDNtnLW8z z>m9NKczq@vm>f!VzVS`H&>lO-!x!Y)4eQ%r3e-8~ePJQd*3^+iso%Q1IK+8VyfFWz zo_fvY_)~;|#&a*{B~Fi7i%aA3dck_V6L)DS)V*nH(96GeiL(8XgDE#P^(vgi0L3wo zd_X-r*mr9e6%sd2>}a-UjQhmuyAiD2nIL#G&NQmUnBLpDi^x*%wqbJW2ZcSNN`PL-i|k+#+$ebN92JBLjDln6cQ!XNf9WqV;pnHWO>pruY3t=TYBB zdkw(Og1~6b8_*s28^{9LrdJj}YHD%lS=qe%#tc}B!Ih(H} zzdUIfRO0p~V-k8U=DgbO=>lt!6x&4GU&7NRYES`{qgJ{9aIO{)ABO+o{A@G2f1y76 zS;>|d>S*|XID6}`CcMD^7X(2iM9ING6cFi-!2l5{Dd`50?!kc35=sf92aL|q-6cKA z(J{I^B}M)G_PzIce)sp>``L4ZZy``AIlJfKke7=Gekf5$`c!3ZA%M^cwVy5SK!D zNyYTI!>FUa2DEibxG@Sz^i28PQ%8bkTt~PKmWcO>dF-P-Pp8wN-tkid?B}LhMAoRB zMz{_}9N@Qlr7CQ-B~re_AL=pH&nN|kykDN*w6j!%5a1JkCgYftu@U?0>{(|jyveZ& zCiRq3G<*}?(6%`0rNRFg#tX*v^aAQQu@VQSvQ>PE2P)f=ZmMiP0aEPA!Ar~c@xmstqd2V{L08b{Mm9L~SYU1r4YV@O|d zDynN}z8@Eeumsb)^?IM9A#0&0OJ3f~x%&|%90ve3_x!kFW$w^E)@TqMP4SeRC7vLg zl^!P}X?<(&@T{n~q#V=K+w%mukk0aoaF>k7>mTThM_jh1{yL}>v8~}h2Wt^wna~YP0mjs38HiTSe61bnBGb7P%64*=E%%Q~Qe4u7SxC#0 zVxD?vcrc}1DI=H35|nM!h1`$A;Ci8m7ujpufFO}8S=80!RwsfX>d3s^2JvoS%yWJ( z$0aovhFwStzN;=VS1v&}5Vd+Vpq6ezMeNfT{IczPnI8|{Fd72grc<#tRxT@!=CO1H zSfQ*pk~m7l$BBC1LnWPghi!h)*z>6|hK}i>rIR+s{76FB^H90{m=xza`6Zih6;r#l z5SaIcU@kmzerppL19rPl_~@ecGM96Im2B5=g>@PkBAQ5*h{v%H{9+M}H}1C@oz2cl zpKas!66+NEQqjE0JROFkhg^>&GwLs-@naW&?@{2t957XjtyVG;Bh<{{h`R|!0GGD_rOvtr`z6f&`WlQ+~=3pqRYV` z>$Ku>&ZSS8^}<{Xz8gI0^r|8ssmR}Vw0odMZuZsGGcU0QhRTL)y`S6ydc#JXeVq0jASUtt=ci0?k%FB@rA?ax>ftb}W z@kR4*vO~mzcR)#WRd_rk?`{$ACZGFq+ZMeqWyI$HWNGoirg#2&_YbeOxUR1Ar4*v-Ix0;4UDhz>VHUfzJ;cGGV3YL(Shqx^j<+VXnh?^a zr{mE4P^`w!v$VR+uj=do)dv`c!8|L+{GBegDD24OYMfDKo`nh($SQStQ=X3{j)s~X zj=)K=wx#C@Tj_Vh7@>Cu`FWnM^Uru{?qrfHQ@l>NHBPSWc$^2Ph(YYZWck*TtZL&E?} zuFzkX(O3u#p=rJgd;5#KK29{s(5@nBI&l_b%B>mJndjs>q$mc&6ZDVZ9H+2TYj-j_ zFS$}_P){jFot0p_wKaq@4OcAX8T)8%EZqVmyOA}{Zp?km&ZE|QuZHsWQL z+PjYAO#8|c%~ek#S(K9#Pf-CuoTUb>B|G6J@I32{sQUwQN&umTfJkMW@JTrEfuCTg z%CWh!v$mZcr=OJk>(s_6`H!58GjpmpQr(q!FG?=XBY&+w6de|}ne*~-DsEWZoYbAx zo~92Mb%+e@9X6T@CxX-2?K~lyu@CS^48fLPhR{#Z386`b=jX1&67X5ZLm9APLA8hX zEOxxXXPC!)g{9w@dp5-Hu-?`k&A^CCgK1z1kd*kG37EU)xO&^R87^JX`=WgY3Du$+d ze>xTMgNQrqHiHwRlj!eV(;13q=jg5;h7>*Gjfs#43nc)=nYO}7PnyYr)!y!Cih8>M z#-<44hgs`o#`bl+8?@o_n*5)RES7mMNSiGuz5>Xn8`bX-nEa{VYSrEzDRc*Aj=Yr3 z!`fkBT4_~U&;n%rr`rI9s9523a&E=+^^<0gZBtZFbi#+B65l=KhFCQT9?TmE-V+VX zsaveNb|{m=rZoubs&XU5yx?bkkHE6P2w5PX-@{p?%^%+14=xtIs`G~Wy5!}_EG78s zlS0N6{Nk+jj5-teg6n5Qhk@#LWM{}G`F8&w+CDFQLqU_GjBYkf%e=4(g;6>Gl9;@# zyZ3VoMj0!ZD!2Y07?4p;dEMuTIT)Gyf}^N^|zZi7jj5%&#?RRzTL! zF~f&RFBQG?<_Y_QHczf$MqNgyOvlfByyEts2&3b~;j%>IvH(}(XIR2Tg~}Pd-``nO zDlbepzRo<=io;$g%b$nFYCMV$Uoh{!iiDYi09)6=7de_;IleDdke-7smgfp2B2 zM33v5j!9JI)ReUuMTVl}c(@90$ba^xZs0Qm$#HTT`lk1Lj2-*M@_87){Kmzb!QTZF zqYQ%Hh=vh2##=l$*_PL#W`^anzZq2aM5wh5ei<5j6bs{kh%BBp)iEoqmen{%(!}Nc zQ>>FjH?myMe#&eysA~BvO-?n_=ARUr`_6|s&R0EOPh*`$$JklNudPEix75Gw&rMSk za>=qEEp7dfY1Rq%f46S9BWluuIyt^3J}t`#GexhiL|n~;yD7Hv6U7FORq7@uY1+5$ z=)Gq_036v|TR?=*UL@f{kQq9YCPxo&i2`|5b8U?lLshhAymv3T9V;o^A3~wnVLEYr zZ{P8K48wQW9yGgWdJo?Jwn`eMyM5LI%IZ2s6Yc}8XD*EK3 z4ZY&KgS4vY)>!ic)H3J3=?^v60!C9H?|@iD*D3@<5FCpA=#)hGzX$z~LTak3bfy-G z%vc{360kBGeVe=X+&>g_$=u-azNJ^c?y(*H_0_b>*us5X(h1`UJGQ5_LWii-;6wvWp5w%2m&@^?K~AxK z?AiXxFQK#90q|!PSfKP4ZCR%LWM#KIRyscyu`=vTc(K5vB{>j;pm?29SK;-R;1FM` zAZMeLsiX3rxFZ8Q0VDn{16NvDAoC5e2kDgShyr3?+i1Lj~QEwUO9tJ|(Ln{*a; z6QY0G?{>#WKYsvgQpQ7&#%BT0pGmoL3&$d{@6K(XSL^kgIhZo}TQcNZ%3efQ-!;Q> zmayp`4eOU{ZWy))o^aY+c!YnC#X+c=@9@}&NBO*vH%?arD!QhP98CU95;+W9n_az2 z6DLCGez05grnqdrgw66VdDP|B+fHSh081?BHs37++=jW0bLC-haQ?1r@Xa~Zz^~80e^6Se?w=FPP?(I%Nyj#PR*w^1=ziEhIg@cmDj0u9 zq1s1C(_!S0Ug&a?%P{jf%o6YPiykb{pE)X%@>I`HdZLuUGmGAKR#W1MeWBMO>}LLW zBnz*ZoJkYs8cWwY@T19WLJn69&>_9$8B7?t$H3_f#I()0h%BqK*}g}sGj8|cQ{ReV zO_*$zFl1t6dG&LN4~@4W9>0*`#f*H!qM@cAYF@bcbNF)!tIz-B>qcwzBSqDUfRm4C z_R`Nu1K$He9@#pUVm`=8{_Jf~jb^fxM9RE+oEj8b)QY6Xa_k)devqEGaxkpSkv==8 zqR5L|ZUi+xTGb~^@Fqm_5I-nNTZ<0;xs8%meERBfOrZ!{qK=Ve%lrw&toBc#jch>p zN=rM||Jy@r?6zzD_@Jpr1uCyF+WG>+Y^hj~b7$S6X~yGmqvA2(@B!i4`+D8w-tQ41 zLFjylq{pnch_9aXEL!I@y8n`SiGd_Zt(Hgl%tuq?hr80B2q7Jc*+rw(2~`Imgt3%0 z!q)~$y#DC578%LpjpDRPd6Gn97;nvNmqodwaf&A|bHj>F8|dEYnu+k zwAj)`6fNG3!`7-0z^@ep4N9SY(t?n0lU)1!2()yOQD@%f5^H?RbfIlNTEx zB9R#OA-7S&ZO%4I$;MuP7? zIy;B_WS#$qgn%9-!Zx7cTe2CN00 z6x3s3S(>`*MJ!p$>?^0y7ix1v{@0<^sTNJm=pm@4sD$;6Xd3wA`l*``%DCB1flEhJ zI@M#*a?4ImS+t^!#Asm4iX$sA4_NB3>o!i_^xFZ4s9S@*^Y3tBonN#c^{+Ar`N+@B z{DXS|+u_ectVKqla!5I(f-G_HBN4RHvW6n6(Hx3OJ{Ex~Wy)*N+|as4gH}E*WlIw~ zkg&@y6KfaN*WZ+tzh;P85*Ur_C6B^S825{0O#m-!P~ZZgG#$!@)KZm|>@x0(TB_Fx zlW&(TSQE-K8wU&rZKSVge3`*w4#~{fo(`!`cVFQGPm}vZDf{O64xU7@MV*T|Lb`@a zHy;Lm37-)72QRi7P3^46MqL_WO)FO&uc-seqM{o=-}_ItdBSnBG^;GU)8`64r_V5e z$FC-V<2!M(079>vdQ6Ga#{>ER@L>jdn+`FJmI7=GPq?|IyJd-v_3 z0j|^{WY*u+v`LOHKEO`93A*74Qd4Q{fsiiZm!s&QQ`tfZKu5l*nSqH|OdYdV9GlIT zN3t&)Gm8c)#$k?lJkMujuV^LXk_$jz@5GQ&k6wB8H+;Pp#8OR|Gb5jXpvvxF>-Zu< zyKi??G+-9u7(z7>Wb^;N9o3KSLClqostc zh(FrTw;3yQb&AF25}nM~^`)~kG2xOT)z7wg3n8 zntt$_ijmy^kJbXdETmgAs&JsiMilE!lMyn$W)jG(=QLG-(-+JzlASiTI{0lT6xF`r zdW`_BTg8$c8i!1^Wmy3s7hiQ^tj?ru-woz_!~mcK!4SqR=I;SQ){YGo2)s3uVK+Ay z?;tD4i>N?WhX3%aG@dTlAaDzCN>%y|7Wc{u2?ZvEnl4rQ1t9ppL;NZ4OPGk)W%)$p z^GN<>G%q+b%bBX)0u@D1g`5zF9VT9i4dJ3UAFdy%l<+h z9w%G0W2e ztdUK6bDfz9f7KIcn&W_zn|yfw&37pSxBWw^E;6zA(y%@sJ|Ox{GAvwKBf==yVS;yA|8p-ySQI^()PcG$}}ExjzdGxTZnXgC~qhXE{SaB>4*Gj12DtsjGGU#3LW z6b(rO$%KVIQnHZBXj!xlgjCX+No`k9ej8WpzDb7mHJ{@x z$QF~rc${+d??ahp)9_pD&}(@hLqRZ5G7Yr*ZDsdY0S4SQa0B=LGYl)ty)ifAD9A%( z6|L&cZHOwqWLVL9x1L>$PGpLO-9W;Sm&9 z6jqiu3H5By`F#(v2ZL_zBok$Hc_o@#Y=>LQqAJ&Q9ZFF#GXnCGvb}F(%gLnjLv{y~ zh63n*G|=1?*1c89v=4dBe+EI3^Zxq8Z9U4JNVkhX)n(T}RCy9@YPfAQN^@ z%_=97YgPBLo;OHwTCfc#`PKsut%#X{bU%i^SG8N~378PyMK>6(cC!tYi@*l03gbQw zKJ*w*0RS1A#T0q{?|4?Y&rfagQA2ednTQV(WgSuN=J~xP|1>ESp>%Y&CX_3w)tR!z8wb9lxob z`WYP<(!Xd6*%bp_eA~acdSe+@{;i{GvLx;b3K}if;e8<}D_bc4{!hr6cQuWXkW|D~M1%o^2HBG?7I!=Qa!` z*TYi>=B`{ZE#AHDp~O*7f{r&}Cg9v>X!Z!GH`9!w2ai4T^S4q%vIF^$IED=Tm6~*K z9{qh&aAPs-JZd29kG!iNQa#hOOrs6tisw`5d^}o#pGtUsY#co|5&zh21HVVe9Gdzo z+Lv1KS-V`sjv{GZwB^@NQVZf6?^tSL9Mj_5KYE5;S!Dt5xUILR7#4;~<-j#?*?fdv z#gdJhgjmL$OEmE&3kx&%e#P;K$P#QB(_)`8c{cgjiW2aLlFioO*_J)nCW;}Z zy9*e*ZDyEl?tAHR*mJJvmt!qgGQ2=lW&etu^l7egQc<}_zfW#LK)2{2_UIGAH|wMt z?}FkeyH&2x@1c)uHme^WskpSUYJFI+EqGOlpu}1(hSMzbz5E z5aaQQ$)I}EO#?A}rI#jVWu}3{SB!>f=b*2GqHqD1Dt5kJ?;^>8ecZ)a_w8$%P0!on zE0Q-ac@TD`swZ9sEN-`TaD0Ci)+UXygOd@LjUvu44Y|&1^s@oFsTZTkvC@V!$!Z#I zC1JjHrUZ1hlG#NBZHt43yx*hSyq1a!L^KCg3=DR>w_`x|zk*Pqz$U7rv$Q5#(rmcDxaAbE~5s>aihHN_oF3y(X2$RbE89xVl3ZsPFOHA~?!!==LNVz_xz-o8 zd4*L8Q*8{!Cr!Pf;km{v0ngQEjMX$<1JsX2z|Johb8C7-dUtye#)dPAZJD~r%DkeT$!bd#LCLmpd!m3hEItMHkl zUZmN~Nk;1S_V|Fb(m9*3b6hN4^V6<2jqZ+ps~M_i!*4(5qKFDBk6iY+7We;}8Cc)z z*UjwzRWR6Yud?BE_B?N=Z(&*@6&I$U#cpn+6I}FXaQ1|DP5`5nFt_DrN8_Jyt39oM zv&rrtQF%CCjXzKUZ|&b%0z%UKN0)FgI%@JwnQZ{q(w*Ckuq&-k8x3w%G!5(iT%t3< z!W0IwY#RiIt&uti<=K|*+>xVG9k056*Oso`pmIfakpw)Z*=8RFtwH~Uh4tRjZ}|^s zNMR2p+b8@SxLX&>o&z4_yi+YW4m5L@ub8}2dhaKiUiPGfS-*)mlkIraH zDO9uE=wH5u=9lM|C7(_8Q{G4|aBpd;@DDdXrWIt}81DckRiZ^TE^ap`3)ks9 zm4igb)Fg5*7+@w#A}1G#aISA-+uO62uWC7=24=g>3IoynyV>5Ht}1!nCeF@Qs?H!{ zQm@k}#Wdyuq@337;yyFQ%=?upx7CXR;Fe_Ei+A1^K1ao0wE?NNQfh9ofB~TQecWm0 z2hP8aB>|n3^6K5BY94UEN5c?x1>)y^`b_59{k>wD(5>BGxXZNvewC?+b*S=V6U=jm zxY@=BBM{p;uc{ZhTbolB}(I^@6AA7W^fOcG_?9e}i5^zr7s= zhjxUYF^BE3?hL4V+1uV5%2fE0cHk4s+wR+rggkLp09o%Z%K`-yh2e-K+>9A*u5AWC z^y#p!3*`~_t@u-3pX6y%S~(|0_HPyV^GdL4IRyx7HSaG?UWAFy8hKzYb-sj3&jO3n(}$sk*mCCLJ(u5K_--aa1RL>ZpdPhW+8!$^-j9jJbseBR zDX&k%+%N8}p?N5TadK&L1DRiw>c=o^RM3l4)!IcSf1VpM=KI7~Su9c|qdrh9`!I1L z0g1sXw8}iH9&KBP28xhIxzfJYmu)vWjfAdFr1QX34CPy>oh27k2cN<>PgXEJ;uXe4 zek(JUS^wdwTEC*-vlXnr`gmpga^YC&JM_Dx7)!y%&~3C=(Ya4)v$Av8>t0>r=q0eQ zct8_t>flP1YCI%2j9z@3mLWqUx%c3Q_69hpe39?#kC0_4>?&^3D>MJTht!8li$}UK zeH5>}^>uMkpOiTNZKkeLLe1B#j}iMiDN6b7ykoYL8??OXaZYmVE2D<#m2u?T-oEJ| zF1iA1cTE5GG1)A&nnpbx$sqBz5*zERy#D=LQ-ivv=p$>%E8zCBnQ<>BX+M3T6RT6J zALU9!5XgTNp15gQ7gg)p!E+rAbCBG%rPW%f6L18gn_Y#yk1&$jx zqwExJOFk{F0_)l^Api+4Z>_HqF~`TV5X&wX97iP9D7*8*fWeREKs@5i(hnq7x7NOguu> zsi*7VY$w^9`eY+{h+j38@OJqi7cd;Le7UY?4$2^xrM{~8Vz3M9g;iTT8xn2$;?cGv zdw#yYcE)6OC3rR~)^><`6@T6o<_C=~i8*Rfzt{dDQ2*SWU;HLHle^L&erym5A;%-A zabR=bnhNngH?kfu8ZtmKavxh94Yz!yqBOTB(+_<&*QvT0s{R!9BtP#%`m*+8E4K;n zC6ektv9j8}teQHajR}^zvqN_oa!S0sE|L&Qn%mmHl>^?_dPckng7HU!o(UaW0)-3A zyDh#pMs8D(qoLATw6ZD|>Be%fWb$_cPWO{!G@ECbN75p!XyMOI)D!#Gh0kXSuF&0# zyLV&f$rVQTkdE;uajeM|Pl3QO&~4H|+(~(EMOeTrv1?s08|tAwV_m2I?1yd=f6AIu zZ`R+S^09xqF{XyP54*hC4Ji#^89%%6SD)_=e#J1voEvO!pi@Y~%sAJT-4J=~^}^aC zoBi`U?O)2goo@WwJ4yDh79EBYIbP@E&Tn5v#%vfaZui`-pu(BBe_Jp9%0h)e+&wH1 z2dke;zD>}ve4FT5%G^(H-vF0k{F|-$5L_jtjAR=X=OVE&xs~MPWGlTsd=>k)f5d

yD3})3IYlN{DiLWNQ{W;=Xhlj|m1qk?uhiCZ&=0NBMA`WZiW`VE-MZdDcf76T zmwq+K^Op$9{UiJo{Kstl&AB*?U3rFa?g{-tB!dW}<074lM0(y%Y6 zBaHMqO(^@_7_#-_44O?dsnh3c0^>aP@iOs9g^4HC^LN9lYg-whB}%_+^%6eahJ8 z$5Cc)uc~pl9)pQ55Od3D--h+3OUqDCk(->K8vtj&7ejA)^CH^%mI30Id`-OvkgY6p z+t_J~q>Cd|VHD#XaIDtE4cc;M*211*dfeliNNMmHbx60lDM`1?>FiPB7WjC*U2j57 z$JXlQF~e>{nP_7IPCO6^VMd!-TsvO z#gdV$!n`w{hKl0sFx4oZ|2!M&g^|))^Y&n}N2*fie|XU!=2@Z#(7<-_t>DF7gAOFD z`@=kYmT0vq5JRsy0$E4@EShldg&RgqiOetB>pfT$L}VEGX%Qq>PkBj0jwJZA7s zIJ;f)w`r#AUQxdiyA-)HDJdbuWPMN&t<Z3LWHaE<-npTB75;f-p^(IvZ_l(xMFeL+jqAAv+#rYI)$1KSi;)gEHU#K>a zWuvu96*PNq9A6h&*ezR8)C()Dbm5(7bN|{v|KnL==Ns-(H)$*3>g70C)rSO7#eF)F zx@-xQtiv|{OCIiBBw4(0!(>Z?JLg;njo;a+)iflz4g4fE9pDgRt^r=StN#(mT@^3-3*5jUXuyJpW>Yys=P$`oR@+rqT%CJX4PRcv{NW_7$=mE;oGe54x*1HjCUxF7PB(R5 zPPvT}+w^BHRX z@S01oiki(KCyBE={;q15cLJEokb`T=cC$)00o zEk{yE#G(FwG?Iz@Lrolx6OBFf#`haMSB?$jnZL>^Q_{}{Gc;B20=H->Gw?B!p_czM zi~S8@iRIHGY!e5E$9b9Ko_were`m+$j5b~i2rCdG6--3nw0By><9TMngN@aioPB$C zTLkwGOk zYo}y-<|-Dy$j~-i92oRF8-MGO;4*El&E&xhOt&T=Yl&U^g@xXu`ENpJa@^}+mPYH5$l;pk#)&t!CkK0EXFZ z=>ciDjq%ILRvJrV)j?h{mJ^4AAl_&gKYrNV-Q7n`$G=gyl0<3Iw3uWe_DQ6{fTss0 zroztgE!~QRRD_^0O?*Xz5!dm*kp?pRl9=+ayh?*DL<-8K~oEhR&y}W_)2Z4Z$7lO zTjA$miuiy^Fbf^HZQSv-2ei6zjh98|0N>>GVZXv3zrQxHreAFtyYP=r&Rj)RqK@B7 zxf(LDzwjffwP(;2b|5-0qj7hB#X=$#Va-vJb)={=1J>wT+)AA36MQ^W^*}nd(Vp+Y zd4X#K)~2Fr^-}}@061PcNACQcV0us6s`jw{@!Fa3?5vC6B!$tA=3-ummQ29LTEHX0 z(WiNrCoy>eB2i!8?W#b^3H&;s;4SAdSZ- zlB&84NHN~OS*U_^Ot`xCbK5?Dcisg;{fNAvqR&dn=S{aZ2vEptRZ}PTZLEoQV_ck< z2_`zIHau=*ke4c&P-bMKmV{YGh6Ww84=HabZ+sw?v0r>WiM^23HwD(~i`EP4X;Uz* zfrvx9dv`B#(Df_B*P*DAbe9Han>+?TaX}D|Q)*4e=&H{$lWQcA@~4Gwc?ow+xj*LS z92}QEd3x#-KbWr>E{pcAKnq}S->>Jm;|kT2hyj-1U$kJ6#joB$*V(UXoueFnuv2&*%gK$}>tDsJ`tckGijg4<3GG7E!x8>Ze(QC^_8S?!Sidf_d4pE3G|<{+O~ z=2+_X7D^0z6uCsNb<9k37V=kxh;Y5&m<^Q^f~IebH7s~$D>w_l9w+NGW&E_!J}S~d z_@sJThL%*Y{jWyTgq6&L~Eu-WA2pbR=n^4;9EjE-f1s2 zD=Zl{VbimD$v#tsSZhEV6!fg!G_idO9Yy|^vM#Y8Q<1FAz=5M;x{|FPhf&{C0{vX; zdOL`DAdb5|_GhM$1w4G%x~-;;<;X3C(;CG{<|ETfSICKj=}wrlNVKnih~e&QpZ+)- zKsH}GOkU~2io9={Eel^JmE3MGh4GYW*y%Wb|*OSC#LKj3T2&0 zmkdnyq!N}G*2K6Lu)Bxl8Du^qmgeZiA5e!pA>AiJCg#r~J&$h?4kUl5;Uyw!34mAj zaJAz#BbXq+5A%Yr)}X!>3dz|a3+(^^fpc>-vLrRW)X8bN6sgaJw*Z$ zrE6YWBe-?G0scx6YM_1T9?;oVS?hS8*#f`uOS+ANcegJv+)`L0Z9f~CEt@kA-RVN6 zXKFGUZa83@_V?!@>ikshyQp3yu+?vKKnqv1|)RrbWMx&w66+W7@!#R>IVG*G24$FA%3J*(*`d-PxU}U=3X?IKw4f&1Ol?=?W90g)T8h6DRB9l*oz8%@Ewq<@xHPYZ z8lT!x-qdeo}h#&(M8$m>{EI4&s#$b4^| z>Lq;MBs2^t?i(^EF?luj$x1+BVLg%YlcN>G7_fP>#>S)qtD9p|)IK{%P2GJ7(QdjN z0k&=Ijyi1G`XU@SM5xs^IK_OI^*EyiKs$;xqcHN346Cwe#0~#Us}4W{>s|J}tH^JY zFVNrlOgwapo$J6?{i)h8Yp1!!1ny3Cv|O;MtTjwUq@rzd$(V};@y=-9>Z#?0AKn)3 z>g2K=4ArJx+`I&Xy$=hul@;w#K~Y`myP*aQXKQiiWblrpLTmXkfBC@q-)EW-BO@ z&ID(aq>6pTq;ytM_1w>+(_!9A|NE9)p#8E3s!^x2y4HRnl*%pI^&G$y-2d2QuTlh_ zgDiDmf6I(NY29^O5F8)NA%C&!GVQfcJ3z6^#2(0UtE*OA)iBLh(Ktx5xooXs@(0q@ ztx{;xIv;wI2DT2b^M)GCIOtpPMQ)PD7u;CuG>lFXo$|*$+U_@H2||e0|J4Dy?L-_2 z3UpDtrIWonwK+6m62IOip3qiS7tmx;BscD|)+tr0^g8GNUGIW^AXsM`(9k*br0lqr zAs!E0FGNhr4%e;QlX&5sb|>udd}LA(XG*x$l5>s8y3tl^V_+$A1N9D^-$lKzv>7zk zXCPB^8i@mDRm|I8ayq-`PhFDwS$XjI=eYR*KfKypbL$OjXkJhJT5wW`6vcZC+VHNV zne(CPEafQlXUkInh(Qzy`U5J-{PR=L7p{y+d&9bU)5Bk<$3^psU4>~ZJs|75Ywh3` zjc2=?DaO{9m|Txa#2fmh49d2Vo8&S3DbEGA$~jYQM%CHtp`G(Bp>J8KF0Gce27jmQ zcUK43%*3-!lqcI3icZl%)-!jr>?*IkLAF{$3q1x!*_0O9Q*nUr`d$Q z2JnhX%Bl*IS|2V3j=J-b=BYK6=V{py9Afy+Ab^he1G&4`T{78i_ngJjE&LG$Y{HdR z+fCVVRpq`(bq#09+=gN9zZRuSaZMhrFK9#5?rAyLVRYpUBcI?ZUr$({n=!eKa+mxP z_$}eU!BtUp7GaAE#&)lQ@VtuW^gy5``>M_dLs7WE;L3FZnjmI1#+*qTSly(@^J}&? ztrC^s_7KvW-4zcHh;m$>`_OFdA8lDw?&Q}+@!4ygr4F=Huv#a^Sj;PW0MirHyVa>3 zQ6hKBhq1&`m#kMTJ5WE<9$;YXsZ^8@$SS#m2C}hr_L&qkYM3gjX*!h&$GdEnZ4jM$ zNj~|J&ggEcFTT&~k@UJ~o+Uw_w2g()HU+b-7s%lvdeGT(kVvd;WM!?IVFZ}>tL^xg zo)WSS+0Gul>R=ZuYKO%lHAa;U*)?S~6&Z_(hk8~T^&1u!PD#+&3V^`TCI6$dM5#^0 z#+;gCduot>77_l7f;JC|nikG0OZ});-xB-QCc!6>O8D*Ko9zj8bW2f-*1*f7m|6ra z&G{1JkU57_nQpJTBF;7bzJ9V#%pGj8nbki>?o{p3i`-nWa7mw5O_J%(Prws=+r_eL zHYTGPb8-4xk@2`8tKmGn6KOX;ccaw%ZNFDKz4e$FD-ov_60$Eb>slb0y zgUO29MV*+i^+x@0EN+}u`OSK1*s2s*gpXB1pX^9@Ed$y!0J0P-DsOXUl&O>SaF;tQ zPta9TN^$`T!~lDPfqKxLre1?{jF+}^VSZi-v?5Mcg(O3P(63Vb2$SqS3>z+z_�< zmwF z%VM0|bWL7T3Jco3g)XgUG`0KNOOiKDnsAwFO2PLv6;(dGU9pg?gN#9>*|x5LCLk4P zc2;|P#vicZaB{2Szci1Vp#V@}IxIvfZCyl47TQg|)}t;-8@rwXC0G6JvRgO2Cw>C3 zUWG0+Uo-rZ#{m?HarDW1zM^>lnpp;tOcdq9}`5(1XEm6f});$F- zqWnt!=vl6xRr4FSZqD*K~ z4JPNd?v%9|+)jZN>62OOj2%}~t6Uu0k=qr~Ef^+_ErIhA+=o|X*{0orNa=RZZaY@8p}?09sUUdwO7K z_em1)kU zlh?LxZD~w0^?P^S|8RXzOvH(GkO3TO?fV5Dzgp$mWxb)$ofA{ZH_JX)K&R8xU`UKTRYN9b9hV%pG4S z;b;whDQK0*EKYvO?LT%nj>_6pC#07K)H~i1gP83mrHw+kkG5wT}IS!NSXd%6LtH|M1*LKCFA@I`_bzeCSx<*iVm0 zUGHvJUO!Koe6#3Kgxql`#g#DUM-<6~gJbO1e_EyxnwIRpY*Tb+^n9-n-3C~e?C#Wk z2XAdv`M%%b8o2J`$jV0t_I~l<8x*I6eCW7V!m7sb9XJJmV0imK-+Gyz=ujG?mIXxL z^}^|fyhKrTqa?>vZHWU506P1JUEK3ECWELtRyX}G%qp8G(Ls>KpxeW+^i&L`w7Ernp9_{wc>KU zw{KvaB97Sfuwt)0R_3_|cu!2J;21_OVqcyhOtMCvaLATEcg13* zP;GpNL2?B#Ti037>3-l8@E@-Eb!pwW>k%+kig-p1!tDE-sr%{YBL>&eaHGYG+GXHK zaMF3g1Om|%L^3RV+In1Elv5R2j7&}t%BJ8?0r)4(sT}F?pEK+gMl=MuG;}?cVUw^H zUE4p>Ln5@BJBfdS-<`bd9eS(hU`oSBLC=YlWnp#7js3|3R7~MgDt`?k+QeISWx?v4 zxah)fsFm!gsLmx6{W|^tpT4?VrMRN~PM+aEH++jK&!F=dUMV>aY#!O|HBVIu=(1na z-*x>0+j1X%!Ap57Pwi1Vc=bVljqbb;vf)1{$>)?$Gm|7d15=i$p2r%ADO$Qu%;Qih z*=L)FzTk#_(VzRr7o*BRL7lE0bn7gFKSWIb=WxT(oj&h%DO;VssO<n?p)+4k1n(mL!xKTEUW*LHH2Gdj?Ral^yoW1h$*hz|ZzII7C+DcH zgxv&<59fjEhm3S+YVMTY%EEizA!Qt>y*uybx)p8r=Jv*{|3%z;M>W}ejiM+D`qHe_Ku|zbno77smp(rRwmo6tLkkdEr~wi>Qa!=<*S_zZweGt2taZQVuP2k4J+t@h zHv8E#W2#|oQDn1!N12Kh((bmai6Iq|^#QLsG>S^!DOhN}Tqa>f-vwE4=~lo!^WI}K z2Ai$aO=Fd~QvNRG+ba&)#Q||>O)cz1Q{!nRDSDnpoR~dYQ9dE3g;s$?E6_;PB)6hB zc&rM*LVK|;gbdLw@C9Ej5WG;&%9+H9ip?o2Oh~9N|FT~Bc=Yk$17Hts!MpZE?G!T* zm4`N|tcIE*C%DW?a|yUNmvG(i1KkoUVG_G@mjzfy+9&t@&K+wTL+*$vo&nR(41!*z znJd0(8ie`%Lr0^sZrwXqxSsmIsh!K_;n!v#d7tH`r7bMv z2EXSR!N0H4r)4|&b`5fhqHO!R zB;@8XX3NNd^-l9FA`h87tO2CFP%b?$76``&A#^;$JBuxHeqd50?obUubNsbhgTJAI zYmxZQ=XLJm{3t*DDw&iDeM5CsIfX0vx#6HrZUh?gRcYPGyW}NCLq|dJC9|_VXi+1aU|JW z9J?j_vbC{a<k0!!Jbc#o;diuq3$u)S1kG{>jbEyZ4=Rtx#pJo#$Qe69JMTR;j z>^=|2?O&s<(!FHHRz7rD0x;0WA#we5_n-yZijJrW{k09G8QS@LKOJ2B!^ zFT9+*3vF9uQf2{h1<9>JM#JcE_!MRrpFV6a-?U5l@Q`@$H?`x^D18617>>%oEN7V_g?%mDoQd~M^gEhOe8=z(yu2* z2XG{woZqYkEa3@`+03E#Ii zpiCu#zj@WguO3v-ijB*}^+jd4L6!2d>rt!z?|V1Kw&!R!1=eKZm(jz|;Vq8qMP7>_ z_XPyv;Zb&TPDyc%iuIR-&og2rmP#C&$oB0eU~ix6G#1|%uw^Cruwu)&AkWq^^uE-O z{6#C>fUW5pVD`W=#EBxkk9Ws@l#Y>?g(Zt}4j%%!ooziAU0WOsZip6L_$-tLmwZU# zYefQ@lWn2xGU-EAHA*@4hyB0s?~fY31tpRhCn&NhVn_eV}ylRql0GCb6w)6Bz``6(CIREY)I( zUFC>rdaorPvxVMET%pQ5c9iCcRL=qPZxYsF-&LHNJnxR39RfcsP3XDM8-%F3pz(F~ zr>_d@B69BXOki+14Fk$!I$mVu(Vm>?FUN_k9N)VfKlo+oCj7MevMI3_gJ&C@x{`K2 zBRIbvOE?^8%EU34GXjIwTkcy8zFiAIZQyDao*%xD{;222R(+hG{*3zn14zJJv%Y0~ zv;w@QlWUT-Lp=LkE%FiV=3T+FQ=79sb8CvtWsNw2*=8st3p=G;HfANF)>UzZH$49% z@qqm5Blp&!X18WYwtd_0mR!E~b!d}q3xQg^#G2bji)d!xqnJ>4O6o)}@!@^UAYVUO zM9m$fUt8#oG_z0+sp2{Oi;%=yWVdY2Z?7Tu(K8hkDWiRG5Wg+t*?Gbx>B;w?Olx?! zRiJ0cok_~CI3iSdHbFYDL&gQRDR}J3-+*nBNu<7G6kCF?tumA^IgB(y8*#rQbzgO6 zdwa0ye|uXwQHPu<6QsX2nMFqT^WcuV$MQA2CzmEEbySI|kJ zJwYn1ARrPaUEQ^8dl%o>$)9!o9L3Y0&b^340K9gQZ3_*|K}AIw5GG0rrah~*6nGLs z$`>ETNJ?VY^-+NdlkNan#f8~Ews#ZU)kB?hpwJb~=Y)QUvoI?=_6>rm*~M&yq|QCD zj86bfPc)6SZB4CJ&DG=Gf^wwlHWuZPB@d?q8Yd?wKP?OgK?_@Zwm}uEgmrzo`dRC` zesz_nzksw>9+p9=u(>9^!+a#WgogC>*eDtB!wvMVgKBc<0p{0w9g_y0Njb^y(FnNFx%XA6TGF z&Z*2j_Jua|4hLU3npVjRAG0(({qj5Z{Rm&g$N=5e)B*9ThCAj75J>xsUYPY+6I8as zCa&7cfZzLmM#zB92%I}^_WdA=le^NaqN^A!?fBG^l?07{om`L>KB$S&7=gfN9z@K} z8!fI6zxG<|kdCyi`C(C-5Xstv`>`0E73?=}HmGa#_0z$I%I#STjMzu`&3o=fC3Y1& z&z;U?re9&W+2^Yr=8IJ;schFLXSnHSw{aEIQ-^SJ_^I)^(n+cusXFDZm==0v=f%%4 zUBfM&r%Xfskylh^uN@jdJm-vy$`?INH8?iQ;sG!P4VA}FC0CY-!40o@g8{)@j~>%%xTRZWVf;TBvk%YEd-xV|mXj zw!X@5Y@$xz(L6@Wq$0{~wc4}IDOtEKGqH2SMUcX>p_&Rtv7G0{D+aJI9NLXY718ttf4 zAg`@N2Zq=@@}f)^YqVn&y2%(S@qwL=_No-)45I|wv1{Uesay;Zu|JoWkdENsw>rmb zI)amsV? zVxNIi*RmC~wW|}dOKyr*Ze4pY%9#2-#UR?rA^}I)>cGwOZQn(oV3$3i%%rPh>O?Uc zr1t zG$0>QRIhJ!u|&Z265H50uib*3=haR2t7^@&{-NHVYHYaj=QuzuccRYjX`NXRh@^aossp#U09-Li?-1mF7 zM6HpK`jz`>b>xkjH)JD8ABBJtnLFF}T-FXwOJ|#776hR+J3e(<+CQ=8nOO)tDf-*| z!Naj;i2^)|LnV>}NIeYO*mT)}P19e&bn-Nns}ExmMTDG2#k>y9`i7672}g#G;<<@^ z;B*Q8Ta^g}35DJM-8|qqAeB-yi|vlegNtd|6;Q zgnVYS7AWXkJ36d!#qk)_J>8HYi4Tdn&iBI$oZZWDcZ*-eOqXuzr(>a7Sj2FZQ?k^L zPrU+h3+SH>W=IVWcXVQgjiMX&pvV;{uL)2EwAIPJ^+XMsci3-#g zM3>BYdA*g#6TgI?KN7=m*oz#Abumv98D5jv0X)^i-M5hBtFz50#IoMUhuJ67kav?W zR!%G;#gW__lz1bNdiM^8dNuZC@im!hze(IxvuiHzhe$roA z0kRbMRE5tNqjn`Yj?F;2ONKKCFqi&4UYjtUHhJ|cjWUmJ=TYJm(K5yhU1YgAmf-I2 zun=#kbeH(cn=MXQs;EQJkYqTqtY4#Q=cs+nT^oleV9@Gc4EpMP%c;qt|FA;;N+^tt zO>KR{0Fy}B=B=s2ww4_fnj^LJlN0s@g!sV)zdo+xTEEW|+vMr)er-};J#9o3 zK+#f15WaI@xn%|(&&Z1*XWm)xG^O-JjJaO!U~q(lMF|zo;=fzCY%L@f%yl^NjhEBV zm29$$EF^r~babJ2X#}(|&Y{=#y$<|%QNdVZ;pbY7;nBef!UV`I*F$*ZS6wT_j|bm9 z*Elj2BD!f3x@8r=l9tpC7I1g2pS=jsc6pc*NJ-Dt5ZVVUT_817KiGxTc@oT$T~52* zM`%<9?nZ`Y7#F`S0{?W4687>ey~B~2Sb#h5s;#T&mNxN-*?odOrp$ykH6egS{`JK-xa@Y(^xXP3XI-SyrCWtT07aM_PxWor3O?PB zJtwaHmLD!j@yV*lm|wYWVkDq@n(DR~ImiBN{D+Ns-dj|A^hd`Q>ZXzlUaiI^Q1hJw z(()|9eXD$2Mdfwn;BfVqM7wxxEe#4KI8Ulb>a3rlcT~?pBuKTZwC0(UXk>u(_~A1f ziXP`~q!)?S)BL?B=18|ypu(Tr)0G6S+tKdL z;k(EZ6S6rd=Nc;R*i@E!nFbCN*98xQ&68}xaP|gW;|Ezzhuy!O8iwuPyH3&NaOwd5uEK(QPUgYrRD}H5daH+QGiYJ(zjqg$k~i zAruaEe?;OhD#NM^m2O)~dzCZh*A@>nh3H5yxNpSfBSIL0J3l~Y^Bf96KEb+q^m~)` zba(IGo^Mo;_tb9+KJWoZ({L&G?OH-R=zSwiO-e(QxGrw$Wcu^y%$)v3`AeU3%~*&^ zu4=x2VRx1NqT;TNjL+YG$Qi!36p$S6Nxnz%TZi<{_N7G_Px~Y;jx=+uQ_z)?g^97N z85j95>BVn_ZlQ_v-m21`aEuq0@|qged_%w7yCI{HgyKyo@x;Eg`ogyG6M^?4L5^2* zgcZTITR)&I-LvMw)AS0~W=DzA-09kwzJWB=SBXqrXAGq#p9dGjB&8GHr5HZ_(4YvM{@R`# zYkt7!;^spSDd5W-n_pt7(>81HKj~Tr+!t+Y_;$FUp+xdLiU&+&6S#nyby^Wb2>a>$ z7%BMq5M`o~Er9wOP0M7!T-T+x^StOAWr2y*;R}yF3w`$3UPTYW0Th6b{lmzd96@1? zb~P@ahhlHDC{*mISUN=|vc< z5ddgMRO6DfWY@@m`)As`sq2WG$^ht8_F7qq_I=sP~q;Snorfdo#HK)QX0x;C*2eW=;~HkY8^FpOdAsS>;5&FyU&$ zJ?je|Z=O2m=#27LbR9ssL%BW>UPV5|%SiaYMsl&?)}b!L6U%x7w=5vgPd2^kqUgN_ zfsSc*oX%>*jd-<(IxHr!^&`#~Tb}vG@;jvUG1S&q5VWp|MZh*w6~n=Ud&Wt{x)$T{ zHByhEobM+?jzgOEm5X#5?vEsWxSd z3QHy)CK{HAy1A3Dinb{ht(`kLj!}ev_sG##UhAw};G1}4?(0^;!cY&JnHFwX&jpbD z>HEz>oxPW$+0-`ZnfcfkpwDwHQZyz`yiJ4dcSJ1J5H!GT9Fe;i+LDRy$IS%Ro~v}K z_kt+8yioG~uqAZ72P*yEczvI?m4}!s_T>AUYR_t9`K>o9ax)0YQXP&0W%3ytn}?m2 zjr^X57qZJGcLq8P)b>MNH%l!!a$|Gc=66g9F3B-Pg5@uy(u;CZgwW(Yv8BKeE1`9@ zKJ(qW?xU9u#nsx3RnfjL+h#ut=>V_dd-vCNW(gb3hO9SJT``27utN!xDaC zwi_}xiZ9>DEJzO*?9BV4Nf-_7T9T$6R;Bx(q$IgXrBQX`rnd%p(?Oh~Q)ZsqytC!Q zbfKHwvW4&yCU&;+G&4=FsRl#u53?7lNRli&f+8_0I7|i>TeUX9pZTHMaM($oJFwlJ zI@P%!WA zB9}DZ!nq>r87jDiB?0c}xmAzb=Xr}{xc5#vKrtNtZT}{$!LnVX#A%hC{KeUPozOiA zc}4V6i?#EG(rz<1IfN_oI}&O)F1Vr)@y(Y=g`qYpSY^fQW1D#O5!$8BR#!B?FTnyS zGd$pvP=G{^*f8Htb}{ImdP4nbsjKdo2(dJ5W^T@;KRNc&!4}sLLRR}5B%|@rC)V%Fm)oPL_`VOIB zF(~Z~OYvtsX0{hxY9ax`(hw%05y*j+K)p-%h|5x9nm~O_GoRSn@POe2ouMAH3N~%; zyz^6OzNoxiqogIsp7Y`^AkEdj3vDn_RsPp(V@DsyDZb+YV|I7)>9F^&{W#n!Ca9dY z{m@*&DBhfNAw@Jl{d;)m@RCPC%SR;xxYFG(*@QOZkpMZes_yp4h$f-<)qXAJ#? zc`u(jW3Tvh%YBzWF(Z*mtr2x)Y3z^~6DXCH;6bA8Fn9n%Znt}WUx>q{U{;)$65zX& z9#wi7Oo*LcS3clS!}X_2w4&h16%tL)yDp2`EpJC~B2T%81#6TFMn^;bCcEbHA@Vll zh=7$Ld`bYhFBh-KTk_(+n|l9 zr{c)S?xhn44@inlz-tyZ7phQnkOz{lW~p}mBO)%RDDXVyIoFp5 z&z2YH^60%TMs&cM^64 zni;7yk8!4ubNru-1OFdG%bo*Jf%x)Ic|=inVJZ@%0@(Nw=^Lc>-OV$f|AzyhS0vQu z0kSfj=%w@ZNVEETTmtIKDm%#4b!2~IX+^K8B$b@WAx+%JO%>*mL*f6IPrxvI$lI@v zE#1A@(Ar?i*H?wv@AeB#>l2gQT{rib6~dM>PuZp?Za~>K6E;Q)cs6_n=%Bj!>;IHa*;5W|)Y@x;07|a6C z&Xwc*Jpcb@(195_FgAQJ14GKK651a&lu0^Ig}Zgs^HpdvLxMc3^--Qs!R3pcPW>o0 zZUPBP5dX9PE)4N}4B60PcZ6HSsXQS(>#FI#>Z@s>qRt=L2Gkz_+LxLcPq=5&vj8{3 zuK1o@YOwqzHE?pfjiEoR+9|LYILQC#|F1$haw0sFct!561@gq@b5(Wd1oWbXN|G@e zqzH&Wd|=O|gIrOXzi{EkPETyBgk?xHIMR@12GX@_lLNj|MUQK6mQ z0(;X(5WmtW+7byN^OO`-Y)SmKmY&^3ktZMNMj`HUZ{QPYb>G(4O}J#^yZ5X-0}dTI z?2AzqJWW!OompYC3AS>8H%?EUZl^_~ew4Ld{Yl$im-o-^U z^h`!f?f8Zox+q?Qu+b?;y z5n=3*o~cNtrcBV9?YKlAN3Khy-_utnQT@zKr>1ZCgF8rlHcf zW%!TDD@(33V8%ns2DLR?nOisX?eWei1&z{jQ%d3(!BGu1x5f?M-!h^x)O?{}|5H8ZSqM;=ZIf;cP`^h>2& zVva5dl-QXPdJQ=}0iHZD2T$3&2Hf4QG#hv)d%firzhmVSxhv)yioSo>_AdECP>I;{5MCL_>0 zK4$QZi;JG+hxAI8dpV;-hua`GC=}!$4$8Q)vO>@PIh)bZ)xUaMmjRMz1;e zvttYu6JWLEx-HApsM6e}Rz40WL_tI@CQmVzWz89)tG5typte*Q#eBuYIJcdf#v;IBBB6ct{+)ZhxZcE(ZX?J>7MV{U5yr1yRDLKGmG^=nKk zI>tb>Cm=MU2g#_d($a|K@OkA@@gQQd@IB8Hy2h$^fyr;tvh~KK8E@J5$(>gMG?r5V zX!bdp#OOs2#TTv2tErYoxnxq(!lM4N?ZS?m(avf{NXG=U9W7wPC1akZ**bpUQw_aU)ACKQ zs>FVxk#!JsvvP2kN8aQK_Fc4OZo4EzJ^p$5%2uzAnS_skyT_i^Q|x`qTg9H|qC5Sp zMh?U4D%R&@fvYDDOAAAr5P^W|avb+g^plP@V1kp!dpz7-$kV+(Zb&zDypys!CFUF4 ztWILB&QVpNV_nnA_o2h{=acW8Qjzj8sz*;Bpr!NHtH!c~ zTf^kutRX9*2CFxc_#KTNYNR&fJb>qC+NC|w`e`bVccCuzE%2JslAzA77nm0hH>z!2 zZ}6bPRASU}w)%2bCZy|ex}2+@u=4ERuD9kk>GRjCHE9L*K8!1M2xm{)=?dLv zdrwS=`zn(KshydLV(QWwE{p=s5Q7qZiM1G=$DYA;f}79<8SP>yPq(hYix=J`v5ltq ztCz5?Yp_k~BMiW|vd%(Ex8Xhc%8sW88R6!D%A-u&qDu7xboFFbaqbn1=(5NQGr{!i z3swau42cfJ&v{wNOU(8Xj|@>V4_dblMsil6W!ry+K{UkTrmn3>Wj0Erf|i1Bis@KQ z*fvNf2VwYfg@aZ2JfXqPhMQtWTfIxO10FYrMHE%+K7H?ZHXekS+;5x0-N~9#iSuJn zRa#ys6pL-&?c+l5=}UGxOon?iXSIwfT(oGO=D!N48w`v_e?&XoEE1_eRn=UsGa?=O ztGx`o1NdejZ<@=M?$6QQGAM$s@PS}W_@7~N(_lm3IJKlWeH*WjfH2T6<%{209p+4J2OR|Cz-93^nH3fHxtYGCwgL^N~ntZ7cqs^tZZ4>n< zJmeEWe_SRv_g4*fxr^D+{jr>kvKQUzjzLt4%u{Y=INFV_RlkQpP@>olZwDwh+%~6+ zg{NLB#8y6ybBd?Ud7I}~3lLX$xD-VkZeH*Xy=R%T5ku?vZSodxd+q5uxy|Xi_QV$s zdcs%^B1zP$Z3+PSO>r#|4?rA=`5VD{abk+<-Wfj8iOw;+X6?kTq+>%iAvLko=7;YR zb2--DpeSt>EI3~wmG)Veu7-m@8Ox3wPb+Pm)-E0@C}gVlacmb9zKWrqPY~VP7px)2 z=pB`o4p$TWFFRwl6exWi_yxH3g0PbASU+f=ju<{m*f~w01<= zo&pT;jhHDWz=^sL|4R4$UccNFNlg6OO3QSS4qHf0zE9P!h>{0YJpz^>lGo63EkUw3 z`*TkYsY2D{1}V$_=jMZ1Vw8Qlax8c4S@`gk6NgD7hDoIe4~P0c8TI1C<9+}a;iDiS*m$oPPDkwAlssxE8yc5 zdGEI&^X$E{?=QrR!FqcHniYFa>^@rlxFqT^wTmOH=9!KWdu-X(a`22NgH1^S6)!(Z zWWhKVA78=&I^>uIP30IJ#~*ioIn*C>D{d&Us1I&6Sh@T&2GrWPA4^J|Q+MvAqM+$q zZRuV*fSi_^@Csx*rX@$_RI9j`laCqKX|uGCNgx8QJn$1cfH)@*Wo6Nkl7!%MQ-)iI5WMyU>r-|6CgtWqiKiQ=ZB*zI&s346BKXND0USmkx?dP{q$8H05{a2eFV*_g_97oj*RLw5nBb*uYOa!OUB>s8kdex6cx*cW`5(u2nMbf}v( z(WF}HnbPMvcUzbOe7bQ+CYqwgrXwvad5&L#w?89!OSrbUa}vgI3V7eAjI^^q`>s@m z{*{!^=_Mk^LJj^5WG-yVC}GV9D$Uq5=Pb@pN6!^u#fM&MVj5#C2+Y&PsM;Z>uF83i7c@PJv7`wruB2`iTC3_OnM*yhB*PV&&S56Sq5X%*7nT$D`1Df zl&gj0To$IGAxz^FXgvm-dZ)6t;jRTUyj5Vfjbk40s&(JVhWcYy83Z&M^kCDK=FyDL zs-%MjvGT|4aKc6hTu9d6Gq)V;njk*#6EOP`6^~(b)zSB^(OWqOqkmYrVORs5%o;y> zKGqFl4BDG7e%<3<(>l4|6lvoMF}?_8gT>rwR$XFb#DgGP$$+sjRQW)#$6W{P4bx&z zJp<2%(6Spb52J(Y+8foqJ9KM2mf~+d?}0njQP&EBCmNGqYJutI0hgC1Yr?H~x~6~t zI=WctI^L)x!xqasO`{Lim&esWfcf~Q5y7-RLKu5J+@%wuJuY=vz5y6vvZ?{RFj*h@ z>)^xNqc|e2cPF*6E7@FJ^_G23q5Y^Ni_Xj-$9Es~$9>Oh9J)}hEQ6p}kZ^&*Y3F4sNE;5ps&5!wHvkX)Ll#MWIiPe5Ie-*b< z(b{xixRR!A_OTmQjLQ}L<}9-;(7mhb%fe3QE@o!FA@ybt@0C68yv3sc=w}_=3!&tK zT_3+osikqN#KIvNJ#vs^?G)YxFwP$Bhk$lhL5_R44roG z2x4xem9a4dM0nO+zo{L=aHFpFwjww=nUqt55nmT|{^T8+Sk~*|+qno% zsCSE%#-V={kJLYs%FB$RtzD4e{5GFJA?D$p zo4lpyPOtfJJ1LG4OwWuz(CDW1;vLvaRDD@(sjYtZ{53#FFsvJ)-c}_6&M``CGjhbd zrD?ph=tX`0ub%BO6tJ)atuDr`>N`Gv02GJO{J>eGg`|czb6lEq_g>?Ciqm$lz0lOq zRJjpBmI#msL-cdU5?oma!GM_lOb=iEpofkJP;9-*evZ8V)hP`r{Zn$AaQM~kq$I}s z6V}qg&|($x@}A=*bZnIq!^`-sT{YuP(9zzAg(O6f7lcIP z=}{22kZ%>g87V2#GoFLhT}|uCQ0AGu3U4xg#6r^CZ2_cP)|`1LqZZ?Mx~74sOP1Uh z09WH>4L7G}b61hF4O$*G!YlV;?k7>sIr9p#aMc-Z`pGuv?xF$P5w4|m7)_mS6^$td zmO1#rH6N2G6U+1x(Egt7g31h&iW$wg$#Cs?z@s_IoAZ5h$FY1EFr@C-EM^K*UINzk z_4N!EuTB>1ncU>+Dv@Pe=(2m+Efl`hJ?or@*&zul(@vC|v0Q*jul9AXHmTn+Of-p& z^uNA1-!PR>ZzwRNh6QTMHLH2&Uq0BVoi^+fEYS{G^;MiI%s$P)TGR;FXXN)UT1Mtb zFfh;jLYlot0|ZOdt{0Tmr|cySv1E>PkyZdivYWcw!vj*?rs7I@Q!Hh&o;kLX@>x#_zIA?8Qf6lAls_>b|@o zL(7ubVKVo2bHV$;r(O3ck{Sd6g?fG;U9-f%YCE+piytV=@=u!~C8V0BZp%!P_g^nD z2_BjrN-&8Vwnp3D%ePN9X2NufG25XGZgcTWncRZ9;Jc%O3z>Ia`{GeY;4qHBlEOIY z(Z4<{MQ@R)A3007_>LeFd(ps&O=BU&hD6`IDsAK3>d>wbA-Cb%%9OXV-y8+i&Tw#5 zRCym1ce7h0ZrKeV|MV2}@3b4Nk4#SY!@4vnsMo6-gXR-GN=5N?e(JJR`V)ojEN+J} z0oV(wmBzOV(prn`UBFy!t`M+u1I%R#IG%VQT{C2g@_b+Qx`jq-pBJaEZK$jJ^6-Ug zO6{ObMeyrBS=qj3!6~PgNI+tNlYMVM^4RJ{(NRM;jvKG1qEn93HcOq3IXEN**-F2F zzM@0j@eSGaJ#HAc;o=}pNi z1rq)My_^f+!wc_!4UGBf+W}CVKCT}WMheZ-KU(ss29lnNbbEuiedW~Q3ZwJ zhSHKxyEh)znoDWWU)~Zuub#r5C+hzc$}3ntJbXyfP$Fz9%6_oitS2PWl7L)t7wEU9 z=C8${J4bajZ>QJ-ZI^7Q^)Nb_Pg_j$4h&8|jZo2lI}UjrDDm%a0dfk4{ISYBbfTpJ znS~7Y9RiDQ(}idc7_&yn9)NE~0ch;I5o`Yv3`WU@ZnDS+3_KwRKyT<0yzKbhcRs$c zKqf1VUH&%Zsswz0;d#vtY~0<~UMp@#2g9FBM^*LN;^NWH?e&zIRmGjKE3%ITvCZ_A z{z_$({{w|qDObkS`aLWPZG{dCVgguM@=TP_aynS(h~%0xGy5mA+Ru|eE=d)jdPD>6 zV!6nBbUA!X(4u+S&0Lp8Z`080CPI-)R(=f^tHorJF9C?Q8Cj^Hb zz%rQ@pm5zOTW07*F6f(9(!6v;->si}9v_)yV*1A?Y(A1#F_mE_-y^Xv`U!U0T!$a` zI5_JXlLx_D`0>Yd@pf3tK7oGWyKWH$FIpoAAD$3pT#gs0`H6TtOvq;Lh{+svypWfsKv_+#U2v^-nQ`WBXZ#b{_=*tvY z#mDYhPTRb?A~vJUwU0ExH-P$HZSgcbK;_~lGhhD^HadYK??>ZqQ+c&xmYAxlYcG12 zpnVoV0J>FQ3q)6YKn9+xL?* zv5`r?j2S|vAN#%U+gBf~ZQfoUkup#9CQ-MMzQ{gaI?7!!GVyY)nJnI?a_S#x)u5Is zc{B&XmpS)^$;eiTu0+C@_8g}jR3qY^+rQ|h5q9nrX#^c;#!Mu7*V;kTh!?JN$+?z= zTLmmwHgpJgbi1OPT&QK^Z3dyuXJ6|6^~i9xiznIUHCeAVmBf8j*H+|z$&^aBB>Fb} z&Wk5`d%l%neAzdKs%{|g9`YAm*_t5@rE?VtpoK-A4iiC{atC3NQ!zK2Eu)s^imlqy zwbPJ+@I6=e23tqR)e?!ADZCr#*u5la$L2eq8YaWWUc1JU`kIo%kMP)^N0rOy_FN)Z=+}GW41fpRaqzrqv|6qys`fBhsaMO4T-{o~i)9_8; z?XT;sT%U64p8C5wqmOKTie%Q*6Qc&k_>Z2mjTP4aLJN{tiFN5hk)>Uz6{cKZW^|PU zq{eL&`hz`a(O+6UJ{T9QCab7hWT-gBuu3%iHV-rc1x^z&3$T;1*r>~EByn6W=p2vg zcOw{;!AN7xPa}NPV^Vu3ysUP1+(e)km-c#~^4o*^#Lu2IiTk4rWPss5jaFr=G8hR@ zAHmgzRQ#wQ%TeWlp6~4)vmIZDOq=3;u|(6wI$)oAEPCH+M?EokpnXI&TXLc|zyA7^ zqwMtG#0L)o`53a? z!>9(H1jq@rL7eF~PGvc^(#eHqP?U4`!tQu3)HXo&3%5@P&tQ;Yajl87XFj?VWEW>R zxi84v*Y>A_vo^4F_4R9?10ji*VcmW$h>g0xd$_!QY3Fo+i#bvyjM~+1^K@`B*-;q+ zmbMrtr)ck{g#DTs$r z2^HHI`4w!(pi=ASe6DVTzP?9npmC)IInAvRKW~QSQSdY1X{P4ZBKZfB{Nv>Bcj~I% z!4~VGQCkl!=MsD?ai z8aWyel6@s~efa$PhLUMhus*TQU%6&`=+SaS5r;z^@N{vyk4!|F5$ci2maLS6Wf_$( z9>sUh>k%2y0;{oVGAGmnU-rIIQ3^it^qwcz-TAxW8IXSWmPhN##A#n?*R&}|I^NCx ziS(}yg?P3^0DYfP$^k)ND6U+;;Lz>q2*cmd$uiE6<$3_|_wZLleW@<-DxdS&zjNwM z=Fn(Abs#Q%V8hy>kpAVQB6;7v(^CG{*Q2k0*S`L_I!lh~uQd*{QL4?OT|XV5l23_j zgKTD)hkxbX6+;z+LCLGet*7HYjenSZY>k!878U1t^*6;Nc_e3gLgr5gJLC?|y=8A> z;OT5Z{t=k7;{H8`swgj)(-^0v!mY1|^7ES~*b}N{-@;1MqT088@Be#Ue=pcsUGf0` zqi)S)`P{VFzpApIvYY^Y->qBKFPz+&?$cc`-3i$Oku_x`*W-0Pm&n-@?&&_w1=Ic4 z$A4o|Nk5e8LhxSlBGMiIE&SwiK++fSg4Q4fXKNx8W7OU-S&(mS!O2jfGUeA_!RYE3 zPRY|k)@y@6-ZTBlPFMBX#jG~{tdtCVC%6-TRB;GOqpo`Vz_e8MjCsgdH!#GXsUqK~ z#|}D>U6>II5>fNNLw9lb;eR$ge;WMJUA}wQtB|YdJ1PFsXF7uS4{(`?n^j-BM<0?& zjb6$n>s^LFb$z6G?YQT|63;5Dle>F;OkOFRbe+WdL7#Z{z zkHRbGK_#@5WoHvR^bcDSy$5Be@-kxQ6BH7dhq~CH$(Wtt3lw6=q7NRgW9F}o#;wNs zOUvkP zV_kC(tH83!naV+>36=&L#psLh`8NUVI^jCK;4IHsIWBQV*9u!8cdWnOJWCgyNljCZ zdgk4{%EiQNhf$+x+>n0pI@?6nhR6>vm(z9hTh2Y|D>vD0U{l$^gP71R^5rCAR3lyhSyZ&@~9aLQ;y3i%!)ie;bbH4PM5g;%_VdZ3^Hap$w>brhv`BL znX7xIHB4`SHwV7C^vnkTrg->A1)Wh9NY!0EMRh^q0VFZV-#Yz|=X0h6f2{R6T4ZM@ z8gX3k-s)Sw`A6En9xAF-zpPG_a369fI>8zgqgHSHb3QvK_$Tb%(C5^Cl%({G3O;=D z&lXhnDfVmd=s2++`24JU_|?;B86BVpkgR__RLa+Dy1sY5s*}$Bv>|BQ+fSxhX7E()6CMK=a>V*gg#5@Z zwTb~}J*VvFKIc3?-yJJhR61|K~(yWa~`Z~ zRu=`%xF5?Noc%mpk6$lC(P!5-^m#-bJpod6c??Nv=tiBc1NS~iBDB{l_Nvf_#HIdFHd-wmOisbI=F3D4gpUW$Uo*hM5@Xk*l+tQwI2{{*?c_OtG~_$>+^8# zPu@D-b#vHlU>?UjqN{jLF+))+k0N2@KaMSqD)K2P?u45l182rYMyX&{saExPGO(j{ z$*So9TiL9P;~fSY+`oE6s5u~JlA~7cwn$T>%9=_zJVN?@Q^3Nu`+fG3#;3nw{FPAT z-UU}@$C^i!TFblqkKV~5OJW`6%?ynIMcYxQWav4;)Bk}4LT&wDAkD-TtDjP^I2Bm~ z-qb&p-M-=i=ADp}6xGI(c1OsRlg{58IC|D_s6&4DWxG3}w4i7#dsK8reR19DZx8M{ zf=;DBa6O9U72Z(Rb~Q8R*$K^5j;GT5q1brhmAW?r=3+ zQNgJ7D5c2kjKZ?EP1SxQwZAD;&?g!6*T^imMTfm>hXkj&hm&(HIYrEmtY4w-7AAw= zkC4s9r@)U`o$+tqvTGU6raFu%ie_yI4kx8r?MN3?kA}l}P{59X-xOp4VaWR1Np^2A zN0__Tq&XGwHsZKW2lRtPu=(ilb*^ZvIJP@5f)2(NEulwV*`C?HkUxepvZ9>5?3!}* zaEw>F(Hx#E2xJ%eOxVV7vFl%I+iyCf`JrZ~1OGM`G7)j>d4N!f6>D-2|JKej2(9%(1fo@t4R_k0n7(@bUwT{S=!}5He+c*=rT?tYLfRdd zUH@B{&&*L~VwL5Dznzi)nbfqLAsu~YrhUNoCSFR4#?SAkkolhXY-RJuK>mLKKuV2H_i3Ty);kH12X6QJ<>nk$_K0ZB;eC-@o`Db$v?P}$^Y?h$Bw1iv^wv#&!8O4j(Kni2u=ES?r82`e=B@l zUN7WutOH8_^!pDt#D`VF_RT!o2kFzgntxc&GnXi^(s3Bzf`{>Ty8{31+YPi?r{z&o z2aQtGPa7GgqyK5;%f{RyM=rI-EJfkv4hY9&hWOh<+#d5AE{ixy-1&68dp7k#f1Dg@ zMF*{!M59Pa%SBn~e{;kf?q=1U7z4gm$d5XSfBFe$h95{DG9LDUr)oY@zfR&GVzjw8Dm&iZRR7M>c;J;KAgnFZ*EwEuq(DGW|_~Q~VEC7N8b0-s!QKune7E{Y+jA z{G$Pih&HMhvUN%AUVZn!*n7*UxR$L^v=gLB2ogmbNFX5)+#Nb3Xs`ewI0^3V4gnI} z3GUXoHPCo)2=4CEjk}Y(lD*G9`@D0`clLM3cyGLK+}l68YgJd(Dw|rf=JY#JdY1f) zzkKp@E?VQr4L2>VDGQ84SQzNhug-tMATVyRO}pU9ymaR3F#@Io!|Fg6Rpc)y^8WM47pX`Y9tw~?&8ug?fAT`xra~=AVwfH(PrHC_wTjhJ= zw90&n`o$Qf?(d$9J~F7wWdb!>m~nqx9tdgp$vuAfnXg@*G@5{AGbSA79iOu(u=R^e z8E|4g#~D;rHtg0#+~nFt-~o)^PpAPrBKEc$CKmJ86z11**^|_}A3Q?n4-{~TW^z>C z$EHj|wUMqAAUwE!farOc&#B*>3-F4Y>WVq8?%we6yMC4mu9CY1*ZUbI{ENZ5kf3!Oo9Il0g@Iw>bK;--ugLnHcN+A zc2Sc{9=N$R_}pl=zxHSiZh~8INje-xHi1_7c#GTE=erI$b?{GOe9v-;Pn0(3X+_-E zM4VS+;^_`E)>H^TFzzDusgFL{{Ru$5Vq)rHkhhw^Nn_5o={X|(S)_@=v6*vU8cDfP zuUlb$q2OHN;gz+fE^Y!JRx{2rc~CyUqnu&?j5(d^5{el&c;2mKYA&k;&Dwxu*|cJN z>*ni7xhg`rn^n}X--{6~wAOMZq`*evDe5`qo|?r>J}Wqy<=A0*H=VF5Aqtr;zd3y_ z8irZjuWB~QrYMJWEMU^y_7#5c(xp}4z&g4r@TLf_g@a`mPIp<4XnEeqX;bc@Eq(B0 zN5BkoWc7~yvx;ao{2BW)r=&c$lt=oZ}V?pn9`^~-QnbyA~uQrJf`U3G96 zcZny5Ug$wmGv@WHxJXYvL3nRXDa0ks_prj^9}wv4$Sai81m;j~kj@pj3#j2)@HIQ6 z4AT#vFBu$-Iokz<$4jYfRWM{Et-PIurzsOVz&QZ-;N0QXEn1&|02&j%W2TXV>YG#I zh*{c?B-_~!?=`O77;oE&POjkU`|g#OUO&!&@H%9R&JQb7;xA;2a`p^%H0VxuAS7y} zBE=QulQkc{8;}(WxEQio_yJ1mIqiWqz|GHRkPVA*nkW^oYY#7ao9~EjhJw-w;XZk( zmqzy1&2FOA4PMN9DO0XQ1zRcOBe658%1`C9azaB2pDAHRT!s#l(A@a*2LrI_7Z6+U zr=)tj!y*2Dm#3cGNBKx^&R{F!ll+h<$R!+;)828rJ0u~qrbd~aZAzC@RM>SJ`lSfqG?$FM~;%HLzxEs z$W4DZ@v*JG8;|3S(BMs6ib8w8hya=q_Om#(T;bPr(0prRLXdH_XRv5j)yiu6Ha4yb zc4cBab$DCFLU-1JyMFz~SBgOI&~hYQ-4g2gf5%+@Z)LqnYmDm%jB?q=Ao2#;iP^Yc zMoebS6VSqtP@B@({1b$>ydFYM?E@I&unaDQXGu?uf#G!Xw$u6K3s+W{F$#&KFh@i? zq7m~g??QuuGBz)}M=n@OcI;2JnfKPPSd1j%i~!#Ft-@{GZ{66u)Z=Xvky8yNl@ z`Q=eCYZ>d|Q73NCreLG-$$6KQgiiz{ioH{InGfv%gHBiO6?(Rwuw)W(tQYvkxRJuV z1T{%W!@hGpiZ%o>-l>lR|B3LGf&pjRO>F6sdU<34y;XxErxPu)eNT0Qc_`nzv(CoD zlrPTYaD^>lQ_Q6tQJ)sl3m*&0Rtv)$VONEFTJ3e{6tNT_CQK0Y2ngL!E=4bsf9Ru^ z0E0zG)20)#wDqgav{zi-SU9RWOlfFqYbSX>;9Cv?hk>bnZn(enc`zbBkBGZP`Oqv7 z!O_5V5T$ccPkPXIYFRg(i<}^tVGiR~EHu+7D4@HO1oNuAb zmu}%Z6=e&`kIv19xluqh{gxx>8+NkuVM)nElFbUX-hFhgT9`Xw#0$tQ6W0P>);u9j+?@a1WykQG&`AuI?r01dIc% z7g&?LDq`@rT)|DsWHN2?MUoM;ON~qd8s=&5@WV3G!cXy$w`Mbp7 zQVc;(bEU(QWuG6zRi4S__5Q_dvhJ%LhTNdm2vWNP@SpMsj8 zT2&LV%v6=n=~)avclNy#pn|xyE?tGJ3LP_&Z@RO9OB{ZHw9i8M1KKahzk6Ap4(H3%fUPP);fbna;fS_$s;TIR|60f%`{boZiA0 z1i(0n$;az;@U;4`TY+(6`W-U@<75*oap@pyO1%mIW(NmvQ92=BY|1N5uq?l!-_*xLVA7ygf|^iUy=g>V*6L4b<*04jT- zZu1p^hg+|pB|yG8l(zx?5l#jlM|LacDT@)`Mpf`51^Xr z<#lOdlRfrsS}d&gC_99iY366kHcZZtP+Tqs3)7Q3ffNG$>dj}zhLdzH0l>R&hI?Zf65vn_!mxiin8N2s?w>_YTEa;xoP%lOIp!Yo-@A?4@zn)V`nd zUdBRwZI}x@&);5{VbtG!Xsu__2N`Q4<|on)HE+2~)@f?Hl^RA@>AMD(<;PdqqW*yiw8(3lhDs_FIG3e z!}!VO9BWARaX@bYuG@P!@1q_1EgBV zc_}Y>B`K@fkN;}>>#$jX0erGAKL^g9z7wxD7_qikx}%42lLuv+BYEmX#Jc5C@~PqU%_b;=koJt6@N+d|P#f zfgyTqz<~in#34d) zxH+&LtW5djvd@;8U5MJ!vpvYSrdc#GwGQZjWE{|{nn#7p;I2IQ#cM%LM%;6qD|cxc z@KZk5-52a-6miED9H|56bo|~n@WX^tyOF(4e~Z2?l6~xUjK7o6LMR#ZX^SK1sWU%8 z))i$;)~Pb5Z10HSDDSIbd16|psg+($GG)@sdHd>K3O2_M?89pPR^;x^B+qf+KpmM~ zlFF?LIkpqx^;4IPp7WuhEB7*fxsyXaQ{MS5@)*&>++TSmBjk{QCByl9^fsa$FVfEy zuMCmb4dbXlN_k|Eaw@}ssAJ`biqX|D3-~4^c(g9Vd;P_bA0t6d`?1-QYE<>Ha&E?O zoU>bwxAL3qLhYR@3;Rqr>#=jgrp|m9CBCdY28~DRI<_t%8`_}d5Bi(e(mZEwyxOEq z=r_3^=Gtx0m02GBHcfxGFZl~8D9MgW=~jhnQRPd(mv+CQlOvU>l6P&zkz9M?z8cp; zi_9Fzc&fd>fd~dPo-_h!!Iic@M33v8{!j5^fXzk+2%W+aWE;7txH{t!j zft*)K!JgUzIh{T|=mH3=@qk2nr>qChrqTgJBdYwfuszA}Ae_3`ZRI1 z!+q~imsCt}(Z>-)jNxG%Pk23iBnzkJ+XgCUqMFXnwFmVngH*p|o@+i~1x$2|QKn3z zj$bj-{=)OT##o0D-0+3IFBQ{!xLoPV&lKu4Vi9hDt;+Z6v;gK&OpsVKzxvKvhl*{!pVJO2^wg_b|s|#0~DnGQ>Kc$iSv4J zw5$m(cFOsA7jgQbajOl8ATSQ~wxRu!Rin^rS=)hp&)3o=v-s(r@}GtG|Ck0#y;`Jh z>**xbvD?Yq0G7-6EDEERz|6UR>V35u5I3qmI%1yTE}mfbO9eYgFGI3xu1SLd)! zEsVLfO@PB}mJ7>qbSbUptKR0%L{Cc5rcCwXnj~&(8!g9eyotN~hj2!mp82LPK-XOR z)=ic1_kcQ(de@`guld>84^Tw=M$zT7%5`t?JBV*v?~c)^9terZ=p8f)vK(J3z2I8D z)X?g1;;IKB)zCIukjZj_;>NvTPP6t;Ix zQqgks>#!ig{Odv}qMesu**+(H9$)8v&tcZtPq_a@A)~FFmjm#i=s@eFr7K~Ah9UQu zm1|AZ@SdtD&?0tY=YMM8FTLe|Mj?>Uz)>nDpee~VhH*Gb739+yG_1qgG;*eemPmDo zzB*67=lr~dYJ`@v>0Zyl4iod9lsB#Y-A3aOSH+_omJP@bzi`}bYPp@bR1#MALwApcInLCS*TAG#_ z*bGANtB8b^NbpGlnjG1^sTXZn)P3D~cW_QUJcOPLm{nGTd)iJY%z&L}S=T`lv@JAk zZiTtz9Lh;D?O8Rue0Owm;GEM;oBTRoa5!C4pYfWk!$ct=C8xlUJlyVEGH>oigmNVIq6Sl5a3hz_V3yejl4%TZA zsA5iBeD7Q%YihI(?{>=Ag={fqE5ESU&GQmBdS-CdEQSN_b$!mr%QP_)A~dz)KQpSR zq+kgvOb!fBa@gnW+*{rQf>3`_mDh>WG$&ALf3?|UPk>oD2j+VN=#Aqal(i~KK750R z=dX8*aG?|MjeaS{EBlHelDX4%O53!Y`6x;{J1ff=%qeym9nxTQ>qTy1V1Es3PL-`m z%xJu`D#@*8jpK4=Z~oSCEH<)6wjsOJ+#Q}GHH2}Ep(GKhHQ$kW*aTPO`KSletOm<1 zZu8W%%D1J_Ug5VT?C!8U*S=#c8j6ec#3vb?*}d0(O`5#Rk6sBSbTX*n@s_Scgv;;M zx?*w8ekUI_8I$aAMD&Td_m^ObczDYk<_wgf`0*aj&b>kAZSJr{msDG)Se&PjnXu35 zB^?qsr@0}rOEghz6}@s0`biN)>^7G%EvOA|DiDuXXbbwHAKx-8Fw7^MxyaZTTa5(^ zip{2u!Fw($-;bruB%1RSC&b2VyHpgPd1f&sF6Vb%_4$Uz8Nk^m^4$}^Yprk0GHPeN zqmozyu)(w+wX{W~4~o$eJ!2dtx;j?9thk=^de_5$HkNzhta?it+N$l z0y7jDBZ^+boLS&}BQ9x)6rd5#*x7NsDx2BoDVA*PW)mER*2RJ#D}2qeJ{5t z)am!D1f$jIfcavI4ZHV}m-=V`cs(*V+g3Kmw%TzAe;oSnJI?W5AVSyqgx{@WTihc3Sy z&&siO#{OaqJp{S2cw3k}<4T*rjWZEg9srZWsbXA~Q+h%T1Y$=|H8V|=-uC4|)le2Y z({(;AE|#ANr2R&$hfTf}CcTxUF$-@e2+Its4GC&Fmo=fcE@CST@a05dr_*Fa-hY5& z=u!k(DClgDoOhJ{7)c^ILL8K)4k-(WQX~l`QMS(2rP6Vp$CdQ^nlkA6T)Hs)NH6{! zR4+T~aR0VL!A{skJ}%Lm^nr*0|068;xszMmS2a zBUmt3OoTIHH3MM@8nlrwwQ^1E=~s4FG@JVAI3{xz5>1ZX!C}7~3;130XaG z5!`yWK56HlJ;pSi!vJ{|-9=KXbi3*)y1#GB*misHD}v}{GW47EB&hheg9sx)_uoAN zJ2FkTy_Fgnu5ExS9u$sqEBCsAZci~HkbS@)HBKUB>6mRhm@;7Q*1G5&^6b})GGV+V@YTcHdlJg1ZMEdt zl0Q+n*Ue|fu@bnwjK$pqCcRzSg=C3obya-z2TT8#5(HOCZh1MEgFhL}jDM&>Tw|nJ zB;76OUiAYc+q!c&w{qqlb6&ysZa@R`)jyQ{YY(K<{@e>L_eCb2gk=_K`wDv!QUos( zzeu|*HRut~hf}LkejXYrEG&(wA`myr;oVvUbs8sd2J;VpvZI*8!g_*p`teMI7p8Oh z(d(+LAX)u5Eay2nOvBX!S?zSLYCfu#H?u_0Ay6G?XwWn-PGRi;eGb0y$05+qgcpyh zd!N(VC82w+Nd2hhrO6M_oZSzQ&y%rMt-m0t|C=IEXwDCi{21eW`1NCGrtF`jiGP!{ z9VU9s=Zje}=nH9F@=y;ZI!y7Iv{u}JL~q@L@3@!su(y>`w<|*IRFJ|6klG2Z<8n(P z!b2?%5+2zulBM-%0{ehiwDSzeu)j-K{b0ajUMBAJIoUi&L4X@v#5YG(KRN>`px30>eWo`Yo1CX zQKWOXvfPJPzijoAP6u;?W6aT#cIO_MD#Gky&1Qz8y9$_fV?M<=rQO*vH#QvS(m&Ce zx6}D__qg|*p1g8x7|zpaY8U^#MEu!CmV>t1Dgjq810WQaq>ib)tCScv@^>!7NsGOR zP~f2<8mVcWS5bi+^=xiIiO$~`@jw9QxPykN{NKWZLoA2dWhe}tlf=;|^a1N-R z`$?=Wyt>KTVec8W1zN~x5~Rff>p7d-#F3tl4hK%U;YH+TKx;5eBwE2N1iq)+Uf*#L zN%AbhoR>KEel77UBJ0Kv0- z@i`batFfI~vV*gFAXjRH0uU^Awk@O0)gj4)? zV)Kc%*V`^lRedAjn?@1w)4e7ZGrb=?m5zJ zXpkbz2#)oQS9&tIbnsu6?lfm{zsXuc!TxMa@t4vAGn6S4TT+VraKyN=t&iI>8+}F$ zERp~+%A;gywk?A*FJte3-4;E;j`EY1S2ZIM8@bb>C5iJ;R>x$=m~>u^nA^_LkBTVk zOaG+4=bN9l#{ldk8^J*7J}v$x+} zz2}UnvH;AJ{D83RYukwc`e*8>yf-^OTht-%_BEPU7Z)xgNgOe~k%<;Qac|p=HdM!Y z)Qos)_hxj=%-lFrdJ+7Fxrg=L1;Z64Hnz69BM~J%P1?zUY{9$z{Vvte6q^EJ+d1)^ zth%}id~u7|@4<4>M-~;U9NIN4=D4%`>rcMb><&Dsv?-`$7GAVo< zzr;a#ctvjrOIgDeRgJap4Jp1{*Zpw5T7@s#BKwkGQg>LDa`F{}aS1=^w=~~u`<9## zuD%T2LP!GOS)R$xI)96JPFmQ$;(O12Kds?Ot&<~jYazMEaqx2%1@ya|St4t2#Y(cB zQHPU;q?# z@24O{j>SoIg0`GV(c)GUyzrjf#ufWrTKO-3XkbRf6RHyJzQYpjJbdM0&2`HB)BC-W zLwsYj4rqAll$7iYS|;J_RkPnzsul`Qy6Z$*{-E0UlBRQovsu?nVPM#~^%1}6^(}%$ z^oQ$zypf$;;sU4N-av$eiWFurFOxTf`1 z-Gy_+2vRgUeRMVG8jj=+l#^(?phj>8804z=VxII+ECjcO%Y4L%&D^x>Vb9Jn;c&7W z>X-dCt`%sleOrmcccp&<~bV&2Q!_0Wxb;&flJ`??F~)1MeKukJ#2{vuJs zxB{pH>usKojeFRfNs}et?{2YYd;3yQRWW1)Q&Q=<&ja6$2Rpfg9a-xXQhF zo6wyInpYOP19*Kkv=ighW0?Ls z(rW%%DIVhwNK^5TBOFauLnji>J`Bf57wN^J>3N6pGc4@(?$+do$X=r|y%^o^|Au?~ zbGEFJ;P6rRDOJN~Swn??wQ~QMM?986)=zu*DBMd`UYk?m3=wB9HnZ9W>YfW8&c7D9I8^dy_lgi^NPlcw+5wx>)Z6@&>}`EWw~ z?EP=v9!7^ed=OcIYYd}F{aU_~x#y?d6A5Yj%`y$#LN4n97^vO20aky7uOK?ocgL!1 zwl1}K4Qd!8j#Sp)SQ+9_etNQ<`nhIl25OO7sk*LO^IBL^f;aU`{^bpfw>NQba<%vh zwe5s?ZCbV`g4uxCd!YD`Ax=4GJxkjtb=vx5TnvYL9m7b14W z916MA7Qf2WT=?QT=k3sU=3e8#qTw@FFw=e7a!sj(7jS*-CY~H4km$ZT<#K&r{K}c2 zQ@7ZT(j=vPGvbZh6jD3ed$fa0rEQ798ZAM_kt!mRm_&HOCm{PeBeR4RRynMSqi7;` zhdns_`Lq>ZDP(7bV!V#oUF8{Ysjm67NK;LhzB0I4%esc6>OKE>5B(od=D&G(GA6!7 zsr0B$FRgO!LvB%_jZ`*VWR19uyTBM4RDd46tk1{f+;5c@pV1=6_KHEbCLLm8Qz($Q zmvGi^JH5kCwN)Ojq!tu-ry!&>BL+ghO4@z6^|;Lg&qytT7F$NH`t~)#pe~^4bs?X z3--_~=`FjxM!0C%y9U{zcJ1D0e&E9@YL0c)tivmWjTyO2v0X zI<$Pa^{E`}OUav28Og`I?KAkK(`$r%XkNU{Tm!>X=EEuSMzD3ZnR3w6xTNQoESA&L z1emVy8xW6_cKBRLcSSF(TRb)2;x?^>BlHn`e^!NRjJ&Iuf+X#w17Zx*5O>&jn24Z6SVW7>pt^0^J z<_R-mZhg;12a2*yZRssey9tSP-N3IIWOSi5bIj9CXCY>?21beg zrg*|LnvN5zDZ1hyPqJNKeNH~&)f(o8K~b_6qSv_n@NSbV9i_S$am%P$2t8$hWbH!D z(&D^V_0-GB9&6HWy^fWv(2$2Cw&^zH48p8?p9q7dv};5rpPp6DSld>pWT4`)wX^kA z*2i!0rWWwlPCM*Gv;x38^eF3>_K>tMG4esl5Qpd;0!%ixd;C~z)M7Ky8}u@TAM4-K zV06V9In2{-jJFG^Cbi#POjx5Vk0i;~d&e`wnPM`^8zig`OV7I7b(~O68iBwwAetc) z@}~SJvhvRv&;fbgG#hBKIKxFV?kb-Q&HjsLnb<37R zWL%}$3dtXc1s@+uU+Grk6o2~d6_ulpUrZmcD=G{}F~q_2EnP}^tpmQC zR#VJ4gC`kk#~zNoXOHe>;1S^wOLygql9g!UwzRMy*&;3GwoifoH@Q44EN$;Gp=Eorm7M9CkUwP1za!QEB87e3C#X2=W+-^KgJbZ|<#1V;OGVaa z`&YRhRgv|}3MU#W<#3o67C1?S-!kIYffdBdbOtT1=TYJWrD&Ny5>Gg(aj?4K7UM_C zFY|D@p%w5=~$TrxGAd?@K?h^=bd^ff@#jXhp%?F1UGHpMU+job)CQM zpP-BAqp#0OBR1{SY#mTwPq%Hcp0V~MHzFABV;rml;+3#o#U1#o7xh+u{x{hES2mq0 zbm#$3-zyEaf^Hx7-mt@MyY*)*qW*hHBt3Sdd?^%Tb@$onZKrgXq%?)}QU@Q(l&Gb3 za4|u~d#$WEK_oMoh0p10EJl^Kq+moPrg0-YBwHpQPNvFTRQ1!jX1U4t3(-L=Sm@dq zjpgi$x^QfIwNWR1vD4=|wrtX&UW=oUesR#9d3%abezIO0?AoYOH_VjroIiD$o~Ntn zHO!`>U1nM}&T0LQG*{<`)v=HlYG{6u7()Tkd-|;H<1u0olK}!mT?Q-k2sm{_4T&>g z3ZqG@Q%9wyG<4m(($h%4)qGG_QK^1B>4LmaeCXf)TCei;$Xhv~@sH-)D$MP*#}Ts) zPm}EV3Y8rTC00EC2{S-(;oMm{#|;(TS3~c3($bsT|nV4k1s*jYip-sz5M`jb>6548+(*Wb23Ico6TOvhT6IoFE~)&^W=YCEx`W zSCNtdA&ahbQEn&4$;bMzQto5y(%i=`rbC$2+!^3fM7m?WTufLp7mdJEl>VN(f$h8a zac^2Sa&f1thoW*+$LBG_Z+Y|WIZA?~IYYS!Jf`)@)i$+XAf0-w&$+u@jvF>db~vJ6 z9BhC5Gid$m^lco`^Q3Bb^q9TdIJEx+1^<-cEo+lGP;s9AT3%@~cSc^>AZqaIdzO=y zd9)KzLy`inEzt1-m@HWJb?GddZG+T1#a3|#cni&^`+RJ@ZFkte_X&_mm$b zrr>nL&Cres6n5Zkh}#^ZysC840{Gv}+8kYs z-#V9>m(^o^wTG#s)+RrOf zj)?w#q=K%4Y`aBs@1=2n5iXVe7Q5ay>j`{{cfIL>kp8#AXQ)2571zx zD2m>>l;*JTYi6($YVusmsS}NegoMI6Y0()IOqVpT)TtZ1xua;B)v8^&zLC|g&ae9b zC)0oJ;o_r#>H?C~?bUgv8x%T8jo!QyzP(F>C-Jj+HKQDBu%i7h3=ci4w247?d?_40 zPlC|+q`_8qG_x2tUd=6Wxj)=MUQ(a@0Cnc`l{1Pq?6(e`__{G`^aZ*Gx^tA7+3u3I z0E{+7pU%<(*KUuLwNvkSd&St0%(iK}L3BXXxyXf(Nm` z1UHo*C50dv4P_PS17iI&40L+}BZ!ifV*vtTCp59fyI*b=!?nD(R|?*j71Ke#E2#g@ zPG+#M1pe*^$fIA)Xw5m+V|*NKQfS}2ip}x%Ev2tH*u+MLbnvB3p69A!F9jquyo68jPx1D#P+sa$=?_I2Kv1z`;E%nhCnJP zsy^XLM%CTxHE^!w^aotwP!Dz;nd$|3wJyA|{U(tmHC(>ZqlLQ{V$W2c{q1!BEYYnG zT(sPtp6xoGE!;2yIXI;hgg6P%1M16ZH}YecWRdTA+D#mq!IL9AlWX$p=9uAAr5*F- zT_?bpT#zGcJcc)BUyycV&wRo9)P0Xb<+LyB7pt*hE%tQ4vsSFvIof2*VI}&JMn1LE z@)-NX48{C>9$h_2J57xLKi)U_qu2i?@vkWKZRd=^p()yI52kKXMrX8xnp$G9US1Y2 z9O&SN@qS}xyv_hgk%2`Iy|m@!d7pxDR&`SJlos0Mm(*)X#j8@=*7fZ5N`PN)L=d`9 z7&XA9a}wG2W*F>hr&oJY>wgu2u#cQG9>b+KOc0OTtKKT=pRd@(DI1?dx3CpZ0U~Lz z!E-W|3)TdbaxGa7+x-sS`wmmtZIJfC8f}#I(zgXhqcZzurmF`ehHX;mP`nFv&ExLA zF@m(@G;dRIRJu?yJCM_P@OVH|@HOrvYlsRPuDiG550FXrcfamJ%FJhz*u^H3_>M>z z;BiPM7B5EBCSyw2I-bKDI0O`dT~7$;2&mf*+Q6osiaY40Lo2>>S*uGa;2m|V%kdax z*d$KL{Q#Xvdz|rW9_NnX#^FXx846w_`vsrnU61fA3~9Q*TAi%F)lW|S+q297H@wJ; z4X+b;Uxjp)%~-)onv`xl0%)IyiQvo6oVfXo0tJo)zuaOtYL zhpjWu?FPqgYzTNQ0X@uHxQ-Rj;dzk(^zgBxu_-Z5Yc{&SQ9jz`zHM__b#P>jzTow0 zzjmJ#upr4SjNOI8nPd}y#{`7UuRg$)R$raj9@RaE_wHC5_ETT?DP5JiblAw+q)tJB zk%@So{WgL78=q!q>;~{V%M659vw(@=S+r3S>0}Su(Ac_=K@|u~y_T}dFEG~g4+=IB z&ifElliF)}LJy8zY!Gh$0czJ=yDo6Q{pK)eD4I9Ai`{2+$<(V95g@JPKo{Xn;c>*s zyJ@(ma(U%IGQN<&=(YNt!};8EsG-$nZiF2O62;>#s6rp0CiHqE?WOJ0p#FUwh0{(RZk18rt>5G)9a?yoW)UWM>BWjFJDSzz+oee)J7k+B^(C%+b0{aDBNmJ668^5p7*!{F>w=X>v zE_YMhWR$L8br#6%^~5QqCLZwei2G!=8jpdK^j6+{5Zcd<$QMG`cMlV%WdB%XVEg)$ z0WU6(1B5nMen3P$Uc| zk^V%#!&ad^aBdaDeaoj%8mSH!a_>M8K(29s?dsCez);1T89h$S3M`TxE|)y8NJR?L z{u}%Z9F43$KsVNdNq>Nveqk1y;kxnO%qrka7dazm=O0bGk$B(enJ%l^c$~BY8&^0u zAu3Dxr%eJ@dL{2_%7ng{eNWl(fTB7)z}P>eF*CLR^%t=9Tal7-f;zpaWGUbRquu771)d`{Rk*OQ(O!_U17u|A2k8AW zNppHruXlW>CiP+oX8Uh^Ce&-|;=MW>Zio3Kq6dfS=y-k6hIyo<_w&x1Hpu)KTM{nc z=cP|~?GNR)l0oMKDIS7{z#7E}#*&=bwj5?nF>xKGL-kMDft`Es@e;9e{`|OaSHSCx z|7XS%7sTl`0O*FGNj3uV^IwIYTp~8E9y)8!&HxqHeyjL+AN6fJ^a7eS5^j{5!QsGY z)jW(SeybQ0J&!k0k^o{2T=KO*Tt_4>ojG5HFSs!DA`Rgjt)l|1X)1H{PXSO$R+IMM zF_)+-txo;cooadc==bg0boJu6W1y|`H>B>;;et4yjhfP?_=)--Xz2(2>eA!=jiN*4 ztpKj05aG+{ybE2Yg#k^-;E)MrVvMj0kO6G**DetH<9he2zmW%ODNBBUUf`V({HmgZ z0)XI(Kvm=P@6VPIna5*9+xZB}WdL4ZFbpnb^V&-W6^{ire;9aN=QA8dLC!fcIB|;u z*h`Nly{+it?#@DgqQgW>Cu0~{l&WrI^m$L}`*{nMbCqKE!k>^acmAAXAP`uHpMdZi zAxoK(W(AP$@91zq6HkJ^9M{ejU2t>6eTwD)m~gU4UIX&$^?pGB*8>nB6Qe0Afm8m- z99zVb@)V#CU6;VbxcTFhn=Mb;U;*YUKj~013pqo*n?HTIwof{g{3o^Q`nm7R$Uc3l zQ8eNt)fo_x7MO7hSt74#V%3d{PP>u;;?Ef7**>-Hl}f^V`GWQi+n&2$L<40U>DEB7 zlp$3ppR8p3E}`xe%_MF{^@j0i@6i=(%zT6c_I^W|zEqi9T>Z^Ka4FMX?aZLcAgMUj z8NMh4W~4eAg1qZ8?BqmytI)MZ{)#{@u5wBco$W)r#EEIh5LvtVr+qc3Nx?{sM_ONLC5<`q+)oOe~&o-cWg4UXKz zvpg?V%Xr4CB$!DyNyuVyjtyA^FsZHpfNeFw66$4S?}9Lbf#?#zI>^Kltc(c`K;eP< zqd{na`j;vIU3CK%N6q~;*~Inl`07`wrojl4<-a59=9Mvy!;~puUw~@-9L9uZ?ERIo z`-34S^Y=HTJ%92CzuL!(QHvk+Hl+gEM+Zm875&8M>oCJ}B~xD-o-(6;X^T}7DFw^5 z^U^wi5al11O<^rAw_Q|G9%l?x)q`#*k(x7!?1-(8VX*k9XttU77Y&@_RI0O50~zC7{W|8Rs42*UsA z6rX9!Id8c_L0GF;KEOA`0kh4{c>&istIsI`bT0V+qwI!;lX%DR&R*MWG2DVy1f zoZt<42s^v0pu*G8g#rf)O6sx~Q+vQEF4vk&nP2+KSN#hOq$*DD6x&BJGa&j%^W*Qa z8RTLw4o>c5mu>4KEaJ9)=6EX6Lvt;u>>laZ>s^B!2W`SUV~;qT=!o~~Vns9uuEv_9v{sxWsN zlWGac4aSbz-wHw~@Fk6LX~)Hpat9_X6)(uiyq$ZH2zVA^UVX><4)vJcwLLe$R|NZW z@A^SuG_tRo4=%?No|unzBi(BuYQ`=?dV;gNEDTYi8vN|dY0CUkSvawkjwz{{B@%kr z1)XV=*GpuKx^$8A9)HOYX)SVfjYu&2KFiHtFTAWol2K-y2q+4)X6c!0A!BUE4=dTF znOC~}FB&mKzlpkIfbZ-srq%B^uHtig%v*-%r+LAYpMGt+FJ{KFwzhivEpJ-3u{Mqw zb049c-R9j&-|d&UxIr}&*5dm<4;#Y=7Vmr_w_3bGhym7`rL>)YXcwoSNKQxur)L=G zZWdjvc8doDm7wbeRGY@VA0V@D^+mc);q69cYGzR<#!`w9Hiay$}A09I1EgM4FK8%y zB@0Mpz|r%Wo8k~T*7-ov2RFm)F-|H@u2%|!ZI&K)5?DPfG7H3ZP`F42^XfkEv3?n? zsmLg4rLFj>L zWXn1f<fR66tXcK3uHXY7z*Hq62$b8X#V zQ6s8K)!Q?v(F8jE;lK`$n$!@aaz{b{XP$AyGDNrsuTkqg05 z^$dsnEjOZ^U+rirOJd^%)T%j#TghZfO^R*Ow+Hn3k=>^K`VFNV5SuubOq5~8zhLgX z4^XbjlZwWho8IltGzARD3rq&hqJfru7q#z3?=I84<-1pv(gChiV@7q;kG>5pg-yEd#2Pn~DYxR>u^C`5 z(0?3^ooGfI2L!i6tA1?}_ei2=LOJR+B@K$^V7LQ0u|u{^`Q6!-W_foF{mL9?Ol01n zq!~kBl1|ag+;WEKk~ZE}{O$}NxWDXU*M_%iO(RrAc-^>V(rJg<^S4eDqO8 zHn<#p+fJbKVkdd)9P71Z}1w zSYnn z{JIkYPg6q6EDGMF7fNQ}I5L}8ITFWUW?4>8rQgxFSWQW{K!nP&zz}r&I4*Pg)ow z5C#W~>rjK}#g8Q5N4l|3m%v~89?G>_ZreW*-+}lC^`#wP6K)p8c%&i+1n89 z%0UHazPzQSqoWto(ntPv7ZW$Z$7i=k1wQIJ^V9dc=Q!i-nF=0BY4{~N{f(daZ(E}O z=`8vGnUs4cMO7*;EKcKu{}1WA6S@g;eUAYIUp95w4btn-J)p4i-wcy1@{DZZE>f#wYa-mu@W?B za1Sn_xR&00``h2yXP@*LdG|yknR=(x|8ONCD1XY2oyS zq@I+Aj3XZN-qn{0mUwP)bO<_P_cVfBgOlra zF0B9Dz62K%OlE|9J)$w~RJRBnyC^pgFW_YQySM-GoA}r79WP$I)S0~C6}r8KnxVw! z|6f)k{?lmzSw$A~R&U-Wrx`xmsPStewyd%VKdSDY+h?Pa04~>F2WJmgQV+Wj1$ra3kvUY2DPkWFz%+J9t^WG)=# ze?3q02-R;Tiac`jdg8jUvdG!>VS-(#t$O|!>G0Ll>XS&y8?`HV>e`Xl+%FmtqX{vb z1yM!NNM;W7*Y>XuM{c6~x4xB@k6^nZ<7>lLk53|LTE$94l|c*NM_sDSh4wv%_;@!$ z?|7OGbW9%!WcIY&e1Evo={>aIj5_g5UOZN8HmMuewW%0UnU6e;Tb<%Qj~S574{C%F#OAA=UQ^M(SOzGnkac>eqi6@+4PKyM z;GxCU>-~bwrWGo$i8WET5WDAC9hY%uYG;{>QWF)48olFPIDyLUnN?FxO?h78lTT$d zkFb})UiVAX&eCh*>!+1&;zX8zLU3sKALl>PPjqLwPFENL&pQO4yPnfW(X>~aa`Ukp zypPPo>PgbR73CrpPGE(p&j#NZRz`kUg|74hj{C&t8AJ8~5ks!RVaj((_hc{jz-tdZ z{lq)a3w`Y7G=ibmO??;^JKgfGQ7{QxL_{g7Ws~($wO63V__&RS!h`}X3FRm2MTE4$ zYE;_iD?3HOHcI0gA7ok!X!Szr`91NmS?!{;A8w)dwO9LHKf>_o%63w_HsARKoO#p4 zf0y5l3QYDNIV5?R{3*^C>s|7^mBz%iqOvxQd+YdI>*Zr8EFnSG0L9fFelfKES%@V~ zxD{=Da3|BFhvB+BA1-AVhh$Ql$Y_~IBA(yb;h?`Ezlh2W(bBD}c2YyE4~7 zG5~$D24IPb45G{l4~NlLDpKmbRChcG5Hb4T0XTkvKcDfV#5Nh@2Tr0s@D^8@hz|#Q zC8;Zj5bP#~|Dv2~ygy6OvP%htY)!JD=Gv&9$^V*8{(b0L@;4Ugk4r5VOjcd|&kZa`>xObhAGr5rFN{CYirvsH zRA#1%=Hcl;K)KSEjrsgqN6Zx?{i@Ty?@}eo;_`-*`sMkdl zo-si#-9$b)h0)L+ED|fRCmI^Xq|&-WI~MGHPGPh&!T%*bCewdOF0|i{YJu~58ov~A zah6fJPdVBP_nQT{X6@RBh9)#F=o@)$R(_8s29S(FmegZ@9PEh%43bin`Qn|eKebC& z^BTbk5@P`#kt6-nVZ##wy{q;T+EUg}e=Ts8}YwwO8|-@R1bYJHLS+BD*ZxDQWUNpkNtL z&GKi{v28oA$p^YIxUqFwLhKeF@Ii|it0`@Y#YSF|dn*J$*v?tT9^m8*58ZjnIAaQu_R(h0VSP-gM;)H{T)21Vkor6}K57%=tyL9TkYtPA7hid!!pY7XG287*>uuaG z16X0K2(DgNk%#nJ=H4^g*AET z(hV-mo%^b+K}Ti4X(gmE{7CG%E!FOFZc*IHPNGo|o@@5Dnxm&vQJViarM}$aK%kPx zQ95FfMs04b8kvl;aO9>o@GXmLPT$+A)ojbs;@SfP^#JYYJDQ%G5S~b(6bcG;*$}!4SUint+Dtry$ zEf2xA8HOMF1PjNh!m~WR*OM{CS_U$KYUMc2M}m7l{QO$c%K6)xPYTzJsP(BA377Ag zQ_#d)1o3x#r?7sHleYG=7aq^@gEboz5Jb}+W1xg9L}d54LsOq2R40q$b7V~GKE-hn z`{C?vcCpDDt~bzMH$rT~-kvwFk^NlbI_Z3pos3a;3S9T-9iw{mYj*2rEZ0r3zZML; zgk|=qNlzpOHO_i3D+Yt9e%llKQS%!M$>#z!jQ$H+{SSHc z{{~|J(}c8ERrb;-KN8dg(OtewS{7^rimR2Ib!2qu)HBn$;*%i*|D8^Y z9X;QT>wxtNOsW zR^*KVql&ShojOjGwjIXEW6LmV%vJQ}w$g>zC?$KD72d~y!A2Rx-^EG_`Kj>5j-A~oXMEDU zwB~(6b=aa?D?FL?IPK=rVbh@xu~1eV`sZeMPw=OIc}?@AgBP)knJH9LRa z*Z=j`yrQ&-D|ff&KdUJm$d9`ao}qmQo{-JVpD2$;wQ>04C4Q71Zv*#}v*{ho5omX5exwx$6yrWMIWtR4&CJXi zm0s>hr(G4n{o?x&j=>DOZ(dBW*}NHqT2rS=As^+i_$3Cc*(ts|;_XBtVYUlzk= zWR5mn#gElb!2`P7sLWv2oY|7sI8Z#X=hdWhr6;8xUG>joAqdjZdhM)`{2vw;fR~4^ zM5wt)nMz?wHTBidry{2|R0wXcr>U& zT?kcYhZZVO^tnu9U(e5*FdCNHa!Qyg(=!IL8N1L zwvDV?-|)*~Dr1InNPc5|+t5@@*tSWzCP}OMQsFn)`}00(`biVTj+1DUn>cY2I$E5F z9HH`Rn9^&|BSRPO_;T4EwLz}B=b6H+-=of38OygwKj0Q6U>RDPQ{be*dY+;~iwg;= z9$Hh=HP{!q;_^v73%O+uJ1UnzOm8uxHENvayreo;G>F)#c$E^|He9XfjimKAAGc%S z+53xZvphpYyB|?G_~d%(@mH!hPoGwqMsvi~EF2x z_yQ~^!Bj8iBoD_c39KTO_*gLie$LR_U%}=Sy05yKT zM$_m}Dg>Y0by9@uWvVa@I=(cs*wv@F;7$qL4aqBWfYK1)x$&jKX`ZD7?jS|TG=x(R zN*t2TjhwQ5F?IMU%k+7c(g;Vz7$nd4UTSGkHdf|b8b7{IAEGwlJuKOA1pyUGnCo-9 zTX#Ukt70tbbvs6_JXlL!5+C^2>A%)- zIaEj?qs>%oYLyLgs(SpR%?A{(CmQmy*7R*c>$kx}KZ^d1xwt?NvR8z0aD*Su&X(nj zj<^;(!(m#Lb`G0|a!gn7JFBr9Euib|JKp)s>xGY73r=NC6~D1e-9t)`78q~Vx4R~< z*wA@2vmD&~Z~%-OEKfcp4t}Rm z0!!&(Q)`S^1KuOp;LR#YU|RBPxx^EeJ-RQFED{i9S@mN4tD+u1?igCY!?m^yBKoGd zm1n%xsmlGyssL~2?K#lj!}S--uE|~tFR!oeUch{bjL4wxodVmR9rxJJo2>;N+^79Q zNHTcF(8OkSCEcf>d8Ng(6O-NvRR;XV3b9CPtKy+`I0sGva4`M;>859vE?yBq^S*B9 z&IMz+F(?MY143ZryJy4B&7yE%?Dqmc1hLB_^oMUm<(zNpm?UjJEC3xcAZl{;lkJo( z;!xop^|AdKpaiwj?Wv4F2f3{*xv;c+lbMxg%}DG4u2mW;tu{>;) zFtSihNX0%|=H|*UYsR>~XymBF?ed139V476WA{fqTS#Z8i%rN_4OTnbf4bOny1HGf zQb)Gybh56`u_pjWoKl`8FP*( z;N*sChRhy$YG!ygLu(mZ{w9R`f|s;1X&XgS)6n3zs3fO4=UEc#>caHT6a@m);$I32 z-~ALXKI2MlCEvo_c`jhLrCTD>f1$bp=Z+GNMAm(N1h3+&r|#p;dg@)Bu{^`UYp__4 zS4Z(DUN7;$D7QvWWtvchI-6>*#}*@JPv&e&mf|m*6cvJ^c&>-z8eYEq6R^iteQtkf z?s8r4HsbkL*8h)De2QN{S|Ny}&y3xp(SBFW<9KgR*XghD=6`o|oOna;2}|gGlT!mJ z?X?4#HR_NLupaT{Bp{cgQM)c zt8Yg{X5bIrg3q~A=w6u8fQEh1WW82fmV2y@^rcMrhI3!!5V~Xf&WU@5TqI8z&Bo@| zg`i7cqKBTitKlIwUd}A>PFwSB`BmN5iho*At2byMm=~42r+Q%~aiP@e%+R-Pt=Xmfac}f;Ibe)v~U+hOu&qH;+$g|**PlWVB|GPafJX;!fBp> zF;74#J?~HOolPmrNTzmU8zZ+HLyc73IQd;Ch>0~lU|4%$c|3gWEOH$bix|r3X#?w$ z_ry|m%w6Erx>IZ6$L%JURc=g zK}krd>o5&DfCFFjO{)goa3EeF z9NSYBX2)T@_Zw?u!@sDC$t3tbJu!~oqOHUF%>%U~E4?n1KT74UknUui3?a_EJPL+B zHS%DuRg*q{C;^TXZn%0Z-Er5r%Q+)MYcqxdBZRV40PwWYC9~SC-zoZ!EP0p;NrYD@UsBS$?2!*j>~IoQIL)9G#aQu3xKF<|;PL zso<{i&odJG(CQMCxp^F^o*58TX%UL%sd{#8X>Thw<<|5%G;1+2c(nUGPiLL@)-a+W z1B6ypqEjTAM03VBLA|8gK^iLGDiJFGBKu8y8uxv*4hvepgZBY7R zk6)~3GD}f|?gm#79C?~dZk+~p=lSu1wPH5yuxXET`8qBVymxY_W*YCPUdtUM!B%M} z5tW0S#$i3v8yBZM(FLWZI0~>fPIUz))A$ccA*#>}esIAHqDn(_|*A-xGbd?7DyD z5tl0%m!JLg^1FHFYSMR>t&Qm|`i!EI;%$O*(@{;9e0a4Gk%E^`$21U0N>@No5M+h<$bk<+Mls)ODS|*Z|3%=mP#&^G`pT^TbK!0dSx(FVO9+9U@}$ zmT4aU*B{*k-IU^gR*~?sx1(-t+`G<$#U?+B6YQiz)APs;2o)DPyjNbd2w&*e?dFCw z>6Ss#RZVtL=8GO__vjP(3T+M_t9mqlCM=8DU!Z0_f8|e{1YpsTGfGsS3>;s5y&0{` zHTeF_TQ%Rgne|(x#vsqsJ#85*PSgot@zh6`X8$w)x-#JcGySF42Sm__AMOgd<5)dJ=ft%pUlv2$c$hotyY^*5_X9g zKP}zUuB+$WiXFdi`$mxgW=_rG61W;Y2MVsKGL0SWD5qM~AUg`}b1Y3B@?TP;L+}8l z2CvH`#y^+x*vIwn;|<%zRlB=xZ{MR}Pf;c(^j>>du4uX$I;{0=#bXdjx5l-eOt_Da z4{D|@c6o%66)0G+G54#6jNrtyfUEm9v}?ztTmpi`N^Rcci|J+HjHJrI)r^DegwKr0 z$RrA{t~}VPUdtxV*ML!(cMC;J=1#QPWAzsZh$N3{{04%^wwB|HE7{NW>557K?J)tu zV88e-=EXAPV?`nI5h~J1+VE)Cj6DD{ol3GM@mW%e3w^#(BPN2O{7JHPIWe|BzD&m1 z`E$o5Ee*#PHJk(|le%k^{#Y(rBsc8>b`hVn&!MZ<%~~|CqhM3yjdhqwjq<*Ju+85( zSNgOd_a)ie@gASGbA|Tfqs#cc^eHoL*EA{>^fQ0~rK`L6D(Tq%$q!&S*MZ28i-n7r ztcv40A1e)w`bO>08uqHF(>*wvw{p%Zt6{v3doWOG5=CSoOtmG(uaWusm)1sO+btW| z7s)DlGH zjhI|lkhLvTkw6~5nZ?}Lk~(He-je4$@>^@dDXUoYEhK3r+ocT?lZZ*ziom|pGGS>< zwg6ARNVE-n`~0z7Jte#PX}w^uFbla7PRgY3CUqy&_1x1+cU)-ph_0BJ$Vmsf*~9-i zRZE^qc`AYjhI{8OZ!(O0I8;@ysxLpw{qes6_TvBhfIX`;=2%ev9z#lonN-V6x0{tK z3U$P;w6M#6P@^G3{(kt*D&BDgHtc|vl|JP^SiSkrU|QT%&+V4gyy?VA+!=k+48w1M zKE>|DDt|8nSW#8j;LhwLov(r4kg$3(KKl9b%{cLWH}u{{>tf=#(@cUl&>pd#C{1(w zWr5mJZSTyDj}I9spjVE>jtiTiSiOJLoS8~s_H$dY1LNg*@ z^&fcm&Ky;CgbVs_K?=!ch|pH>i?Gpe5p5RBYo!SnOqB7BVsIHWj^Dp z$_!1fjMKA(^e?|mQ8^+;1Bm004v~cp_L;!PRJ#lF{|T($`Il(@&MVvuEZT9+dLfM^ zjwdOve7cG=MG!d-k?}!J(E-<4W3c(Q2#n@tIO5v%=C(Y3`#09=di>SmZ>+@8hQgJ| zjC;$U{bG7XCV2r^0CCT27ngUMijabP&!dWnOHOTL&Pev&sTx?fJzcpaS>{s?DxLpn zv#>wL6R~N8ch_4a03Z3-Zz{a!xD~|kQ z3<&$x(IwGfFH-c5aP!R0rVRt|G2+=6fbaDW37`KqetLK2c2$;rEO!wpUibIa^ib8% zr}y-G$J&i*z)&gfY>LNSVm-OHTU3wr;RhAI%Fsmw=|NpyO`CcsGu5P=ocbp9Uev&+ z=E8!lqzAoAQsN3i2IR!iiP(`V-M8v>aY~_jQbUKmD}3sbP$JK-u|hrfFDH#Hr}X(# z2VQW?ywhTo!E3?i_1WzWXpA=0y=@%B4}8SMAl@h%P262@VXGxA|7@0NN1S>++yQbV z)EyJW$&#Js!ZO~vqB%p~bI*on_Q-8h==%Fr|MMzAJsTPI^HIc9Yd-c!19~$A*H>?C zBjL5~o{b2{^#Z}U3pHih9iH}O7|^w_ux+3@cjgp;Akb^z>dx>=W-SgaihHC_X92Y^ z0-|*m*N+*bCYcN`&U3syenN`EIEr$1nJJr9Y3CEfD2AY@7BJvuT`I#s$*7^S9eBiW z$Xx5`*AXl7Riqpgyug6%3;EipgJbgTB}vosZR1`{X%Z;ydbA#I#HZJQ1tWr*+e-K% z9Om)Km}(5RO-zhTjpmnes^%T`feum6`AC%?;Wxc$jBK9T=fpQY#Wp2*{2eyz8&UdfXJ&VgRI32Gt^@Qi0VB=y$J-J6IE2GVgtYM zj;WC!Mp2YdnBQu-r-aeyUj;tJ>mqG`+@wc~d$=C?PB4}9PF0>uZ;v>k?;`>QWgiYt zuLmr#$+MvkFglkzy##^BxHjRH`L$&X_&&R_&Mc=yq+WU%Z&uK_N$buo!s+wEVV?F* z5>7~@418vi1F6n@?L}A<678xrZL8gxSkh;q zc;5E;4pp&{vAZIY)dNafIl|9S^j^d7$wA{7nsKBW|D_!D-rKfZgbQ}d*g@Kn220(L zjB|=;-MZ>@U++$K6!~$(@d;E?!-=;velIfbp=%;vi@vh0Ywiyd*iW0E8|0{%#x=kp zI|@!9Xl0v;T~`lnGR*14!3YMu5KMWr- zVBA6SC0r^{!d~^s*lE3dQr{B!8;iCd6WE}VnN6$=SZU+H?6KU$*}-ZGwGx($>{f>2 z3_roE%?M$AJ4Pih>mFK(d4p~!%Zbs6QcGLW$893XNXN2aY;=XH5uJT4Mv38^7r%uN zwLs=Xv0z`o?ZnYt4ul+#P6!xa5#Cv8Q?`p&O4i-UWw7>Ca^`l2M}>5QBn7LkiYzb& zPa>mZO|KV)5FtHWQT*IqtO?pKd)tv7=~KD_>guoWQc;=^b-`kLHirW~r)!>*p>xti z1>`8TI~^t)YJx9d!{OizeV*Y)ozJH0z;}FAk6De&<~h?h>m%JqTmkck{Bb^_h*Be5ec289U54~Do4WmSKditYLTV!di3rkHBV7rH z^FTNmuXP?H*J|(C3IdDsQq!H@Kx1|{T|)$iF;;@kM|1uT)?EY+q(_-AwP#{YpF)^8 z@#UkmWhi)M(RGX5v_?fs&xdHHc~qpY3RKNGZONiS=YR%r~!u2!*Cz zKvOHx@nw5B33j|0PcB-VqJHnY)cbaBZE{Ecjlx~)R&xq-TOe^JHroqzaVmtY#Oepg zdV+6G*o=%@?6r*KcB<^=6F?8|t;#XG1-qv9KKIz`*_1vO0~G-z$jD+K#UN6jGVQLr zbE+YOKe*i?<$&B+z;P45Z%83BBw>;zajH(M@$9VW`N2a91%Pl1Ksj0N`MJj2j;+H0 zl1F*)30Y|FX;+)Rwm>{RYy@H`KpT*$}1n> zNleP|y+JImgb3(@?U%uy#zma;#BJ*Jd}C8$(_|?J4dGb*2alaFqS$d3 z4$b#bbHhQ2t*ji|-`JU+6*RO(F5KV6k4P2u#6(7Q zP#ZY23SE9h&Eauzcw9Kv?DBxIMSxS}1{=WM+k1q`CLuLc#UFBwzUdRFntbD4;c%Fl zY?zX+GNs^HXchEH{BicOu#8Dp(D32ivXo(U{X>QtF69Yi@H&veS~3#Qa~}t5&0clj ziH_#=XDL!x`Uv&Sb+}*LlD~{yyqO|L!VGNz5m7jtmI5oPT@yuyXq%W)6BLvev>^N% zf*Vv!LvGQJ?D1f{ExD601N~Z-F{egqEcK%?dSyshTG)_P;91p=u~`4ggG0J7hm1E# zH=#PZ^O~c&#SDq1{8us+K%&d^ftu?`7W3JgIcq3iM`dLU7F6IBmcv@Pvg3}9Olj6S zo0sgT#s<$BI~rPw;r#ntdRh;(*+%4&a$t^;J-5JR5pes1lkNp4Wz5%;|Ja9~xZ<1#!7OZ996%7lDz0S+R_2K^t~up!t8dgUh2wytDytN8 zL_(vSoY01Y#iD`^XS*#pZmrWXU0K}m-{gZeq}Kle-~ZD_(SM(i|HoWhffwN!1IPVn zp0>%YRrkipQ|!S+rl!r65L4ldoB|cEtw%C>`%CBJsI)>`^rWJq(3k(n=)GI5ahr=? zYR|iQ?f?Ab&2KDlE5!{)zd-YZI{VM^$F~Wx(t7RP;`#kiT;e#9>AQA>?o}~q=*rr! z&Q3PYBQH-#5kbyfX1}rSl{ky_6d5Xn!1mEJjdt-~J}Q}87jrjS*ODvn>_{(FuCKg! zzF0skg4H@&+T(-V#c}?i{HE7CdQxF}@AeZe?t;`572Ywxs@-Fs3K8Msa4=lnb z)+oO+d1@-?dTkuv9$4c|!^v8YPqvQuh}waGXsG%N>g4j~@_D^@UQi;DHe_V>)V3ah zunnA`p4uHZZ&R-pX_1$tC{#>hxzHFbZJ>8y{_Vl{YmAxeXK}63)YBMDC)-)(Y4Tg^ zey*+NuIX@@GOht=E{(bcGFXxz4di5~Ui6%w4 z+n%WA@2C359^cB8-V%dWzdR&(tv2R?SChPxjeSzNi7ViE4)YOvJr9RP=E=#4OR-V& zA%~z~p(=r2J0~yteu~S;Q8x956cNUL$dT{dG>gW9-4u?sDv@2e9jhVC9I|p9>_0dF z8H53z?{8(Au?+*=r)_4?wFY_hqu{E0hU7hFLZvH<=_IC3Q&fvZ6gc|R)XT0w})JxADyNap^h!_Oi&6Jm0^-w;VT&zJ@*qc$zO7Xk; z1vZRdhR7`zT*BpI#(*fQd3>yVx!S6{83poC8Kv!Ka2!ACvwQoi>%6T>Q?gWPY9e3j zK^~d6jYVBegclfuod4c6V#s2+vCq~A>mruS(71S^i{2EcF_GHa@Ih791V;i3qo8Kz zl&B^aPDmdEz;*LCR@no)YPA7h&!Ghu&CYvp)7Jpb(;%Oo1%_j;P1I^u^Zp}sIlNuN zDc^JdWlmRcn9kGu^_N|na}&zDS(B?P;gyCWGQxjnNBO z+QlIpjzNwSp`yv5qgxRDE2Vt3k`gkkieXwas|tH>&V2ESJrmG`vi6F+k~9I{1!~w2 zs+G%Mt%baRbn~cvhd?-l;J^zf*Wp}2meU_3%~H(sHcTArE$3@c7bs2qyM)A;L@JPV zaq_6-lte=8Y7ZfJ4Tj*EZ7e%c+a@=P?_`;hVPfE|j6iH1^fKue7p9oR%3fp=QsAZq ztt04bd`IvZ_MDiO$D?veL=1!bnd}4p-03aoI^*~M26L; z({usWBki!Eqh-P`5O|0czPzrj<)x;*qZP4d%&N+i0vB-UAwMpuIjF~afeIg zmcYhQXXCcA8L{4VHz@D}BuVGwnb_p?#V6j$M@^t z0#gBfKvX!2VF>>i$o44exNZ-y{QDDa!i(!S)=;^&_aXk(pe(PVtBYT|uCNxDOS!O~ zlM$VuQnstVUoNJ?9l2cf&ML?HZi5p@sooIB$a(WnCfSy|deXvA%|J!< z*(G5Wr2D@9t7HFV{BI6Tb2&|sq;*WFq;bu+@_qM+Bd%K*EYR49_4Q82ap2AI(MzCfV~Qv(bb;I`1Z@1r}UJy zQ?w4rQ$lW==Q91ZIrh1>7s8j{^wi9*(c>o%$$Jme?D55lXnGq>*2_&6%avz~(8R`d z(-_77r%vxlw%^VMDsr#(dIEA&qsSLx(z`%0IMs~?FI7_~-9x1}a#M%s>DhYlGhbLr z?r8HF1m2f?TI8C_Q+T6=?q(4BbV&OM93|$iFBiA};ww_78ORL-E>MzlZQ`yd1vbSG zRX^z_D3VmEdEcO%=GlJ&(v8ilnt3HyCzw_C#u(fj#Bn?@QZ6B4?cKI@c|YdM#OTU( zK3CA=;bc0)WI%47{b4h;zCddDT}cY%gXRII^^w;i22?u{``vf-E61u32Pra!%O99$4MNrwXs_4E%g%b+$fmGqs<*x8!MIMw?qUkeV@{A^>R=M#o(?v@wq?n^ zxOr|YrGU}}r*TK9b}{#6i$p!NiV z=hTsXNVmUm@&Bc6UKM5a?c9WfK=U7OI6g#+KJ8uQ3G|EgW_V%{zb|8!*oyI{ z(M&xdBSZ2ebYVDzk z_E1D*V9OoAzJ6?f7^=gD9y)W&-R2F9|e%^kEoIl}IdBW{A-;Pl=(IzBeEMr#!7 zJXrO=L(Fq!>yx%oa;)N0*zT{>aV6R&6)py z+5xr-(z-8F=n|AFuRm3oIrL*%0qVGi^ZH8n&k~+WJT#6IG`r*JVkE50fN7+iH!YoO z{C8F?|8@cYLd^x&_dW>AK|HVaOVp%*yL?H*oMOKqft3e?vjf}WTO1debT4Yi5v+Pi z@B5i&xt1MAer=WVxvexW*SAt~toL`1Gqt*QFv4?YJ1IVBj9Esb&xJaf7sYoSDzV>K z7QeA{;_-U_T7!R#;y-SeFFINv89!bI@>~nFW$K}2fIl~4N<3wd>i_=4e>oTTnc3WF ziW&l~Lhxq)ex|sb+ixuTNsM(^+@U-%XHCn`x-Nwl^z(-z5CfCFO*1ECt@=vkI@}M{ zzHZRtq(vnL&CCBj`bO?5UD6H*zp}mfrTswOe4~L)Eo^8)Q*sq+z@gh6lH1So!m{=4 zhLDCP)vbLbsNPq)HK8x9OYG^Tcz>!$x`P}ArbKd|r2a51pe}EXdEE+U6M~yj@`z`k zy58S920r!t44RVvB0a}n-o{DCrChVVomo#US^w9_!ua4%jQN>W#-w~xz1z{_mPPy# z72XZF{MB@}Rgk*wDy%EGM~o$_NsYEWWEpta3!w*c2G?7H7ca7K`DG}KKt730z}Fg) zb$mIEtws{nU1I3BF11xyy2Ip9gud%t86jbh8Z?#R%90zs@XbeW4wlzNNz|7(AziQ9 zfx|sTOtyp=gaTN_5eN68qH~WXer|^m$CO!hiCf@6;Jh-9uf?5$gmOzmZg>KQS~IWq z)X%iA>GNS%LxWgUgPZlMK+mnv>GCJe{E_!#<40L;JzFpHs z@#1c*ZR^ZR8nlxgHlZdpK|#gT5qt;=Y9c5n`juxH@Mf{}?QjU=qB9nDDaY{R0hHd_ z_d_jaM}51=>0Mmw$Gp!1qMxtLQxhcU7{pN{@|M_b9tY0|Nngy=>q0T3(kD z?9g+ae#-eVS+*g&SY|0-->&y zlm5QQfyJQ3;v7nj#xH`e=+0Uckx#}&k;beU=&1LMP4W^AvlQgTeST94UiD}RF6&K2 zRfHSW;@iA}eMSXxhLDb;WAX2j_0Li7vo->U=ulDK8lOSMoP%2oF{{t-vr}(^m(@(0 z1yRd$5^zW zra`b}NN(^wAUt3`Z+6Vkk#%MvUvaN(p@jN;>Yd#QtWCGjwdonG6HJlu20L414bYCY zy0c{d2cEw795Ery|Jmb~^q|*2`$JQwqFC*Yh=9SWUM(MK%((0-Y{hZYlh>ILPT#T# zrH$+T+lTJa%P5uR%$3fGmCyXR%Ue%5gt)iEimR_f1-kg z+V;CPS$I)z39JwC(Z^xnWsy0x84;x8knOh1-H)2$xwfSKUj*f=DFcFET-+3=SKI8A z0h(ti4TAKylf;2*=4dt3;<8P*YWcmZb!qXaGtHYD%#pgP1M}E>$-D9NH`dVj{Axr( zPW)Sr$#0T+yPr7-ZkVezkTy+v_R~S{C7)ED@g~okII+L$Ktchao z1&Q*XyIU7=l+mfsyNQ&6dP5tK(r+F~FD$a5Vq&F5jioa9Yg$W*&2fS_*7=+Cwd{bM>oI9grr1fCG!rDUyt82YBzI1)OW`sElH!ZmsE^bU}rbit6Tk zfIteA06;ugS&P)QosIpWlD)J2vFwpDgSM3m)gY?=!N7b~ZL89=X<^R@^!RmbGbcLn zPMR6Dz8g|xiI!-dgPb-xM9<9ZxtMmrD|*kTYeqrM_UnlWzmnf50UE&+uqJ$>J*b++ zUcP{kHEHw!pD_tM(RZ@}z(6uv(u>qo-C=!fN?!QWuhE}Aycu!=(^PMmaBkM0he@eL{a`}jj9G;e2EG$G7g})MR z#FT+xTd&UA(7q%Y{*+FLdTXx_m8g-wF9roX7crG9c>FRtXgt_9W~+uzs2lq zk;+?x6(XGP{q#TT*Vyl~~C8kDR(z`j+9_zmVkr zjb2+)C)GB&2vY0xbYrFG-+XN=jy4x-LCyRJRe4XyQC13J^H_J`7*T!Gk`#ykg2wT$ zEtv?Mb6Zrj*)&|-FL9W+vtPQni9}GVLh;k>q9Tt>xH3>u<^*0{YBs9lMdgYjPG$yr zgfh4Cc&?S13X%A!{cYu<+J{g>VXtN%0ggBI8DQlhx|NV6ZL>ClzxUVyC?6B4p*OoS!{%?@*e{DjFbZ9O0bj*TS>f$uj zi@5~46@!q&f3siSyekZC)2ev5ZP0Slkiq<43e*2pF8LP%^@Kw2CXxCq7ByaZYE%a8 zre&tb`FU68Zo{;#!sLS{YXjZCv9thsHe2w8F`JXpsYyyc;D;{>mJ}>F__UiJ`8NmP zEKYjx1g#;=%^lc*_PF-w-3~6eEgoWH+}#by6Yi&NWf?Ppp&`vtNs z$*!DIR91Ox60#pfHw2>n95(zT%Ib@o!>K-a-K2G@+{()q=#X!9=m#%SJ1L|2PX0?E z;6RZ1Bq1-SshhD{i|gsi1cO@^*hqT!C{dM9~NgVyiv83%V$Qo zPHcU`uIv3C;m2kkkkW}7<-+;_MFmA*9y9g1m#aBs0q7bqOyg(JYdQIzpPfE8B7TZI z6DLI>oXs(k+8=9kU8w|+mUN17n&%JhXm~5XJhb_=>d`YCWm|#@nRFu?3k@=ddjM`K zctdS!HpG5BBk=*n?A4C*bxCFWhxuRBpJsAR6eS&x{~y}kJF2O!Ul$FcVxibTkN_$m zBE1I*ATLTUBE5s5cLE;`E$r^LaG1vS(zo!VYJ&-K(e!Fr^_!nG0&Z*n-WHZqq}TZG+mJTQpmdQvlkD;jOUtITZ z#8&ur#iH$fu80#t~%*LrD4sWViDKBf5>>nX>#?j4KiM z?dpkb)Ox18J-0PXXudZ;o4`YgRE%`~8{qJxVWm-U-6^}*@k3mT-)nV_zVLJblUjeCXq;wMA zmTH=-jI)O-6>Y7vyu&}J5Nz)KHlFoc)!AtWET`B={iM-`;+aqsH1GzNl~de4TFZ__ z&LcB7SfT2A%+gD>>(r1C@Pa$>)3;Uo>*lLTflE5!lrffImF=PBfxIvs<8Wtt&y?OJ zpK4gnJI_3pJU)DW+~xhc0SYF2Jja?@f}eOswb&*!f3i+;XD>%bBf%;;V_->T_Lhq& z+D*E9#4~q1ck{a-T#0KPwW^U@=RM%y!!U4Q@q1ZZ(bikoL*nbrp;X@Z8%`2rvGZr1 z^*1|1b;6^f!a_G(;0v}KX>FB4IR2d}Y}q7V69E&`mGm51ZSY6RkBN)$j`)o;&NYuJ zP>?cass_^FW;ki&F8#_9`U48sm|7-1!vGFd0oPItHOD1zO@ClK0mESIl4Np;EnPK(5@PMVi0T}_I@6YoaX~O@xLiA>UlDm z`%YnQQ2P#fT{)sJYS*aoVky4$(z`D26K3iTt;Q>j%q$h$1^0~adxXSK1atKLcCM~e z)d8Z|8e+xxs;EfRG$!E=a}ZFdC2c2rHFqid|j zqR8T$9BS&j!RTEYLQx)z>jSqK)!VAUTRvsbJ7Ta)z3RbPpYUWoz>!}B;eyDw6o+@i=ABVR*x!;^P;Y`Zaj7emXG6;oqY^-BXuTz zI&H-)10cVSk4$KdJAeV}r4rdb`Y#+i*^>`L6Vbp|OpjS#?Xr5V^NW4x4ale*9#S{f zec)_WX5A23=LVGFtW|wLWuUK<(CPTy?Vfd;Lt*82ityk)@bGlrARBjzu8^0y>9c*5 zyFgO?chC`0^7cbMiDzfxmp%K_ET$~dTl2R$Q3{NP>Kqo8W39B3bMOVX+jx9;FYgK# zx`(KR9xz%LgP&=W>TH(!vpyz|tgb^~%8QiOk(bqtzV#%vtku=a?Pz~#G%ka5bWYA= z8%;4D6r;`bJbZ5Vh6CkjsxV=Ye3*8q^oY#O|N1uo)_?5UaeN~A5}JH&>L-E85%-hq z4e&HTMP$M_CLWUL^0x3U+JVpMs(Y}6dPH>4Jq4@Y%Zh7g6R3_2E zH9EMA+unp_;*eo?m#5A_L|PUx)NhnW4014F9Z*$$Dj>5$>TUu0uE!f!<~>VDO7$+x zbEVJ7EmkzjGal0`@cUDGq*Sw~rkY~mCcH1-g+9@?Z_?G(39$^1iFNXA?SqpLuAsXZc8Jq_O5CvhVv! za`yh}_4A>=c41AujlC`P0j1?;Safl(m3!s)KxSGGI&==Sytt%&Qt2r9G>{TnN2#FU z+m-+O5mOkN$Xf=Y*&O|?MA_SNKb)s1vvTNQ9=~P}n=+A*{}>FXozvD|@pg|ap6)2c z3?PEhmv^#oQiK3O=Ek;=KWBPNwV;h7II)Uf^ z2D#k0@m!2;&1doao_WV}(ft1`Quwc*-%@tq@a?f?w@fNZ@c4d^C=?EZ{lC`rFI2o+ zZ@58}+4(t0l1n<(FfXeZhyO3liCjqhFPTn*Mtz2daTRu=e$*%i9@W!zbP<@9bkGz~ z#Oi^3I4~bO=A-Cx$}7AKcm`mZEACtKcPw@L{4bZ40qnFt}}!_k-8bDy6_rVa{>E z(Y^6U_aZ(46H5!^Tw?`;n#PR(PWJ(0;^orkjslShO^l19Zzk9Ooy}Bp zk(4uR^dG3g|N8hZH5xMk-So|^v&UK2L&td2FM~zH-g6FgJBI`U=6{flt*Mw;&PNv; z$@vqJ=}YI$1yf7EFM0D-@|9V@0tG+g^%?|&YeW+sx_51GVu46Shuul%$Sj= zycB!o9hEIKB)!y6+5BCHU333X*?~?s&kKX4-$q9Aa#S^owZ`GPK+zI-tdH^xWw4Sv zOPbm<5$lbmN%`d6qn0Bq`y&e9&kJ)kkgGA$((4BEafhl_Hg)&kPFH;9tq||dOVT(A zkC7V=5n2cob`SBh+uSfE=RNojO2pvCOP^PDnGc^X+VDe-6b;oSnP37Q2wGtISSg%r zYJ@w`n?C$%U9);SPBJ(7Wvsk}PTxl#+L5mr>wH# zU@O?5M)2uDTkR}%`D?uJg7J$Tmg^bWttC6W7@N(D+JFMil0z3_lsUr>B13yP9al+la#2zWfZKR#q4uueH2xUwoYG+dgg{IOxgUjM|Vnu z9znhk(`Gij3s;*a-j&<*1{lBPr*Rr&6&!jERtR$MLhs$uz}bvAX7@OnYK!E*uO1qx zp!s70hKvXLHr#JIG#qzmSgB7Hs|;ec)_%`FeI;H4L_A}{TdF#!`RCiL=56j&;)96H z6xiXgu0D}SCUf4IzEmlTf`;ieqEn0}kcLj`_-43z>y^FvOIN(# zrdqo!C_h{L)$!>FU@4NV!isgPy&HM}1R8pnl#z`$SEXh23wSx3zvH zZ-4MIun!@CJI#yiX%x{qo;3|-dpRSSckFoaZL_W{gPXhaH4-Zoaqk|hlrQ>BG0qL~ zl3`l$eYL|Qt~aLlaf!m%(#aCYmu)=j-v9xz)%~WDghA7}eV+i`?$zxLJxbHEf>?Gx zX?jBNuVC7|*eh-1i~_nlbhH*H4_6x{I^d0JBlXQ%D~)EX+5Wx5r$S-zzbnIauVweM zD6HDkg?it`#@~Fr2&-oCF8LwUw2^F@X5s)d)wP3I5qy3}31Sgv57~qUG%iL}HSj#v zANqUNK-R9c#MJrl1-7T^XYsI&#mqyN_sIo!M&9zPeqJICO>Rpt$*mO%?El>0(BXdN=ETZs?0=pquQTN#&f z*ViQ4VG;%{(kp~=`o5PoWl(napnQoY%zj^bv(u@(`;XpNB}ii}R^!KZj-V?b)|soU z4t=T-8;$o){OUKdSMRe(#{|%P%?x|SqS{_NM~(~^>h;17sV?IAc{WB93Z$JW1Wj`} zvJ$>PY{H2j2u27t(59&vN(~kUd2WxBNJU4@&9Z#}&5tjEv=`qudTH>b?0O+L`zUaM zySoM_`p#ax+_RRrY3?AZE+HH<`6=wL_pZdmO&lxkJ}NX{?Bcenu_c0H2Q8Hg;d}x>#b#`LPq9ai>U%lQ=~CC6myPMF&2#5Y_09N!#2Em0nxk+7~ltE#)+ zaPc;n^rXY$+!QzOE1y6MuHzRTjU4d_m%(eSi>zQTT~En!8qNbY<CDvX}jF(5TyU-bNtXv*6Lw!S}-`r2XdbGg3}n+lEXK zG(jlobZq7o2P;4HER<%4Tupyun8>axb6S6+w-&Zh6HHNil}1)4KXKXP8SN-2@*lFw zZ;$>4SQ^oum5J-M}&*t|6UAM%^O zpe$B*L7@4c$2q~|dbFTvmCKs!jhvY_tT&Npuq^hu$9tP$0j1a|MGZ2_?TCOp&zz9wLLB^wKv(eaMbV(KL=KFh;vs6g$}edR|s@o$C7w%u*b zjzlHOQAe^ub0tt?At#n%t+%HQnlf|6aX(Avr_I-pVnKHRw)xdsNKx7WQ9j% zygCmwQian}t!lqXv3O{#>sOWS9wPdBgYg+-OVvS`q@EogtlP;xNiWZ$DRNv{ zM(t`_vn%7`fD(R(Sxe#|m}t6+#yPoV<~Z{1L@cB>RW@)q-Zzy1V?jCSC(dC-q}=GzAX!ed*g>3*0dyKK@aIwUCk z(bTf5{>@=8?HN^(K#4=b5&qV52Qt|t7d0|6s2DbUI=Q;ML3B?4JbGZIr7p$?e$d}e z$vpvsSUFL40)J7_nkJfa34Dbb=H;~Fi2ga;RzsH>IYSb;96f{WAdI|b04-?#7*WDt zXx$Bq^KIC}C-5!90_Y3g4XN_wvy3LOdnUQe%?U**e&5B%`S?8`k6!?nxw@=NF~da8 z;OpL14!ao|cc=n$^oRCH>chNFd;){Mq2u3xfQPP{YbPMS#6_!Sb@PL_BeRgIp&Qme zk=1ff|H3r;rg1Es;|8&7(h5+h>?SK(=E>S#3OaovVBD(4`TC3JlXLrjSbAJTRO^;# zH$?A&=Kajo6Zj3*xtlu=E(D5~YP!>;n)Pm$9Hzh<#)}!g5HdpJv!zFC>+$ZAOLSq! z5Bt&YAa$pVd)5h6$sVv_tmtDbut{PBeV>qa5a~_)7Uyj9a%?e@zXhj^@BEg>60IXA z^pqRozb!awdn>$MqgRu@3=Kln{k1tFYQ06mKL!zh*P3oNTTf6J8;qOH?ieKA;F#-z z!#vnzIU`CMB4RT=te^rXjW_Mu2&#dTs4J2jgps~AD<|V7kRd1WH_yOz@@Ho zer2y=<+z#)G{bhOivKq3nc!gfELr$<|GoZ$4dNcuP+u;M^6je6*pWQdJ%sxUUB8_P zXatt&cCCwOlplLgC5zauI_HBAzv3&Zr=`cR51JT6F20V>H>{sJFc&XW?7n#-R9Os^ zN48#jSuAr?VzKGjxLIgnp(C4?M^$Yf4NZ=ujg*FY8hm4+cGoA($#$c+b{SRQRWI`1 z=xJH}^OfvEduTP$Kb}XiYx876 zF^0pSAcXD5QZ%g4mZV`XLH2A0pPc+kEi>4vzf<{_$lfx1quQrt(LBd|r~iwtR#0d$f-_#_h2$q)HAgd( z=*jTZx6oRvduKV*miKLaTAxeO9B_B=sK0FC}xsNuyopzM5cA?K4pKA z@FQAPnVghm4;T0$A9P%vI@!fBmlsG8rQS&U#;Vv zTq5R(9Ug`_vn`Xlq1n;#Ui+c{T&>{S`HD7fDryWDS`jec+D7p^0fR|ifrEh zJ@V{9uHD$ux8P*rjbv3(z7{w4Fq&=-$|#YZUGr}TskOV?Tj%(~bW&M3=4I?i=ohOW z`M!n%LQ#}ugqwgXP|_meOcNHm_MBfd;{~QFrcAscW<+6ZcWkl?FmiI~KTLM_>#(I| zVNze+Z{+H@RQSi4+LFGU*+`AHipjv}mlWc0Ce!0^H0wr*3mZKFR~fHgO&9JqE8L0N z&Jf+~?4{rTCZhN29-*r)M}^pOZ)wgpa4z6QbFmxdFb*paPBNZk&c0?`c4n1M(Di!Y z)Ou}CGSX&enJBuuu}Nr3&p8;|gSZI%XvKA|Jv&~*nwQ}goImeZdY@)DP&PKaqWraU zHM)beOTUIb9(9e=8>@0Jw5<_m;_H9a9@RZ7@`z&^ga;G*m-Uwk*;!*-ZRopqb-gTmQhPx{t`DOmlnEjS-*@ou zpQ7Il3=P5Gyw>V{9DWBb)jhtX<2R&NcPqu@T^Z_za%wnCm-1-~Kj19z!BGF!s&)SF zF<`&isGvJXf**KjV=$kGzW7J?7i$D6h7{Om8@fL(+dip9UQOyWU5Z`F^lg`Fk;H@~w zr(S2FpyWq>D^tWK0O?gL7XR5&IYYSZwtNyB^&BmGJ(1$Bu`=_-(oNu0MIy6NZ+AMKFCst*M;LF04+sUlD-0OhlZ*VF-qMEpqe)*uz!H?ayHs3#=o+VqY>raZO_NJ z0i@4}X`1Ivm2=GUREy=nfUew_bI0Nqv8>m8w=~Jy>jbr}6JRsbT)Rxtv@)#r<%<{b zTVC}$&2)W7lwEVQGU2BTg2z8=l~K}DvSyG3C-<$4O1*Be2XcG0AydH=F{7a9MqKBT z0#aB%edP4g7-v-%Ntb_|lUq9;F{IyHH`+J)*U42lbhhEp)yf?M0$S{B%r$8fkKE$( zC42bRQYlS@80Q1&TqN(e2QEp@tCwh`vq-%WQSE_&%7P9K=#buW$jbR&a6@i zt#Od^QyhYIxkKG+gj#~!Ojr6Ce&Klq^dxkf_|t}i~5ua zbAT@CB-S?@*b$$UdV$E+eZk{|LL7{_(Vy)YriItim>bdQS^5<gM(j85;&a)%O9}e*!>gBkYeIFn!;BbG zq0|0@o)~sr9i!>d8&CKJFp_DEjASQ6)h)L@%kJ$GeEIhL`Z0nl)!&IqYg1;6ux9K> zX(ueq5%(ECjiu}$i!#inKs&gGde>#OoQ+?qahOG~^y0b^b)6&1`jG~-D0&AN*u62= zc%KO@;@qU8dygV9^>G;OavHaT0^j;)P^>#aFP&EdiwzgJ-)}-J&O{y=>)wQUALBc6 z6*>HT$B>}t4z|aJruEg6T_D@Od>NIcFR3w90S|yITAIurCz*D;HP@bwUY~ld-0qNp z*m5lMw=OD+W&tkb6pSyF{bkMX+&Kqih$e{c%ASJbjgy^1x!1Du(wKhGWOO+TMl8eU z+^OP)uz?(x*XY%?6yNA|+pihCuyCL8)VNxvuDirM%Ovk zFh~TlK3nfZ>{K5jb6C=C!+--mazUKjTG^NNx^$t+-G+&aMa9oW#P z*m?R*kScv%C0RFp139t97Zpf}{IaA;+jn_+8%6*pv_Bl#H5g|Gjhi-+YCRe!+2|`# zc7hL;x;e=nVCZm(UM$nD07C%%0%pB{oaM}#8H@aV7}2Svtjv&_mtCdZs;&s+x6=Gj zbgkhAh!I0B=SZ!-4Ykh@Ud}i^>lvw+5e$rA8}%tvcC><#1=512^eZ za_ERh)Xd~Um%O1wR=`OukL`O{QKo9ewC>f?Za%_`SmxKxRwTg>X_QkRu%Y{AyujsW zs=e2T`ALJdmEt}|8CK++Nnrm6EEQmRpcF22S}Ez!G+bFj{PwbLnme5f-u`^S9p!JG z(z;);*L)4?U1~2zb8qs60bp8S#_@~vx%AClfuWQB82boA$Dvs1Zx1Rp*3h?SIV@|g zo}tM)UIUZeHsWG~M?%}C*1It)r+ec1C|-A0)}Bk+VZ7huVDS=->$~nGZj>bDRLj6k z$}fvO&^f6;x|8M_n{B6h?Yx#*C>kJuk*Zm$mNh0GnLQGr4EfQ}v3opzbqfcZjJmN+ zklX{k>n$*Kh>+rJim_XJ8fs_I;~FyPWtg6ef z2E@IAg1iKccRM=O4E_?go4(6*#7q2uCNUik47|x6X~XoG0c7rqAJS1ADDrT77X64g zQcj#tzalL5odN?%@7(n+m}fpy`g1HD8h(r*I%Z70o*KJOrOllC9UP8Z#Gxw%k zZSEFSa8y4E9?}|aYg4i@eI|^kV4X^9{e0-h)+wX5+UM=3sZ3&vd+Cvy$k(py5Nf2T zqikJJ^brZr>YTp{BwiKa@Yrm-pkm7-EMg0oYc8m0p(#x9EJWtwYOtO#_lo25(Abc0qRmN=A1cfKsmdo>m{czM zP&9B^Y!b^zmF}%bKNz~szu}>d`Re;=SdsZrHwBSh^_L=RfJDwUpX%v$mFk)#uzYm) z6vBrgx-CkPdP{&W=C6%kvQ#0I;lT4X2V_cde)97kxqh*psIzRzampTjU`-?OCw`)E zSZ|MJMrk?Q(S`;9q-+p|SD>yU6tC1Ek30``ZgEG*b00B3K>HffuFm5_#F`W0%GG*) z#%XaDl_@+;hgVJ=(F)d`rx&n^tV~?6Ip5V?Q%O#?@q2fp#WLKr!4-7Hjn+L-0YP2t zpUDeam^3g)zPn?8dYZ_%mS@e#+45T6RRpI!cd=M)eM_%Z@ivbz4v5snoreW zS(+il7Zugc6wf7sWaqeEj}oNwMoJ1i+a6wM)UJf)x}^!+K;EJGD^L4Hk?uB^MzWtl|^0co{EX8l{=V3bO{1rsqaX-6NKyCNHfms++qg>o$Ux% z;m`B+M|nT8lgn&RrzhHKjG!)=yx)&D$*+d*GH!5KK)Lc2(*H;_ZP%2$4 z)mEkHAF(T4%B;3`9VC%Rc8-T13Miy~iv5$G8}@I(qq=eb=ZsS1l=V)`dAJQ9)W-@< z4wklf*_IDfiY=!2rS6jwEvyt2yNv!!AE9e!-euJrim`m$q^%QH6?S5#{ak!g3Qrr||R5GytbUep-pQ66;jTEC|0?^+JrB+v7StzuMdDCh6gMxx8=|V!b z52}aAZ62DF|IG-*3t9xGGW8-UkyA ziL$@H@f5t#U$LLm9E*_MAErC(9`ye>;K;kbf9Uf9k#9fAt3xW?TsLx)f5rYmBW3^L zjjT|u#GerCmdPzci>2?KRUct_IXT&-6Q(JR!z zdIvu&`Zr+uh#WCOCbi|hI2G|Pdl_&!cv=2}Ch9-qi66uEYTPJ53kZ6FVCby+&_8$@ z^Qc>$*!KV5-1_*vOQpg~TCyd>b5RCNf!*UVnYd*6C-FR1lF3P*w=4m3vYz*@oaYq$ z_T9*CoJAjao2fO6?aZvaZ+ZGsAD0*gOJ}^t%F#6{@pu`v7r04iNPzXgg(p89Z2ZU* zyWiEd2z8gxk0-A&0Cz|rKb{{r;(G)wJ?JcxY@<@@p0l~C;lJlbB_W8WOzWEg{jRs^ zeEc&nFVk~Rx-S;~@|hx|%PU5(pgS(9d+&Mg?vKKnLG8p$&sb%qK9e0HJ8-_WR?=>X zR%IRAo6dU5pF&)~NBTW9cF#$ZQ>WK)YtDD$07Y#6p`xDikUnn`JMyFJkg?tHK%6#_ zlX{NRO;3EA{7d3Io9@h=TwO?T1qEGRrS2Xn>%bhGFLBcOHKrgj~5bGBz0b z76b2f5yIbixfN+wC46VrOZV;!*uMt)ZdS-^)+Jl8=C~K~OYp|xB#x-8*IQc^_p8}2 z!clW#7k?ILG|B&0nuILp7$ZSSm|Wu&-z?Xx_*KOqQHVQAO<*0pCQly?p||hA z*khN7NXv^)O5t^KOPKn?>LJpyK!LVp+A^NISmJt+F3fG`z`k?CNJ;qD{o!B7GwX>! zTB$RJ3zNSAVF5?ugUSBW-ZF4XCY@!e!fxDqf+pS6$GA3SmjXs&ebFIITQcr$<&VOM zOnzS{ejL`txDG@Nmdpuu8ig?$Ha{RKvxhs=Jc$-ekmwHIhV+Gm!0!!~CBJ}wG@7r& zZb87%a9j2U@2B4NtTc!04O09jGu{>2K=Sh(MxQ+egwG#wrnFUwY z=@(4KMLYL(ukBz4gN0Bet7mz2tKzNsfoVTPWZVsW2N>wmm@Rp?%ftw1vo@H z=NB!{?6U@G53(@h$-s4xSPc^r4}c?HF=CLq>2D0ywkj4QL(?Qi?qU&}JMx4Fd|)M@fy|w2XAS&#Z~&POu+$-_1k?MQr;Y@N(En@?KNZtM_xN-rG?U zI{e_OcI1h7`9A&lUHgiK$>w(U!bTn{I4+Pu8#B0IVH_@{=3XUi^hanxt$}xUHkGYz zBI3%ak-Y>5YVL@EL^0oMu}mUe^O($Ze3Wlzll8O6{(d*@xzr{_+1)x8G%NTf<1R__ zuHR6bNa5T6C7)_hQX!onaJ`cB4_|(BRb0D7nsjr)qHSw8_K-xT3f~ra(qkR-b};Iif+11q zVz9#nSmV}5wYa#5aXAB#Abe>u1)ZVmQcDprgF1;5tY+7EzXLW0{`A*wxsSI;CV3MU zf18>%nx)5Ysme6X9&70vSCAgutrHg!e(B&{1-x_qp+RFy_;zHddz{Uw3w+x=-s_B*g%}M00Q%y0JWsm4=N~FfDa-ccc~;@Q z5b6`=u00|y1Xy%lSXQr5`!qY5zxaD_IYlNjR+3Op{DjiyF{rTr8s{q z-9*xuDnsc;2w+-2^fXC8Li(ae%Dt~=uIu=xRX9{asXY)Rxv^V12)IX}yZT_;Pu^sSDn@RGI6b|hp6p2m35FB%^L$$V zC@5XMgZ!4-nN9lne73=E%r1TVwzBUWz8{xI5Ys_h zx3Z@=@(VuC$1&`&8wsjuSGZ&E!MZ3T<80O{B^cIqY19qjc^#fT$$uG)QjV}3v2wWa z?YYTV*UqObR*-@1Y%dNNGVGBZu{$CMWkLt0-Oe23+!(2^y5VRjbfp+p(Tpf^0obuO z2P>Y%MLWaryn%pjjJgs*2S8c{Gwv zAHkjkVBPXtH}J6jJR_k_+O@{QJ`Yy=XZ1IkY*TDOzPZ%4(0LdsvW1oU@zaIcMvQVH zE@sUKeQm+~wKmJcir3PHP4DNg72T2XcXcZL1+sv0ws;&TjLjV+LN&*6C&;E{s{FZw z`*5?r0h(T_8$L!BD~3)LU6?4a0R#`8OPy&Q4?oq@CeN3Dw%O49<2hqsfW=f>l`9t;&zcb^T3`aC{%3c{xPHrkDENhrj?+*Yh zJrPJb)-%eGpVWwi<&#U!?mbyZMP!dpWa#esH0dzfJ^QY7xsDp^{DZ8?f%|vtD9Nct z-HX5bWa*cW2GPgZ+;~@w9FUiLu%=pHX>0$(-;_&~Y(@l0+a0nEW6{=;kk8)$Q_~An zUrKNM$G1k=pZBySQ;ol$e!agf*}fi#cLC9YuapxG4bPqhFdrt0TAh02l||31wHzUA zZctXI-)U-ISMy&lS>0R7{ixEZ`_TBBV=9kv3&Z@U$n@KwbCszkyp618*->h|Pl2?R zuCUO)c0)Ob5(ZSU)3*a^J0h;ZJyOl`L<`Bc4&lndM= z?M0~FtE6&8<_5RXE0mZURKGzx?@T;)AZT2t7X|~WJf21x$!m!8kgy#Uh3kJg)$6ST zb+!J8r+tE#|jG?m^&0IJfPnr>qO#6AJZg4!cb2unTct466 zvvi7(k>Cxw0Zxq#^k_IF!b&{J0N#4zPDxHinvceJ^{ZvKLU6S_5?1UouV5PRZTH{n zC|ThX^0sS)|FlS=-wG znfB@8wZXsBK?+O$j|n+$N#=9J%dy;EUGVh?9un)5bVMS&id92hqm7hO06}dk+m6ei{=s|K7Em6?YMn&s$EfxiY{q0^P6!<3zuM~C#1B64SjD(BYpzLa(q$3X7wgi` z=B-j7laPYXWq<5d;PY@C>sciOi4`Jo?GWz&Fnl{5M!c{+PDz)t&B12-`OcmN6g(SC z!yabZPBf+0t)++x8Ro62=1;8`aYRs0xe-QGlnIKD^^1LExX?Uq?otwi)PtI9QfDI&oa&(3}$=dRs$y2^80-%NO@;0YqQllN(L|Yeq4U+O@F$r zEJP$+JSEQ=f^a*(l>2W7%vgo-DxcnOM`voj;N)Z>pc6}=0Ii|P=I`24(;S<+5)J!9 z(#}~5M_eQ6_3h~s8P1jc*>Yk0s_bxkN+Xu7$R_Nc3YhK2d6{o?X3lK4{+$0vSD|Za zF#7io>EHG~Abouj7xU`^3cPU=^*=f){Ns*Ra#KsYfgu0=S{kTv)F8_G-x3P5IQT=K zpRQgVtgJ6i@Vv56?N2RKrhe3{?-TLmKg3c0!%-A7B>vIl41I{?lnY9uVo(*Ki(n5C zq_Y4v6l|Z;g%AfNC7*42Vi}m<*ba|=>3zf5L^8sjoTGO=;34Ox?m z$eF(Zi9YGFA=|H~q(j!z0|f$lq-6r=W`cTl6D9r#Xjpbejs?T zqhR9aR;T#1dceSe)6h0VfZ_1tmq|>~&-tvPqw%>{+t+*r40q13=o5c|L$}3pluH%E zmx>Xbxo&>RuLIc2KTOmd%dHlyi)qlF5;k!UWo*dTi}eIn2|om)uo5wy7+=ZCoaZ^5 zlcH`|7=?K1qBv{8e{Nce;|d$PoE2bYL;VfNmn`ggl4{Vq1DB{#mFQ7fMKHTGd+y4E`4pkf-#NS-J#Te<{9>N zv%!yqW?J|8X>8EWV&1H28gGts(UH$B6$AUV?^&WKgkZzA&0mBW%8ot}ET?pJ4l_eD z1x@uW20g4iZ?7BvGZkhI0T@i3@0Jj6|9Lv8fvGA(aPdZ7&-yMF-oo{m_Ho2umu+t+ zN7Z5YI?udI9vN0OdCs?;@5}BZ#6b&4`!fn$1~FoP?wFPQIU%(zyAS;hn6*W&)Mh^f zm)03C*Gdkk;J)oPeed{VZxJ!Wu6gH%bb|=mZG#8spB@{(e$x?bmLj8C4E8>|=BH|( z_vzc#*Frl>Vf0IlKSmUi%UIANu73MeMnJps3^%#D)U3Dy_tON9J~M4DGI`PKEU&5G zFqRT@v4kdvXUjf4Wi?lJ9O{McXANO#0pGt-Us2ex+}u0l*)9 z1jFRmj5Iu;TgDB(#|Gld^wzwnDW?dh58vZuJKdtD!P3jH@hyRDmD5g z*Y&21r?->c1b513nr1u3xv!w91d?A^5fxT@!jggGU^;STZBt8!l288Dp(l4nsq z>?0%D=J)6>o+}xjI2yXPZiLxx+=M7drm1upnST$NY6fBiQOS!D-S>}xCltx$y|#}LG&8*b z&S`|hk-LzSCUZ6?lBZ$*QwATzlbA=gu9AsJjrEC}APyoEp?WRn++mcQ-1pTxKhsy* zQ(Z*cqWQ6~n}#MUfMRk?Wv_N(n@;feR^@(7!ur2MQdbqq`&k)polr} z%6l41cj-^$)Pwh>c_@kURMS5XLk7Dw4NRHlz$Vo0(9|GiTy&cfB(gk?XVS3gVx+Ps zJmM(6=~)^H`vvcz>>MMYK9iHY+&KKM=XdhBl_Ra$N+x33{V|mCLpK4m!)c5%m^Q;0 zn0Tz#tX=YW&4do?yZY|CN;?|8iVi{2w#?0mp!^DQ*kla6n^*)F@XXU+riyec`bBkH zhu=JIw}Kqk94<&idK|f(esv)=&dkUdHWC*@rky07ytAqm;k_TKnK>vLF1IZ0cditRz@uEXbt`!#FkHQ4yE_ z(%!*bpMvfaW~|%E&vJPYYhjq&gqxonYTG3o3UzkGqEvhvT+0sh4Sr->@;fTc5PYrE zW54e4c{RO!dnsI+87q8gTWg;1by%mz>uQ`}E64q>*;m7Z0F+>VYg9O&V*#JQw?}4G zJIn7TxgE?10AW#hVIQ0;^-QuhR#n&tj)}Qp(>zpFtRU*D$aXzOGUPt_ zzgud}$XgiY&qq#R+_dY%@b zwI(!=^@^K(5|fe}F~oXjf?zgUnxS>W^&VXvlXRjx2q8VlH!Y^6+IZU2P#K2A-&khw2CYd`T)A+f4|7_SAh z8h+n!WBex7n!MlkR0rIG(w79*3<#(f&`!S^b9gTOH(=vnMl&`%q4N|mdn&1I;1p#x z^@1D7Ma^%=aX{;$@#xXA3)+&hE zQJW-J^^4;4qvSnW`eIyV(3d*`rfqM&Z`NH(-iX@nG*XMEjzK1vOBz$tU3d}_z!^QG z-E4l0EG?9f&n#Nd%3Hr8(}trQ*aVSyS?k^Eg4tHN;w-PY(TdwtJ0fTqK6R@wFf@F+ z%OH0%@^V$sEpV*PEp^^-C6C8S1u}1-DZu|qasPTN*3fKv+CQv8q%*NX?ZR5jtd#rC z(sXXki0O8On!b*UH+DkpLDw&etDzF)L|@V+fPh~V9RB_A>gw6CDA~o~^6Z|Aud_A> z7_->rs^>Z}5+W>)%<13zD3POQcSwd3zV@XZ`ue*zC0=gUcb7FJFN05wOx~w6)dpFV zw41Nhm(t1kKFQy4bZoEpDWR*uOr?IJIU!fB1oPKaIoo3boUx zt#^F^E?zb_7Nr3z_qf^9s+v)m4;=qY`9nOIb|NV)wQk>?I{m6(CnE|oZ@975uIsBe z>EKiV=PU%RF8G`}o^Zi5)KZ#E#KjVJ%64y6!xE%UuxY7ksghxdLz5v5x?r`&p)ed! z_3{pQg}y7Z!5*Y699c&X*jb@j^r3&4nVhuqYGJO|ECkt)Tzdwyt9iiQIw3vqinB_V zNsDf1bhLbbV7yuKc5^q=^?;1Eq5ey;OWCdm!lqMe%q9wWa1TOgyG&*i zE}!-sS}(N=2^4MWzhQCs(?0gf-DN5r`f6#wg(kjQ13sQjxc0i!-SD!Lr@^8yzl*7U zx(u^jZ{~Tl&MO5zOTV{|RurOJXiEkx+}3!?S^)&!iAz-ve&j9hcOPiZp7d>@I3%cAsBdD6Ghul~4UX zx@u={ZC<2Bx<3*rdw&K8NDY+UB)biFm(ga1ulWNyFIUxFHJ?=OeI(kr957eJZW7a$ zSy0g{Mia^6L&cZgErJBtQ`5@-JoY>&xYs@79F?q|n`i%CzQik|uFgg}gWYT{>*H#q zEq7sv=((|#8lX*LALPF0(Pf` zdJ9`COqV-jj1YI5}=6`EyXFAIto#G}4~*~A4D7Qr4goF3dZHZZ1v zJ8Su5Wg|dQ4SQB1bFpXBoO`eOV%3;vMJA(&t|`-M?64a3tD8Sc1ue#g21i9?!Z)2a zrUYKh+2Oux0vF}XGiz()!6=dyblzL^){^3Z< z&G1%p*d4R>wwaf=GolVu`;WuK8pVI?dafM`jvHd8^Gd~qB~0J+m47?y4`Pz?Ms*4s83QwYEuHhtH=8{!Ws^H)+13dD69p?sD$ZR01Ap zs}HEJG)@R5aaWSP6!ZPP6Fd@r=R(9U69tR4<_}c(y%>l_qrOkKT#7$)Fui@I5G41= zv%H&^-J;q?TRr-YXTL>|!VV(s>GxKuyj<87top~Vybkv>I2hVteyMlX*4l8G88)P# zdNGgbXp6=#ik2}ymw2(U%MWB$B~mX3-;*~_!Bf!*(5|ZSpZi%Bh4C;hSS6q*M!G{y z3DB0q2)dj=Wh?41Gg?;{(HrfWZKpK0KW(DsW@&;SD_A|mbbGc`Cc<~guvA=1;he4P zZ`GKsyrSSgGZM}OxTd?9n*hP~aaX(PHd$mv`$E&1`Iugh&8yMJpPQPM);@3WQ+}1Z zm*2@M%KRwy>QzVS1u5x^^d(fhWPbIzY+NFHv1c*~I2#o9yXZ39x1QB7#MljtDDn!! zs=yYaFVcIlMt_WMBm0>1(2eHcr2ypY;kj>g1VE^gW%^t-&bA?)$E;6NV(NzXO~o<4rof0gj@f2oz5{O7WcY#^;aZYJ@>$2@= zT!r2!)5(maQRDbNKHN0U;&1t3SxsVD=GGv2l)>nELqj#O|8JJ1-;9(?w5zp0@_UgR zuzh2>rph|2@n7> zO`H(o<;YvE$4sjxkIO!8m@Ul7uF~&U0n)W!RP#PKb|Yt$haeaab;8btB8EM>OBVdk zp#_-UG0%VjD~x;|>1?bfMbkOu{gX^qf#Ywm6;iHp{Goz9yL>G>q#G#(@I8Dp2tD!gh=e-LUVPSREk*2X{(&@yJ&uVbC z4?(w=6|XhNrPNL~3!N#N>@AoPR3!nVQ8Hv1O`OrlT6r|JR*+X3m5cEpeEYi38JS+D z091fJX-*uUt!@v{p^qnfFqP{GsvIcN_CRyUL8Mf)xkTOUK5WE=x1YQ8hoUE-Nzpz8 z*RsB}mUs}^;g|N43>eJbM%UJ z+Weq=7ZR9LkHyy@61=LTkYjeeo-VT7FM(u92tJ8tAMx;Gz2>g_+E!?Hh#!^$L@|;N|)|O`y4KH zhjGs{dI;ADmA#%IsMj(If1VgY6cm4GOg^`f^1HH3R^8XC{PGW&3!A6bAFp!`#1R8? zKpoN9(xiIz)dt&=@XRcavY12sf;DR#GMetl-_1^lKV>3N`f9G%QdHhO(L4Ch>DnjR z4@!H-;u|JhrG%?dwz6>UmvXYA;#qgw>u!^Co%7z03v4c(HuV_^r?TQYnYZ+vOT9fQ z_sOj0dz*Ew=l_7TJphh0Bu^OWqP+j02jfCxYmw20o>z7&W%Xsk9FAEHfL50*+IR-& zCq%)F^v}8u%O?CIcRA=xbR4z=f)g(5jVJ?zA6+hwbZ|D6eS3ZXc*fUU|3o&Y zW@^+Q?Vgjp7k=?Ycn*z-+<`Nw@AN`&`DLo%3mwXkDT$1|d@iplFI|JyyKa%lr;>Q~ zzPD;Q{zUrw?Qk~8oS?!>vn;WaXxD_x3KGw{EkpqTa%1gk3|YHKwQiMxCu73|mzI;c z#+AwjP+5=kM`0PAz3qHMjsAq`%TMH@KkssUy)=Ei43FrD-X;_Uk&#}*zp3K<2crC) z+BXrMb4#dt%|_wwnd=Ky5oE#@IvsE}40h(Yd1UYp!{Yx>@qZM?f&Ui9x#&F^k^}7a zD#)&TR9-V_A;9ld3Yu32huv7DXE(2GPiI__w`+NZ!Ucgwv7VTs-KB)tKR1D@X$i@N z&wXgR9Bm-#VVpjTpO-=D0Y>RqQg5%_`2)Tb^U2juKkO79ZV2@X1@=6P$b{7zcY4EA#yqAEI3F|+AvaDTian6_(U zDbZh=?Iz8#Xq`EjCIlsSzB#qgWEsHR?+aHe8Yc8LDd?U-kj@)G;cyjAZ&y})`%|~2 z$wz=^?B@PP*zYKs)qO%EFw&kuN?T%3m+nZBMW7W_5Y^VXdAoO&0ud~N+ZR<|T zfVaG|IaQr^Oz@Q***Y}lse1t9mUw?b7EotPn_w6-!ytYZSNP{gs*6WJG%f>UatVZX zGcw0N?mXU9qVDas!{o#{8LzMA7tEzsp<98%pL4-MAg47V_-!pXb@yp-SZwN}*;o~&P!ZFmilfb|@vCKOV7)KOjP{FYNL z@mTbBKn6K&BzydNFP}%ufVxO^veL!<1Pt-Dpu&T$E>vRI_u&*{nHs*E>2vz)tAbrZ zg6-O%kTvGj%J>nzhUn*5mInM&@fRO?tV5LICpYOtQ|SQRrimbzslw6{*u(J1c(Hz$ zcUeWBgBOu&VK=AZmyg&Z*aI3$$P8=}TXX@ch`-p(dDBEsD#O})@;|;^H;I88m+BC3RSn? zg5pq3CO(zN?q9G5ET~K zZ2tDDf-TdoU8;3#XlbHKRCTNVoP{xyv0t4CE`9hbL%I1W+sNZ%oBf%DR zr?|AVJq(KO)Hl-Vg-cJSe+wN9>_kD;;WATkb0MUC%}OI=Iq9_+*&cnqBx9U5^NhTz z0;-QcUaJid-;Zm80kj#1+m{hI$y51R=*=X*2)S|D)RB)%xto%HOOvP33|RP$r5@h~ z|GeVm@$HfK63KWQugfsI=jhMF?WyS&5mTXHjAWF*aF4xY)GVlY5b~tR!t&sf}tqI1*q6U{lY13#W5NVGm!&$ z5&?ics;c-D@A;I^Fxki`pA}W@H&j0&0k<2aYpKH6onZmz#um0;;Qf)O_`NfeXJ1B#j%y%<*)OT)1tul^?OF zUIE}zh2ZJ(jCu>}2liiKuwDE`8o2(qn?r zkjyF`0f?q5x>=>vWE+j?zmWk01?Zhs#IGGjTg&k$^!A|RTbzIWCpf%m!{VeHy9aa6in2?|QD4JI#IM3Iv+Y9s1Dd_`r z-SOD&0yZ;0H{;uISy5%bM|^Ske$)?}1U1H`0Riw9dX>5D>i~06v>Wj}HJ9miWN$Rk zf*EQ|%W!URi)gkb@$fHe@(QYEC@RmQu}SBMUn$AUPR^TxL`znQ4gqma%-yZhsNU%= zyYt)-Zod4gxJJGa(39V22TX4RSIQ6kDb7_h6ELkBIy}v1@5y0r8X7@jDx{*V_}ONi z?i;gXz9yDH_ewhN9Y}-~W$S+nS((PHp3DF8&7T2&Ywm2e`bgG;#^bt0zqb_bl$UkM zN87mJj#p+-70B8Y)LE<%Why??iW1%%Dqs$f-#ls%|jf{~783 z2ev4`dj9a})8P+n!*g}?{H4-4W+>gTd#z}BL}c;3ql(R&Z^4`;xw4bA4wqV_&aW3^ zx+9Qx9!AB^-m?z4ysz=+fW^f3pA-iGgyOB)we@Rm3oCi_nb2>JtV)3Ar(aUA zlkl^Q%&RC~w=i0S6}n~>4Nyg3tTh6%Z>M_b9=y>M0ab6!=o*wCk~5yR_3f)Hr2=Pj*w(kl(u4#>&Wg{V&|GP z@nv7|qeoISbk0!?DPC!FfB4$zh(G=QRPM1UYnNCg2>D1>2YNAW31Va`@I!yxU>J48 z`($x^Co+saAmCi*Vmjko$7#Z?$#j+jb5msmJ-fQCR)b?s!R&0o+`RK!Zn}Uok>cmO z&adYoGEHqe{j(ms2M@|JNlqY|{niN}^_?|2@GGBhm;&mdJavrmK?jto1 z?)PT(nqQ%o?vh6LTV!Ukmk%+jUj;qmq6%j_kKK6FEpCvTPYwah$frepI;Nwl^TBA3 zK{`|lugRD?Y~(v;4hQJRy(4$E z?jY+46TgGXmftu5i7U~npl1O0i{iTYs*KiZ8^K;U^0Q>g3OOOGd}`1aawHx}+Y%o5 z9NYEa(Y@kLY;Trh9_-H$ODP{ZlQk58F-54>YYBnKWA)Mu^zy3K-|uGil&SYsM(?bE zk8K#>mzruBWiA`)Xo!8O_$qw&rk$X5qEqslsU`z&eX$oEw}Ej_H?DBHUAT^-Sp-qV zTD2y*?&W^f`eRQ;>B;&xXR3MpN2+%NJ318VT(!~c%duzGyyFdd1^ET;1%Wh!%Z8o! ztPiD-ENV`BxyD&3g2DWzu2;VbXf->tR%-OA1*b0?!Ts6AMQY&QB7IzCwN7`GnL!$a zLwDNY&urS5uk_B!6iYkmWG$_!FKNT*f`&>glT$`Am9j%Z&i6#>gwVztl)j%v(6@x& zUN!g_EM}FXcmxL-IIgZl6OBe7*BkE@Y}O(LQf~v5e-TSag4eX$?5XbYf2f&cD~q z84P3^KV;Kka4uT6x+%E10x{<1N~Z>b*#|n{>`XCMKv=@c^mN_!NXLtDN%|t%ODj~t za}$6A0MfIi50UWv`@)vT#DewF>KvDI&MPlHJ!$EuIv1w;^c;(2<&%^z8J`DEfP}{7Ob;w647azW^{oU-`2ERU}Ppe_$U92-U! zB7+80<+P>mKjtngc6Ir1wiT5jzDSc0M&<`@FG^n;_S7z$fz6usU`q}D5Y=~*F->T& zd%PaZ7hNWOcs_a}v$>t3i!!)WH8CvTfBErA zXz1rh6bgdM^@}kf^X`I%9&3%{uq$5YgaEn32a<~LL(9#bo2(%ZR?^cSoKTwp+?+8U zon|-bC}?)=dsod+v3)kZdi!a+D~D^{c6xwn$@ATnDiP;EfdT*Ie5^z7_X*1D%FIp6 zZx=-*>uyHtIN`LX%|QjqYY zaW{%)O_yYIv;0MImV>0JY{Q?AKP2Rtl=AOk*ICR5st@;uWJSK)T#y8XxdX_7`rGCQ zNWrq{@!jxW6dTJuwxOO@P*>sW*+&cvaR#+P;kak!To9H)Rd?ysH71;gRo)@K4_w}H z0_N4e^DKC&i?V#9rS3dBriGG9K~hIHo+yUrF*1xt zH(!$k@<;`R6^$9c2|2&Fj8SO8X5yYY^hU;T{y))d{^{V6YnAi5*X20x)^ZVlLYTL{ zdm}yvf1-_iwT4*<1}s#o7L6q`qCD#-jQVhCopn34T`W?RtJkI1V7L7&gyB2@kl&mN zM+sv)@`tm+N-0M!8J%T!8)r`>*^u&zPf*k1a8G@rqJatXA+~R#e-t07@L-#_>rt83iG8WF$FX{m z`E+i(=6JK*6$`FL69qx_f*I#V1Xfz+VZlR6uchxyzE-SiY^1%N*INB7HHbeKUCE31 zt$=73S6aH5nE?gQgq>}h(UJQ9R@v#s8~=p7vO1=B`*-)%;I-s<0F}KasF0PAPE`8-s}(az=f@AU4*Z|&P8+@+%5F+Z+eVB!`kA#ofY91Li-#H|K^#*PT7 z@)D9&yHG{9GqMT8JjAOrh^4IidIRQud0J8*$$UpBDR?!AL2 z)yjr3Of>jbU9J+(ppd3$QNZiuUlC)}N>fxasFV^SK6Ne4D2>W|HPpC1e_ca;XJF${ zC~I$CLs}-VXkqVsYh~lOL~C$)P76F{8agA#ACNmXq1V)YSX-m|R&CC@uOYxWVwDh- zIM!T9&^DLOtKL1e5ut_yV!xNU_$rdLd>4WD zY)U1TBRSfMmI{I={7Ij1vLDH9Kn}H0PXZ-Z_N$QcE?l*z-ndE3KffaTPXLblmqmIG zP_)7?ihBcADR6<&w8Pb^|4Ssip*i8A`yonZj>gN(dX`kkpv|isGPJiV3XS3N7JA9o zC#hJTVbYx!1AJrqJleozWcwi8uj1fMK3c6Vui zqoRnRg9GacG)Kuc`v8Yhe{Wdde)RY;ENmVV>DJs2qS^j)E{jccg_B|ceh#8Vp6Xw|IG9;FzV^`g^-Yn>K=HFh4pzDWPmx4E$k+YX zk)yC9HjWqn^#1?x;DwXWC=rS0Zuw}W%`tC%+L3N5`C74zE|K)e9%EH_)PljCr-|&P znZgp#7H^8PtIUbcWeFmad@{Mcqlg6{;vJ6Rl#yFwgEI5gu-TibOZthu{RbN!4XCB+ ziHCX5He_l?fR`(0Rfn3-#WTpWZ}1z=PKjE=7#6i`io#kV2v!SAr>G+n44uCusj0#F zO1-6+dAHP#HuT-dlTOr4_#=x`gfmArxQTJw z`ykMbAcAS#{{3Xiiu&X{xV{TSa?@(dC|d6)bdg!NXF7zwe2FLj2Ilj?vznQT|TP)3Y*U!UwpziU*YQh0i^ zSIq?nG=*r*xI|?P8hDNBzxkr}(mj7J=38BF$m_KYE77>6ul8vJ7)YZDf!}ig;}+kU zqPpD>sW^UiXCU8_#GF@e@SQABdVwF{XT-M`DYQ@C_X!~~+rLRn*)b^4J4~JRYe=$N zc@_@H-#9fOzC`ZETOS#6_}6J<9B;gowJWLFI>^~}m=i23w7VjW3ct}4w|EZ17h1jd zAYu!@4L5OSr2FxPJT|zh$}+`QNMWCHV}$^T4d8%*dvfrKY@~;sd}8wx#e`3=DNwX} zH>kOOJJZXc`chK(w}DNLx-0w7S}CWHZwT{YgVr6bX>$z|C;njYZcg1k+E;LjyFnC) zvfC}0rp#lSXMEUr9;jO(f2ONbNksH0iA~eitsy)MFT!?*6KbMiQ#-R3oPM?I7asrU z?9($qTo;VkM?FC8iOLK2s!|s z7~8n4)ydhds`c{YiEAOhC}MNNEOgYODs&>dGgDSe^U)*i;*lW5x5*;$3VWZGD zg$l4}hz$Ug3F=kgcuD+37v3Q43e#o-MmX#+jB!jBn@h|~Z;WuLHhr(KtSlX}K{JVu zaZK?(F|R3!&RU(arl4LgH70Xo@<|;gu-G|7!7*j^@iPv7e?eW*_KAmY={x9xyuBi} zFL&3Vo{TKkY{Q>w_-dqB=w8L87j-3Dl)4VGdSg#GR5C1Ouhxy(_%&x2e0N}LcuSEr zD8-guHwLu{oda#*fU$iCj$&7WpPg`rOk9hdpx1ovFrUT%5t>nXs_9t0brc;{2UDFG z#WX&m-!S*UXek#=u@6XWFK&PG52Tg`%mNuW)7hUHN*4g&J`F#r8Pv#;=)?@I(G}}TPuhSBZJpuz*XFuls|4->GiEe zZy1}d;OziO-sXjvJ)m3#w%*9bOnj!-dN#g+PDdzoV4?NeT4I}fONR+jy+g>QsA_A$ zb%$o5cI&hwi&^|gkzJ;k7n`bZq%#@-4XW4M+66w^ccptP*vc$t0q~9#*LTR3p zJH*0rHl7zidYBtw2l2e2@L)siB4(<6&Po?Rxph&c+iFY>>R*Bv;+QY(l5njd_!}2w zWDMS{5RHlWV03$dplkJh>7;-V7Y(U5;&s^s>Z&)rRH~esiS{HAvT#T03OA8|{XFw< zJHr0VExco^+GS6Da>+_BW|a`D^L`(-To7~>357MQRL<2RbqTpMRn+el-+i8as7_TE zs1~gAeo66D;$o_At$};?)cEX!M$Vd$$6Xu5k?eW{S*mmjYr<2Qa6gpg45?05sGM?3#$`b_j;U5O9h8meL+kk${Ck;v{l-& zZw0ixMEASVhj|62Yp^ckt$Gmcu}BMrkeNn#k39j3ljlnJC$43x(FApnljfC>!n(;7Nv-W0Gz7w3S4(5| z%((`~w7I3@WYD_YQ9m%HbXZUfZoeleza5ffnAi3l-eEqMaeTa_iM|}NSwQS-CU+|s zSW$Obl$_g5#r}x=){6*b^i39f4*kt~qYZ`WiH}u8apTgp*NSCBrM-<&iM6%min`?X z*HZN8Yz%VLlC2ng4Qh7mqYm7Pm1!;*h^dpl__eV`WFxw5RYA1u>0v`M*4u&~0xqqp znC6E_<-V(M+v#vGY+VGu`U&Z`dEp?}b~JiRCZB3A^*rpr6oLMs935rF-#yX{eT(l%~tsrG0W+3!YWv+dHPm32v< zJfR~g#w+T3pqP!n5~N|G%n2=-4HJ$t#O7SnuO()3B3(aF2k~a6L#e4^PpQR=6__8* zS0YMNgOXpnCN_C~3dz=Rv=26AOY7sN5KEqZYt~LpQiDNI3}6y-G)H91VEf2nzng1F zd6cZjuo>S-veS-Zzjsae7u;8N3ubrJy~o`Cj3fRgo__;LM`|gfa?Q_6!U(yXy$z!9 zBCD_+$6pjQA0?mA+Sdl=v^+I)*h=<~n{agwgoaGH7PJ1W+Y@~z%jKpZH6R=Ek=AUe z2k9}zK3gV3uRk_CVTA29m-Kgz^a%B?rV$dq5%Sg|Oh%1Dq59n<>m()bXR^icDveVt ze!{|qoR=|&AC~Ldwgk|6KPp%8$V`;o^D(!()qDIOv>LJpWx+91ffB*)Oh3Fk^U)(?_G`+{vWKLJht;&& zF|L9z$pqb+YRr+|SJpdw4tHmg1n0Tl0p*H@z#gf$;}-lqQfpUd<*OP;9BAv5ShMal zrAyt0vn=U@Pe}2oRZCY{R}F=J2{eC`b$%6vhqMnL_OZt)8E4ds?&zpn|U}(nkZ+m2=7H1kyj7HpJ!6d z6lbzu9BF0_-mUNM=q!qcW1qP`>5tzoeHfmXmpSO({AzG}CjKP_o$+Ns0JtE_hLwND zMMQdk$l->iI{7xhD{II1ZH9nzyHho@sq3>3#BOT_t<<1(WkF|*@wA9eRLu%oj8cYh zYRu*bBaXvouALU?+e5o_d-4|^36owFkh*E>Ay%$^V%1eLl=VxbmxY+~VOEbIl*G!` zYQ*D3+~p-*wWDXQV}kuPD|r9hp>?M7k~#x>LXMd00oEY3Ytah)&lxw!F*dNIZeRl3P^#)Sua^YCR zOxKrp27EREnX1FekDok8~sNX^RuXz9$dBZhEFg-w?81T1%#An2)1y1YuB|cuk5JIKIN>A zx4qC4yyAg{+zQ~mDn4f1LWQoh@a{fSoGHridK0H4R<{N=cdGwIAqFo5la6?Q;7^(h z*CXuCyyx5ta;A>-Dl|Cm+p6M3WEHaiI>T(wQnATm&Hl`bW)>D=U+lQN%!jSefo>RY z>5KuO{^VJfoDp3AkX3S~gKO5;OYYmxSPu7mDJiOVSWjusOMlJcwTq2L_=1;}fsMUf zmgDOV8aDKOzAT@$Wv^nv1id3w)&&Er(MHn=1B20Zt;U` zQ^~kL2czSM65NupZ^6fVVQ>=6Xb=?*K16#Fl9qsMQgdWig+;y2^%McY_w)jD^f0s@ zyZi-yj_0Q>g;J!W0MzI?)F0vK<6C>}fx8VhKYmr5z6Pd?2U}>O=JbSQk7vd zK%7O^71u1;+*`TEl*)D^aJanRjmA@$8&BqCJ)HP$O@YFmyAIXDEo>^bmT<2wzw;<| zHjA{TDmvgJn=CEWrpToL&t0b^FVb9^SS9lHRJLa?>({kwJ?VER*N)ibqLD~GlK?)N zMhq#6RMtK)H!iC>zkQ=w#+khzboc(i9-+K3pe_Ot+-P+j3EQ!?kP2j%v*e4|B68Y? zFPF|$Zmf7Pf$PUbX_?!7&2Dg*LuBLPmcX9Ay*w3%U)RLrjcVX-!ND@3uctBs8A@MUPcvidg{2b9|$#EFrT0O$zuW{!scJ|;TT!^8;-#2*tTR} zJRBBIh)NT&x2dr9Eb@yyzO%~jE+vI&b>{fsp?!vM6ViZLZqiyt&TIph%EF$E)ko4g zCSb^Oa`c8dzRW835EpEDHWL829cpA zaxWhpUY9_cXxx_$@V%C{8YUL3`lb_noVk6kstItsE$Uo524voFSPHdhPuLZI3t-=R zuhQ|GxA=RzbUBNtW8M<1f&Xwh{=bn9|F5r<82#-GpA$7~zRk<)dzHoco~TTs`am>>#dlmHq_F+}GP&eB6|=?icX8Z>t)9QK+6; zF#O@ou=Bb-O3t?5@cZVhX0#d&2pwg&uZHaaU?H}OVsi4h8b z2GQg)dd15D%(K!w#jj=zbHd~QFmQ38|12HN3F;KaKPOWEsQ0W}`>-!Y)WJKa@Ry@t z_~e$cCK*=4eu)o=m-3jQky*(s>P_Xz+32YH!?I?gvR}quI5cNoesNA-s7Y?R1d?$h zOnMGiBwT~N-}88^vMox~ge#qElah9y?2Ptzt{Ew6PJ5|u_&(#yIs zQQVv7ETz^WOxcS2mhh2g_^NsNex;P1+68(yv3U`^ctR>%`Hwh#1rwf_%1*8TZNFKn zF4?QvMPgq4h`Twt;on1_w2oGKil}OsMZUV-q2X#03BxcP{q4Q}Z+mKH05fa)j@HF^ zfzdf<8la!1J%TEJC&B1h;K-~xF8(y2qTbeRj3^p?75Tms9CPBb@6F0n7B(+&BYr2lh-9wN!$n5mlXIcA$~526EP0Q-cEa&#J*kG!T}EgP*PsDOM>qiNSVy< zvAH=NqV0twT5m!_^++YM)~c)sLtq z@&-G7N~Mu-dA{%rjSFs}+Wfx0))MWz6-0%?HPLaH%n+bxO@zvPl3L~TbiKApd2C(C zG?g!Msf_@oX%W2|hR!4Fv;LHW@{P`tDxuq?URZBFT=|=TYa)+h=3e;KRdZYuJXI(M z>xspbg|v#lx9JVZ|DArPkCXymlP;1QwZgh{Cb$R1a7;)42r2)^zn>aO14BKJ=b!a( z{!aEcpW7_D>smQuP=F&lathA>OYBqH>m#y9cdbc}e2;)ixjs4sE#Dc*J%&>h?6mb% zXkT&~O>&;EL#R7dk`;1N^|g0OMRy@65@I4`DLug-<~F@AJJE|*%tVfXNDEWQCjE^F z8^am%S2QR-<<-w;c~bk!MjU2Xku^+<`m)ry+872aT{i3!x4~$z0{)}wi)LPFQK2Jq zfdDsUFV*#$fC)L_wlmoSLPR$*jE%%rJflX`&^kjaUONfkI3FdsO$i?-Ik>-zNpCr8 zgAb6ejdG9e4%F-AkmFjSm@uEDwg*h+YjtmpA(Vj8Q63XBSs!<6zJ)(jOI$uJxwGb&CO92BHv>B`KE-aeIcyPkJD6^XDb#2J4YV#-1c_eRF-MNp?vGL z<{S$`W#ULB#2LD+NA8qnI zY-wr7!LgM+fI~MT#A{;r0IGXLu=)s1AVZyjb7YjZ=m4l;Sz2~fscBwR*|6?7ZwmE} zq)+|OEazVlgB-O#z*qF{d99m4OZ*kao|rY@H<3QLL9wINRC#2 z^Z9q=R{QTqXmjF2LOh3=ls|U*e(Kwv>SaUQu|pZ(jQs8v|JFucdsU*wyg8C}etObY z{nI5O=G&}CGgB?QWJmaDIV4bVM;e+)Xlz_)YCo+3>_C{Vvo`up3$F-Lz#n&8@)q>} zV}JV($`@T`zIG0mvKudvrL;w0QPk%mctyNBi7^8ufvCE!(0}Mc2;FWHOKD?yNR|NC zD$4h*3lC{LPXBRLDa?iUvE{e=v2A6C(!D4*h}}i*Kp{`fBaptHgi8OJ46PRUghRN4#*{^gf>9HBoWTh2>KF zmT%KBA1r3n{cWZp@5je~QQ%_gp@$=irB25fk}mWFTG^}EXVv|^&^B3m!vtWqm7qJt z7P3r>yb<(>ItQGd=l_qu_kULYH#5WpKlJJ%noUFB!jXRp6H`bzXd+pj<3o@#nq##L z!x4ff$1C=psz{UzDJ@vHvN$FW5rAgp3XoGWaszD0|Kq!p=@Z zv;+Boe^DU*%*qXoP5LsrUnBMP(fHeD9bO*uB=ZVH^Op^S4;_$?=cn{H{PHC|JI`&Z$mfzWt&wN^XQHXVdgVmRio8P8#-L>`+G5 z*HM zKW`rjA_&vHw<@DG+Lv1xf7+b*vjud%puEh{KytLG=CeyfI7}y7m{_sVCdGEhYsNn3 zdhOyVepbpGx-r+vmQnT|Um`GkVJ)*dy<3okJTw@_u!&2Wse^+DA8c%#Tv@)K=w4s9 zv`kHfQK}?J%sL6CTpecc)|F8Y1iGjUNOP-dTJ!b|hOlo$6OiPlPm_1I!4Q9TO#+3_-l*V|rG!yi$HOEq8o)HiGu?~^6)f{ZtuX3@NvwFWO z(l4 zk%AEfw%A25f`SrFCjakfPurW!tktw2BK6;cWpnZq)bCPv4oDsd|Kw|VAaxGhLGrvD z5r)0`kW&gZR$}h0$7qe`v5PosAF=++KK1vdk5Yb%-U-KIEa|R=6x1(z?T(+r+I#`pv`TJ8pQhaN z6RP(#*(aG!Mu3Sodu3tx&(Bk6kNcrH-UhK7Y98-kvtD0@!&xS*rMP_--``0qAyxZV z;u9(fiKV2(6MPVeXy~V$9`%c&446zL>0m8eH1_Earl7lsT+7?lL0aA6+hTZ?(%?bq zS?A>s?M-iYWmm7)QagJR)FQ@7<5EjUR}!x#}2X>izGw<^L{vm@mk*>>p|uf6PR`_25d#9)ku*{qcQ3wY(aY>0OR)tSmG@>31X_|||M3&K zT9KJGo@dd1oOOxp1LfZ?@BjUll}gBpm}_^*anBnyQ1h|v-gEL;zC#Z4On`oEiL(*9 zJ^H_Ff&aYlZ*r#YGZKGe>{Ob`Oh;gLSCHlOLQ+5nQs(Hua{J z%xpg>yZ`mP{MY+c((nNuRb)f=W`k^zqy77~r}A+6-n=o7h0aF=YT$$(qQMZJ76c96 zOk~9)cjbNLEmPt+N+pSanhnC_oFcZR*oj#Cjd%_fKD26%RQ`uWch27y-GlhBot6~m z!>O7DXE9(}Y3&RBSy!J;#6v-^&ti35Kjd^DuTn=Ueqn42Fai$w1dDh6bo;)pCF_}d z+l@azwlww`R~{2{)Z55j-d8l2nzG+BQ$L-FyyarpY6syBUIM<`Dhzh8V$I?)irIO) z`Uvcsk^3J`&D*a}>s}yt-+-D$Nf>CfJPMk%5sbO>Qoe!BGA&i{9`!0)N7zRa`f;cYon>`#~mx3 z(buh;ZhgzWCXk*p%d+T^0M+vyK(6#z@06ciMg|1L>XaV1={T#iXvwBDaz#)^fDUV>&slY zGp&d45Z=q@McuN^}@!g4&P$aJ*&K~T%pEfeyfxLcvTlXaB=%E?y zi$H1b*8)-RpUadV>A`|@o{aDBPI}|zeP7mZzT1@9CX(_Yk!O(sQ>$f$vU{>@v@Zjd zTwgoHWIQEbzy%AkdY*!;edQwl#MGCiuRQXe;gK~q?E6~fU<%Uc`=+bB!@Eey3pTfQ zrHL<=`_5AR>TE5GeHTHo*J@ePdWMI%Jg#6{u`uaV@cwdkFZ*2BxUxRahk+tNYp%JN zG-EKNL_Hg`~2^<-OFbXZY0-M={>YV&pdx7 zpKdEDzUZx{Wj@Jiy>n^TCS_Q$&|#Am4uYYiOzW)?Q|9nXCa%w1Jsdw1pB_CvveL;> zPmo7&eGbiQGvob0e5TT1jYTq^ZIM(YVU2V&dBrz=Oc*7~NB5Os-)>T~Gi_~QW=ne6 z=3DQ}TW1wG^Yyabz0BzS_(&PiyP=*Sn-=!!Q&yXQyTR9nlKC=sNby-Qxh8S4%8K6j zm4a#P!J6uM&rW`zzOQxV00S23`~CF3ymMxOGw@Pb%+!au7xFK5kZw69ziaYi~wEE4p6OISZSOwQnq=$-XwclV&cdFZ{AoWX*$?dB^Bg()SpOg z1HKPbsF$ty7LPP-|Xu1*%N zk9rC3){!q>-C`45C*6JO??iA|oQpbtmS~fI-Zu@TQ}0KjQXjwqflqkb2^TZ`p#{ zm8C%arFWDb=e)_$k<4Y!sMZ*$@$?0ciyDwMC`#*!!BA*6V-vb><&2c?U=K)Vw(00IlZ9qZD?g3IkNZTh?CW6HlRq>V(2f}c$542gJQ&^Dj~ za>GI~U$w4ybjuDFUjDbSuKx|`8XrUdCDJ9hDgEUC4!QZ))t52l;UOu5hp#_xYUsJT z6t^>eT@HF>A1R^2m@Q|dW#98j@4+0Uu{hQBn(&E^@CWRVLBK-(7|<^JBt5&|jSmM+ zTx3H(#!H7TQzDtJ3Gf9y5oi!N?&gq!HTZk}O9>s`1CXgO0GXQjugFvp^{3_kVX*w) zPH9-n4(@iGN2zL9Y5!Z+f&a33Q!4|!JUwu7@l0GUbae)Z&{;1y;of4V`2`a3eQ?4I z#O-vOv~!8Lyf?P`a$tNf_w6Fb{^3>JlC=HOm|m=xeJt~b6U8H`)pmROMb5nP@hYVR zRj;pELFQ!BRbm~Z09Zt>f)Y)^EY$iWbDHgKLdr7_;MBa8M~2wg@u^pFDv;&@?}J;B=H*jHwRxgvzEF)Qzh*4DFl|?-ie!5P)0|bIGM` zC-qY$M~qLMTrLe;a(!v1(h*j_$zZ(JeGzt&v(t|mFiV;#jAcsTA?Rw?faw`eXiC*5*fWJd ztFhA3Q&j;TpK@qcAgMn!K%(&k2B%P2duxM0`3Sgy!_shdU7yy}n0F2`qcFl?x|iiW zQ4AA9x72A?bW@75WDI72EvdsrdRns9rZhS@=F@_k@Z;-f+-#g7pP=%TV8u?C8aCrv ziSAWA_wtyCa41P!2#5yFL>d?;RG}wf;lv#hsZk^c4@fB;k!aCYJS0LvAJd0m8a9~Z zyXQ>t0dRVb=U(5nrdc)$jB;4BW+ETjy%nXObi24vVdUK0jd2+ulT>#@q2kJeT9?xW zDe2=uQ}%F{#Mo=T<_xj)zUEYPo}E-}tX0EkEp6q=@UI|Ji`Qx@A3F9dAd(;IizQ|B zIoAdBn8_N;#8kIop4%i5Q+(zA`Ark$j6e` zt`zbC*Zfh3+&U&^NzX$_hC!ZY@Y1J+Iy)d{1R=1Msia^#MuXx)S5!@hX%M})4Q%9X z*I{C>T*GFyq`a$6+(a$a=dz_3V{VC(E<7-*dw9M|{;7Uwg# z`g?usg{o0kQ0p)1#}8Hb#`?DWu4oN4kt^%Z;VhZP+jscT!vbxF=k`Grx~2!C-H zsdv&>80UvZ`)nFR^P_JbsOm0F`4w9TOGt$OixCifEIdq%nd=QKVpqNq!@e9E8|3-3 zbVtx&h4zxLqj@?46h|N403)=YU!k`0p+%+Q*a=nL=K3urs4!f!Mg9HH$M@xs-B&^y zA!bRPc0%-(llgwD$5RZ0r8bCnAu>0w5c5lanLE^?4^)kTD?8wey4Oo@7$y0lkaT5_ zCWmkGu#w>;5#$bwYs#>tqV9!?oiPhIdSI$M1@WyknCb^DIlvm#4BMgYe{x1O8eoru zaZhxSs5V{eDRg;*rD1v+Err?2*Z>$J;r#Sdb+}y$GUZu|#ONZ?Z5sM6R}wXc8RTF& z`6rRd@^jW&rT4PU zGC7pwBT)<-=Vu11Xyb6=4t+jI(6=IN8bZ?wa!m(|#OPiMgCGn}NG7|TbG}IG%zvZ` z?qHXmr_06}uCQhXC=+EsA2S-bZAg(u&OawmseP%Ov`G@!Yf^{58}g|d2ESnDdp!lR z6AC46aHouza~Zf!5H%9mYF2miLw+lN*1F8*{JwGVt*F7MIKW&65^s`P#s;ndZ=kp7 zn*`pF?KBAi*ryLc9QK?*%|DhDOn7wGxq4`cs%bWlr~hE%q|11g|FQ%GsA9$64=E)- zbhvf5=w6FiST(>GXyOlF=jI^{!XZr@Wc1&DG7bd0!d9Q>GyaobgPS|Xcas!e3BQZXw=G^&*f*Ypr|xkHwd;UYh{h7{sqq18k3kj8keNQ)X+=o-K;Ty7P= zB>y*nWjPi2hasx?cGv55ub5gwIjydF!BOJ&gCDnxI?|;-Tj~4Y_2(F+MH)Gt<6x8K z8{{0FS7bgMt!sT)nCqZjXDkT(cHPOiVNXmvpY|eypX3N8(M03M>tpxo7h`)0S?t;2 zxf?;WocAtndSb0!6W32!bY9){;NkN+SXrrGDsJc8d7TnpY#YNN-)NvdqRPpv-$&Wv zBiM%rk`cwc@Ho#!G{AqQwVrF?r?C5OlfJcQ;e2Zb!jE;5)smmt*|B=dr<(?IGR>@h z>~#_c=t)Z*Bcv7QfS26$Q!Vw=8Q*<=ATzyRL8|BqE9w_$O?E}_>)5#l{vV6X&2V5s zj_~|s3E?&29pRH+Qnfgy#$LSyX*irD|6jDdzux_;9N)jMq{CSv$j4i{Ci^c7>4wS8 z`lK|k&He|b+zgGMiwRS7Xegi@{0q0f-;8hVxDC~|iF<`s?*LF!`}v9KK2ax<^zD3k zAd_M2tFGc0w>i=1Hxv`D-E{MpmMz>BZjZ`()SBcRo+VF9{Q_k;c$<(+>^UTQY>WK@ z6{;L&9n~k}PkRQ$>T=P~t)b+oR2QQFyt)ykL;X;qcpSE7z;8zBT31_B@||HPwF5^; z;W{mletKXKdkXzK$^i+U=QHOb@W(fxIgako4ER*`xvNB@%-^03>aK13aZ@ zfnk|ex_nun7KMMN>QKBg9huvJz&=}w2j=K=uxzIKZW+_9Ke-N0*~`fptmaHlt05IU zMlE{B;OS2X%>BtO?niVrs@F}+m4y9nmY0*izTrHGq3wZ4GZAr`OKW7)=mhY&BO;yv zq|GUNTt9|QUgTdGBfHx`6(+av@8*(DTt#FE39t zQU8l)bW%9DpGn|$j~TM~^KuVw=^&izK~CPT29UBqG&P1gP^78#$(C72%X0U+e7l+G zooihGvTgqRjsKU3y6Id}^CuA4mIYbWz|ry0*LX&02#cVXjNhVRBMMa2+Lh_`ZjP zr-e3b)-7`CgNSf-wS%pe&(|^52+?lx6&1H&ryj>zCYRMDV}^Motv(LS%|JKbD7Qes zCWIhg>KSGKRn64@h}3xNPce9V5sABt{>*`xQI`c^?BPvk#~F0>em%*qP;x(J7hMj( zyNz8X#O$tZ>)N@O`n3v+h>qXxRU|*Yzh)0)OC*+%ey^_s=XjF4jUaNPX}SxWuc}(X7QH;S@HT+l^jv)DncDeShfOO z8MZCvbY*`O5=eTx#T89^n)-*0Oz@8sdi_nz$Y6(tGA?AT@1S1d)Y!|H3(~xAn!N8T zvVc2fjg_&lwLJsMqb2d#d^{I~e`ogYIg>ef!s87hq`qdEW5h8dB8BjblXW3;oja9ZskusV+?+U3Tv`L+O6i{3kI!nq`t zlv=%|y29(}mF4t*H^l$Kkb!Y8on2XqAI5_(59MGQwV~C<8b8;0i)2a05r9a(x+qW; z^$%7B&0LbdUCI}x*w#R?$+T!X8{SpB#NR3me{L;q(fe{dLpVlD*Kd2OrjfMUUw$<^ z`@XvFGaO0ntoT=?+hQFl+HI=>leozo`wMhy1MAQf;TH0?{?W-tfX8l+yJ%~^GI(Yv zF_vyej}&82K4GRiX1+9E>9l*S1k5d;n`S856^$HMH0W&!vRFRG{uJJQ*!zfDveuJ44zgmYsnLVQNeL8#m9UqDuuU0(fuksa>d4EdbPiV^EEgfMr%j3Qmke#vV zm6)hN%O893co;$4TLlTFzCJl<+{alZWRqVYuQ6z1-&ZEt<@`k8GE2N$5jmbUV3UP% z@!G5xcv#KzVbf2i_O*(Y`?m)pwIwH;>5<;V+>341D5-+yr3jm<#O741Y?C8fr-hub z{n&~yADoK|uDZtr9NUY@r}Y5>esUfd8vi)Q`u;CM-p)sa`Nh&MURW!a9?y^kkGYec z8xYvR;Z<@0HY8fW<6_9aHa*?ljQXoQvHu1v{@%OMKQ7Q){rhQBTADFd zXM6fC*xja@+c!T{<0#AKQceO~HF8F7e&C!>MZQoycZju0jZZH{~1 zd`z;j@0%m|$W#7>AO3UW@=#gE;PPqBL`m>K8zTdsUm{5|jEyV;jObcruD!N)Bn>+< zXp`Fas@JMhbN3e=loT8tjw}(Ze^GVKS zuzBshES}-2PuOpn@m!8$jLm)BeQ#G`lKCv5rPr1$V(~H&*x2M_DYu^R<@-YD(|&I+ zj^W=L%744IvMpaxSzFO;E}Tjjq_S3dZ?F%IyfRg+nP@K+-VVMXFfJ(Iw-`mYZLrkA z*RzsYlIO=!6od$pWqKOhzGY~_+5=5=^bBMH(9>>-N6ZI5T$pzh&&1?v&);Ynh%uky z_CI-*YoL@mC4;+OskOEBcCq?UJ+{@~^XqQ~qjb50oiBC3Wlv)I#_$seUyBOGqY8I9 z&=Iv7p9(s$+f$(JeGh$z;#E&XPQkDvo|1mdE4#d0ZBRXFZFG#!Gl|=1H+KM2%z}Bf&w$cpO16b75Rvr_}7+;&UNb2E^-uJd~ z_|kT-(Cpj4Q{SK47heySsEuMm{@5#6zNQ4l3g}X5snh%q8u3Kj^Nj*}l z@d9$PZ8;@N4m!_}eV_WcIx9?U7Wb3fyv!!K&O~-MP z=X$r*BvK-a>6IrrgOZF{t`BPu-`co|LbHWsqXfs4HNGHridSgzfS&pNcYC*7Pr!9W zF=a1Gc(UuIb;SW4A?Cr5+ddoCfsy%-deVPA<^l1zXQ+IW^LSkUXaD%qfB*H%*_o&` zl((w(rrdRi`<-IznW3V7Mo0HA&_QR~jv>VLeh*#+6VFR(^5tGxxpxA=6^SV=+r9L5iRLDD&f|MNr)26eK8D&K{^&Q2hO&k|BeaW`x81 z-Wiz zby5t?W}x+8d-t(Qa6W&=#m+qyR%ULvBO}4hiMaN@vFyc)LvI_WGNrRzMtZ$KQqj*z zGf|U6tJW2txW;aKn@Jk)D_0TnCh4Z7+_qPBUrmfB)XNQh|E`9Y4;Q>ZoVb|C{9ye` zpIs@zMeP`Vg~p_^ZtBDWF6A)uA<4+rb>T8AYf#W%m~H?q_~(Bk1d+D3nh3>Tx%oW= z=MDs|Y=`;lE;Cl*jbt6XtF|o$qePz1L*hT>vB87uKW-r|^CIx9U%_15hud1<(-d-Y zJm*(5w|R<;wWV*V+>a^t64~K#k(=8;E&~vRT*7L-@x9*ULE->Jf|In1Vic_Uxk%}T3v>A~CdR zku2Y?C#d(i`QVR4sizDwZI5OwV;2Q!2<1nI-v(jWf*uA_M*NEK+Ro!;qY(GFS&&!&K zc}vfs*UZk65A9S%A5XkQmQNT2YiWV0z*c0SWMvbRNWL0^i7sXXjiRN#6!88W8~A&< z!p{}-%VL#zuA%`j$J<3FJlFtns8bV$L6QEh-Qnt0l{K%z09Po(I$Y%MjrjjAWl1Q@ z7=0Cr*ZAyi6_(!FB^S`tqC^xPv~ldS#_f;~(lE7_Fsc>WNIn@?nQ_g{>5RIq1ERV6 z@i^ASt74lB8%!DDMzS98VD3}lQ+n1Ae=-RDTT&PisgCy@#>Tk8(!nsD$D4s*;WukC zFgKQ=3GTkKHG$Gos}&u}tV{(F4u8KZP>EigbRI{syMLg?MS8Q}jU!3Jo2cJTV9okc zn7;Y)@nSWDqETqOAGR;LVl>*n-CF&0QJbFqQlufiiq{~0#YW`NMu(@#nB=(~6Sk>S z<4Ko&ah_2spQD0-U8dJ_hvgj3cq96W(OEFRz>gPg=GkV!KEg=NBx47lB?G5+B2)W8QiVgs2L z4)07E4GEW3!R2@~Wh^D|Rk$kAFqPuSCH=UmwXCFx#IWHj)@DJOj0X(?9L3F$0ANC` z_-qEwDs6IYY)f>Ko|or^-0cu2iucb)W(69qzd?N>4T3V^R`+3MZGK2`YtC$|&PW$k z$XKj}7-;~E!lRaPmpZlH?5Q>0h^_AvX8P^B2h;nsw6uiT;sHH;{;V9xKTI1u_#5r| ztM%<-gQffKUW3B@V%z+m(oW{=94(|Y%Sw=m13d%I6y5>DI2t*&ensWO=)=im4==_nE?t%3_SA?CR=Y~RpmZ_#@W#_BzG!;2?6jZ^X_2(2Y?iQ|_r&N!D784< z7yU(#7q(K&gVUi0%d+C?an#t6nLdTm>lUNaVdqC=Ol6E1`$MhCXeI2GAU&FgZQFOZ zR`RB}9>tTBC-l>95BfNIwbt_$u01VZd*d?rGU=&9zl7>;8H!SEuj=as^_#UAhbbwr zLyyNAdbtRF{X4qZv1j0UQJjf@hrJ4Kh8VTyo&F!GaraWUM`S8y6kMD8i>)HQOUGL% zQz2P?f!_Og#EMhBfnttc+KNe}NzpT4$Sw_#yIG^iJitkfK^#fAW54k6Na4MZa_PxU@DQ zfRQ)7&0c8Ni=zJJ6kCE}y#o2*zGy&fKe#PE_)H>6(*v4U%jKGACQ$txe_zaV{W9&g zTiXbEtQ%go^p>nvyd)u8R$Q&ZS;HAQ9y|KG10?2mbesD9tyz)r{meiEIXVM7P)lFO z5kjl>V9XkD!}(`=+bf@DR@@Sv4xKyB4(TGnwty|%xve`ILryULyW``S}2cGvB1xeHTb+mCB>ef)iskLq;U zMsh~Z4xT}Wql>3qc=L~)(*la1hQNePhE0)GNQMBl5)moI1(seg3yyqfGg&#WOfmy+ z={ivYB_yT?`Kvy+vV5<-`EeFmb{|>0YB@K5>y;9NvB~&VGW&k272Q83Ok;DrG*omS zw_AUqmGLN-4k5R66~nM1s3!p6ZK3ES2fOVXpWJ4BO6jR}Oy4)-qIK9Y=K>zaqn6^w zQKQp{MpPCBju2pLwzq_cQ~56Aag=ioh*hB57l+Y#0Q}?SuA{WmDYaJxGzwUe=*XTLX>$hNRN!=b=`P^ry zt|FaIPWs$R{TPiyX{*HpH18U|_b(DJNKMb^S3m2-|2{7P#pBIN!UUbWBY%Nvd^}v9 zW>n4e&sbf@We69f7M$$5Ch@hC$9O8`hW9mR?1VWvgkdxUDeS9XVDAcym+X8U|46$h zntCP?+O4&ySjCM4K0n}`UQdU>IL>o%@%iY5t@PK(jFLbK-rqExC0oR+Y>@lN>h%yc z4d-ljrDj>mtJ$8H{Z0+0k(<$d0ov!f@T;{6t2_G7Vm?2|Khty`5uJZiqESwo(?hIz z-;G4{6Q*HykMzc!35v12``ylig;U;0}-^6 zK!}f2iNhH+ONFzo>}JfO>=I;i{I^LvbjneZWSlvsV7lkGXTtNMXdCJ&Jz(L_*Ral> zFiXBQNNe2TV#ZfFwic<=Pf{97_p)`5T(ezDkM<-sP_);dUG9TzkM774Z`6#4ZBcxD zM*a+g9fIpEhQ2%;i>H8wM zCX$A3mz6e7O&|6!vAqGpWH{&J#d?M|50+EvV$)>?xmYReV)|`*AYF>SjOI8hh|w=l zim$c!kAZkG=CaHaEFkMNc9O?q{uFKXBIkU;c&B;lL0JlkcZe17B5(xN8K^+t|Jj=F zVu(nZnERicLLP+A#A}r-(bk;`qb<5}Me||S%unv7LPJp|cQqE7;wfxDTfMgF^_I;*`5GzHDFA(ky#2M`=`X4Y^N{3J4|}jxZD>-elHv z=#4&#sq5h!iiuZo=|*NKF>tbbg{ci=TwhX`h>46XICaEd_O=@tIZayj48f@NPC&V` znc0QLjOr_BOlp)SS#Uf|!3Cw8Ql&paac4boOXi1w_iM&weMfx_{0|o9|1iRAkOJi1 z(p`Im5MqnheO8%@#Jy*5_Z~0i)TwI!&LwnNbqX^z?irr%tI;>2I(t zhjyRK=%@XG)+`v{z;8W>BG!<(Kf!ACVzsIj1GzZBZrnmq6|Yu9)5!S(aWL?#Yw4WCupV;*Cg)UA0f_r9=B5s+fgB!sdI z??(V3SPz8N0#j;jdo;AI$#i*kj?@Bd$5m|9c@Y-dQ*55O*X<>dY9wN_Y?m^|>`M9s zgGQdJDm?FTx_y&G*yF<0IGQ$^MWvQn1PuUL-zE80za%L_GF{>_-v>p6M-~-X_gxc( z@FN5&R>{fO>IdG_zx!@YA+I@5v%W6-=BCKZ zvnv<u#9RA^OnfVt5@%%P6!cd^KBFL#ze-BbSTounTdlX=mDg5NQ@ zP&NFv80@Zvlt4F>vkXWP9s%X7_`18iCFU`wvu_4F_Yr^-c6~FBBafJBjeTxp9Tz2k z^YE>t7&?n3s4sc!x*t425!!t|;LrZF_zs;Fxr|uy#|4JDsv=%aWekI79aXjtkXPARhk0zpadEH?Yo9U zK!kMvmRRjiY`4q{Wv=YK-@WEP2MWG%S?*^ut$Wya`xwGH1R)tcH5{qgKdv;&Vq+H` z94MJbKI=3yUFuZsxvv%{fYIuS19LQ>y_{e5{%npe+s!rV7XK(2q zGK(HB`u{`p*CCcw_t5z^FAVs0)>ep>GqRyRS-=EXuYsu!)^It}-HfFC{&-~74+kC> z1-69rPI2fDP-#=E+@(uNfCu8Sl|fALkZ=q=#3xIjvnV{KiDq9N9_EE3F1?8Fr}LOd zFIi&@8lcuydDhjdUgcR?Ns!LxU^|C4TS_lw{>14FlnX@0mU!F8cGijJ?Znc%Kinjo z`u?cn7H6Bq)}9uOY@GZ84cV3Jb}8HynCpaBK`QTHcg|2U*J`|EVt>leHm!Ug_Rih( zo(KE_b_w|fD8Y#(`n%E9T`?r^{qSb*Gv<$TZ6ZV2C*Yg|*}R>yy-LV#^4``|*8rW~ z+O!?ASPUK{7P?^E){%6^PdF6iQ+BbnLWCLceb*kS0!k3fm-kP;lF3t`*YA@AL-obQ zyjJR|e{RgKb;Mc>9r#jb<7#OzHUPwi&D^=4U5&rOfl5OvY7QQhYB#-wZNZs;f!Mds z*f%NqQR)nXN5}QhrTV55FIUHHc)Qz?`f<5yz&DA?&ARaoE5!BUn~egKUUdo^72c1$ zDtD?+o(|6~eP8bBDLE=5>0h#1s}@2AMOPQfLx`n%5Q6Ga1p`M+;^;&)^>%?tPqK7J zq^wAS(4=T*B}L|+FvQ>W5CcA9SgV+r*sNz%u?-f1v*!<%f|Dx~$1(Jqn8P~i)%&`1 z<$kmG-(Fu-#xol5rBCENO7xuO#2cwTX&9K`TS=V59(`qQyUZTKb5l!8L6w;J-luoL zmJ7r0-pa5s0?iia`nJL?6F5+0Y=275J2~ z&+tMtJOIqv@SfhM%Q2-!Kg%u#KOxPotr|m1-`2$n3=M50wBAEUewa+Vc!Q_u$*hS9v&{MQ3s!iEfPM zBafBq3&Kg7&L@CF$Mu0~soNJ#Z{N-sv*oxyqolshdvrrfXFTtIN`gm+Iw!^KV&kMx zpdf;w$OTgapE=_4hL(9Tf=`-!-ovH;wRz`Z^KG8VfcuKmizOic_<#E5{`@7657M{( zm>y)w>d8(Mo?f@oo!j2MX;xh0a&Y}Zu6D6^#AT0|IkdB=IJQGdJZH!yeYpzoM(dCM zksc(muf*zO?wm*NoQG+W4w_7#>L(cOxxN@|Rf*GMaPD!=x8YqO5)^inCA`4wsK^AB z#>oE_$aH>;b}H0BLqng_av?3tb1oPtmOOj1B-A>|Om8ek3es?%w9MiY7Shz!LTjoD zsj!7$?l$Bgbm=P|P9?kPL~2d#K$d58o+@0|5hjlf4h~uHrL;8HPNp46v(J1XYZpSYD0yzX?sj*%7KM|t8 zof-Nc|0x9mRN~*7p70!{J>+0DxvA6yqG8(x&?HZBjEAHNyKDjL6yU985;IozZ~68n9IhQ1sYHoY|~X7NeG`5EX^Hz3&} z)IbVa*OlgJ`iGBK&5WS!_CCz?V0yJ}dL+vv%ciXiv9rATAaSE!wap_ zZ#6Nz6ECbBu8Yq#JQ%=WD6DLPFV&geMqc5e;6p`s+cRfLEqG8^%&K$F?TMEoA)eRO zyB`u}L_NB!t+Z(v`ogZP>pYr0Ku~;MI!~_orZeF!+adT8-PQsA8vBpn3tEuK$-Njt zNi}O>W=K-svCQZZ)HC_R8JNF!!*>%1F*`M(PdLE=NQZpbL`KFCRnS#Q#V`Hih~*Xk zk9oNz^4FunD4c2LAK$8;EI9?jIKzkz)>96Pyp0TuG}SX`i}Ju}yirl8%=n`Fk4OS$ zNyz%uHrr$jZ_|O(FLw{xiJj(9?7s2Nr`Xc-(b*RF?NVPD2(e=5-cRx(9rd2VMKLhe z%si0W2W`tr0C zi^SYv@c}D!&kj=ODp?bforkmfZMP(j4DIb}E2KWE(z^z=8g9nXqeE|HWD~^H9U$sD zl#Q0sHsMTXK5wvwa zQeNM__h4C$z8e#cW<0q%EfSwzI&>A9NO9?FE1WrU)OY$$yPXhUj`YVXENyFsjH!Xz zAOe$)aJ5SnhnQ^3T$P&{6-r$(d6-fG2v(M_xN(Wm(ZqFv&a5KTT9abVt|JcVf3N1Y2JI_@_no5awg0aGXP{28Is zF#INhiGp(~=AjcXhw1BeZ)iK&vcJ|2fGvwM8Xb3@7sUGDFc8se^j0!9ZfW9!8IMro zAJK391g3MVR34QCsM_BXr?bdl5Up4jt?s6(Hci4LuEBf<$NSMYBf}J>K4IE$O|#B+ zQ6w!}ijI?xJ304k+s!*iH}oI6Es%3@MFE+2F-@Tt2aQGyiYNq~eqM6!@^W%>!eHg> z^4;H6V}C}5cOuq9?5PBGtb#~iQfW)qYe5i8XrXB>o>F0msNTod2^A?c$MMJX+GMYQJTR-y$w)cSL}R6f7m%BWPD>D@VXb)G1};D=Rl=#LC4 z6mDDYRGZaX-C9QTTQjt&7a^@Vl8$5;|Ir{=&#eS7H8WSxYu}{@D4BH$8(55D>HBTs zN~_xfB112(uvr{*B;Ia zMBR25F0g_se@v#K$lJ=fnupL(!?R*^tx%R1x0phg`};z{MY*>9|J4wu`)WrIWHsy8%~E8WN8A(1ItL3ovJU{N-G_awf>Ass8^DOJTdkkne zR1|?(y8H;y#2cnxrh;O5mylw8U%S4hN^_WUe}?LYIiS})SQq7@m(I?>J7$`RFbbP1 zo4L;phn_mF$rU(fWDR>hK^WvG+SaS%`&d&mvU5=)A|eK;OI@!$^?!tc88+qYMq+ET zZ1z5ynCFx(SM#VdQAu4N(3Wq6Q3TBk{3Kgta1C~lOIlsm(--MZMC@8RHHij0J-shF z7v=;l#9d_SeR9a#_PQz~)qXF* zYvkiX|4{hjCblST0j2#}2QdmzHE{*5Rl~%Uy7cniC)=!`?C>bKHOqjMLj=UrC{em{ zUd-<@8zzwHfsn1fXi44_sx08mS@75X+G~JkOv3-b)c2!?{lZ0t`$3#>mBP=%Yr8G) zUJ}i7?eWk21^Qy&>-S|mPo~m;MMNB~a|C}e)hk5sTADLGoWQRa$jn5bhN~@p4ElD8 zE`eeCYhM=(vWQNx^-r#52;^Eq>FD}eiQe9D{AW&(-?<}(*rjff1paKK+1LwqgnJZo z-)b|mPqVT)H7xphSXrAtPZ22U> zZ1bbA+n{EtspyHB2&S=P7tWLU+qV73+HWMw1^gpB@(;MIxI$< zK6k2b9_xDf^S|8jzwF*vPa`&YjlU!^v<81^o|Yd<{D}-ogx>nHaO*6>%{uFkY?NCB z?UylDw}r*!Di^%OSTep_ z_6^ZxIuMJh2{}v;lcyyXB=SW30`alN-tyPq2`KO$vG*|l@nW@iKv}7Yc7C$s0Y96& zL6!7nws|t&ex?Dk2~*LQXC$XQPx3h+?D@fgu!nnMh9VHGH(DO94W z>RY#p(?F|#wJRy%FH^&F@wwd8ig~E03=5`~3L}9l(Y6TQ(DR_9_5@XzB;PhtChiyl zC%5|F#j755P68!QQD>#+*5X-F6@2afS)DvR8DNiJVt2yWsy^`6n&S%#_)dO{!STWN zwpnn`6~_@@W*vR$|1kP~?~upg=c7Br`xJp{kDt2jfY_+kmj+Y@w|7MNpz~jI<05oF zdbEksJXPuzq$)xmpaP1J+l`fP-u*Y$Kgo~pmJ_Nj@e%nJLs!^?#U~0t7V~lmExj!w z{*j6oC^8>@QukY{B5xTUMM@D&^JM+Ghj0UDx~H*Y(I!B43|)%ZejiR_FP}k2?CG>g z#8h$5AaCTsZId9X%6fOhT4ut-la!On+I#1%zihD_?@It8t}A^HwC{M+*6T6K{sI9L z^Yx-hTK_`={$odOvx}Stb`gGuC$>WzA{bxT`a?OJKPmXP1SS7 zfh-zXrCW`KP(Q0S-jrfk22|+r+Xsat~JTcX##kf^!M-aB|Ps8#W1Q*3K~^7S3FJyr21OUQ=DY{Y(7 z7X0%qN*tidgtqQGw^`kAzBC-QFTtYkh-suh6{}SStPoejGRp?LSQBY)NUlqUfEXgm z8P?47?Rwkk-h{^)VZ@OA#n!F00dq=y)lDCDK+~+>In%vhmJHvuQ?r#k7UyQgYnlQD zuxj&uDP{Ct?~2t%N+1Y1CojxaPQR_r#Vu{oWmsDkK^zVbm)qRgC7(57fV9T&wBC-q zrT$)c-z*N@9sj8cH)}UFr^&MY#)#g=C_sggsn2;J!)L`yJhyG#ftOkQ+B!`2=o$y+ ztRTDts8!>8angi#=l#uVX*-+M*3>W1rBgamyl^IP4k@#k2{f?$Tl-A9SGU?(Hgtu~ zR9BHcwyE54H!k|WRUhdxsU(e1ZsjCPREF`~j>;@NXBq(NdE=)0qZM(psGo*OrlRyUax?u<*x zgVN8FiVbL8Sqx~VJ z^z=e<2q>BhEgvqO&kMtj2H`#7N}Em}G=HLb-j+RDuW)MUzFNpNp=q5Hy{MF$C^qZJ ztG_(JC}|ecws<>uh0~l5ePdcox;7^o5s}TFDT+)o8F=}I-XlLl zke-R@hMpO(uh95=e?8Y!`=vQ8mxT}eCrnD8;D)WPz1zbQRQt8J? zBQr&+6Y?D}iQ%F5Mzk$-taFNVl)35l0wZP(g%XK+u6ANXueMpz-eDKgzZbzGMnYgX z=}5A3)Bf~^&q=gp-=68NVq&Vf5&F_oJ8u<7mBO9-A$4{9)ND8z1ueT2Vj?t;L+e$p zxb<7od2b+}#AqjVO8;T=E}@c-%yP3%DsNe!YJofd{e>}Xo4EMvquaII5=kyPqOhi+p_*#OF7&MG zA3pt4a~|&{nQqNXb;*WHIEY4Il%1lIaHdK zUZK{kv^9L=73@HPg3&jKG~h6LP?stXL3PSU>85HPH-Eiy0N0WYWc;aIVNlIs!bpd0SnIq8UJSqoO=rqTRP>TYbCCMNS!6#~hj$1?Dy z>MgAArB8hU2Mvka4JOInNp+v*NQ3hzSlQoA>L}Di%?87SX5EA52QEiPtw>k2poQ3bcAL|a zW*>-!ORrwQw2JYRtdX})y^#{nmJ~IrqPW>qdlT(_JoW=^e$xbQXwvZdHW=O5Pww_c z%lc&%4VNC}0#Uxq-Dxxv)}^Fe%zHdNK`4C)IBCWSBLeh)xrzr!OS$tm7Epv zUZ#DqG2av4MTY5oaB>=*ao*e8e(+gU{*3mnKr5Lf1-Z;x)7GT~gBHoVP<;^e@kIw2 zotUItD8+rh)lIapg2-t?3|Frh`8Qms{e{xdsE($-B(kHRLSJevAW`hl)DO3Rj=pjV zKA_Q+9}8A#ColY!|76v3b_JG@B;h5qjSvw>8#@6ib>f*(#u)L`0gRUd$<(M$_qF^s z=Y?M7`oTWI=+iZ4)9mV&VcW^!MmzCB+1jQY-eWr$uO(@C^#@OB(5vBc+T(>VDfaO}H8mvE(Ca;a{|E0=Oz{y*y8Gpwn0-5Lc!K0PRHrAR{W9YPDe2c)XJUtU+)Ywx}G*=z6f z{Wxd-m~)aVxyYRJ$@ARzxW_#PLHu~4g8!svlCIt@E(QEgw%>;>S(+zy-J?&;hvh1{e|s|jc9hrBA&z;)0gOuKXst{b8o6EJe*T57Zpqg@)Mq0g zp4-e?X8%O}G z*bchJ51^k~$+x$h>M>JJ#kxwo3h)K%aa^oB`ER9IU2Q$i*1kb__(ckF?b)MYuF^+*brt3(Aqn;g|pH^Zis zrYQ!VuCF>B9xH}JXhHnk(CBAz8w1o)QGhTlmG`l}brH5e-BA+&gI6g1L$On^03A-Pdx zYUi(LB-U@JcYOA^NrBxdrULIR^xN9z*069~!y|TO*w@kBKvDU?#@?Au1L9X9?uJKI zmM3BH0lmVq2@)+PkNaF7`r_GC#dWOMIWFDclZ$%CrLp91?-lHR4;q|zT=5s6K9Q<5 z)M~Nd$BjKFz1oFz>d&8*5)s$wuGI zRGenR5ms}@E2ExhA93Yd6u$r=09 zczS?SSdh%pL}q%#Q+wcd+Vgvi|GOPgT|KJB*-C5g2P$!>lGpy=yQgb(Hh~f)WwkpV z9|vKcmzs69FbO9JQzVnEe!lGsL5<9tR*m3snwix7qjO;IG$|Js#v;R!- zvBCN+pHO#SiseKb= zV*sKU*aoMx14`K6**V~(1;TWPAB8VLir0kK=h8da5U*n}Z5>yt79ymI6tElC=X>vL z#?&Q&V`DX!d2UVKUstFn)PYG+ow<@9zH1N3&Z9M_zhX!wIfSvti8y3sktLtrdYzy4 zp|{B;3{#Zq!ldU|YuIZA&^Fh3fqJ1oHjQK}68EpfLs*%Np!@68ymnLGjCYvtHpel$ z&$!%>@ZNhy^P-`df6vr^V1)YR;8;YX^f>N$FE{Vb3hd!4jwe3*RN3Y>CCPdPd?%Al z`hDzgLbA(&>{mXe$yhTM;rk8zYkdpdd+HB7rk91yM?CLC-L7Y>A_~pO%&81KwQhPXMyi#Ugf zzrBa_vaIuo9kH?DxXB-r(^_05Gfj?rngSCtPuJUTVrGKken@H{a`n?yuR~!M@VXns1wv`A?)RL7c@7@ax*zDfG45@q?zm`U(ntOYK z1Dst+R}*~&ldc)Gr=@5^mc5u}=?)`Lc!>)il~nl%Hy}76q)U{ex`{PuHzpXaqLBXewX z`@7t@$YUeNhCouNs*|svHvug8`cA%|*`pE?H=is2<(|V4*91_}_k;TfR8XJQP7Q&@ z{75Q)wM__I#XAhy+U5(mZN|BaE$Ig}?y7j{#D=?FBJ<($3gR3(s+$c#$j2GZBKoU4cJ_%g}!{)S&sPN42{- zYcJ)vyJP>zuBxge8lI9Zp)NMwCZ14}F93~N!NHT1&lNl1*HUHjB&%qhXwML>o@|{q zzLWN(b+SI*fgQX>D~VeiF^xurQc+_Yt%G-Hg{!zhpRq;yiUdLd7}t%|bli<8*8GJ{ z{%ic71^XAf3>wte-LI^hm8QpLCe$>frDxAmay0Lfz8ursGt(-p`XTW})y!v1{IF4G zm{3H!DOINrSzV8n=9zA6zwN5NeCj^6+}3$hLq&w0cbD(W6*mlbtW5lY^D(Z_J?&r` z^{8hF%y1@KLPpDS1i98JRzBYoQG2oamHiXzy8^rpm}D;_x!9qkaDiolvUE*sX;BV~ ze~ANQ=Z(M?gcN|5`C>Jn;>=}(s+8UHkZeMdiwtOPihjd^$(pY}Teq?Vx@bx!`!g*o zvZi|rFa}s->$8buHSPXzpC1X?^5#jqx-As)_$1!c9vM1c!nwpd$AlUdPjG+ofW59b z1k|85302U>%r)qTosDf>6Rd{C%M_&8aa&I1Fr&|fZ_@OPpJ%6sja8ePWvrJglnWH` z+DPqn+jzs0Xs6c&3G+w!ml}3ur3{mkr!u*A{@&r#X~w4OdgI{emhePX`z1F2!G@D^ z8n`s7ATOcaG}$hJtlI}7t5^DMX!ENQ3BCT3fR1+igk()O!~Dt$ag+dIT`Eq)*u71? zt~ix>EB`EgE+0^1Ap(?1Wl7hTJd7@M%H!X4PzmLTrD9xzm`b$z*KHaU-2>&k%Hu2S z`8HYe_L$UX74uGtRgxz$U(tjSNwir)2qXh~uWLqr6-hA6oF(R7T)r2A4@D;1Vj4~v z3u+=xrL;w>Szr5s|`<22&44n>NcQ}%|^jDHVmU0*%9;zalC z2J&qTd?H2#yNsS$;P?wn^3z^EbsaVz3^d5^-?jRc?bI$;id_Ct%KJI0!~tATTrvp{ zt)j!VPH3q$sOdOn3Eih$y8laJ4DBs^bS1d`rI>pOE4o7M(WGY5vK_;Qw^)y1`zj}L z6;wC%N++{rGMiap{Mxq@*1j7FT2EK+>vTCk7a{+UcoL+gvbm<}h>M^nkHP-9mx{vp5$IsvI5RrbLcE4ZMBtwrJGi5}3qy+#hRv@U6oK2DH#ELBk^bzE#`#Ln={Fo8@8(<#BUsYZH>hO=Udr|o zB!45^-72)SB(p|-UDZxzll znJb5fvr0+krr{nPyC(C>iQ6XOZM&o|favYuNxhiM7HqMzYM8g{Z_(6U>7y&EuYX28 zFTm{oP`98>nXb2{KT^^&Tu-Q;wAN4)rlag%T*+a@ufMt@&wS2W#rxQ#v|P-kA=HoO zPT>;AzTC?A$?^$eg^)7)32c%oFR>`Q3N8gVLTBHhXY6BxKux7P8ArWxV_b!$i}ZsU zyE|@P6kWftYv=!t(nCL)Fe_OT`7-vxCXMVhO|0ZnD6Q59uA19h`I^N=lMF(+`BaVF z&iu!c=n;zPo0NU;2P<}M*wFUwg?mBWJkMdnNn|OQ)nmNvTs)s^JWSC;V}klqMeE*P ztU$~R={8vO>;QVP?w#RViF3smiuA4u-y1*AW>Vq}xC<*#&|th=v~=PagMom(3K7Yj z`0pnrT5UoXulKT4qlG&w@qAC3j!CRkXn>hGg!d^&^7Z7)7S7AdJg6q59E|%&L}Fz{ z9P*^An9vEQEb-S+r?#>Y-lFc8LBR{)t+bxooA=bdIEtU4YG zqtThdFu!Wg>43dzJe6tqw0WfR&qOc?^%ONzpLlxvVZ;?NFL1BNB z9$Yz8eu>JN?8hpVkpJ5FnZ2y=W8g~MtLy7aK&P7`A;~>EwO=%?m+Z+|k zQbhX}+>-yRO--qF3q88cSf2Jkrc|)jDj9_sVMg`+4~v4d`mJ+bvD5A?MMsV#l~A|U zq>OKVQn>sDL{skQRbONRjQ*5r-MYQX}SNKdj+ap(Tb z900C%Z{CMq<7o_$h%zyBVY|8d8?$IVji3y>hakAev@CaSBF;J@Zg7M*XF-`e%TlfxME8r zyb;G>x%;0U%Q;B8-y8|{xy)_tKIr>-SFnfJbh)j{Jnn)v=w*=UQo^70%m1Nh&+o5! ziSBTxS9tDPeED+{v{6^>x{?0bbEd*{DE_ewCr#E zi4@F@TE#D{ctP|F->()a)!+pWhzMI6!(rV(JG8O2AS=m}-eFbGU`8sK$RCEa6~XIU zzaw&v9kn0q&DCkAV;{s)C=+fN7;Lw~Y*{rJ-o8Wo_t1jZ+@+i1>rno@EOk?TEmjXX zf4O=r3+@y?N&W>Br$=?Bk+bZ*UTJIwSl=LN!06WbV%5$!{UaJ70Yhygk zn#TKkf( zUh}(UiL+piv}3wZQ5HY|86epsrEkNdcyy*e&RdzgR%Ajn42rQa;*|jD(lC*k@vfDz zq6`R|-w%`F;sf@n{d*JpH{`)*1(X`Ru_}8+!$-c%PlsAvGz82H%v#QM+rKEI2{*NM z6js^o0=JlucX{6{Dod#`f7uL|kaXL}Yd3nFvJ++O;4*GK#FtS26@+uJzuto8(tW)! zVW7t2upmJwh6ZdyHI06Fpug50c}x(+WN&9fk#)p5>iz*vdS?_i@wEaMG!{9Jn4iJT zTHdu3QJq|7Jwm8Qk}VDUH(gWAC+5m>9;(iWy~zYxMWmZKOB6D2!1LspWSDfy4*EPLrZvpl-Sz{2*QuqCm7l#E%jtP3P~{vRD(iUn8r8NJ^&OB?mdKQ2WanDTn<>CHLkD-~ehAqd zRiPo5V?nJfd-c;x+q7h(TnnR9U~tYJd`huD^Jm;jym%ZIteus7uAd6|<(^{j6;uwJ z6a!#(^lP66Ts~a)j;j78ilyfTSDv@+P!@VcF(`TkYK~aVG+L25Aqn6*NEFp5aU{^m zt{n?=Ze2C+9xYj5)rO<+l`3mq&U6^*XwKN=T0?+aL$B2t=DRsz(eH-g%Q}ZmkLk?T zKA>`*&TNjX?-VvJvI|5_QYm9tTz*74s-nNy!BhCk>mNUx?q~YSARWoRYNz46yhohL zG~GK+Ze?=mo<%Q(@_5h(-hIb6AqTnj+RepXI_l`o1ozbItv!1@+~KZvLX)&yw(uWK zzPCKMv{P1}uONCD;tX$sR8yrdW9ss$=ju9NV1_p27Egf>Mz_8C*>57Fk%l0 z;27DY?@m-%*Lxrx+t_SF61{Z!nkxprVycplZT&vg2TNCIRZm6 zY48{Tw86U1^?mjCRl2P^p&|BAH7}Fx{e2TObmQEXN=n(v!=*Zt;#DRV zc?jKOG)tM0yVuC&Il^KAVP;MybgF6Y$(D2huHzyvIOH8TD!)EQ#2@VXjF3yW2J(F9 z`gjzr|3HEa*ojOa)Kd?$S4H{9EFo~1mM}{%4M3EP{&RFI!VAku<4$nSGnPyoAj@ZM zpv{PtD%kDzFve}WE5@u@M3a`7j8H@v!y{=DtPb&&u7qpRga^(IQ$9G*(0Vp6X%oOl z4hEB-9Z1f-82)sA%8+Qbat6V+4)na?4@*Y8=zPa3`X zUy{=1jJz9+vJGL)0*Wz(q#RZsu{dPrL~-Yt@~iH{Z+be1$`IArN_TIbA=z7gmv)_S)^( z$Hx1R0}&)HPU8~EQZ7ogQIN=*NZedcxumRHV}n)h2lq!DpFm$i8#I;K(?quyl7Lh!lLLZdv%nUa9bOOpPh1%dQxL1AT_X$ z0nRPe<^~0j$=vn8QUI2?nI5mlPa#xS%pRDWQhidJY;FvCAytG1;*OKpjTR*qI|=?hK6`ZZb^X~NIDc}g$BS?KO3&Qd29D6paEXT zgcCit$DPxc%1Z}n%!+sW(pDqxg4v3DZ`7X=hr{NSBgdy|7VY_6N}6gGx@xNo)CDfS z(5;Z)`-T(tI0d*7g?WbPW0*JIY_bLdEMTKy`npc~*ml;wpfTg%fNnAQ}NohYSKX_0Lph(vP5}N4f0ea?xja$QaOiRI=7(i;gVvr0=qy6#i$;HmTuD3!x8hOiQNcuMoS%8(rW1 z9JxT*rQkW;xF>&&5C7dEEH95@>+{E0GWg>rl~fAgMI|izLkNwOB6FE`g85O-7)%?$*5m!NSMm^fnP4puMqn;MS4eALsr4{ z^K0g%SAFH5sjs7_U!BYCF}Am1buYTF>M+5mZyk0`uIT|134igV|JS_Q{s!le3ED&G z_9eCZj0W!Hq#~NO$WdVS6}vR;SLML10K54gl9f__|E>J5PPln9J9SiG4eJqg;un`j2@bI&_BM?89by;KcJ8Sum%u9T#1@FDa(yy`X^1EL$e`%Qn zhbmpZx$Q?H=b2gW|E}%i2Kin;1~7`nOOsNh4lg*@Qzt z3UxPK#b3JN$|CG?N=&$pAAP;g4-GnL_LEz*yi&S?`YHbTfGI|%#IRzG7k}Vjxy;8U zJlCQ@wNk-16E}4{r2mzSBDVSYlurF|iuy(eu%YvlqyQH!vGk0?mPixI=3j6?3S*yZ z+$|DZTE3)k#>(dY-tITXooLt{kz-jU!v{G=M|FnVn-3r8s3KB&H(?}5vL%r8y?i^< z_Yvyyx5e=;aG*b(cgRIV4Af$K`ZpX+5DIKyFk`rgWF^~yn8n$bN54ehAmcedw@$2E z^nfy|JS>3BG~qsc-+Ok;(i|Pq?-c|T4!T^Bki?S*NhdW0(x?A2JJv&jUJS4%*<>t| zk!b>b12&*-p3QwUv?bup_Y0L)0};)^B_ZD4!D?a%3{$%>4F>MMA?T$2SAss$8-b@W%%Q)Tb)#4C`N#V zhM`OrkWxz=Gv6)J1@C}$>C2bg=4 zf7Bo`FQ_)#O`9PkR2@Ucks^*wdUyr`C*sNlQ$oGvAK`}wI<}#D)RDYCCq^65^Zed^ zyaoGB9Zb(LSzB$ccuP3@hP5hc&gSV(A4z+yn$GW-eJ}cmQVS@|3w`U_`I492#}=)g zsR}}fqLOAt=d&MGetc7rpWNmyvh+%7`ks;EK=;0f?wO$f!$Jt;Vo`KsGqdiz6d7z| zpkWh=!z{X<)CjxN%hZhzr5H4BSnHX}m%X zSrjRXpD^tP$P7}df@i(-d~;Y*5cvFsuGHhU>XfHut=%BEOcH>NIv+=}n)D6>LoND? z3gc?wqBIo712&s(F158{^Dr}s?C9;4&CKblND!EsdN5mkwN@DZECRZO+q&d!k=(BA z)#kI$vXJD`PapO4#V-t=0l63xt1cyPa$sQxx3ntXb;RM zLIJj`LsbyPYLkbd!17GS?eehaA=N3Fj9#IG$EV3+tp-YVR*Z+ADjb_=fbr0+gN;t} ztSn=XX>HTeodI;CiuSQqbl($pyEkjnO{bb~_e^$}O$@Xm7EBc)D5qNKbPD}4!IjiQ zz5($Xye65U5?ajMn_1$1dDVv8WqD-w@i^$jnK$2{x6QFn05k6}!;r4OS*=bJ3)m4c zS;`WZN@dkjK4w}aWoqV-vYaxbxvPp&VGaFw2(jdMa;0-a3UH5max^M`on}xDrdBKy z)~ItB*!(obX5}wgu`8fQdE~&*jSF?wEzVFTx-Nf%5FzTN!#@&w40|)~Wky-B?J*RZ zQSvcA&a=5Q0Cv3tP!`z&u>UlqB@!&bE=^)ws#r9R@ew)JB*XPAPJV1`7Hu}N(b#v1 z$&FY2y>^`82lnV?>b1oeeb3okMo7+zB|^=&R{>K$}@v zAB`&aYF=~AB4dAA*=xs(2up85^o6}xJ(i>^^~lV0tGzpb2yQMskfDr&p06C^Noa^~ z$XWS(r3ob67rK`{Xor_>wBzWoML0P9Kn;%}Q>M0lYYYqiKq|tOy8`Gpdo#!40i(wO zS-W|YGp4&sEY8UC4|Sd&-z_=8crK(RwQO5y8w*OyvW6hgCs2jDC34);lJ?~9;}5!< z4K!Zfj|dBwmlI7iHe%wMzRcW8D;FYA^ME1ITps(|<;4{hBo&3x1&ZhIhmiGDG92m+ zaI9v$En;+jZXw|?e1~oG=bew8N#0GY=$Cw94a09~n49nNRx=bbXc^8jZe_05Maf!@ zB$lA5$Je$yA0yO}-#gY23G4XxFsr({^1A&IJ)~wFPXs$TD!^7|>*yRVfysSoC5|d! zVW#qB_Z^OL;h{C3V?iuSMjP90xJ#6w&do2~QO8g~ChJ+jnLd1AMuM^~4y;^4sE)|J zcOH7>L@u_e3}U)6RYk3f_}oh1X+E}al^JFy>(E+Jw1R5)F&%nGhi7fm`hCoV33Q?d zCeeHp>s4R3kd0nCX&ZSzN_15W0TiEq$QfsAxA&?b>Bb8Z92& zblfdYf&_M#_}=Sm((OKIcjgfT?dsgfA2_CzdGYNqD|yyR*JhS`a|@V{dgq35As?pD zL0~c=e{(Hr?Ushy5+)8}hhP`X`l4O7kBw{00G;rzGq;`XUaZJ7Gj!J5*xuAWQtr2JQP z{MS#&0BlPvUa>6upBa*l(_D0+O1;sMjmE+oU`b{wFU`GAp-4vd%W-sDY))LLgTU^x z;bqA@PXJko@Vank2-Tf+$X$l(FL#@=-ZZ~hW@SFo(eo;*EU8Qgr|0oqyzq)2#q-yq zA(QD_+`po}J(T2R{ZQ4%ogB_4GmXF9%1s6HjHI*N-afGVUBo~TLc(WI4_b7Qa_ zZ(1{uMb~d|jiyNBZH2r(cn#hfq#rZ*{J z=1HKy;#lYlW|Vi6)Oc!KT;ix0v_V_94c0oUrKe)k*`zSzo{t`7Uk~nT}sfyLXd$MVDJ>Z(r9u+m_>1sE(18AHC@FI!k zZz1ZR|L6ZBdC)ELw{~$PFqLL?x~8MAtuc(yCUh!pqFbk0U^%T#`B%_KKCj3r}Wt5KO{c?a4N6$N@LYyIIIdzy8qj6 zix6~o`Zxb^P6PBQ#a3N&+ZcI>*a8Bott9VQpYvt+zf1a00|xtoJbzA1V-_z||d&d#KXaI4X4H!#D@Z$sP=__virT zGJuk9RTT2_d51-aN^xlP2Fa5b8Zf(nm216oE%$lG%hyXT{^;th)OslEbm}ltc&~j zP_O?k+z7CJJlsLVek2W3$;HLw3H?ZVp%PpYU{T$ozvXj^F&1fvUcS32>etxA(g+P1 zaagpQb8azWa;tP!T^iAzK8zwdkVz+&baY006vDdZ!SMMOHL2o_n%<=+ag`T}IZFQBZDpPFF#KUzU~DWaO4mdrd<83xl8@C~wFGI9>tQgJS|w8Wi~-6mgbfDZJJkYw*z z)=v#lRD9MM;$0XTjs38koIDRR6TJ^@`;}hO0bRYfOOUPB@Nf=jVJDOn*mfi zT*(5j^c70MlPzA^M=s>yz>Vy*vxG+6MHM@{)w@`9HG1wze~Iz->-ba{-J8nGpDuSj z8YWxhU#C18pgkCL113R!Om0hMiIaaGy~RJ zFffjbNyL+Z?oSVu?_a>tVjd@xu)>~?N68_Fu`5aA2Z^E`@0@Chr$8Yq_4MHlZ8Zb8 z?TVc}C8x2n<&IVoz)VZYr6s($50U*IMbk~Y&J>fXGX`yqI27K!-ybAmb=uxdcascT zyW|Ma?Wqb_%FKd-tj8L}73aNdn|d#;pm2A;xSa2`*gWa#HXw>Z80%@8B!Re&Y07E7 z`(2?DGCuDzXK-5sLGSY#OVzq(@&Jv%Sy6QxkzE}!h1l^eJi`j8Bu7{*$c@oId_29^ z`l}3hfFX#$3Q1<|rsMXK+T+I__p*o5KV9El_(4C1`f4X-xUgD+b@Z%=pF~wb-BLb( zTr|D7hs62tCL1rRk3D{9^v}u3-X#(5MtmXe7k;qe`u#wFrucrgF`XP;BsjM4e%m+bi8VbUpq}oyd2wv3`(1Acy5oki__OgRX`*tMG#4LRM8+Fz0cB1{VOj?{-S%`J0~x-9v|P#JZD`>! z^CV~MH>KOphSTszFOil`}?sXKk(%;28B80ntlE>q`fYIrlU9-X}r^LM zlT!LB4By_{0tQ0|p%ARm+@4GsaR!t2rt2kE5iE2<0NcNZb41x$3^JELIp^$2t}3xw zzs0GFIx$7F_6`e4dh;RnT38O-HRIwopIe?B|Ezb(6e&lJ z+hNhzhfLFP^V<11K3P#7;EtrTbmOP24+ULuD7ftGKe*&!vkKpXn5y=Ih^}8Oe93q| z`h4cAUqK_#UgQe*#cnycMrT|^WxN?7LY&zrg2`N2xwme{Df6LxcQ1U=p)?EGnYkY; z1)|)b1^$UK{IYtV;3`%7u>;CTzOI?(X`rZIcMtC^S$uQ1q@!7!tl4Z9M_+#}(P}J> zuHqsDMbfQR>`^|US(u{!;q?cklS?eqqT-?Ch_Ah7Sf#;h8|uw6RUR;*_N@1X`N4kt z>h^&)x+Ke_ym@T0R(_T8nNe&AV+SF~&B(l%Tda;wRZ-{8Dj2D|GP*3^$tr!1Lq;>j zX>wCp0oNCXgQp&HU12BJe_P26 z2h2v++1pi7*G&R@_sL^azG>Wg&ls@ck0AO3M(8(41M_h`5!pIcDkR~y0`v!Kt2o0 z*e?;R8BB%&rd6&q+5d(a%L|nG5^<4w;&AXTD6b*)SKKvH&{gh8=*H>is|zGl_X>Iid?b!87&SBoAOBKJ@@A*>~kK znB&j>BX_65760?Mq)>NWu39R(5lSE|yM~_0IN#i%S;ME^=60osj#08EqoaCqp0EWr z?%Ly4X3OOib#h7d*}yCmL@jwm;9b(>PijDyhhVNXsT&5Be@{M|PJ>RGuK!<`Ua*?& zZ|ztvR~NCm7H&TmFAq148vi@r<$u~<<$@*G{iVMOpKtEcVs0pdJvc@b^K=iJcJNkh z8OT4v5E5oH0M zNhRy5YjXIqDDZeIJdUgw=!PHhc8&uQ{bimXW>Ha$xMCrU3(^4>Dv>(lL#(=15NM%wrY7q`ZZ=lqcVBMt+Fva2i`1i!jZ_WJCi`TH?RD)ElZq- zP!o)yTTbNRsFfq56+T{@yKtvQRq}TdNGd)lYRM{Mu#9JQ$s

)DbiYwYv)UptwiePzj~zV z=O{IXPoGd+Xr%4(q3Lb2ALD^_*n*dL8!#S-!j@seTscDA_qHYsK&!>&;s>i* z0BxoM7nI&1TO3bacU^#8tvCNBVQ6(vHZmCnpk9|9We-5+afXd0QOrW3+_;_D=^T7^ zQ%tutwS1Ck`t*7=)Jw;Q5e&<+BE0_d@eVB+%~EBk2xfN_nX^-3`Tn+ zLFX4-l*ggddG2*?Hz#Hm`aZ)a$FE>+OWx%H-mwB}U~UMM6ghjL`MWnk4ovR?@R+xt>1X2LfW z@+rchH+LZ=zb5Hy2-Ux#geO}^2~>9urZ0Y5x1W{EP>lJWCd{4|d81jjEvsmFH2DPT zp6T(NF9Ndg0L4#_ZSR1zswE@gar;y3g(J?3Yuj{A<_8NzLW{}8+V~LKuQWis9 zZ7;F(mKK_>e>G?K7toL1#;<=P{LQrI-sRc#P`CQrnm+FKDv6l0Wk>FpwctJ^C0$rN zIRmm$v-YX-&ekI{(8@?e<9;@A!u1&EBHk4AH7qrv;djQ}QH@t>P9>|X_I}p9do~m= z|Gnc=6LW+Xf22SUy_8k};ck9>Kcele4C{#>%=CrAaA-Yp;NHQ#zD;XML zv5iPnxHoym4s$uN6G3+r+N*#Rzx@%~m+SQO2CFXT@icSar73cPJ)5|at83i(`b}(M zB{98=i+Vk`n~lcCYtx2Lkd=*%mqNG>*uDj-aK4pIo0YtQxeW3*%G}1w*KENzkj?b! zM3z9DQ4=IVC!C}$Gkub$b1XzA4E-s55kURp5C)Lno z$n}K++9~3`A0y|mi1w+(MPie6)*WT>fQ7X$kbJ#`%OL-rzC)`B=I>Zz>TJEH^=kRo zSQd@v653KgkB&t@>g=J=e)wq8na64~sWcZHC&NTE}{ zApisl{{Utq=|)95Y!1?(;id2jM2OTg!v+M_Gj64m3l~4dNyi4?S0Whi5ih zcR_cw(O6J3{ULwc`x zF*kxl-74WJaOjI~Y5J_Rht+ZJUNS+g9kuxb*UnL!JBwTymfeMtlV201l**O9z47RY zmdgaA`D)7|g$CnTo3X6owR|3`hcIExOf1GXWG`E7dTOT6K`eTkTX(DIz2%Jip2wTM z<0c0lKW~UL5sG)}RPU07+@}6nZv{}vf39*9Zq~Kl5g=98L>3WFE2jU}L^Q*av&FdX zR?I?Ax#B{h<{+RMT-<9N8WCXTaVPt_lDZ*zUBjy&$NoW#xh22Ht}Jw=^YRtDzeJ_zjGJIf;B_UbQzuF!E7WVS2n*TV zgJiYaQye`MKx8|@^~k|2!Fb!kLbFUJFx4|kM}K85sPV=!9jpdiE|qJoRh=`bIvDM< z*U01ri>Y^st7#q9E>gZtb7gPoF`qZ_fa7_Y6u(k)v#q{yO_$uE6r%I}A$3iJO~LeK zMlo%_&r)IaUw~k6T8w!NygJsu>G~7tf(Zt5)n{=Uv&yj9{f$@ zd}s0h1`I}MI3v=sIclZ{w3zqmjvjg}1~#JQRRL?TCX1DICtk`s$Dij#k?4#e-|vQx zBT<&VDmG;;&zxdE^ezKl?$aj+yjBowA=BD=JieC<56G_$uOa3tD?gyqq^Ebr7P_6; zTio5+QS{x=%3Ue*ow+i)S8AUhMEJ#wxE>&OZ&*JHYQ<#)ZHb)40F7V2JLSBJtC5uS zPwZ=%`>P4WmYk5M7@5Cr!|#-cjQ&yzLd7@%FzOq!UVKO{Uh)xAiZTp~dR&U*=MRkw zc_nUkKe%qcSSa*W$qd1J2dlRBzogoO*rBn)(lQ}cG09rfZh0EI?CwU9(tvfC7W|hS zPoVzOxMCyp%OJg154I}bR2ElE>joP>{e7z5X9V?rDNC>B2-(&o#=kK$s_0RdmZ!@W z5|>J66iB-JLQulNP@!m!Op{i5y_ChQAT*nSH+Dt zKQfP|%a@alU;}J0R7-5KVA!}37BTbnx$*}r!pG!X*|svbRtD!u1W(y7Nn0CMSEJ;o zEAF;gA*62P-CLNmk4Equ_!Rx@qy3?mME-8tue<&_%h$lU75BO-EBn9z!cm$_7?o+V z+*4B$<>BP?f`s9h(icFjFU{4Ye(X5?^4qaT6k z8*72zs@s2D*-iRjD~I5u;zROGFK7@~s_o=H=@b6nQI(t2P4>kFA16Eb7FWS0`MiF? zpM)g2HQJM$cXCYnAJtn_ZpcPwsLMyTU19&E0~VPap~wnA0XcY-*-h{8g7z`_wju$Nu;%_ zMY6Px-vUCs@DX*G`>R}y&hr%|f?gGk8`6TL7@0MfPscp-3J(|VjQOQ=bESV*6S1{< z^rhS>vVit?pC|ONiO0WSY@FWQH@#{yNP76Hx4hi|<7nPpU7o_xx75(KxX%Ysdd6;# zL(keHheLD(vdtE&ci-W^l{S#-Z7wAdlvxL9Chc1N=1V8Gvmj;rKNPZ$T0N>`yA*2s zdMJC|6N>^u(r^DG%co`LUOf!?@`p<5dCls)E?v8a` zqw41hd~s2}2#)T0@Y9IIC^kjgw(qw7=+OQ(&eBx>xTC(!C)iZRR>`7hTzmeHnDv+p zK)bp4?uOEb=g&c8la#C!fA>)X0~do?c7mzfDI>NF=6KsO$BN+ar*e{^H%4D(UYlPu z+ibLOh~FV56y{SR2fimAyz%*g%ZMSae}C6cHT6J6 zT%rOjoyKiGtx3A)3j&UWDlulcQ<69NN!}lTjw_7k&NTp!wG!Xk`J)T2gjp?S`d6?S zT<_V1S0aJG$=sG4H#jZ~xbGJ!(RSYTgUTv2h2Mf}n%nl7-tkVR0=4MCE!`tJzgpAm zk)G4``I(gH$g>$!^6?xBBPZ9=#Bzt#mx2Q>813_)9UT0OJDd5DU zA)|^mus&vKrMglE-XTozs}nybQ&-8fH1cGl%rlDf&d~$PjM4gx09g|i!B_i?ie*tr zy2^FW#XV@nPY@tYa zv8HT#Du1NBH#v%nl;NwP_*$7A|2C$ond{4+gc)WTrHbi<>0^UwioZ#M%0bytCd#IL zliCxwpTrQ1AA!H?hE}Y!d*RY`s)yi%0Rs)Mk0UPr_K84TH%vL|!GnaaDXbD2Mc3kCpK%zS^K%96>kYQw24*9)m&S0 zsSxoR%NmeFYxEd@@r(8);kNm)BuL)Yx2fEwv&bT?AOC&vQeC4T+Ps_$bes5x#QZMp zXguX#xmmiuFaIIg;e&kF|1X)JnRKK?kvrh*;UB+(ZpcAlKj&3&kBQZ&Y`~t7kT75L zQS+Uqz(ox#?x1R>s5&-*qqdFf5FN1=MJp)P$}oQA{<>9INm?*D zFtk*XoCyNoE}-e4*@9^`FmZJHoYv*J0iBD%GTcn+$u={v?V*q7Hh-Br^G2H@mt76xa<% zR0Q~9?OKN^f$!+JS@D$HT;M&@r?T8}y8jjz^p(@VT3OW_9_}sIF1! zn(X0gAT81T)zKy=&*^MB(kn zKyx(TGbe@ge&2>4MLOocJmW{qO+n^`vBUS`Sros~^`4$u$gY#Ao+$GDT38(I!~1DQ zh5S(=21wsJfR-RJ!lDgmU!PQcr9%I!8S#=)WqKhn5tW8@bN_`hMK4Lg)+)Y~`ZQ4( zfcKx%h;#N(QHHu7*q?PA)c5pIetGixwHJh~T_1a2#d}`hUZq$VwBA%aE|vBkTl@|@ zID6rP|Le0_2SvWZdEPB#D?e4iVF&&1(>}0yXc1USXgeF+ z&>$IyNF0-=?qG9yk?Y8NYc_r`a5qsM91sp0f36gDX>#;!-;@Ak?saj8e~Y}8{by>E zQHw@2z)s<1ASFsWk27nFm*1~wg2SOHgik>F;}`aK*NhP2g0C*{O=?6>T@(wHPf0=* z(kCVs5#;ol%!EMhf<8IuGG-P*u-}}I+gfvZ%h3EfUWA9sCYet1#23-}275Qw^RZfE zmw!AWMKJbwp=+0ouoSzOFZz^DkKjAiq+lm97-=%1WlAj=u6hXL8sA9TB;)ykdg`LO z1x#=Tsm}wPaV25~fCU4=Xl~j?77uPdO`y}bwLSe70j~BH!F1l?EW0563hd}4k(sH` z6crCU94B_Kan;8sTvZciArh}H_)1U)Lt4VPGi^F2_uq%Ho8#e+Tx|+PCe__Ee^s1N zlsC;RR5RbLOn#ugB#@_?(`(%()=7Jlq*b;zV4bYxe>CGs#_&*);5}7C#Va7_qKYBm4<^XC3H;s%?5;> ztE6bbGKZ^tN?B|S#|6jo1ZxfF24k%7hAUGlR4H)X|DGzb_1ia0D#WLzBJ68YHzWVc zT_%%re&6_8QDeg&TqylZ$^eq*tjd36$Zm&`-C2-xC+;TfYnr3)i=-JD9oqih{^Idr z7#!-MPM2Ab=~MZehc;4e)vn;_<)qcurK?^5m|4um7dfVG8Wp$ua`q3bbbCI zX>bw|sJG%RIsTj9fWb=jYOMZt_N)CNTZo17)8u5CX%JD!0u*OkU&<6?ecqvsbnVxs zCEsyNtKG&g+OZu*67gFRcknGpOf_lUhNbItd})XEn(xEgs=FFAKsLB)UU&FR#IVPj zC)H!6=u27=@>&-uN#sb(j@PG`qL29ce3F414Zj?J%;1OP#x z39&9+MNM0})lIRC8B6b&Guh1n>41(0Fp@#4FXM)GM3JBj$k3|lVJ%ijh&P;-FKOT9 zSshEVDxQ)@f_o71_!L%Goxl6Hqq0>E-z;J*<@u>BDMj;e1CR(NVj}k-aAHX%h{GYF z(M{Rhp3Q`8SJY=$iyyp?sufZjgKTgrnw$Id zY3Ccm*$`jpaZe)~(oi5Ye!Xh$O0u=p4SJ%~9JWVj^Av`;O+qN!sTb ztp=Um2b6=eQ)+5PTR;^GZ^p$%+1}j)l2{y^%4+)qdhVgW8$&Vjx-xto2n0S?GtdCo zkk+-wdhqteie8Lsha}_o-@?QvEui&YS|N2*_MpQ^+L}wNwh$pPQ8;@R+@)xy;Kmz} z&eY=t5|73hcC$>u73o~d(BWzYVG3;T z8wGW*A`6sFii?{~W{^jhsUkl5+z@e|y#Bl2b#jZXN?I%$?-%onptdQW4qlk;(hpd- zaI$eWjj_Dj1bp&@-1YM>5kc`i!}v6mN;kr>+Wr0!D%#%wy-B}N-gUTjAt@F;5w#s| zwMz_zvY*SeE0ai{;`m;}-`Ho6D_dqo@?E7mAAjVOTy`?H(ph+ob^pD|B;HnADV2zH zrjSE|cvY&aYUkY>W`#t0{RT|QL6E3!KGM!EzNonAWC(9DBZ|T^mAudsaH!MF0iQ*0;utY%JI? zAgKy>eYHbxD=sVaMYB?yEF3F^%}1$@5VcHQ>X%tt+P6)OYjn&FCC6OI64I6=a@(%| z29QBXDHyk1&4S_tzDh~V_tv2v2ra7FK78Z{zJ{JBYQz;f!$FK+zOf_Ls4J>dzvT|o zb|rNNR8bOH6xCcW!X=Mo!wC&m@5@g|5Oh(~FElY63NIyqe4myAqRS%uEjCC3&-VoR z*C}T4uxb%@wKu5nTNi~=8I^KwNXegZ7uLf5oXZNCvn-7Bp>l~4H%^rOU_NNft({5_ zNkmDufd)fKq-x@U-krZY{otn0i)sNt#V-_6=p9E>f@Ookt1e`kZEB5)k>MnE`$lVKC|nU&i!V&s{J9ohs*ayCmO6;RkmOqRj4(z<^5cV zOj?@wwf-(egr|#I>Ia5}FLA(GNBLGGw;@yash1BnrLSz%hnzA=ynntvbR>@@^IZP3 zmK<)x6V4%;vA|b0^5f6DY7G@@;}^5u6b}N1>05COOpNWsvTWhP#;CNLdFhF0`_!eo zaN1zxG%=JauhJF3Dd<`4_--cv2_>;T*wCaJ8`raA*R$>-M#2vEG0!9?O&uS{Cha@A zU_0=1F>0I?!H)OtjhJ}GKW};3UJjCgwx~UMbkAzf9V5#a~f-*62SiN%)Sbt|H|y^75g`{k0@rXf-acBYW0UYtw523{O2$%MMYbOZJhpMEd2A1$2VcvRG~ z$m;`#|3kvz&f;7V?KA5A$6obizYmtAbOJGRbx{MVDvE$NjHy-(1e@lGXZG+R%{R)5mmgsp`=z>}O^7^3iK2 zsWTVlLK~o5GbP4HOZ~eSZJ+oBV0$pPs>;TN9fyY9nLJa7v8DFm;O8q0^n5kojHz=S z5rDf#TgNNF<&8?#a|%^PuM*>Wro4y6g2ZPyI0(W2ZYN{lcm0#2$VTk~o1@?|bvRm%=`+ z{pSsKs#WT)U5M9KL;-I6iW!-O|KJZBA|G7g>5HnY#(= z4^3HCrO)Bn3D`{~^R<3kx694EuRf&veL*)B-^>%b9W#Wa@@DUo)k6?EaRB3C0Oq-8Bp=x6s($3{E3HGq>eHgdRY!*LI? zr6?(GIN7HM0NjlZi*;O^2@9oHjnB{4LZDGxQL6LK+RUgA8Y^C6E5pU^063lfg`dRY zEbSCg!L;lXT_ck-TR}GGYD|H9{7A;R$1r-wy$_A8c}*?OpavHwkXQSR z5uC$kl9uTJ2@o_|(s6&uD&8;Eja-wU&9NArER*K;sx{K#*vq)aSjfAEZ<3s%G{pBU zCdPiC-)2SnNSeS!v&Z6iiG?vHvYtgp6vrzaIgk|qYrZ9H)$6O5{0Pv$~1Em zT?v=MW`uhO8qkW4=TFYM9%kJ1=SvOkk1)?2A7A~&lF=KX?(<+SFBxN(VerZ~7pP+; zC88~feEJ~cC*bTQ{;`E>fV}eKn=%xc^L=W-eCIfGo5m46(vQiy0}pcfw)x#HX>`2n zV^P}gg%v+Z`9HlBjzmi#$`{_%-axEvCs-1)M=o=Pu(ScOT##ySR;t}cqZ$HaHIPl( zx)S#oeE0OciR22>0W=b7eJ|GX`BMlXx>?0x6MJ~>U=aXDQhv%vmG z>A<_JM1(ThMnYW4_2&d0V!w6mgK`r2uti`ja;(_#Z7d9T`NFu_wRL|jY3^%zA834} zx1num50C_@t6q?qzyNfteM2tcih3b#oYPG%Bba+bQV?6aQ6L!uQvfTCI|&J`EQBpY zS43guN_|ScP`xXD*4>S0F67|f@8`P^2fx2hHa#1Z9HF+g&{5v9*(H*iY}7vvwMIQ= z1tVnttyercR&iT!xze3dcry#==5~WQJsfY1WlHdSxxx_$>~$vzOyTv!^-!$gt*Qv@ z3U4lB7wr>%xKBw~Iywz-Oln9_(^5J*dU_tx2|=pb^+NKnJ{xhZJJdbG6}j(yw7(Ez zS-+Qme!u;J3$pi~_IGC>eYgS9ILh-`Q9xdPcRR|#qWh)geRq26yD?f(W-gqka_d)P zLsm%<8G(taOEE#8U(EYX_bwDVS{hb9I-Rv3)Tuv-NgGW{R`Neu?p59N0(*8I^0xR| zKV4`=60BwtUdiuQXjvQZOHAz5RT|>%MALkTV$5fo9{@jrATO1TH0o%h#g`i58tWFM z8XD4kC4Ct(OGPExYwKy(tXE0%gKq(OYd$@)5;!Hs#x%x>A!_En>|DFLe0Iv*OuqZE zigNL{ca9#5`(`!#uT-7ja%3|N%7J#KhM^nTQj{blCHV9@1HC;ccRGS3 zxw_t7G3RZPN1nvJj$1%vMs&6Y%T@Pxt57J2-JVg$B@3$Xy9T>Exn!;+LNocA*Q}@OFT2_5m*?}6$4M0EXMgqv6#89X ze@vZaSd)MFw}&7DX^|eGq$o&tO_WXn zK|)b-jAnF5C?$*%kQ!a1VYDDfjIL1|4CxMO1;uB-|NnT7=eb|+)qU)H9pC%9KG%81 z*0mqY`BP+5?;NYzP#(XEqdM*h1xr;+T~VaALA}4nBC2EUnKw!^MSd+!iI|)F(XE3w zbG73$C!N1RJq^veW5+#8U4lv8_GY?UZnh~P_^Bb>m%JTiQiwr0!B;*J4Hg`=7lEFk zi#u(D_wTv*#jo_$IP(5+-%JdD?&O*fC@~%2rEliiw2PjCT5V9Dy!`5&E`n-H)?_ui8RX)vFf7b|IEF%bTcn&`*^yTHQV2K091_(VVQR58YZn2UD}PJK$@JdW=6itf;_leMC z16jwzH|z8nBo^D(4MMz?=QlIwu9X;+boSnzA+7rsOlAW;JYLzV`oxI3Yz?KYu?WAu zdY80bkAHrit_~ag^z~Y319-t@Ba?99vM|Ld6ZtnYmmSqE!uqyihSN=H;c_*s zd}DyX=!C_{x@!A9kM{JGxKIO~Ei@=ej=!!teiZMeF~HpdU*{lvVqyOZ4@;FhPPd8Q zkQTR#&PYs7$)J}TMOxc86#~<8E@X%Xl1WKvb>Q%TE8U{~*wOOcwmSDfEB)8Altc;+ z-e~r$F5p_N3|9=pTuT!MV;?(=ED?tcu@ygOXQ#)XbF<6ay1Od>s)=UuN!)h;a3Riq z_UMzq&W^>HZ5(Yq>hcK}EdT%nAme_cPnBt~OO>l$@%VyYzg)m+HGXPJ#Y*C*a-Wc& z<8UZ%5q-Ax#ocf%qi6R^;fyEoVTBVS5t+BBben@yteP?dVtiu!>di8A+l7#^jL}<{%f!H9M?5sWZu<&1ShjQcLIXWc0S=UY7x;^~XU}5?{N&*k z{q`5+{Zw4j^&_*NTXn~MZ9i$~x_t5$ z?0vXD`$^$m$NSK!qz+ntVYfK&k~<+a#1ojv-f`DQ8tG%voMXhkoBZnF7)N=}^yO2F z+Xg|C3a$t)dCJwrbvm4g#w$6egOYR8^05J!qH%5VCfFMRTsglx7-uBelM?i{105q@ z3ZQ+e>db9x?qFwbeuvEkB!=IJ>1$lUYUxSriw{fidRRvl^ec9ipMX46U;iaNcWjiKq7lKzKq zQf(V|5wo#1Zun)<7Z>-uUJMMDLDJB;19NYUPfkGQMQ#Z9O^$%_gY2hl5~6 zSi1Smj-qgkm7$?SOTUu~Mq`;Tx~@x3nl3Iac?twrUcud=TB{pq%+S|WI8BI7I zC_N}f#(unRSaQM$QU${9)mLy(icGJcfWrVcTiE&Ely4Mb?cpXqL48RP4n zsLSgDwp>dqcX6IWt&V7Umu} zg_yS9sfLoUycUggo311Cg-4@Syu$E|%f?tqEK;j&9P@fdOixeG-wVtQ^HmLI3Yd}# z?9)R|(~Z6X-`0t&+@XGl zp)#Zr0kmMHoHtv%!8cTzH`Tp&IaQsI2@vy@Fb0hxaNa`Up(*K12D_2A^yHTBD zy*7y9DccyL2LB{xiDw@a{5a`@yCVDuyjzTHdK6!syrPdNK{D!c_#d|B_iPGqztJ6S z!NV9N`C_LeUsD9OU@~_1*baBBc^dO`#yzNyTTzs79$FS@ReY-X8GP&j*R-L@{<7km zQ7kTVC&=F>_6>VdBRW0S+zQUyyCuU+)mRZoaE3?kPUMiEwe> zckgD8R#>T9s!?RWdOr8!#miwy_WETA)MgN0S;#~8b;)7@PR%~{y9XoaUr<&GFCb^* zc~PsF02%nN)=orZ-hoyzD2`!GTq>YB`lb}isZ}13$6neRBpx90)o`Y>_U(UwhJ)Pw zN~d^!bu0B(3_%71SV8Ck?2M zv^KvF`D0L}Hgy&iSACJ719Iikt4Gdh$w1Bb&6bjqW6o{J&K37BN)YzG@m^O)l4Sq& z-59QNOG^=f{uwEZ z&*ckzuD#$wYdAly)9VtY5s9VYrU+=$&Px+@x9TRT{K;|A#3nE|&Rrj5Egd!v%EMX+ zO=h;cEj+}uy_T;)^+#abWBu)R+pyK%h5i1NOT->wzeo`NGW-#$MQ7I2Sqcjw5iL0W z^64hxz>>^@62YhF$>>!ZQ*hIqe=J4R~+NE%{jle7ggMg z<6C}YM~uXUPWavR>Xis*e*g3!d7%Vj-~u)4-5V?UI?Vh0@l4T>b%GyCbIn0aA^hO9 z_Z9#R`hY-|mR6J`XClc;!(XOp-ixD#;{3yDZqceBve?)PvG|i8)n`_ORjsU#dg~LI zoc>9Z1eOwoz{nOLEwEKcri%-(^p`?v*c6q+YxH*7`<9EkEmV5TRvttJxG4}WquVTLgw#AKVSzeJ%gd9-N_z4%rA}hwAG<JzN*YGMr7C-Ntjf3&Ez1 zLN1Qj&5x~43zHrt1qnhiQRvL4?gI-OUePT3tNH+g=Q%0jCTC@{43`~&uM{~V8nkB7 zwgst^J%*ykS!~g=A#8o)3PILv?FgcWF70v?QVUQQl=%~VRSj0Q84B1lnUFo9XdO~UhC-MKR}8P@YbSqEnJp}BY@%`AUh}G zm!iYf*Jwq4Fjau-!O-vLWp-HCxT@p?A3ll>V<5fa3BZCFq&R@*YJu|y`i7FwCbDx% z8QNl9qYCp%@=MQ8{FwI|-Pxw}rNlOmIOOAbBE!OZWCnR}UqacGFzp(X=K+BRhN>dT z(tbjk_O?Zz?1nzsgV$O3l6)Tz@%%66a>TWk> z@K%+T@HUE1iG=R(_=u&*=FI;p@V;*9uxe`pme*Q=RRUyWA{~{^XiXQTIZc-tRHG!V;fVbQRfFwM zuhqzp{eK>Tw@kID$Q`g_^VI?Gx>p`7fJAfw2;EDRl8DAq*TB*kZ2y0EUjM zkeDAJO662i`9|sl3mKenLB+Irc-q=tm5y#arrT_j^bjRkB>l+`ATN`5`pwRi;vyH9 zlUAztLe(@lvbiijRz;g#{*+A&C<0mzCgXR_*zPEF;t4*5q?+L7jAmsF}ZDUJNK5G;#0sLB;Co>*+SFm6_^U=CD1yUt_dxr;tMHr2=gJ8ecQWsd!dV$A*!IH-%%($ zbH%!%!$c<7ys3UgChe(TO7!9^T(M^j%oy-y|3Q=;L(}zAR#{oPzU2n&0c(_-rnU%M zch(QfIm#piH*6h2@*#bjyUG>UZu6w5!&nJff;Qh}-b&gS50Z}$l#V%YJ$5{i;7TNW zuoQ+hnS*56&9Npp-)n}(6LOe{1pNt1$|RNTD>P$A99v#L_wG-1;L%;rr&Qly^Y#P6 zQfP}(>=FY00FS?NQtK8tiQ(=!-54UHpAvVFw782~l$d2pH7E*X@j#gzy>pB_W-IRD zkOyIUz1T{d$rLH(ODeJ~oeOn$ktL0drgs>XiX`54czF(zu}1_~cO8NqcDPYC^#`9V zy@lktlh-esk{1U_&31ld-<4N22krYDt~HYQY|9p`;1~!BB^L{;R$Ta+z8Nk+-IThq zD)*N9a72#~wY6hETT0k4k;qX~pw$J&5b||lr(#=>`4xdb@OIx%aXIglzG!UxEjDCc zSc<|qfe~wtTL`h#&Y;ZbAy?4bp?3B3WF=oUaC1Sxp4URD=&WaeZ>&g6wU`BekQKgN zd}8gD@zrYNuA0YuxR%QkqxlQby7I%%XL0v@oMd){P=WJ%oM9ltErhJ?X_p6>sZD6! zl`RMtzvkGkpW56euVVACtmGeniC!UjR!Zrqlw{E%!fupb!IR!U&W4+=E*=WNQxOBG z_qoD?<(r@`6PcaERWO33w%aGLck;!iD3!6TjMhkC&hko^&Fv2tc_|(A7oSW}RqzRX zwP%xd2W53$i^BUMjV`i8_@(Fwe*@17Dfa)yEWQ{1d9DASF(s?GGEz>!%xX=tu%W$9 zN5(?>+uB&)EV(+ce*ixBRzUD{mLG0HRz2_-g~_2 zcL)k5gJAYxbwDBz7BtQz2+^k!|7mHLxK$f=CZIHc&R}7)ipvf}@G6emKX-}f5*Q4* zur$}O(Y&uym*H-dSXFg+&?zcPo+-!H3J_)nJpKuycnE^

v}~&;Z(y{ON;5U@%sR3 z0l{~TQ>Y~Fb*|&J&@yB=B8@My58%2@a##HHGf42!&O>tH{(k_m*|_A&EZsT^yejk& zo)G6FBTiuOE;3+_{3)Lg9DJAXc$jTGf#v~C{Kul~{t0;*0m@SAEjImp0}*seJDWIS zgSgD?7VG4;@oQAaWBR#{6zS0Dq=-1s$Lty>h-X!U##ZauR8+2?ABWcQ#`VJ~)HFt$ zZCLPu7tLXmB&P8mUSkYMBbLLrXj@8>6l$(Vs%A_OLhh<268q5vxMx;0Gd*1w&T79hGXQx>Lsy{?l_$Ui>t~ctd>>o_z+5zf1xWli?UzGk{g#W@1sWUpT)}!aTiPGB zBf5GtsimAB<@AaznPN5B!&fIrNw58KWArlH<2;YeSp2^{>k-%6hFEW{eoWGPRKU}C z-~}QAMm@Q#KuuMpv-*lwIfq&kMRe;{XXjUjRpDtI(eEiqaFA&p2eTk|5l_DhL0K^~ ztNTKMUI+!h{8E8U$1;+3;@d#y2J}qI*C~aMy8p!<^=+CtFg+~elqGXo(k3bcdZ%Fn z-<>hGj^oo+ge)pjc>8~OqY^-km45*C?eXBo+*z%#$$>S?m(+yLM0DHi_z@ zBL$Howt)!Hcg3+i+|zIbRAOZ%{sXDa9(&ktTA1#09+A5&;wlGRx!*r0eV22PY~6dk ze;IbhrB0b*LYApHus+#aLBS#^V@IVRsvNYOeJGMxm&Ux|YlEH z-B|C}#;$ID*ZF3zM6NmP$(AeF1OGhpd2;p{n}CnXa^TY+oV?#J+$ay3>L+=Vi)_`l zH<*XP%WI1rEnYTR3+O@d;|*8DjCs%6l;&`lR9JxN)M+Y%dk!`-ia9=eCC39C9tH6n?hwpz8@E zW4z-Iv)Kelr3)%cqcz=MGH>^G54o8rO>`nVuk<2%n@)m2q5(2J=d?IvI}H5HNka8_ zjSYNqTb&PshKn|@f`2|80dPC?7IZc-M%`jn;x$Zy1jq>9FMC3wSVWo_w3o}fpC<2A z*?>wnlF<|M1m0q@^vsldS)O;luR+cHPyrUpG9E;u5G8|BU8&Vw zQ~GQU_A&HG3G$%#`@u@zGRN52rDCc?yvPvNjPw-5j&7!S!H4aG*Ud36zWVYBKn;=Q z__(#PgRlXmv-^I^f-f)eWD{XWYWUYresrVZ?yErR@5T1zPR#p_qc$yZ^w}!`GM;n$ z9UvCX>qo&uF^$f`Z`u03(r}p;?_g+J(T@auDQe9{qp0uGX}28gGX;T(%R_$3CXKRp zgc-V{^o2Ur2kFgy7a}?}mn$RZ25KhLB1eg{(4R8F=&2mO8F&0ceh8_`=uyxT_xOCN zu2nz3B=n>6zAa6nTTA?84~xP}A0@F);=b;lB*6oT3h!WrsugYx1)0;KEGt>5dSVu+ zts7k&gHNXS^T#$ZeqAf0KmprNEH?eJr@HVV|9Os|TksKwWLB@V0xt8_i#3JrA!kf= zK>`0$-`6s~{eOSP?SS7H(S!|hTxe&y2jAJpxLPO=qP~4?IDUGE5UZFWtIkZZ)+vpa zsc$;fC23h_W#h>X%836aM(Hp;FLBc)Y2e5~zgHRj_AlC4Iwbh)ZU-rH$J1jH{VMm0 zO}RRrG~!&`hP3AOFmC?f;Mb`7M7U$#srb8Jf0>%#N4A8WW3w}kjJ#f{#pTgBXjFR& z?4T<*MI-#)RnGgGs-Ay<(p}~1Fp`cPWref9oZhI<*9)7NN7Or4b8oA!rwmkXVx$yJ z%6tkH+tr~=5c!NIt$zT@d#kQ>VaG@6Z5mr$TbBa7ix!0SZqC*nB9?0xWr}ZiD12(> z)#fCdauMAXK8H}3)Z39xK05;umgdWw$55OfElobD)g=1u%fImf$GpOM$gld|&O)hE zMoo;h>fhpL!~KsC4t2NPw4Fnu6diJLx;Kr{-2VXOIc!uR?VnNJ@v&i5id~s;H-KUHcy`kk%mb z+$08H+ve_idB`X$K1Bb{2G9@Rmq|RJR@ORpHL_~#?l~^vQXL3Kk0+yV1d1d zl=-o^27V!a^(Q&dzW|%F=tS&*|Ju0iJT6M{V{PF^$Vc^Au z&bg+?aCEK!czc6NNRsN_J!9izBaBi1e15D{WWAJxwFFTYfK()$;%v1n%N&-7F{h4w zYDIYu1ulf|pNp;Mw!$>{pHoTPGd3{9sBwprE!=YkW&RK1nl{ia<=PR3t#vF|>RfOx zFV0U>atUNR4@iOko!ZPrk@3qci_rS7OkJDmHVSoGoOPu3Yu#bVfaLkD4sIn|4cfZ- z?E&o7iD&Z87$?EHPN+%THg*PM*fr#5ab(sXi3(ETnqe0^Le#-v(?`%t`)XTb(YWjC zCbh=3L+KkH=7jPcTgHRPX)DVSO`moGZa>HwYC}A+sk{c}CV-CLw!6$aV=sn|u27BD znUSA=iL(!4zD7QyNeLbuPZ5ytE#I<9(`6}d+!&lPwtAAT{%ki!?{wYPT6Szauqf&G z5uS{vZ+A`IpAI=Zb;36d_b;S^RnNXl!6Q8YaVPfjhEg5D;y%$XPutemfFy&LbNCG1u2 z0CVLnn}@60{5nT9p2Y{R#sY2N`|dq-U#^IGls<4oaD`r5aA2+Ew=0Qv&tU0-T1?Wp z(|L|*9>+0>`X6YCOGDbz&2}kt7)#T4KEY-rP?(6-*_ql}eQw1w=Or8BRwi=Mq|fyF zHkp19-Bd`tVrwfeLp`aEXaX{g`2N|~mMa5e7quISrqOeb!XNnHHmso`XX-&*8jbdU zp%ne{8XIvZ_BZ84kWt0Q_e8&5oF_c-`v-V79>xSXJ1^9hTI_Y zrJJdZeuzF%UHcE&VxU5u+jilijbham1%KUB{4hvSMBJB&ip)?^Y!9tNsCF!cyE#ww zOU#a)ZRRfGz1y(*I>*-~Y7=W)Ja;4R6R^r#KeQ=k`cE;W@U(7ScJHAX-p<%arua=w zrDs(T_QDWLx^)4*ixJpI;h3p=vu5_eR)$_kVTO8-#Z*Q436TR+O#Xqn9)e=&{5fvhKZ5zcSICkT5bryf-X$ zT#O^`rC|d`6XFUJZ7(qkE~%!hrH4jS-+veTda+KehHyoUE5&(dqD^5R+V`$sekq+c z_3L{M%`kL#c`Pxdx7u|n)7aZs<<$jM^Y{EtZs&{boM`%}wQE(h7hRR+|6aFl#}QA@ z>(-H0Vma{BpD_}3kB#jagk8FzQq=6Mu^(g7_vuk8P{6gWb(T@;Z5Ovot?$3vm{9$dM+xEtCV;51*U7LVRtY zXh;nx|h5Us);WrQXo0?et8hG9o{RgtIymAXbQz>GD!Qkp`}|G zJp0+Si4Z=sHQ5p*dfuSWn(N;ZEFgXB78&_e{P%?p*D=7dJPE$svur$Fq9Ep{CWo6fFYHVb%D9q3(>1_Z~OgpheOUO5b zNJ~AwIRF+);RNMf+7NiRlGwE5OuilxQEBg_xP_E11LHSD4)*W}=bwxc=FZSb~) zh~(E}Lla@qgho0}!g>xQzqHA`TnH7nSXva8_-tuYG(V3}ia%KK2~uO^Y<4<`BZNBf zioBE~K(44HN!72{a4KcTaL>jnsH!=!IVpfRluY4#r@V3#C$-=xk&`ZNXr8<0%^lT> zKxz`(dFeaSKy6kQSis7JJYpu=y7`r3R=ciSacml0+}osD$!{WLl9yV;3y;}38sjZ; z+I9{$V2h9)WBk(ATJJ|Wn{L#9 z@Z+Aw;Oi~Q%T+b53^vK>i&4A$$5+W11uvtQQ=&Kb{|fzL8{w{P#FF@aV6`a~Msm#6 zI*$z!?#|js!MC=?5?!5diFs(A;6Z+^@s8sP?Mt6oeyF)*#HTse!+VTolnx9|O}&!E z(=wI-cpyqLzv^TeG0pm9hG)jJ$7SkD5Me1+qA4ut0*s+NesE?tl`H?0^5|WYRsF(+ zekrUma=ZlQ(s_q3eG!UecSj~o*{cr?a8t$I-J);1%%;9g3N7^EE)|k1#io_CSV|(0 zG7mOy%-Cz6M|?PYOQBlOA}M6ruef;+(q%mI2ge ziZpn1VKw*7mdXBvuHr-}^;O*J9J3NwhY5e@Kpd?b9vc@eP8Nbf)hwDsj z+_j(q2N9CO`4|}*b`3mSu|Bqm50$Lqu)cMth=hdoAE3zlbbj-DW9qcB$3deuiR<`7 zK6WD-yaLzcP0386(YCHpnYPI8-e*`SVz!6ll168175td?she@Z4evJy`y={4P63dL zP3wa_5O=~=D}fHnU#K^}G0`rae~ur|HME2*r)^0@pzZfvoQ>C7lSD{K;VjhLnG|ny zsh&y@I48l+%>QB!pUMYW2G5xvcPeMyZ z2%X86?uCdBbb^wA)X;w`t5ktgIzVR%OX8nG;Op<<4+64LhWbs=KHE?xBeSC26Imu* zvhlv89k8;2TCTC)fh1#J)$IJ6Heu;686uY>ww}tIFy>$~33b(Ak1CjzaFI_UHr}_(9*~VOHFJtl6x{JOG?eQ|2fi?BtBVt@&+C`#ugy-2@**AxzZFox6tm|uqY8QQ4*+b! zJ)m^(S`S=Y+v0W)xJ7O^DM$A3N^ZMlXUxozGU_0Qd-14~mvj;w3X5w1hs^6WHcyKO zQ7ArF1^xrvWn{6rzK|p#-G;cAHJ>F;MFM4{3N*_%9IrOz$Vq7uL7Y#?BQQ;qZ@jlp zJ(E8sq|9Co1q{x2C%=P!vh-M#?n!WmC`L<^mVZN*3wWy)Pce84!7Z|BXAJAmY)7Ah zG}xB3UsKC}35+H04JU>DZfQ1kY3nYM*i-auot$jS_}L|$yF#y_@oBuhB`9kNM$cr! zs?Si(XRy5w}63S?Y=;HB{j$|rf}?4;>CZA9CH$U#ufGxg#7-~vTm{h8PGH^lmX zZ6Y&@p=#FNcipHEnzH1}nK_%W=h`8&7D5}ZB(hGk!4+FwY!f&OeTpF` zmY&LGWRl7nSBmv6otb^QjJ?%O{N@`OqsbO=p6B5zUFvbOuGe8W1J|)gR+^Xlr*;f! ziZ&{^J3Fo?GtU7CS>Jas1C-r}2g{PpFFTSKJFn{hS~TQTS~eCV5sgjedtt4HRu9cp ziZYI#h_;UY6&m%IFIwYfUQ4`no_}TM!a7Q6jEluWrjtahhb}UmqJA%q(;v~gS>>K} zVbk)0jB(+Q;OR(zKxUfv^l#-qY98p+QAhCo?On*;!}}FQ2*FtYdF+EU{wOguy2StR zj56W0K6zZb75@MXSqJRDX#JBW_Wo>0_#U1915^w}V0uY7tX)DP1#eO>7hrkJ$VO9w zDaU3DaC46%Hx$stOs1r9fo3c6?=dGQV9+^U?l*Pda*HA}+wgBPgafJ(NY9Yg6BEhx z08Ml;5a~#E{|D04K6K&CCl4wrZ&y~B)U%hV$}thtt9%$skzQWoUY4%9J8ZGIrmyQ6 z>DRr^&SNXjIVwrox6@CwjVY&rp&V|`?^4O{+ILanF3L`!j@%q62Kvind;w(dche2) zF0AO>SH3Ykw^ee#=zTx`d%`}XH1!eWg2GT_%P6Sq^A&eY?mkyinZn8WQ-}hmTas>^ zpGjKg8zs(1%JX1}00o_$Cc1pY&AT48an*NF^$}W!XfiT|ot?io?x~!8uy0`l{GDTL ztqr46A@Ktt_s0Q0Veco)Q`syzm!oW%71YSa3En_4=MTr1M6MK~OhJ-W>ew6UOP z;{YzEZ1Iv*OkF$T4oGvG4WCc;|0d{(9viCim;xnaEJwz!L#N$<}8C!aUnr5SJtHD(=9~l*!y{T+-rU(4mMk3JwR|Yhu>2s~y@L8%@$tYvD#u<})-{mHh znhKQf>al0I^Z1j2E83v=L#9vm8CX(8i0jq&<^CZcM|Gz3Ez5mR*PFctJllkuB2#G< zPFoXqHdCTh9l4-0S-z#eP)7jc${4TV6iQ-{@}>h>S|^q)ZWt? z5RPRX3G`g6rlH4f^2&)n>9+AXLj#J#UaBtcrg2+}NhLro;5GbA{5vzJsXH>$*-Mya zw?C-8(yfq8dY6J@0>M2Y7pv~+QeBk$Ob@(O3Vwf@Qu`iQ`43>41T5NC$ex}%^J*HxWgz$_^zbsh~6>KyA{(G1(8Hsw9PH*r#v5=&qDfBnYM zs{Sx)OKoKHt@?agQai1suxZ9}g9UHPkzsdZUz}f4Hje>Wp=UJXi9Pb~DZ(kere`w7 zrsTd8AHI5{cf1921s*>ocaE?;P%~0u;w%#?jFOjy+;Bzxv7~ z51Nbknr98q+r{ToZ;sUO_exX58$G=5o6f_?sXC!9oS7=GQ`HG+8!f^;X3Y4ZEmBb0 zr1Kjz3zQD5^6(&8k8{oT0t>gXH+U7=!#U6V6VQea|CEW;7|Tt*@t6;0_vYs0ks2P6 zWKi*Rc7<#7jAx8H-n^h>n_ifK#TU=83KkSsmc!~6%O7~Gap8A2xJTQW(Cc6^1OH2m z(krR>Dc1z;9hn8s79+!M$YK=SVUH*2KzL*I93i@npL1Xq;8z+)?VD>qoj>ap^R8^1 zP}Q8ZVcUqK5;*>SyQb1N?#> z$m(s!NhI447#1=PbtK{cZ*qJVqcnX(!fKxs|I^+TMNqRwwDG0I5qIBS8n<9z>q<)C zN1W=@NT>2(JDz+#Pc$YyoK~~K4<~#nskB0}UQz~z-!nwRY)Ql5UD2z*rER#`v;FLB z9&aj{ji-PV+MXkBBuYUmeqzeJmi=KAT)39d>IK*C z7`wBPy4zl(^vbe&4{n2Z$FJcuNGcoh$9DUF0!iG_@2K^>F8w4tFL^u!WXXA$g|^^_ z+LarFO964qSRUX5oh`U%m;bGA^4w=}gB%(Ptdl(nj|1*{*^%#xBh>YY%`Jatl6s1x ziN8^FvWy_IWj%(3W_+WWr?}$=FBVBnU*|MWH_cd92ok+bA^gm{B3M+au>UBatSD#H z`HNS-slwMr5E!z)oTqSW^Y=f%gGYxl1i2-U7BKW^N9c&`Q-9)P?=iKgxO4u{(~sF- zO>8&S>-M3{mNac1+aI2fNZY_=83M|SX))(T zh*D4cwJ3)b0z*lm&KXXFGVap|z`Yq$%jd(Eh zXZbTx)K-RU7X=fd_jhWlh08QbG*ShvczEgRtNhn}y~WdE)?)f7P~pYFvYuZAcHQ!C z_Sue~nC-y)lK3j!i09FFvESUjg~KY*&0GnWRV$zSFQJqr(qCb+^^tC*{T}FuXyq{9 z?D-DyTqa!;N`^x5{t?oZqHNdH5Fe4@EV4%9`SSUr@=mox8NXKGRC9uqEc1y?dTepp zu<^tii*3Z0?(Ro5#;~bmb3&4dSnEXpvETf!`s!7P;qA<770NFkCL}dR!6-}yBOO8SAi^Xu!$Z(NKbnU}BwI2SL+k@`Zm#TH(Ii7b0+Vhhe z02=;xg;@_DW>e_s^8fG{3eUV_cKlVlA*Dyj*i@M$x}~xBHyR{M*Eikb*t5~K7QYVq zC=w`5?jw$lb@cp6M)E8zXJtd>-bDW#ZI^m_ELDEt`xmoEORQz>|Dh-e&qOdc`j2P6 z@}G`xvl%;Qy6wF1S^op z7VZ0spiG(D8--jK3Gv|Gu-RO(N6Gi$WJ&IxrM9$SF^MgN7V^yKN1hyhh?ieU-rg(Jo?bZ%D z8$Ddg$(S{FsmdAr z&bg{q*?uE68%D7fu0TWIGoX|zto>j`)1lOn^kv7^*Pm`r9*mnibG60%jB;>i&ojFTi=mOKX5 z)&y$8lf|glin|V$p@$Ee$~4nN^W&{wPgkV@TE&MsL39p)bbdl2qzAFeYhYvY|g|Sqm+@9t;IQjuYI7k|Rt4GIC1@nGebK ze}F!&i~)uEDPK~EaEh_yoaTZ)LGDHL>QM`+Xrp|+%x}PwfTB+Peo}n0v?PJXS`8WC zy7<6qRD3ZhWNu;Sn*5 znudCNR+gWA&0T(g)Rt`$ZBTJX)F%@W(`>v`_&^lKs*0i3)WAfIC%k}(@U4q@MjKuS ze9r5_ZnI^_Yo(}KUMw>9AW^1|3y>zyu`$oJe7s8QH1@@9_eyGy$rtne2fX0^Zv)3C zMo(3QuT~!)dn?k{ZNh$NkynRCu;c7g3umuLFN^k?pGnK9f9FsOXkL5#KBtDtHy?=j z%OtsXA>Gu5v?9ze4yIzNntkXHC2I6-`#xy{_#fig;V)re)a>h(=>@yau28FID*IvXjXHi6B;e;UHSq|E(CEm7%8)pplhB_*1t>V&|`iXLn-wTm8Z+mF^;p}HoGrB*|FRF+j55CZ? z9e!Nm*W6fw0g-5OrEyP#FdwW?!b3wOzL(v+f%kPO-9sGQ`KIAY7vX`|v;cHU9 zDybU6Dj~{kPaM(tgnk>jd{v|Ou%(lEM~3r7{=R6i{tG9vgy{nh4(dpLPj79){h?*k zFCsK9zzGlSfSonXJD=5IUZDAdY2ct1l{X!2b25JIOAm*=l6tsox#C`zEB@*(f|X?0`~#q&B~^*USPEjcT-h&w zG^Cn(Tv-Dh*qJ3h_83_1R1wxB3M+!@+gV`0v%K>>ykZhp^6u($McD5^d)%%<;3vbu z-ubRo@dr%Z8)&2PG3T*Gpx)2W zq#?~k{DkbGTehbFcWF7=LX&T@F@kfZ&&0^hwzhwfhE{tmR6fj$R;L46UWt>}p4-*_ zYXNbY7G>e}U)8sUszbBg0S7!>vwt~I-XoSZ?WQx+Q{eJO=Ww+bLkduDGPIFiU``ve z)kPIE$vxI@GXmlHI3~>*LW?{?-78HNc!+1TIF;O%QhzG94V9DJDR~C)euT_Rq(#Ab9#Cq z#Y#|6(V3cK=j3a~hHD7QwjZrlA^&iAo^l)}>n?HPwvAq&0Y)t?pDFI$>kuAlPQ9t-eoxYlDnXO2awE3IOm zG}d*#H2jX%__YSrj!Sk8=Z5qX`G{!{|Htvs1@Apk$Ke>2eJn=36)D{PmSskc)E;pC zo_N(pW@G`YQ8%yB_pL0+FRpGiHW@WBcaA)$*caEi zk~Vijmh%QZi5a7e|K$e_^`Sllb4PPsaQ3Z-nEmZT~q znig!UlNQD@rnLAGrn%Kg{qHOTwa6z8D^dG$xO6p&(9CN?`cjER(J48y%*CT2bF!Gy z(A&LkcL76`VMIU{j)65;vW#f_?J*A-0Ks4%)^Tqq1BFQU#k(0`cqMsK(;b_msCIaE zSKRXJZG#KQx5J6gZrZ1vtlD0|f{FItxD~{bqH_spsj`p@MWI~-onLOOrq6mxU{<=b z2t>7GL0*&LvDgT=wd4KxK`NrJmO+L%1Jxtr3=Dfd#9oFlrFm`k9%d*1L&S;vQ+;Nv zV8<7T({pIBN%cX7hU!-;JvEm=vwp?wvH+R`p1wW!pG-6+#WZU52 zN?c#b7-QXEBfIa5lz+w3{;qCT7W$8DlYGx1jL1?Q#OSia>w7hY}LAWx!? zu{OuCFVtf7GL-3cc=9WW_v#jD$WBX$%ULSZtF5x~oRxSR=2^Abav0l%{l7V*v= zx!;mV53w#7z5VgR$VB9{w1Ci=$E)%puWZj9-qi4?{SqF5pAhb|;aZfrFJ2lu=_cU! z1h%0EGfWih;Kf3}v2-MEMiIX@`VXR7hECJsLB4`3SRcPh>Y*Cs{*;g{@hYphBsJj3)sL z$V991p;eOkLOM0ml6Z^K_okYf6qJpU$sC3~w8w~54Ui1wF&9^(%djz(Xq}LLx!D_% zI`g8R!N+Zzy4=3p1N-tvZX|S<(^!mQUuomZnxu^60;D`ln0v8FDuy#bHYwLL{54k? z>m9WNw$g*=Q~JoMDJvwuP3vF1WU&FOV>HWIUY1nH+fw1S`fu6`!a9|076o@_(ZrS) zM(fL>Cq!*?xqf;VL^9vWG$#-9ai27EUHv z;uz3VvbA0KuGFOSQg?|>iVw7SU|KQnG?o+;@u%D@m`rN?dCn7#UAw{=ni+0udnNKPH6`-Ac04sCc3W_OlL z-2ugqx2dO49O*c|%#hp}pV`^T^z)>|)xrCTw}|Ig`l?x!RI_Q-NoY^5^UiL@F9zRY zeMXyFD-N0|`n*_R&fec;%9$+^{|{|%71ZYU1?+}GkpjWmV!;X&S_%~RLP~Kju9aZH zCAgCoD1~4}in~LR1TF5xodkDHa4EF?pZvaW=3JfI^A7XgF_~oc-fQo@)_NWggp%re z4?)!cMa(8A2mb|d1Q{G%k-iOW9M)IK;Ia6K->^NkvxEP`C^Ku*CNPoYObuygV9MxYl zZT9rnVSDLMeRC+m@`nU;VD)t+p3{E3grp7MwXe1rn^y6NW{To04@+uz9u?zJBbC?n z0#TtAtw_E`X#M3Q%3T?km&HN6m8`3l7a^BJT0t%FEPTBxJzo3jww^KAh9s=&6 zUBZ(hp$Ktgjv6DF?yo+>b8;BBwx{N_C9B-wxNfl9D{JQS{8*R-5OFKu3!t>=D3!dP zY@2M|g@V6fHB8Je9*5#>Y)K1G8mFaBYX?|hC7;~m_%h8_)k)7M`0R`y_?uVHd2#W~ zlV6?l|9#)nk}B_ST8nN!5!!;vW>TwF8TuAaV?G{+R7w^%Ob#0hf_!Uhn*MYV@m zP5vK8H8C-7{NTQqRD>EQkfV;6l>@=x=@||N-6PehAPUgizq?fF} z^-tBS*Ed^uOr-3D;v*ai0a8Bx7(=P(iieA!V&>Hl;9Uv ze0oZTwSQT}nz3HbY9|}yrZWl1iH|d>!Dr#&=jE5&k?N+lZ4NRh?&?+2)7{c|vF0N} z)R@e8Lo=_V(0ee+*9j`(4Mv> zi;4N)+0;%KMAY=N3^n75s0yY30X+Xa-gj_v_LdqZUt*P`3=CnS{5>I}uN1hz!d?1n z-q7S=ry#lc6b{J4-N4Mh$) z%_>%wHabu_YyQEBW?!sS2)Qa@LiJ-lE5}<8StI83_2=H=p)5pR56}DewxgBtXIaVj zsLm7ia4;!5VzogfABLN9PH{$9Rc~6(%%V=vyg75?afgi~i(L~gam-)b0d{>LUDpRJ z=@+pT^?go1o##>#X*-ABso2Gyhs98HFGK3@D&dRY7$f={9upmzoox{Q#y@?$zkc@g?hppNDU??y>xUa%Bw{Y> zt3_Qgxm&NI49WYY$I%}u;jn>MA6hGFg{zSknuNY_GEDwgMKUUIA}!4}L;-bH3YeTxV$REU_vgjnLo zu@2PfjGTYWQOnce2_>=pjf~Hi6<5}vwn3r4(3;r9gNbWPm{#4h)!rH1nyKOJv%N;2 zxJ4VHSNqUO4BW;$T~5CUXPE4*9-W{eCua&w$yN~?gHqW8Y9bPPt?@p|HCn-3{;75M zy}v|aXRnlXEy|xkHO6!dBv?t(q>c$&8NeMA)cTh1W-$j_*EMacbm~;X((E0cg%Pnn zK?Vhz;o#r8{-L4p5xJt#{{gV>J{hkzO@jGV*%C-fqJRXW{Or`e)VhA$?;yz9BN zZTVo!$NVIy39XcbEt%Xn4)7sM{<@ksa&p=ET-;xJkWr7QYU^g@{{ooH!8C1eTj7u? zyn`d5O%D&PKrAWu;}dXV#O4RV`(_!B`-<9(MBJ|ru4lTZUizmHFsq$6|KJ>aO}?ug ziMw#@Xk4AqYy5Z0_$LZK)A0!8**_tDy&)^Qn!PmivoC`2UdOmqqnXwX$g6LRsbyz> zv7sq??kD?~8RuL~^S^2)*A@?C8#zkhMO)L3I5(Wcak zbdK3Usc6mW5A+YkYDw~W*(1wU|6oNl2acWkRzc&p)anA!KUVin^Rt$n2{$|=x4`wfe$&%u zJ#rPUml7)V2NLNI{L_|5?wO1g^^8g92KKV2WKoKVnq?HMWc5}BX;mQ_W<=TCK1#lq zzqA$E2RFq#vL>ezFG|Zgsz*{2V*4}g+Kn58ZuXvZl+6}7xX9?V91Ms&G>Rq!xU(KW z5dc|{df&}CK@^9Mk=UPqV3WDA!DTin`5Lw{ zGkU#RvUCQM+W&S{IRhaZ2%RtY4`+5}zZqu8{zg@474Wk(1z2Wd zcdm1jd0$$^OJMk=YAxS+Rwvii&wXEu<6%Dg)dO;7eY-2l9xg|0!91m}Llt!Y{r>>1 zsv%GCCLlj42PbA~T ziPp|^uX%2?<#n?0j!}KX`-|A8+QchS^wo&e{{ikt4f7MORV{|b{l-H>fe7i?93N@ zk@G9u{fOqTZ4Z*O;~z^d+anp0EpP@tvJ|{P?}LkW##>v}u19_Ul*-BC>*Ek1#x<56 zxH}g8V9CKhr5w9uV}F;MEt!umj_^bOr+&`he^u1@1}k6N&a~;v>vY?==J245A&t}@%)Qmc+O9iWi{Lt;-WiVprf506QAsj+GE9JKahDF_-}$AmwEF;8A$ zbDg6PLuO-~7Z#t5x*8i^g2glw->aSk&B=NW95(8FqyjI@)#k<6JDR-&FaX#;v6dN3 zv>Ms(G4oMW=9PLbfF#n%(cvoZWlC5fOW|)W@OCuuzs!Fg>m1@IkIU5ob6a)sJboFj zi!SF;l%*4uN)+nB@50}IqLz1PeLC$eSBts0>bhjv(6U*-e>Tze^p8kmg@e5$#lvk$hlM@#hzr+Md zBRjKYm)-Kot@F>2&izdQf4l5Mw8B&To$9vH|B+GZ(-h0O0meBT3e7 z2T?e&FGv8Cncfm7At;xsH)kDubw$;;xIE-O%$L0ESO06*#{!;{sOiU27)1U;G91*E zBPoDY3M7(h-wP!XC2p?fk`Oo=Qz?2eX`7?qmXJ%c6mq!`I@vN$y>Xf&NJP=$0}9)X zNG?l`-OTFu_L}ip&(UAr9I;F7FPv>dr#H4ltCe`4_zi?4c%=&dm^-JTi2=yY$0)W^tWH_GU|U#aG^}c;lHR*He}EktrusM0TuBoR7{_8s0Gg%yD5W zj2FOJnv1qX3RjwJl0H_!ESkADi1?SAgx|Zy*Sk5x?uj?0S|cGu5ccbbsc+5>9T(J= zhMTO{?ymwJJ23t)ck2F4Cvao?-DDK7R;lI23_WSxgkR&nl`{f-|D49rhv}J&u8~;m z$oeKMZjnCoA(nD~<9-mvwTbY6XTB%7=h;Q_MzMG7m~ePg$>ShwgZM$|){eFNKmth@ zD_iD?t~V_+b3KN}(!7~Lwgzs!_dmc)TPwa7`fJ^P!4@BG$)^-T`WOBF2gs#5WDQR( z=<5HOI;_aEDMa+?|8_z{=6}MHLokh}7&w4}0jC?Z+)Wk7?nkc~$bI&srfc4a49Eh4 z1WYe{f2*v#`eVw`IpRqiU^g;l+2nSNBt_8$#*xg?^ zTzjfir2x#A<&#h8@MaW0Q4Gzv?BqK#k^uoue0i|N^cy&-@2QH&I0r%QcBdrqX0{sd ztGg7cADf+->m*a};$LyJyq*~wD&FNz(wlsHkb=AXP*f1L`K@2a+dV<)MZHwJOw{hS zr5I;n!T>{$@9tpfe)41^zx%3OETN>OTaTcfru#5j;m>!GuBxN%3l%@~=_r&3nQb{( z9VyZ;1voV^CQ)SEFj@K??{;8fIrzsx$>YS^?yy}J^&Y;3^{~u_Pd{!$K^8& zQ1|bSz&WM}sb^4Wz+s(r3qM(YYxWwk*mztjE6&=Ekk7NbX{%nQ61v$V)jj6Pcjd@9 z@*}z;LUm=XCPHk0FyU6lIQ?>5fWF)>=#y+~AA{$Y4VHKz^r+{xtv2qa-0WTJMncCz zfaK{0iqBI37oGl`K2mDL_AnI$g)Yhu{Ztu=<2&g=EE*Ok z0|}8HyQ5YsLyPFX4O;T-HFuo#&g-o2N5!q0*p_X$yf6EK^-$Y$n1@4GfKX~j+ZXh{REQ}8 zt|#b<@XL7)WG+a1<4zMcoK98u9xO=M_lbRtc|oP{NqbbMOeX|o5cFb&lV>b+;Y4kB z;UTDyU8Qw|6!mP?ra`1G_(4%{^Y)%ZfH2K^Km}+tK#-q2d(U-QtTr` zSK%3R2aLIVWzoa>pF6$x;Nu{_^tNR$@;P-cO8BO=i zFdU&zoc#{`)nf54*hNadG8kK^p4`aW3SR zQ5g5dP6Ru9a)9iW*CE~Cnl^<0@j7tn@@w@;a0%t|xaFqnZh%}`Hzj0>uOKA@gWUP8 zVtB|}OyNlB2w6oGRWVQ|e`jQOqatDVTmb->_%xi1i=K{@+muW+{_=S%{o3bQwNOje z)?dGfT;g4p)@E=`X@m0=+zdJ8*jB0!y)y_Ex37wcF_3G^WiaU)NTt6eU4sW6RVXZo zI~S}?GkGQ5h;YHCMrC@ovyCDCD)9iWH6VZjKn-24vS&>Q(3mnz*FN<^XSGio^0D!R z-q zx+gIUyG)?1vszV?wA5gaNJ_opst+_}s_0Z&VtE{c%m zl^_2{sz~f3tJbY5lJ01PI13YkBbQwBk_DMl#lL4eOgbcufNJqO9sLjUgr*T1MlV-KMjJW1NnQ*{^q>WE@N(j@mZ zmlGcl>%c>nWd`w&f0K_I()%oDq)+ul4yxb2#_oK#?5e`|RK?n#Z(ZeLR7u5lRk4(& zNar{!WL0A+JyY1jZ!X^#t7ujD-u13+vP=5wLV{=-G~U(45}2w4J*;lGsGzviE(yLf zXI4IP0(OoOpZ`4Om5`>Cn;Hf?QWiO##i>E*b$j=5dZXt2);p4m0Z`A*KCI!t~9p@b|vC1!`J-c@TA6?xht$TKH#?4?R zW4q0KEG#?SJMrmI7;)V6ExpDxbW}_MBmE#S(@rp9cUca%v&%Xa0w5sLuZ8K)`N-A3 zLkZ;1wAWz@TMP_(^qn$qZ1lMUzASTIRHAxmJ$w_wC391xMKl&*-Z|kt#n_s~J@#v% ze#z#6jHS)KF}Z54M7RQMa-q5o^LbIz0`>`p0u~?~9GZ4ZX-F}&wjgO+jmwpn|th$Tr11S2DU#AOd$@lV+)ysLO|>+#!l`pO?o^4XX% zuRN^N+AHQuXGaL=r_pXGPb47uj(@_tjj&{^QP03&iO-?f%kbB>5%xCvATpqg%V&h- z{qctC8!e^D0w-x^=$Qk5(j1su;#0diQ&a_KxS8*g&dj!Tnqw#lEbJ#pDl8MQnjwXL z_2WnLghMRqVAaOhpX3txc+h0dd~fS0zP8FfQEy>mvK5_8M0|+Hl!Yi@#8Y!CE|Ry$ zqMygJQ7ST#?{7ngxm*HNp2&bXQAAL5%J8lF(Z^j=*GcW^)H@b~ZCpfo0d-OgnGYFc z;S4|mOX#!+UH(<7%itvBP`#{+FH#J=Hh*u>P- z#H6BH{JydSma-q%Y4744vTf8H{kSC!=L=gLp~(@I&(`S!vaGy|?3_tyhYaog3@4*I zua~EscC@>!E}n7pl2=K6L~k+j%9eSKRtfZ3+KX-6#Y6h$ECv$dV_J$#OiQGjuGCj4 zp=A7cY)&mvHo84@y5+$skxn9};bPliG3^ewMasXCE1Gop)wDZ% zF~=u^vR$T79k|E{Z8EyzFx^gb&oW3=KckOqrrW06zfnDT9y$7rqv++^8?4&6}sM#S_Z|8dW;3`Ze;hai3EY}t>U5zGHF9`FGncLw%M zUrMwR35$Ekz8b~Ru;4G|%w`UYYB>n-`W3NkSDDR}R*lHKtZ`B9UsGOX4l2r&4C`cB zU!WDV33yR!uPE0$JO2*F4N<6WU*;Au9FyB~AKR2kmx)m8*M+q4Ht-QIz}mQAs9N*m zhDN!IN3_VaY*ykwZy{08W#}MLxD+TJu6DF&o5e4x#EHz#o_U-R^iA?o-@rgok3wdE ztDkj1b#erU3roZ!aNwSMEDitQ zc`!ugB$GF#d=XaH-1+2`W+2gOb9CH&1HXo<@rv?j28BCll^!rZ&Yu#@7eij`gx5)z zwbVSJ5`=VhjghY=j7RnBS~f6Gwq&R;@uI{hTs;o3DsLuuGemzRrhJlEy8Q6RLRpd) z0D3v0z$^SJWl^dFD`TTMeG8rW*QDqXQ7P=_-!M3bI^vW(T3z|4PNDPOlA#JCo)X<^ zzWlDVV!!AlI>7rbwgvH#*lJ<<);f~}p#b`65vr?-{I7_7~-Ux%QJ*u4fDwkZ0-=rFtZr{TdU7)%(;AO&J>cQu{m(f|5fW?;uBk+UjFBE5n|0rhRn!sKj>_j|k+Iwdzp ziHGXCrhE*{+ni>^q(zjvI3=F`$oq0BwjfJov{E~XS{MhN$iAkGtINvRk4;~A=Qxc# zV|>mwH#axaQCU`*x;pr8y7z>EkcaTge^z?-7)yR>2@CPqU>D?MvS@-;7Wv2Of-*md z1Du%Qsw0YulAuYFh@ck|Wg_lX(DGr*d>?t#QXVnj_(}Y!f$^)9YLk3I)@P1ZyKZZQ zaX!>=U#C_`gEN~~aM4do7p6v|k!7@?vGMT`1J;S3D=MS+geVha2cp)6RZZNs+AoTH zRo$n1Gvt61dexxbJmTI!Od^9I;2EGf0pMrY-fDe%R?1QJSM~YXx3k6#e&x@Li&qYo zu3IB;Cq(Oc1yP`Qr%%)+)>*Wdy-fYp*a|O;x#!9nTme`9b&zf3&{j4( z(i1EwYLz^FE8cbgtCl%?ic}^^N9nQhsn#>7wPvo)_HaxY z1NNqg88-4nMvKka+JgJl%kGX}n>;(+*1}DX&XxAD_lx!~aNqMDB6SmYX?+UQ6>)_L zOH1dNz|QvoYNcqaXw1}Qqnu*7V0yf%)A@3_BYQ=ocA#)xlIrdUe4i+;37M4X4v=&Q z^TCvprf&sxdOl8jFO=HnpMEv(o02^bz;hsWQN4+}D(y)Dr1OjKF{npD{6WRbCA_?l zlGsbSpMx6~yQ(|2Rj(wdCF5mv!?mWsc%g&=@`$E~9B&5&rBA#h>4jTdWKO1zhSWN) zq)tb0dX&9<#k=hbu{qd*43ozZ#IG=}$4hyFi@eDvtu7rKR7VRO%=#Cf+c-_{S2#l! zwRCsRP9jA^@s>h++-WPd`mom{mWJ>Lfxz$V2r6+Z!>nG{;JyLE&;z9^1Kak`pn7l>NDFEtyh@E%T-A~Ujd}I@FxK$Fq z_51)k&L#WnS{dNzQwN56?>_OprwF^y-J;$qek~2t|-!7bCP+68t$5*z2-P^= z2^b0-07+;AHb-blUD6;3hVK+Y4U!8Jc$*i&f18s|xFsxc8dG6(6nkgFCfb}nxc~GLXhf85(7c~R0Zie2gMz^bk+Z>-qwHjuFQ)) ztVa427C+3#NyuWs(R-;mKygo7l2#eNLS-$CiZ8%o#kj<37mvNsZ2axT%1LZ7fI!y) zmU)-PsGw!whCI`l0QT;?3*q7yGMHCc=#<&#Kcw@aYYlT|Mft*gWJwi% zi9F$ElA8zCZX{`7d2u_G90?L`Bx>`!QDPE>D6@lW&=mm3aBpH=<)(*a83mPR}c!qGC3N{ z@}3!USy_8o8f8B`eUT?E!~@JIx2JJMo=Ufa?<8L`T@h}=PO!^W@uGpJ>5U_AQoFUqG~oE1NOIA=o%wHZ1)P21nK z_TZ0zq5ZlxmYi3nYN*)E8IyAgdIvjSrRs8RJx!8kcaRTAR)0^DJCBHcVXkR*86;k2 zs8n`jSo78(qQ|?jttl`8nKhKp)93DD+2YxR@nz9| zPk^J4Vf`Vj`WUfsMHN*$D22%MaX!%=+iR3jsYZ+s%;qj;5bw(ud1nNF)iT2DPB%7p zo!A#;YEgm#iF1R5s@?>W{ESCjC*XST&qyp;{qOzvb4=0Xn#oR{YfcHO=bUB=TrQ$# zgWw$_%q2f-CFZJRX0DN5&uFPIC3(B3=oB6yLlQLzSUdYgr6TUyNSS_!!H{c3zEzUj zs0P;Prg1|siW1pV78A0%RIYXuxoBS5qJ4V#ca2$|Pd&e4^$k;A=po?3} zb5RSIT%K0XbA@m4hf3>Me%tdd?!0Dul7s;uBe>x9qjQfPQw2oK45IEJ>2m$xph*Oz z`)d;96#U!WGo3^{EM_;FQgI^E{`Q?+!0XoWit5*kV7G=#%~BybENz2wlW4>}W#wxS zB=i_8CMJMJDpgpcGSu^$nA_6tef%`7yk?gplP~m>7-!j;_)-c#4e`*6b0jubt<=l1 z_q9WjlQTy(%s|)G&5=nGhop6rOiJoa4F7P{QHUS$nfB2vd?km~{prcgiSNu=+4P=W zd;Gj=9@t>OgM|de{tAmLX)g5;7gfqlOuP)1jRjXj8(N(fjO zav^EADx0GJ@VOJfVdv^krhytIv&SfhH|@)enLg6@$;&DbDEa==lru2*$~y)z!|H8O zDWku)jf@f~{(fO7isLV-f>3-jtYy95yat+*Laz6Otts$wwSV0&%dg<&#G823Y?wi9*JH`oCAUa*4{gPG^W*HBB79w$-TnuqKL%ymK&KLM__QRD2JiKy!zE+ zk=Y)D9m!~D%lwHiAxE`igeBsBfh-w2cTPk5@E^MFzqPPb{g`9_Q3_M;*^F@UU8MP;nbPQ&f8uyP=D;1Tql+1m)i|Ilzt+K`RSxMHtXnix{yCk zxCad6`rbnfwa_SxM~pNjA-eEAw9gd4W!_zlEE#*ZEQ%kS4phxU3JVhQR~EQoh~!CE z<&g;7>5408%??5BcUXhfQ_R0=EJi7fXsn4os!A*C%K`=V`9N1w?FipYMP)o&W*^TZ6hMR&QT%m!= ztTrVZ;2i{NmfF(0$9K*k)*X*X(Q^M>_@OVtlT#&rlT?msGKjN5u|fd(_^WMkLaOv{ zQ%X5*C88tGLO+74m8GRIZMiARhHy^U%7WOq?tB2mKEtts?-MxHpUHd26t2uH!X(+; z>03>RAXFuZrm)L@r>0?>SgV*T{*~(jY2YHXSpDS5zr4c4k7-m4038y5n9eOn1z3wn9{}Y>rU$F_o*qWkRo^sTn?Ya!U_JXfePn_4K8|* zdD#xwOiSzNDf%=S8FlUo^V--W#A(kqc13|73K+-Po=`eZyo27V*coHBh-+FJ=CxoY zp*=Er0ho7mIU8A>s)O;F*&u3drl63515twcnpO7TbP8BRhx=Vdm0#=t!^+y43Kw-_ ziR~=RcEYmA86$l%Tr}tt?jb*8~C%P}XMJaNhzaU2rYF8o$sUsg`y%dAEt2 zBd<(;=@qZOGeox;c!iJuEjPl48M7?Gh#ZKMt3CLya7W*Tc@31&VBI#Tcmxfb{@v-*@Wlv^0UIc z%7Bt@{YxLlmh7T8KvQN4oRZ+(T{UNOhj|&dnU?G!q3lJ&7n;T2YDW$kK|+0PkpN{M zkzT?+qO}F$r3PoeNq-RyO0|dnQH%TbmI^oAz(X{%i5U>LPlR0CO{Cm{kE~?SUH*OQ zWd(c_Oxm?q7%BfsS7Que?u?#YeQjU$WLfE6rAibq zFU9iUPR!Giym0_nCqeCF85X-nZUI8xnxRE#wYp4PijYS9N7OGEQL%ZgdW*W6jx{~g12Wq-$fqOBgE zb_5T*P_^#Msi~Q_ZYpWajI##7m#)~_z>0n|t@xzVYpi@>rHFkMiPXK8<9A8i)_&I% z0Lt~1Ia=V$-B7pJV5bmUjH3-kT~5Aue~HO*&d^W;E@sfw6)?U=7z%3DwGjK)JeB@n zmU7Iq73{AKtvYseA{2h#~sQQMYn>J7=`y+D1>`)hLe{6NF)wrr63 zOlCY3fG5%SGA06r`-eUTzODTci{8uzp2HyFG(*L$JKEQ|K~s@BUmH#tpcaE0gF8p!u2qp{3en}dKO@OSop z@h~JMOD+`Z;1zU6t|{i~$quUwXk3~gBZRSbQ~R|}C7GZvca{WOzUs^{Wf-)*5uJW4 zl?8!(juGeyWv3^Bu)B4WB~A9Yn2T4S=c1!3t(rF6hOl zw@YPRUSj$o9vc!?Q&P1{0i>i7V_ExM=8t}=l!_9G89KioneibcXT`13jJVtX(*vhk z!f=g?R$r^;W!{!Z2WXh@J?E>$*k<9VvXy%`&<9p{==NL;1)@LPC!81NHfOX<&=4zE z{)5G!^o_|3+5w1iJ;FvP^fDP;`F6Gz7D`Oa&`7uk%xD(B-eL zEDt7B$@;LIvQI9H_{$p~mYG*04Mm=I^iU(#RoYq(7BDa8MP#M>!(!NALJ0PIO!V)A z*ikNh%K}LqrX@{i&g8zi+n6r>H)kH$?)6T(-r63<4RQ|;S}xcaS|!vM+;EWH%C_;3 z&PNY{OuGQ=F_m>&3vmfEj=its~AhqZsPIjWoqlO>HFxw@+o zIQ8NM4x963^h-2Gu;BChpe?`xv&4Q**-=BZqsx!!_yeBq<#8aQqHEU|^tFF8eb-MJ z7vOu!QFnnW!U(Fh!jQV=@AAaGuf2R8H0=n_E``1lrIAJDik`Vsc5Z1jAwS7rK0kV# zy!bS~abfMi{^)vWy)dS!)vIPi5zO=Dn)3^O*p6Hs*R$j;l{qtc{M%hV;1qs9wr_(l z!ZrH!aJPO61-flWvZG7!Y4?yHu!yky;>y|UCjOU(svpD7YH_P>jO;G(1^5_ia{AQh z5AS8aj{Sq22PlTM@bsVokt&KWd1K3NM3mSgYY#wfY8#XHc0IHKnveW!RT!P2TbG_a z$7>yKxvNR~B@`b4j(wY?23RG*Iap3-yr9=G`Kt9_VFY;}hy|KQt^OONA(1xOG9~MT zSXseGEMOmspYif*K%40n}i;a{rEY#iFW+5OHq)os>7)QjKesm7KrLq^91s9+m z(nFyP^J5De37=!#+3DIRmvkL~-zC_51xa=4?&@eor+@qO}x)VH8QeGzq?^)Xy&E zxX_ix(*8r{^pL1ifTA^}<5#yeDjwvmuKf>#kCvm6X6U=8`C%Q`{_x+_(BSY4gUMEz z@>v7ve%zvk#M7xEEs=FR#wM-`2wj49^~Q3_^${U4pX*i|g2I;fL{Z%jS^{QS|F-9b z^Fkkm^7!a5ij2Z*T2A(%UZBW5V-k(apIo6(pl3#?bzMBCAzx3IF=ngYiH=hy=> z%fc3wL&~xl>7lyOj6uvF0zHqGSzAOXTXpbepev^b*#H2~d{6gh(qb+>qFWZcY>Cvf z+%GC`S#ofj`qCwgJ6|bAcnU;_(W>VDhqj*te>JAkn7evF|wB z!yXMuB*NPL7a3u-(mLk(&9ZFgU00*Q1L9N{xV#bWN1R>kCsu2xMbks)&sYJ+ipsH) zmMAt2Q$??^BjGpKVgs_7K$9tuOzUgPL#^rPvxQT=dJGxcD$CFj8_kD5yiy`1EHkR) zS6**SG504s{{-Q6SuNfKQ!47tW(Q8d#u*dW9eim*k~%lSZ8Fu%10bxh0k)Ui5P^qc zWE7{2V!a9k{NLWuB!;h38J$f>3U!9hBky*aNbmyWUDmpZR_(n@~;&TQ&ke?ve|piz{O=1zF$#P?mVefh1?!nwwep$np;D!`C+|5JI&dy%wyq) z@2195b!YsC>#_(-#kkM(Td7Mw*LJTi#}7#L6*S7gf8jBCsS>7?G~lNlDG3;ap}cI-+zy!&h48Vhmd=eYU)?wDRR368=px;I5wLG zB(JjxNPxBLJ(c#$<8~kC#GYTwi7mvqUl$W_m#@Xlok7SSjDX zAVK|EVDcsSCc3uwA&INQ54}V6$kvEKmo zdIV|ax-ym7AItwf{=H7x*h>pvpY0<#?&`y;QQ0O?-{?a!)#(#l#s_gfRrT8l7JP28 zea_hMPOv!paoZ^3iIoCTHhUb;qjCLS&!&L^1!68I4;dZ-qR`jS7ha_K{fC(wJD`}b zPQMhFwzO*Ebb6sRaTV{dLAo2ddVvU0dRO1OT>SkYr#x+xi>wqbMX%)u0(1XUifFbD z%OvlqU(f-C>{V$xpWy%Y4lT$WO%_ZOQt9CT1N^uyM#O7ucEFl{pW_LP^ZtheBH1iA zyIdznPM=5CgmFjz4EOyr0kS@kF@Zmm8L+#(O(Pm)E-HdAkMs=sMv0J_)b8*unqksc z@%VOWmY+11FOgo5$dGkiZ%BH#M=_?I?a@3|8FfX zan$}3`As?G{{RymiyjYvadu3EtN$#}OYu78QNnXgxqQ3FWt=W8gC=ZvgSuw~`z(_dS_i=P( zsA^^G*5cLMC#f&qce00v+^h4kunQg&ehZgMfwIhkLgmKD2Ks&dq^c7yT6EB|v;xgl zo?8spoPqHwy+yxlFug5}1_uQne2nRCXf5Nsw%B(Q$6f7Yc8sSjue*hQk`g^D z9Yx%e)KL8T#cge~MgC9txUHqWelN$0qm_o-X(wSvqVOSvRKQITIv(vodVa-=c<}+E zkPXf}v)g`C-E1AXWUZ=``o%15apOh*yoQ~7*E*r(8Y|K5!zoz1u!SfdgG<;WE9rOA z1`2ZD-~63)=AGI+!VKp^%BF$09=%`2Sez6&m#jS37?QN#;qSWkpr8#u zA&3k15&wP^7}fd&QcG->MFkr$3C@gqKleJ9LA%P+l-=rT{hvwk|GwB*cWMy`E8)^dbTZnD?KO*_wPE{4HWS!lrmQ}5h-Pwo;I8~1J76y@|NotL|Np*;)Am0j zTO&rj)o)w5vJ5v4b$OpX?bl=;^~~Wti$I1gSy16~Sdr4e<>Ce%msvWA?n_|NCkp|3 zGVMPH(JZ~B~ z8+pZF|5tboY-x#l_ROZdEV&j;&cc-_xh9lrowNmDkN!*fV)_7E>bTrs^!n=UQiWX+ z$_tLz+@kVhbC{$Px$3FOO^*6Mk^BGa#S5u7-H<{|EA-r@ds7XR$ODspOOah*xM^JB~&|$08m@RQ=5wsXV*9| z>1l-2nF~w+^^B(KyyFzRNQG`$l8)M=Az}h!7lm)>veuz+&e4sN3-%HAi08hhL^SwT z8+%8F{s>gA2LK2r5q(^xRgAnU$v@#&fix`dN7Ar3i#)ZL+w=vo@q)j+byBo8KoR>k zcor|6d493~&KbOoW)r5sttzRwzx542As%UpImGjW@Y zzo-(-s@(o1I~T-Z-`oF*l4=i+(D6~yJeJjxPat`dBEywaY>GX;bFgI_49`b|M|^2T z!eAFYExhUDozw>G`&C6nRYi%34e3nje&(%Q`Y+|;SbABB*n76ntiQI(9|@xS6NM40 zX6#*O39aF9KBO5o#sBG~8UKv;t+i#@s8U|=MzgNH0a;DbCd|qz4e@Zq)L3)IsfxF@r)qu_Jr(>2PWnZozKN` z0pV2y1ouI683wb!vUIc(*ZB2YY2s9w`Y-*u9^#AcF8jGf{I~=2xK23!f?-}u_xUp{ z(rrYTD4}z%>A&9`jy0@XG?f2ju(;2Y!Q5sYj~W~BR{cfQ-muu{BYQ8^r?t#Q{vNOa zjivaWBtH8ZZL+o_t6w8k=)t}j2DS)=)6SZUqOZ!!#rz|cO>kn`*M@X@HNOIn34QW7ukzq&?0@d!i zxd$AoYS@o>+Bl^u??tY&1s>GZjbHQ2QyM}5uei_E z-m+UZB=lzd+6i^i=r>kV6)VEUuF#B@iGZWSU;0D#b z@L|VEY2jHjzN-I+w)cQ)s$1JdgCL*~KoJB22vSu*I-wIligf7&1f>&thtLECM0(Xw zmEJpnAYHoj9(wP+3W{g>?fvb&|NGxN#u@iNXO01DC0T1_X0CU>>z!|T9&fo887&go zlkrK@IPt4KD|W8as(S+UX^>|snq%uOCGSgT2gJ-AVJ(Th2neRvmr367UFH$PQtz|; zxC(bTd-4+!gF{>y6tblgk0OtKwF;Y^=O$az^N7`}H_H{w<&m=GfF9HK8K%D^LR^6br9L?$%rrMFeUdLsCs%BWr@DdNFSNteZB11c7>{b_1ZAe*WAyd1nt*Ha@Z;&Iwjr=i?+3_zj}6S2qVE z3;^bm@izgWg&U-KB2TRHwoPr_;-j_7OXd*f;bORReAu88QS%y}(A|@8y1qZ-u*iZM zc)FR0BKTD;O1c8mzvt9O{_uT7q#(aQxK*9vgnWvQc+E=CEvL78V9ZLNouG@JkdUv(!1K|g%$)2%c7}-00E9lS zL9;N307T{vq>@$7@UNxS8kyAVPTIM7(D=@MDe+dA=ZEKd)t54Pn#9VH;)vZ?N{k-n_7J3u>Iw?2GLZfL(O~0kk)z9lh21~k zsL%y`!mDLLU7z!kTxPl;Lc2+B6RX(Wok(QH;U)e9 z+(R5F$Ez?)8;+PLyR) z>rnoB+R8VbpDqTq7%H|@*s`m+O-8+K`aEZ-EJM^gB{q&6f}*5}%#$ocp%tToIRNoi zA3#`pY!Nm^7?azzI};UwZx9f)jGEvF%!4eGKqy%dt^2?Ur0^M{N);s_b8U#t*p}G# zVCSXre3knyTJu}i7n3%Cs;fG)7N`3rcQqUj(9wDS($UAv%kN=5PwX&{V>Bsla=4(O zF=c-=I<5K57dLKuV`(0bS65fLo-&4TlFL27AUnJm7U?RcslK^i%8{(K4*ei=I{h-t zYBpCrcpCoqaKZ>^Z(9sy48^iY*hSjE470d?nUH06`H-?tV6Q0F4P6VWP;zUO+v}Ej zes(Ux8goJBoSB*RC1Pl3xJ9{B)T=LyyIGARTGSKob`JoEF->RALBWAQqozzrLFWNT z&v-hnDua~1PB{AqWH`8U0j8;fcW+Sewv}lxD>6}Ta2y~);q(qtvW|FGzZ0aYzju}C z>gjgRWx>O9A)~lznzJU1N8ScKtggwwBBMg|+T>bEicnZvU488NlucfKZcGr^HAbL4 zvr7TiIo|7F*xlfewQVYFdYQP-e;yP`$e*OtP^WF1*k_NnzIaq103H<|0tj+>QIrR~ zlz~DihEi5y(7P_-WL2)dQxudXW$>EZ>i1dW24Sbl*pCnE-mq}ek{*5>mz7(mjNXH1 zLP1Wx;33XzQQj0AL+RC*^DWs~{J4-R| zoRs5^RROgA%)&qkEj*}`XdvlCm?X}h1;SGh}ha_wt>E3~L zTU*91h5{Cx#mwlKib-c#d6zt6ZxJj#+u7feZv=bz@xDh7jV8q`#YIBb)b}WVDe>&{ zN5W?)F(p-FJyQkSwsxkt-z<^PU15EBGcea7F)U-9&FgNXl9H-NB*=p?7fSSaypH9~1JJNMP;zb#1z8bvpY%VJKiGZU!yPQ>?t|ct^P8 zW}oA6vC@+ly^E)VqqV-z?@Nl631=7VWL4=5B=tcu@s>NG&6t}ASBF|p~xerQOX3>>ytFy^7PODTewA;A$u%=8a3EvSQyalMKgsLGq9kzCF+E^x+ z$G(>Mu-7TtS6F4%+8?2+ZxVpcKP+z*5~W@qKuy?rAZk*z4tb{c%w?0O=pVUz+>3)O zzGpeuO4xroZ&sdkgwtG!yWaE3&({1$?R|xf)IgEh8Bt+QcR!XyBW1JlGPjS2kUCSx zTgS9HpGH0}708=>)0_8pI&@zZ$nq_G+X_HskodgdJ9)yH+U>eT&Cb+L|6+Xo$y8^2 zk9dlga<1jwk?5tt!|666g9sZhUzRr|jwTFgQj6Md64n7Xply)(cWK*GeeaeD(DZIu zdL>Lk)JnBSKXG8nuWvRl_$Y|?ysZD32MeiweR zh)+sO?7$lEJZPt=)AHuy_SSA$rLPZR0piU}pZ4MNc5Ij(+!o;<@wZdgM(Pe1L@S{S zTDmF}@GMA_J-u*>3Bzu@zzRX&yc$dR!PdF+%5vRR?S1|fw79A7paaEvFG*6IghaYP zdnXA&p|$n-%V)t43}1^ey%hzV&5X0{JBM)0;1mII62tae1w(*Y8A~Yq3|KV`6Z-KC zgxn3i#3LaA<5I7*wUg|}@qhfO9Dd-)MsRzk_-L$Wo(mFT0*OhfbzZ*El6U3U#z6q- zrIxb~bphsLBmJ%ByX5TWqtZ0?pa z{KG9JX83}6W&DBk{Pzy@!~+Nfr3xeHK|kJih}9g2k`$!w9pB{Ce#VkmAV;7)`~9%3 zUz`fyC#!vd&Bu0N3X7h0i;4FlLHpucZd^&MFk)&`eT?vpIZL1__#SPDeu^oBbMqQ9 z9xXR->hf{7qii2~Lsi(Rb+tEsBGFz$ecZe+VzG}oP?4ZNU6iVCwQ~x)06n%6Ye_G=wU*nW8l$3A*4|~wNtsGS6oiN8iSnpBcbAtrwDsh*GN;DduY=G_63^_}9kfF=zCx_-V~4)-%o zz0>i9O-9S$JJ|stbFpbcyHjs&Ej5$N(q4f0CL_|RqOTJT;Z2TYz;E)}nRD=iX2srB zxI5krxQ=k+sRS(IhZ>?-qiZPL*ErJ-|*<{?Ckmd9{!BBRMdNZg|Agxm z+OA}eHwdHYHpv8nm#k1k)=AZ?d-*x-Vo_X9hibf`*u?!KU!i>!AZ9cd09aKiG{ft( zAl~PMrNjGnNWoDExWT$usK9D(LNq@9uoDdRnnkdgMLI#7sVs!gGDdyz1f#M}NU}!< zx2C@d79bNi@NeZHJ`gRt0L2`Rjz^y73~3nqbL&y}=ZIN=H22C)Qz;`abhQGc!0Zj9 z|AWBz??$7ReLc2!^=PmLGb>_pI@h?;wY)lv2^~yAtHAJ<<}TVH*a(OL@y)z;)jzIl4ZmH%;zgcpywn6^a`dNKS6yEjOESLYJv%5O9ESgN8Rz z@irx|NazApfc-&C|72tMzq*0tVf1zyD{YWZdf6V3 zCZIQl#$ey7>r32;YH5S|>hqXYKUTn9=Tgy=94AX@^A5S@;$lE*`_P*>EK+e-n4OCq zaBuNrXCv8?HzJbukc1At4beBfZNTsA3Hkw;uMkn9t?VipWN*OEU)Y z%m~LK4gWCG#0GBtv&!~=V-rYsnT2&;7NCq9Q}6h}{>Vt2LXlQh&2KwXLV542Wfy@B zxNfjh&!AeamBUrbr2|nE9d>)msbxqwYY!T^&PO1g>j@;tY`_p>sK9}2*HgRe-ykCj zFeZ$Nc|^ezBnnzH^a4R+r3e}2<$tlcO#3TbrH$_;p10&|lmwSIm~`qt;aNC{^3lVy z_ptmBRYJ&S@W-|I|GR{+(v}nt)E8$tT&nv&1gmUWblp^K{2*r7i!5Ig0ImkRtNW6TUQ4l%p{fc1x?vk)Ye(2**6u&a*%MSJq z@&sCG&DpK>jJv_({Ot@&X;qrUxmaOliq{Jy)) zTZ|L<{LgEV!gKQ=f~MAwrCmSOhJJ(Y(`TwDnU9O1>s$3t@{c6RPyD}`-9HoVr(`pq zKk0b#*E{XK1*4G9jpdHl_rCpj@cvSA>Bqu(Q~4g<9OXY>Uv88R%#xJRlC~^ z2Y4wuo>_~P?YIIU&flN_AC1$-d+jADjm0PHr#`OUZ-&h#zp5b@l~q$3b5)IX$Ip36X5mf0rJ2 zk=xy*3vY<2>-76J!6ytp2)%gZDYWO4{te+q_R6v-lJj!@pvJtwFY2PS`=_!0G9`^l z#B|@vGdRA_7BH|sB*Q)@h`c2&upaO7LknmeD7IWwLr-|WTs9x^50ZKcI~GRK`lKb4 zCR`M?sS+n%Pb%Aw^t&6ST)0Tbg}mH^p7Jl^o-)h+1~qefN?hi@U2j6AGaV{+=JE)B z-i9-soE@W_6$-=2R|cG$Soa%VMqX9VE}}w;=V_ek8!}s`(jz3)e0RN(m;%;O-i0eV zgu;r?W4^avMb9k`cgGjKUE2CnJRNrr&aO!mk0kGXg*(ODP_x-amW%D3d72U|Xs-A@ zI`Y5&C^93a^ZIE33E%a-??0`9o4s<)#WY1O1gHBzOu#Hs{5D;Un62w4aQM@>2$?4> zln*Le%T`_w5x%b&v@hZIc!7;uvN#Fy$mZpnYn zaJ};zWCffPy0A@|;qe=UX&R~ARNVH?Pcus2fE2siPdWLU0vKYf{)(+|q6!kdr*CR=^81>V zg2DDu1L34L#IgoYr>HAqCEr$V!ZauvPpR?ra2$69l-VESc?SsLx5xZ^6e_W2L+l@| z)-xHjoH>ejQ0~}43)Uo2cS9)+SLNVwdYtkDd2LF{SQ(&xGy(O~J!CxFGJaRy1DIie62jA6W^~zMX)Dhu{&?%ip8|NxO)&C& z;=NIBODDr)QydAE%Ti#5Iz?W1ZH}*t{bUs@Ru#()Gi`S|ltZf%m`ytK1c-5_P;B;Y z&8zzBc68?9o~OQ^+oQkN@^*7z%XRhCHv;o6YhMrj<~JytM=4nM;sfxPT70^5Lp&lb z&8zrzQslfqa%aLdW6niKt&nO;%;{LsW1sYP3ALpy&QS+E6;sl^hdJEReJ5AvY@|z< za#e+()xpFHzNA!&jsi1c31F}b3}iF!@Y zfbYG%FixSmhUvv{-IcSW26BVQyNdokoZ*}2=3jB&xk#QK=0gPps($!ZEfZrB1u4B- zM;D&dKn(@qgWV!w;-)zwsL+}OXUZ6$qrkmL9W zirlwUD$sYsT_vS)%ZyaJ(DGuc2gIR0xw9UPe|a|L-C;dZJ$p^tcH#Wz?ydT9@kB^r zOB%-6py!^ZfSdpd;V#S{S+_^G@%XZ4kv|R4&)u(-xi0`Q<9Ihw(#A z=U4(#_{q7TID0;!%>RVzA~N^OC|7@JWm}C7yNyh3uGJV;6ovC&-0XCEyRray;Eh_t z!j_+JDZOJ6Hxm6ds@Xx`woVX8B3N&S8BbKv5zZF5l2?K7^G~(A9ZHYQ#>~O%*A=Fub(+7__#ydc-i5;5N(s zPSThzT`K9ig}nc~W0U7NV}d3sYi{Pu&EKxlDp|5pT8*+whC|$u_Pfii2au5X8-a4R z5L=WfVw}2=V>dBuSrPNZZlso)ae(cH_%taQU0V_vnQc6C9-<|kZIP5r9{{zbrKduP>0v_ zcNbv!f)i*Z`~iEdOPg7Tg3-&yqUx$~1CpmV+crzwH)n0mRYVeJv+9sbdw)`uzX!F_7M zApq-K*BM>SOMN@U%g}xT=KE&An9{k4`v)m4 zwDL(TZhdXm&8tsjVL$H*c&_yoYm063QF`6ttOPZyj+Y?ADL|X z#?UQ-r(=V>4jn}`X&Kvl*nEf>gpn6MHfBJ)4!^5+s}06`=S`HOXyC1f|7nK@1W{qB zv82U=;Iv9*n&IOKk&7SS?ChcTp)lt4uW!i^wh*1^U7g|8sp5IfPMZ>n7!3@BY>DRq8V+}SUN!5Z4B&plLUwVju>>&b^{oa? zd-QYsgB)ImQK;8Li1P!htj#UGZ$=T@_JBa#DxIy@*+FQNpsHGO%xIX7X-DLPKWl8qj z2?r)j(j7@I6b(e&Uud)`L9&sI5#`mxT`!M7&0J31PWx={Vc7pN690S=^!A`lOzzQ= zS$Ucr5=Jnn?m7hDV3%Xhv(683HS^O`?sB-t1HLs|aTM z_oMy&w@_^4&GhEAO!O-mpLiN7cuGx!J}xHK(gupQlIAf!Er68lQ5aP8Rwh4F{-rI( zSyU8!!-eDM?!#BO?>Viy9{hx@z?!P6-PXES__^RHYE1^SUU*W7cCa%`BUiV z!qkr>lj{$>cR8=MTd`UExFq2S{yA9JC?{50Uza~4SPpp$FX>=~ihwx$?f$=%K-4a| z-lQvKZ1L!2WRa%&u#gzEQ8(QM^4HpyJ}%%EtO&z{@cm-Ph1{zhKC!VGg5-N;;Y4I(qx@+!NDhv z88lgPJ*bJ`?~fZCB8ML{Z2uy?Z)ED6Q@5LLg;s$t9J$3{H>n=6>mkwbZwI?preE`f zvcrZD zAJO|UjX6vDwY1^37wcYWJX9yO3|MdH&6~$+a0l0+UfTP&6$-wXWe`+Xa6<`9Vp8a# zEH^7P5e?)yWSU zGjqgc?Zr!w=gwlqbFkV!afJUz(-YvT8N!;kqdsWsbMoS(l~iD$>5<36(|#rAb8DuKYZx+pk|m9DU^$9+q^a3|vsOKmUZk{GU<)3)xD|*#L|6gqCYqT z>VVEtv7uv$n@o{7({tUW0%-9^Kow6(ae#~l*fv2eVu3a&_!}Wpl!G;l-Ibv7PL2u9 z!DQdL?=Ppy(?)RpR}UfY0f=aAKN6q{|1UrGb^VL42qM-5H~Wy`@-0M@;rMN#v6>Wo zGUs3GWF*{BOEz}K4y?D_$(xZRNz;i!@zQ7GN}x2sk&#;#JkYw&E&DzZVg`%R1k86m zzL>8a=6Oq67mi)8YC6|xdurz7=XoLL!}5ci)m)@-Ye7Lae}X#yudThBYp9AOIaZ+* z+uvf3;+0uUYZUAuTodAJNS7v-R6Kb%)mV%b#}6Jpt)8&iYI$U*rIj839jFeA>`gOR zZpi|V$E3}TLd^e8biA3Vx0y^|Hj?0t)R_KK3x7Oa&%tYESw$vKSxe6lNXX6v7kP@{ zB+6%Q+(B4ZU}?{tvT8e&h>$er{K6HH3mX?+gBJI6UMAv`tLPScwD(8aLIPX;R%xKR%3>%mHqG6I?QX6EiKZ z_Do*2xyvMwyKC8Mg=VOkl=t=@^XdOwqmj(Y_zeo?Sig>9TL$=118MCj(|gsPE@j00 zW0LhJ~5qdDXi<(uAgK40IdGS@y9pbygHK{ntv{}X5Xu?y!C@b ze8TWtVdR{|`Lhyk!sp6k$;^Y~z<#n) z=?R`vyOYo!yIq08t?4U46N1bB9nZPQYI|NdRNx%Y2o|XPH$IQT`Fytu__& zbD6{gm#>2yPo9@u(Qh1QS=07SJ+}HOA`{8nzy6%>XHu0nnVsx^6?b|+D+S*&5#*>& z%=n0=@s`c`k2iE&=URTyW%_vfHyI2Si0OpZzR#r-AC$S(96zJAv__tBv&1TN&8$^7 zlQ}Bjz9D2x4bIF~ofR?y_ojH!_`4E(7O|R_jd#q`JvtD@Dl3aKw-ji=Fma_gl|b1vPV;izzht{8 z@fLIbX+~S3wpQw3XV=alLP~;lpEf1sE}1PJy`T3N$}0hSEaxfZMP?YLVu*HZF$l7M zSD{0E9>ZxxZ&8gmF*zpg#@bco%h}gHR<5@(B`kLSmIIIecomkQ#Psm}aMwZy_kH1S z3n1b6J2IJxZ_=$HubOtZwTH#jyPcyqFTEyVev30^-{`w0$E%w#cn7o8#F;s5r6|-; z_L)ZZqR#}Un$vtT^-N?MEfgay%nz;pu@{~(UC%VAW0!0t>K9*8$)hRc?bYje`6;SC zVeSP|6oea1$ouV|l6ON2FBU}G4a2WV%6}~K+%>Xt=ekoYa;OFsBBK9Vg5$g8<|#GZ z@|LY6h9LNmkae{nFl@{=rv{$?Iy*D_eOU{h%B-2KRht2U3FxmCz`q~!u)}>@TbH?o zaeniDHW0~Ckd|Z?eIF~9rBHgRq+*`SgC-q++ivHsX6q8^eFX(X2x-wAtmg0ANJjQd zHCNElydL;J~xaiiMYxXJJ?%$3o*?k8O_9&e9tc#V-e>E)qX?j-2J4V0JW!yB_ zLrBP@$s=+UVw{mFfE0vKjY*f6UAU%Ig?&8@1W;`|Jog;-_tqcs)Coll_H5r{~7dw zE6!>Qz8??@hwtLPO6HnK!hBfE9l24lsoqh3s#283_No}{fG;K#fLl(GdUZ3$N1TD* zh$E;oMB|0PoO}PwH6DG@zZCSJornfDL5fOtL8BspcW9-GBy}0Qgw_&~{NEtuc@pFY zqH_|tb4v$ehN$b@8RRbp+$Pg1t@?EnfRo}b@PiKf5e9}!G=sc~Vjx(-V~n)z!1Rrg zFPuWwPm`1q;MTai-|x2IrZ(U2QLv^yPoDe_IWmPyO<-iCuI^Qu-T4%J(XSSW3l5wzz##qI|!HQyQ}`&=UMq=Ul;Ucz@i%sWpXGnpZa-PYPMKDX8kJI<_;%4BA4Z3`40^mp^`w6s@msiy;(v zR-ffJT4P)lmw7f~msyg7n4Zuck!DILhc2j5TTnCc#6=8x-id}0vZ~O@Qp87(4fjlC zqzQK4ix4J71jFd1ZxcS*daFC&H?4{q)-u+LO`C`4eg6&W)l!y|VC_82h`YS9y7VwR zgA2xIWE79yKUSg>C~3E|_@(^aR7NHRBpTl4J466rkUej#9L95wpJ~ZPqw8mXG#iyAvP+|tJFYQ-P z9=#&49~HR%G}V}xq+x^FC&)pd8Q(|DC4P~h1i8xW#TsEtLSU}N)SWYi!Bjw=Du2ac1(-3PC!QMGyGS$H zaX!@($;0kAb+vHC%!s|g8=qnww4GKNX42Ao#KnI?k{3((Q;@aeJkgX3r^Io#yHjk1 zo{;whkH$D>V?a(tcg5}gb*Nnxs>C!mk3L3EM;&3 zO)AVMDld_01#eh0<$lA0GZ+06SckJ3<2N3zH%MxXK3kGCDlP1}u+5|IlwsDN-ix3Y zFwUfuE1tyz+=gCc3QD5@otf%zO>u^x2W~3B`o}^iw|2!oxmS?`n+i=%GC7YXNWjCL zIvY9}^?kI4^~)0ouM%0;H-=D?{0#C@V6?W9gnylzFNO&T!qCMO)#4huCc~pim7JW6 zg^6EsKE<@s(2p;Ru1x<9=QdXxWclj}YNg+K(jV#??mjm7au51{Zw( zVD-8)zgQsaV|E~ZCv6{|gFq}#5r-!pvL?+ZivMn<#bxVIsjEt*j^5n5hT+3`#7pjr znOlg-{aJzLpsBVHJnGvwz(O?*Uky%F#QW!SI0d}x)u$I-$KprtU=%pN2o!4wgUoaTk1@BZ*%~F= z`Y~&jWNVvUw}MAs4e~ZnDlE8BAhvi%l71h<1YQ)8MPmnR88BMr1QKT2w<(U=dW(~1tm2ZN*9w+R;zX;i}< z+>I}UK2)5oQ_;)bbzlkxeuC#p7E#`zjiu=LSQwt8CG@@5OF_#kEV^+o}-$ z!L~^%*djq;9R7)7<#oa59cL0$RI~;o--Q=KaJv{r>m@e9)kZvMDtD)9s}00kG}Z2L zBRe&1{C@l!+He={3GV&!895JCPkKBSi9vz0$U(st$1yBm6OzB-snA{1clypNxH@oh zBdCA2Y!{+thnp4d-QlD+%hiJwv~Oe_zuR>odKndv?GBSh%yOA7s698=PBG?e_=C8F`(DX|Y4MH8;w%@9mfZ$X}hb zG&t-6oD-UMzd|mqnEu;fr=k5Uxj~zn zj@eIkf@#2{u=!+#xmd7$F{0JkuvG6t?4oE*OTbH_0AsF6sNxjLuqz*ZS-^s-$VwcX zwp!-X(P^4%CtKQ=1c@rZsLznY##Y|PSu9bCG8SLTv8*Mrw^0PG#+tPqVzmnAPNepm zPy{@X+d0VUBxiaTzk4^L%7FT&Ur|w%A0hKH9f#R+aS}nKqX&FCJPkMWB|yLMOSj|< zhMzZf8Z)LdHlammObZSr)Z1;I;m2v|^QX5G#NGhkA1Mhesn5)wJt;=MW6>6nZD}fh zkE?imW5JhDKus#5#QK9=V$sxDHf9)GkgT^==ri_$aOqPim?X;QfRw~uirEqw?5M6B zn$~S<8`Dr~8f>tZ5-8dN>&C&408+aOSwm|KGly$>BJ^D{+8(cDo2JS*I57fcS5}+^ zo^NVNT$&SO$@DSQyADQnFAH_GZ7N|4u3R|>a>FC1D(?rjg+4-K7lZjPzQv^Z06^Av zY%(3Zx7AOwL(EYIM9P#lh!(&N#=jTq^)SFe%e;NM`1~&at2$a}MtmNFgBrFcLJ=Jy zn#HdAGg@5+7cwg@+rM}&{^FK=l~MNQZsK&YfzGsD@uUlb;12iHyL zI!usXNST0i%R7a(bPV2d*4{k^$u+3#p(=qAm%Jrka*L-3r^LE_uHM@41MB53h9psj zu@EEMPPMHG*-7&{4PO0B%R1Z4_GqE*#tGBzxA!>_1sozmDq}WuN={+(cG>o3iOMN) z-Nm>cQq({McY|I`36xBpW!jlHln&*|aG(m8i=es=RqMVIK+eq}2 zQ}D1n@3iu@#1mXGuhg@zP|MJzAj4f3b=TY}yQ;12cfUa@#ygG;jpTGJxE?0mp!-$j zQ8UbM5^H}r2HBlhPYX2JioEzz+5)j}fTwir@!L7M$Q_8ra;J$#&U)Z}ql|WGj-JK~ z_~XO=a;iH0^fL0)arlaOgvVw(qN%+EGpanfdlCs$Yuy(r_Q36W(-wTtkE^rYU_SgC zBs(~2gO~-Uj(cm2Yu)y=&JJU}-Vm6z7pptTm;^XJDoflO;CUsNVMKNmIrDVl0^;Jd zBnV?sbjta@aK8r#(gr;YiI1KWDcA)EDa|@mL$~ZkHMP6bkr1MR?_|>Znvs2+omMnx zU9C0w;UV5+-`NT^)~l#=vUJQ*Mv4_+my2DUK7&VK;8BeuqwBxKrHLy?hb$aWv%f}1 zO_yDpq;Hi41O(3J@AG?msLYg3+~3of&NnYexn7Lmf*vg}yrlzko`Z8wA{%y}s^f?j zx10{JeSmB5aJ&zo?$GUB>JQWVHqv8%8Q=X+@YZ|ro8C`G(!##;!aYsZV&#I4?@ z>^g}m@c=#EOMri`na1vjd|q&3{)K?V0K_M_?+Ljjf+1=EN>$dFhp(}=5{rO_7*=zZR0V!o*-M47F}N-)_Rv*QBKPhIs}p4k0~~MN^sty% zGMi#;_f6sa-50a2ZXZ;wE_tY9)52D{QR~nSxdTpDWvBDV7J@hIJTF6M8BbNej=Rx7 z3|mwqFkn*_oOkU|7Re*_{LCSovu8#8aCXC!ZqmbEBM zr>oDLseE&oI^z_}9VER2$*QTvTFi4|?GfTNL26^28cizXhCf~rzu!m9K3elYjUVB5 ztj6DkTY1kbThWPK?G<3;WfbV@s2DJcXh4)JAZqX-!>>dtR-bb> zS42t!odc?j0D@Od^0>X1;Lpnwb=X| zZpA$NBSMpyWom$bOQ63)KHO#1Y9UA$ARBTmo^sLm8F#;u9Z&ksMB*lP7xvX9n4BnR zx@(yQ{{nDWRl5(n-gGY;v&(!_?eT~StvTFQ+m&HzF!C+dC~5zY`RD|M-bH5#e2{K; z`aF_|Y0&pZS9({+t8itb51R$Z`N{ev4WMUqbA&vN!S$vSqIzF#+6r#sWM-I)ZcZzy zjfEO9#(g7TjtO>;^>l%y+C|wVrjly2rk7*6XzF#{j7;q)yHcNgwohay>a>ZIaY zZN`nKG0jv{Nd2k%^3Th^ppTx_BlE6eW}$P|9%**#FQ z-5Q~@|6CY7puXE9a$Co(THE2gTn?HB_UxPw#2ynhe;bH@w)G;1IQkOXb2_z9YI_Nl~NCq$7zz*WHMU z#4o~1Ou(&2b7eN*_pqG?7~bGH0;yY>IVSDHs3^tY z07JW~RK*hunOL6zSVq;UdnvY5X;y%~9^EeQm0Js=GiP?h2zKd!8M@ zHkJsxN965MxfUJ}iBCfvw+$|_rurIie$My`@uQCF2zPj_!IC0DC840d9H$c!OW#pU zldj%QZqFxSl^x4!&ud>I&n+fY30;n)CZGaRl)vForW)njipaHT_>Lw$N0?($d|!CY zzKQG3aB+z;m0~`_yMt>Z&Tp?)8XISEcH3%W$sO!F6p37=t(ZhDQ1R`*XRBrS#zDs? z_*q`BbJh;)x2cj&&!>FxQhv{H!sG#zot3Ngtk48I9xXJ@;XFKmm#X4+@7w*6?(k)% zAe21W;y~0xLY(vrhBqkHyh&e;+Zo+NrUi}K?FD{!{EVl$rG7nReedrPr#C$-=INn<0mM> zV+H_0^f@P|Xlh>Jlk2-4=^kWJ#njeR z3cpsz@|Y;y)h@?_#(VUke_sdK(u)lOVVUBQgyaSmw>#&9L+MvlrU1OOj5OLsR!@K5 zu4?%gx%x|5T$F*=owxMHC-N5F3RY|MuPfA0)MVa)|0UHUkn=K2xxdGCC++NlpcAi2 znj~G*KFP%bgF-*ZnZwh+Qqc3ChCTk{i}FI2e=HwPSCfx&DS#X+`@N#ale-io4TRwP zmjy~O1WDw}@RYbFU+u<5g&Ch`#QY-b5P@0^0k#J~;+zwMKk=WA(yo3{b>O%BtC=D- zEv~=2X^NjFmid47CL|iJ?q*7ppbI2!aRfrYotN*u3j_9VCa3^ z`nYg&Jf6+(U8jD&Aza2c7&R|T`hoKq)Xb^udcD|$tvjClgITgzklfIi z;hx*W{X+Zw?R_CH$npT=We2h=xx0u81PW5R%;IepRLcGANQW#fb|Kx9B`5INvjHaz z-HjXXk3dNXr((d&)p)f>wsGC8K9kObhhI)_swqS!RVBDJk6MchS`>Z;;*EO2Y&eh^ z@#7U9;i)zJeTG0shTxa^z7*W+|5&^oRhf@tBqovCn{j0{_T74lM|36za87V|w+tj;;)gZLHQ%CsPVbOuyy*8%}k#L2lEWCzKdL4Y*Z)UcR29 z8ULZ6pb#4y*a~D8tF8qQS^pA}?2FU>vC%Za0L$=Ig@Uz#@<&ZUul(=hU8dyHQa)bD zj$_4s!ZooxZu;mXqgvZ@11)RcXH}dU8Va!3-~y2!uOlmNc#49VLRZ#O79xiNrD3kT z!_yD|-x;j!FmkAEv&DvQWaRv5>_xjI&l7|FdjuwRCEx*`SOfLv%s{M)%5Nl}f3{N5 z1`Ky9!`c+solR|p9}jh$*B89+w*uHWqjB(5PerQUVU8Wg&ac{Q5;5!#b2Hy+wN634 z9<4XwG>1oY_*k*}W~xov9(49#|6vx8$!s)|CtlC&D&tIPPs8ekTy=VIKA!VR|Q zXC>ub!_unD?}}`OP|qR1+0I+hy(M+KPk-WtQU1!iZ%(~IlTs3v58mH=nm-{RTTfKW`+AvH_s0~88tW-H zbh-Ph(Q!ts0#uEhEl|N6uR<=d_J$mcN=%+C=*2E-B)7(GC|zHDv(QMO$#K z4Syt$IS6-lAR{jhQxwHF9yv_O6Zmnxg)z0vvS+4ks8BAUN$6pMHAsg?S zfX&712KY_|g}<4Bhxua3lp6FupS;Y^53AI&MhYz1c=j?SVq)T`rc$Db-ZT%~BNO`a zGQMn=C@Z4FdzuBT5{wd=4hiU19Z{uP-;?WW6>=0Al+Y7}x;m5u$B!s8 zDE!#TQ~kead(WVz_OI_dNFZ>e2^P8_{UBH%v=A`TL7McA(o5)sjz|y`AwW=2n)DtN z2%$+)kRmN4gc1l{dJ$qkV{{L zycV?&@2Q$-zGT>{DZTc+f++=MSONn*u&kQ*Bq2e$vgC-Plw%Bcv>6s zCxJkUOnW%hucPtcb9hFVbp2-q#qEL!fI8^%CB7v(S+k6Wp_d`%E6*;-9W(NioGli7szNQ!cW75&B0)- z3fcJTjwXvM?P?QPf?4aA@!7pc!yzv7FLKlO#SiViK`X)h)F-9dU--l{Z*RR600P_e zJip1|pYFeFak#2BEi^B{O*N-9F;*6h=W1VWFm@73MD26&v6GBjQI_(4Kl|f?1AF6i z_~Wu)WAT>bV>%YxSq0&g%eAU`Q!JM@8Gwg`E%*z_gEsK2i1C<)_z~nd=lA4DpiBKVk2tUqjeKK2(*0!|Vv2~g<%7z) zAf}C7Y=il*9(7Vak6o${uq!H*C|J=^U1GB9WVt;Qx9wI@E^|xdk7N16Q>BPNzWyKS zM)HCIaJh$86cw*2%I?(#N7>8SCuVk4a?69JMtqm={aLR~ty6n&z>hbAqkVs5Yne<; zS(#J!tNq@8e>t*jiE1b}8^N5`D`r|N0YKiY!dqwqz)V)ov+mHnkJ-2Xtls~=pFaX? zY7@h^EsPVj@BRLEBpwST=>7r?A6=R%JEqon3Wy$c4&<7uB9d*%l7E*x>JB+(C?iCK zJia>y znY2dfSOhTfR}P00u0qQ&Xr`dDu+~Sw7+PGFw!j16&hH-|!^dBx<{p|W`eaiP`{9tC zThV#p{@cw@J5RGhY-?T{sxItmtmY#ra|LvvW3Qxu`b|o2)bB_#0)A3uH ztQS9Q3tYxC)m>vc53E~C3Ps1QVSm|<^!*~6Ja$k!et>{J8+3DRZ?f8&uFAnj`(YCF z57!QOi60F)>i_;K91L&ldPJlFAs_ zw*qEn3>s>Vcb-m8&9kTvB#Zm~{s9FR!yeZWcoAJz1n;lguAyO(k}Ao16~P5kvuM54 zguVK8RYyP|fMrn#c?N4C`$1K={jYgvX?fO9=~!7vEpwB3EjxO?8Z1-jvFQ*KT{v^Y z8-=G)ncj8|*oMya08fP)0qgmSCezh7CBf{V0oXj^d$+8r+$%mggH1!8Mgy_6s4FzH z2j46&*-%VM1|L%jsO3UHU*d=G5@rnulA^Fg2-?QR==K}?fB5WHSf1I3dOa2h zSB3LGW#v>?J8z%E>kDAv;ysP5TvnC0z;{BI6&2#sqPAWKyL@rcQT5<~BE^7F8&VB$ z9eAfbuB4{2qA&*s>hZ6rObgNjqS(8z);bHdWlCJmYuIMaTsv2)=wpt9(DQ%PZ`Sdrjz-o0e1+PrDAV8{EFt)l{)* zZ|nIF5N9~8bFDV>&B5@X9Y(&F_^qa#Zvxx9Pqbc9)s$cSzQC_owze{qbUPWUP?2eK zRM_N6)ron?B#CjBcRgl^_jkGp|{@5coE35Ji#}KgTa-~YTq!7N-qwx4NfIRX@jVi@mXO4)$1TM zh+tRpJ#poa%}T6OS8%%Xxrhuo*rVeb7~W+}_S_ATExo)GUvL}0J|ZGA53LJJMH?9d zd8LaPVkQ?FRZ{PiTx6^#HS=6w(rO=WvMcg&3AIOJliu3)y$kt`xDapVH6m4xFfNik zwybn?U{xiZ@;x)7eyyJ2?uQaagqN4Y3zjnDIPR+@Hsib?eI=yZb_-z>T*NP)^>*CR zkzcD8I>XO>xP{rGet|2#-sLiIk5WMO2WQ)OS7$ARjzqik$UbCgcw749B?0>v8|?|b0AoVDh{4QO7|c43_4dI< z9=BxaJs?C@X#(1cbxt^!r?lAvxz~cYM9dayBMpqq=ik4cm>hDrY)3Ew z78>u(qm?fC&o|CaX4>>gy9G-=Rn1uec7iqzE=gU$n{S zBj%AJ&?!90+u{Mo&AOlMBidn5=;1yf?dh@ zHk0y-$M0R^to(TvddR&vF>yhMBe|eJII+IuLyW`=Rec&mig%^dX!sksZ%q4j;*VL4 zXTBB=!BtfJV)s&e>e>oqW=zmN-Cf1Qa3*9euatQ5G6o9n%wp^w$mP37!w_dX2THt^ zcq>|n{8M>#^rnijx%IJjL1FxYz;0thLjfbB&Xl%oWH$(4FS^XgXj9-?xOc25y`JVp zMNdzCgqgZ+&*P&XZmg$bM8lS?qTPVs@4?nXi#{I{H#$N4;I_|?`H92#Pd&z;<0Egx z7p&VEz;P3EJ{7)~Uw!C|_!cI9r?7QY?H(O%f&49z_hp$j@g1f~x2kz(nFLwF5nSs@ zGHlCzzZ~LR(_?Ck*)NNO%NI1faAtNguhPfIANJjdXR_uUm}aEE#~=Scm!&zlR3MYkt411 zP`$FM%e*nN&cg*#9~W)qj7-dX8t-`b!bS1o4Lh4)@upb|OkHcit(?wz*KPLM&@Vmf zusW=4?kw8?RdbV7AaLT!#Ke?Af`~i`m4(K=(p4D-&&jpXYPlpup_BOdAUOMf)F-tQ zRP_5#n4?s_Sbkp9A@QGTLq#nUtzc81XL(!=gB4%u za>|DyfkCpnuzCeK?75TGhYn~V&dxvA)W-$*W6tl2>$r(!x_Qx2wG$J)2dkC*0L(s>}ZLi3PaW@(&N#q3$Ps2pRc8tT31gVi`!1A zt8l3`bl2#fr!0iuRZP?sIuVpqp_u@oR!UA-qu)n2vl?UG=Oo+uKrg4E%OhWCsq#c6 z8stsxUkL2YW1EX3*jZ-7&6_><&ooZ#w9L%JkFH#aw{~F@fz+?CJfc^V4n(aA=6H%5 z3qJdxV{tRnTw&&c7+U8VbZ;vct+z}ABf=tKYsPvW>bghO6QL)Q$8zJ8#a1m8_v>L) z^f|EsN#yoXEu-4yMQrKO|5b7>nnE^?X;)C81h&^#`kL^d$(<&H>`_O0y|2|?Y#kli-qqu zs@x|bt__ZLiX%-vR2~fJLDHv6+4qkq!9jxddTSbS+*Crm`}Brk-JphVDBK~iv>Zim zW+nccxF@d|s}mDUNy#MZ!8oBN0+sggYx$7kqutR+m1?VtO|I#>wu?Ji-Jf;d?#V!R zB*hqqLoF1VXO7b>2!4t78#8imh#CBEdQ<)w^yF^9e94^&m?`;?+xYENRl6!ztsI8UAmDYXlq<+^;S_?9h%2aywkr*gL`OxQDCHVod?iP zuWIsuPc3tjm(Se_;`e5P)Ykq`&BavDtlE1)P6M@K!0g3#DY2q4A~78$IjrMbF{CN09m{o_K$=r_frEz0%FQ2b zI`1k!k@Zx6#7K(TvMZ{D0aSG6jbp@wX-(7#!NiTRiJ0u4o$OoW_#Nc1--~X=(v#Po ztI`$MH{4*GUoTu><-$?-(3hJ|lk-7ruaL$MHQg#+{Up8jabb(qOlX9Bn&$qNaLM@b zna9MHsE7}=(COpz>ZF>^O7*ji@xz|QM#jYZ!-^53GM=pdocCGR-`|Y6p|G}O=kdB7 zO3=JcUyP|k7nIk@{R5Dad+d{+xi1h05{emTrNd&fcWWNMPcyNw-*ze6rjJ21&bfua zBUS~Yt(sLE*5ZOw3Uo!&?(cR`PM(1+Urs)3C_dFQUb_7HQ&D-fc={B0k;T7RXf>+P zNE;?9y2T12AWJXv$w%8-84&srlUGu`Ts5!tYYTiT+vT@Ejqw5HeeVviIqK3mH^X4Y z=W!IQfPq6$CDb2tl{(HUb6aGNgRi|~p@kQ8vpwgc8oo{Zr6JB|bfC$NN{p=VLjSGj zqwBjGNO8qbLj0f!Xy(4a5k{`@{W9^A4_mrNh)EB0-OIY~W>#aCYM z%zQCI6Eo(3So9?4){F8>9|5{Owu<&EZFFakvDdxc5sf zfsaPc2fdjUrt6T|8R1W?4xlYnuL|ZBPIQPMmLAP8WQmWk*V)G76jc)Er<^(1R0ai( zYe7j-&xL|S89VV&3R4ho;skZbr)~03%dfR>W|tZ{q!bt9Dy(O>XbwW#hS9#(DnYM1eQ6nKkrxf zk})v^2dNv)n|y60{j339Xf}t*W@c$1HjBtUTSYVR-vb49|ANtNyv8-;toWC= zm_C@P@-Ftp56m08#K{C4#{b2ps85x4Xe(X`s)0r5u~@D$|Yk>Bu45KQgOEo6rUQ1zFHCSSw8W3}z%BL;E(2e&%@2 z{d}`O_hBeqZs3BF5P|Oz(Jp+tBYDNUj&x-zpD*m$QP2dlgQ=12Nmf=X+O_+K@};;a z{_un=jukrF>%sp3HfLylB^9s@UfTOE(`;C_D`7k_ITON0OVt%UOd;8k8Gjh@*8E|- z1eP}-kXVb*A?(5l$f*{dYt=X>&rp65SCU}lx#{6|c>Rs2&miB(>gSc=AeeOG$ITb2 zDQRSKzmeb~QNrZ*T!9Ce0a)B_U+J4=n~Pb-@!F~=v5>%=0+V+zJi%!}Oz#Y_yA>fX zrb2T(+!dKa{L+dj;AWFM=4-TD+w;W4aT-UiJz9O~ZE=KU+66ieYungQmSSqV_+gg@u=@cLAJvO_)Y=g!Jd}j;@Y%|d- zNagcu+I?bV(8Yq-)w(zNGv=a0R(d$I%NXb9aOVTB#o%;Z_yq83haIBeONF%G#AMX7 zHE++;w;K1mH`hhuc=5DV5oq^i!I-0g$=v&-QwV#bA=9}C%y>zBilw*HOQWsxL+fw4 zzMW`#Z5ruXdgHvNO^2*t=3O*%^0dhzWZMB!<-Pv$R{Gm_U71tOnWssu{2h{_Njf!a zT9WRaN#->3VK5ym)WsQZt4}M&^t%{o ze1DJ7_OXoKrCOKR*52>*gaA585k$ho*@I2Fh?YUE|A&IRr#*h>QK524=x@Ah^Zau= z^_t?S-RyHSjW8Cd!)N_*xtC}BCs`>ehpaM(g@j0mZ?4|7_(Zk5AYS(WwcbVvN-bXq zpWT-7yGo6uO3j!Wm~pwsTk_+ym1u%4Vc=zf4W>I#jL-Jf5qT~5>aLDI>}(>5+_d0V z`F3V5wbKmQpAMi!ZNv;5L5kEjc8YHIu0H1~+ANnp7@y838Jquh8{rZZ1=xLD$wCM4 zDlJN%JjMSRlEK-bo{_?+P%SRGi*;8X>#hat1n1ySxb~k4g$d!?p__a-fxHpZvg)$r z6KX`h;bJyU&Bm+Dr`dqMhy2HduTGS0SZE$+SbbF6Hot-Ccb)W!`rE_RsJaG6Qjp{| zx;P*C2f!vV9B(qWy|HWA_VV>;9j~pvwF6l5hrpzEAI-|7faV@6E>OLDt5mS7h5(U# zpQ*QLDrEqKO{i2WUV}fWQ`fwAWmGA4k?Z?+rPy>)o_aTx0ZWT)3qgVD8Ry)% zZ*cN)qUYa_k||Z5+^lduhpd57`ns2@Va$uLK`$ZBAZFHqcxl_FKa*5Vm2HE@79ry*ZJ%rtUkgd+m03j$_ zymdvq@=}y*vUXDaF3l922Po9A%K`E|GsXT;s4n{RVnB%fUfSV{!aujFe`^Y+7XDwD z(*M_A5*@@AUs3xXazD_hOC9Y8thC%aTKuiWDD~mFTejzsf9kW5WGN?M`nlB4bH82L z^_hkK$EwBup9|zDrpT^>JY|@hnp|L`3BHyAlUqixgd7cD8iws0+(`eW_oMJgWkJWl zzp$dP=;^B??6?B=4d)&gmwT+90^I-(X94lOv_@Z$t!2M(>e`ejYk-o_(DRlUGArGd zr%4l5WqHl|;yW3BR)kXAxZLxzwcjw{7Z@Yd)VqSBP*IAdaLAE#{A7I%mkrk6G+_=4 zYNH3l)iQBro|t@F4Chx?Fp6}U(_nu3F`#{4560Yf(WY!NM(DlD@)GwG%($_w-b!*# z_SNQn2dS}eCW)_1kBEeZcI#a;jUC+Jv3E0D)3E=g$qCgvxs+K+e1$aVD_CskgsPjHjgPKzsb!(D!SN`()xk$R+ZkI2P7Oz33k1>}%1t##o zUzc@)<)@dv-3*gp8}EMu1QpCGklGrZXPu&ngdtW7U>|zlFY3eJHwNbYBEppGzU32p z1%)^3QYNxuoXU2o=$?OduF*HFUHN}w0(JtFfe4QK7u)_V4~Xv6n=t}ldfW5CI-~eR zS=G~3ukb(c_pnFDYCFZVA7Ftud+Mh2lhgN38W9|-GcOi+V8ZSh>7ReO2KaCj*14uZ z@`BMJ0wHZLOV71VYVJ;ii-ktb?@7e!FlH9~1E_wN3M!HmxmFDhLFKxf_?V%#q|@ zy}LW*Aie3u_pOJza(LgwE)w9`;>*W}D9-|r&$S+I8Vnq?JCi@+As@!5V0F2B344!Vb^C;#77zVy!?ZiAg38P-aH`>NUc;)*?!czD}EL>Mf%|<6zR;QGcL54waq?|`=W-@S%1%G;C)jMcKBtZIRVo&Rk0j>?*ZgfqYL3QoR3zXXnji39v_hfi*K!}}LwCH3_wWj-A})vIiDKUWPz77lsn zV5;e~_b61M{4L4246bQZ>7wzDBYeSA^#y-7jEr0%Pt^}cY2+-$GYtrX-k!w}uw>&h zLwK70=V|WkGSMRwO*xX@ZIod*NJ#MT>GW+R@iIpjNos=E4_w-&TFbveP&PyCVtkp zx@Dpr@t3ued{QgMEAUr5lL-Fre%adDvTb{NZc&8+u_{^BK(mMI^4D9p(~Uzo+AACk z{aR+lpU=2uZ#4-Q?fZo94Vio&?>MPV3qJ+90l(DSN!`ThUxWf<9K=}VL-2C*^{K3$ zKjUC@RHK)PBh*L4?c{2`)j~8bdHVtETuo_~&&^r2F$>zV!_ct=+$4~j4ZUO3uTZ~4 z71cHCac90qJxXL-M_^H!{2UR5DR!}LVY(xwHrT82>E@d?ETdV+F)1KIzjQZ4?Gq{f z$qN9lWydHwAu)xl`dRE`ZnM|f1E?WG+uK)oIV?DiuHZ)?I!aFr$hfI2*Q97DS^Gn< zjeGBEdk8%2Qrps{;6O@;$e+7NJeFHg_hKm`CTZLDm*}OvnZHY1x_+Xyt;afpO?24J zTpkRNW2|c3ye+{EbUTa~_cFNjkUdH3dBnjyy18CTGk+NiRvZ*TK=?|$gxSGsgn$D17{ zPpPJz7vMO3SaMX1sChk$OK#lnw(HMy z|M}FDTQ0fGC8qXPLwy!zh-av8E}3IUk_{zP zb`1oL{{+B<(gU-!wYbVMKBc%A)fYsVQo%K z!Tp9?Luzkvlz+ql{Fe?s_zRHUUzo2>|^9o4VXV% zrfs3x(7aaU`POtGzcW`)Xo^FWO$4f6|lCE~*kgf{3T-RUJWxKaDFKBV`ug4sgz%oLv<2g3YQ)p-= z;jJSu#XYdImIw?lmBt*xYB7upc9 zH0Jv>DIn6J4Js)t0mI1E-LgfRdCN#eG?J@@6IJw+&raUp?4B-Iacvu5y4V%{aEJ`&8E4oY2tTqMFq!H#~4}nd4DG zIVtTERaM6)S#(!(|!o)FYaS!3*N9ryhR2z{$W3kx$X(%rk^iJ<&n_P+yr zbom=o61bfV;F%7%C}-lS0}Oj{^nIJXw;M`N+J1MS$CkL9)Umg_UNEYA%dz|@g4|b> zJwKhdfC}$S;2LLWH=CC{I>~Kys$-ukX?{3lp?u!MYagS;B$Rz`h{334c4WxbO54?~ zy1=_)C?$=#QY=+4tIg&2E3RJ*FFg?;Zw$i|;?2tM9uDxvah#)?Fj`Tb3pJ`5{rpY= zDl2y_Z$_r#fj8fE4EV&ED#55fc%zCn@J9HM9_0OKwDXjQsxl`Z>wkft{__obN9#A1 zLj17c`BkrJ#aL6*SDXvQ-=Bv>kKec+ylozF<_B3&Gx2@J@q{EW87j9G#fGeSldPie zZ}0tP-uUfaFweUtAA6ns=b{x_HCGhg(cr!%RbC}5-*bIK33-9R>jGX9U6hq!zz(dD z;}P$ehr+obHuXBDTG~Ca;(g83C%(|Bqb%R@TFswU=6MRU5-o7KVM{SV`c1hQQBDp((Oonicf)X2K->_M-%3M29&y|3DJzU?CWvxMeaIs_6Y>*H1285by2)}KklRm(t5B!;ITIR)kLmS!F?IUI4|8b&u_TIAKR$BtMi|EDs$mLT1jNswfTqz}_`(ht*RB zw^MVyV&bjgR#5+PnP#2N;>dx&{Y-j995>&!f8<{bZsCT~F@E!#P;g({SMDsH7Uv*==ABVIKDJRg|?npl*uO!vhmY0K%!g<2%*wYe!+2hxqNCAzH zA;-Gd-Jqp%_e=!e@yBEMSX%*0M_0Hz40 z6kNYg2!G=$q&vRqb81{*&WW^L*f^?7Z{ISYaiSS;rb8A&qZg69MjJo!oFnv^&ha{W z6Ya)M2uw_h+F|v!TXaxM;1)2Uqo+OAVL3X*3ntE?v0(oBY8$Djg1TmG`)Q4q9d{CV z`m46^l&4>HrW~vF&YmaHe1Xy<+KFAiSL$fQ_f7RGZ*~oNk1e&K-%g-oI1B+>Q`cfY zEFvuQtp6!D7tEtIH_F=@Ynw>@`-S0W1mv*M3rl?{j3A;rTgRag={_;|a81drw1)-V zEOf{>><^?VH2M(rzU3XhJ!a&sMc)H+TW@RYrCCx7_SdIRppQa_+l8y;YG|t0(_ZGs zwU1WDeqXhU)f7x~sxv?F5r|o?%`nt36njt_Jm+GNe|P~oGM^R-Zr9rMc=XYUsj3>& zZV>b?>ZL}B%bF)`1e6LuI0FT<3xy6VDsX6|5&X-kz7pRRC^hx@6e>GVE=d>ephTX+w!X4N z-QVZ{7wwV|=Xc<62C$p!>qe~ZdiL;df2C~BC=ko{e&FTEY_D8ZqF;0v1@2t*Hi<1! z|0i|)cU)MfE62t1#M<$kDW7pCtl=mmReCqziw#5=ecPM+7ibF0wH)dqlEmgI;i01} zn(a*HA>_4KZ`y5Kic@pu@O)zKV@I+(+I{t86CH*3*QA}jOOe*+@jh`UO+AzPnelSH zx6@-)g^~*X&(X$T0vdnr(Y6E_vJd`ZS5{%A1;o01wG-Z+e*lPdng-`pVX|Z8XhRjw zv*v0_$=mUl!!#fTD|MrYLV5J#S_@>18y0)4x_b$~bGP^#N!~E1eMC4`sWpWr7H!xM(AD-)JaQrd2;^uc-T4O~h=0;y^@lfvuek^k7I|m$(!4bL`Hv93 z*Fb^)-t`YX;`(3*cM!x}v$eHe!F)6{g}QdLZeEl?i(iOX1S9DiB|a9;ZwMJzL%b8S zy-%dECJl;KHa%j&+A971(tXAelwh4VKu)tFxW<->+~&0bJsCIi*hJFs_#ps!Ke9Bk zE+SMgXZ()778ojB7yKb8BrUikP0cb<{kort@BDM#6?d|ebJj(}A-m0&@Zq=XwejWO zSnh&4Ju?1H5v?t>6tT=_GLxJ8QQ<|YLDZM6ch^zzmqN}ydZoge_+%CyEbJ;ir+D~Y zVQ(h&L#$5>h3UQ|#04CTeGqzm&gN%v%`ugHzqo8KIs*p2Eqj__Eb1%hJozu=t{2EL zMY{FA#y3)Matew~1HWeHIdBq*%xX@G(#SuhwLdoatn|#rzmizx?qy}+>Uhx**Sp!s zQ+AJDWVFzsbXk6j`BCY_$?Q#|0`F?FyA~hl+L-7ix00`p%c>jDTZJgkN~z__Y|PsX zaD)1S5?$uzznv+G+G^i3mBvk8<$S*PB;y#%{V5pZ=A7F7)4nI@_?n4Ltd357P1$ts zIP~+O&_e$;9saaCpa7m9WIoeloNRS z;s2WQ+VcbySC_;Y(>Ps^i1lSjNHX(*?Wodc_WLKdL^FNEv<#$%(}+iG5&Po#Z()Jt zYg-`GCs!tD8&9ho^o2UVdht)Lkz#MKYvXC>)BjtahZGFve;QwwcyL4Msg*vwrCgzFILx^fCAr2QRBz#llT^egn}``?K~TS!4PK$P*~1?hC;i zY^TD-+Tx3soJ_BP#pM06yvh*UA}-qY%f>cjjDYm$IhFRKSJ?M2nN;k(8RBU)J3H0Q3cMNLWORtsAvyt zYJD8#{e;#u_C;Oi`itp!%WGc9%@X@T?rr0{6tIGC6OT$I_%oBJN^M| z1;uCuwjY0U??f9);E@`Ux!_C9o;k(o@2d5@TvG*>8s)F|(`>4k#)x5$V@KoE<8Fz zcB>E2w=)TEbtMDRtO;n;*sbJOvtU*P6AhwbT-Q&Un;8$+AL4G$&r+hpszvSU<$9Jubf{cc~MYHe^! zT)eZH1}j)K%Qw< znaeP71k9Z`%+1zvu#I;Mq9y+@!coNU*HOC|BORf~^NLECRz6QzF4zw{u`7?*QZen4 z6A5D$?_LJ@eFuG9&orX%D$eSE+W=?!xd%0GOWv{rf7K4Wv>2W)f0F3BdeS<&^O?2P z!Ght+<>RJ@OobJxgs+E#7|%hqI1ZTFv-F|5Hj^#Z2&+p14??qV7C_JwdTo>E!{}&T z2{fw*p_umtRdw6)VG<8R)0h&^0q*RMAX#6@;{=nvsE#GOQ=bT;MBv0_`!_8U4FXYJF z-uPqF>lUoOt->SEPzQ74`vdgK0?%&?=7){DZ|sMZvs1Emt&BBz#;%7=wnW--C6zHa z-G{6C3JC1TqM?I({y9sM{c82Ax2Z0^o>Fb08m5ZcXS0QDGRfr`ht3|o+tcdI-Yk%b z<&Ig88Tg@bgY|4sX?t6>b>j+mX|h7oAICc_5w{_DJpt3on~{zq;B^y;ioSt?MJlw}~eMf44Dv?ORi!v(@t>H2ik()W=Kxd=xV^ zgg;t#*fX~Xc& zX3IxBjToAfWHR+d!>=TzQ%^AB6kM|XAI6S}CQW&A^|%SsVzs+qL35JzfO}OpeG)PL zsfpqHu(zIj!^dtVNY=Ao!dcv#U5#pCLG<=}Yp!7X_4$mJftfE(PZUL$;__1P2Q4_s zLDU|{TlzpN)ed73V<%Qnu@!Uuh3{=A1-RsqON;KWdyw;LxZ6PvWAsmH11d+N_e|fH zBU~KTP@XWiN3^fmT1Olm6Sar+0q*oN*h=T-J+MF7EMWQ#}czeXkZCu4@sp^=)q`Vp5>m*EFFEDh` z@yQDS>`Th)Xba>!?(=RPG{?l~h{>!SOH(|H-h@wJ_xXxe1%-~oQwtXpPg>stm6HT8BJoT%4H)$gslkK@+(p)m3F_lyw8wbA znZ?c2cJmL-PdSw`xc$y@=KUx`EdqG1Y9hSZR_4HtHsr)!4oJ~4rdhhAB3rBq%G1c!+> zDmN0f6kFElYo)76J%?5P?UGZ+)N*W2Gd~YI-?&BhOEs59XJJyb?3V|#jVc6s669rl zJ3&{yC0P5N3Z#JRW0z?Q>$X!6WfiDGDus#R+TeCvoMVpojR9yN}r^wBrnJ#>MG)hiOK1zFhq|o z0CCnK$DflEvlNx?O1hM#zMmUhq)S(dG%;iq#`0Z#KVik^nEO5VwLoi2W&8c%ah?W{ z8GmbU8vP5(06l+DK>Ven*;YA=ko*cFs>;{IL_-H2JlJFH3U$dZuvb~iJbQP8xhRk< zp4YV1j!09J*1MxKxK9&`;(ox|cm1%yrSvKuzE?jgx zr^Zmr5bEmub2xY{8Y3EECldaPJ&3ij?zkWuKdCt1cIm*mS&;mq0MA`sf*=vI%cri2Lj&pJ{2v9er2fwvr*AaVn_=P0QD8(zq|-fn6kw3ODw@lKz4(5JWpH!B67NSUiBdzP*_zXmQUjD`Up9_xW6kef1h zN|!VH>T1z#?#OFBF_tix5*D5=d@Zp*V{Wr$@P^LSh zIpo~w1)Z90m&~BzosHe}gY`+sUG}xv8?0`4$7VxMXu<-xysUkE_R;%x6*`xX(gt1TGcHXHX-g}{RkY$wtq9>3^{+4d)xu)da7UVd_e4+zQkW+Q zV=OoZ?<2wjV+@PoC;~?j5t7%W{{@zs2IyFo}2j6gzrXPn_@m zNr~Ln@ufBEjo!E(7hI2QHF&rIzxrLgt|p(v3Fy;giy5-LhywI;#%ofyzB%Ko)Jlwg(!Qw^sw-FZCF2$7vy>_UEB5#z z2~M)%@PF}z4(SbsHKltCqWMCwzJ7`GgYbv*ep3RcW`w(sF52-0@Sk>tPV)!>XaUd~ zhW5SXd1Plk^Gz00(mdpMSO2F(85$;GAwu&Ad;0M<3`GAVn4>K9?l;)yqBVtPDw$MIjy0;j zCHY@&7|?S)Q3>l`y`Yz)(?>igoXfw0&}o4Ce88y3eB3w-jTt|Ww#Zb`Q+zoiN4`rR z2MW3U>p2XYJHGOGM43k8jdYUw2LNXX73@)f>4`X99mO8Lj0nZXn;xhO6^>%A4#5j3 zSK7w?OPj~T9+ zPQ8h?;7s6y1No2j@11y+8Y$(5^r#;{1tK>d>urpe9G(dnQzr%#EE|P9&&E}sbw1ge zLyn=I3JGRd{)m$N`}rR@sH9T$=dq^Ow{+U>?!! z`?znESXr!o1*}6rzN_k8+Leg(_ngSQe%7Rjk2m}`gG-kK(GG3K-j!9KvUJReX4>QA zHDd2@^dnH&Ro+WJ^>{ma!+ozug`uS6=pl!ITmo6{8WBoR#xGg4fnUtRzk8QfO+MQQ*kQWQjb*N8Nc-Xwsi)DS`qp@{-fKuUlhz4sbA0YX)fDlPQTi$JKN6b11+ z`P{kp&b{B~JHI=>-^}xS?##IVNlu<8Cpqivv-jF-ul0Io78O%gbXQ5Z zk4dLZSlF(-sJDni?LAK>$x$k9R*+gS{@!2R`s)*QI*=xV3-A7j{CKE>_f#=1;Atq* zD0olRi^85$2gKVaqC(g*)h5ap+&w7!8(?A+w52~obi~YFugx!B+$pY}*5Wx(-85-s z${?j;x*6zBEf18s9&qEX*YQev_{yNkJJam`F^4x1^X%=E+Tk+IF7f%Qy57sgMA&QL zhPt?~FPE?JprrGMyVvcW4v|B>t)-@E9r#H3=?G-4L~I~i%&gl8Mr$t`^-BWeTkq=Y zfJjYOWgLNz3qdHWg4z|i@yZ|%L0&1k#W7i%I`yq|Y(*=Z9}t@{aMHM-I!hMKW1-NH zKVbL(mT4_lh>vpi<-CQhs;YrRJ~`VaKm+IdUf8{3>7F8AYo1Y){@$r@0thv5Mxg@v z@b3?$fC4%`B~G}~7N*OABmU4<(66L7EOwJjxp|E+TLZk+7IBL>TfDXqN%O{)cjf9g zz;lXETl;_+&9L51ne0hf3iV^{8>ua})x&GYY%}aVObc>(UI#rcw0A}awg#&-FT|EN zQbjFgZwCiK><<9E>-*V{7(ODc;JKOg7re6dC=yDblmi`T6SlSqVhPfZogUsKkq}5U z1Y3RNs0;~G#u*(_T>0?ZHT3TrpiK*qB$E!EsOtL$``403JZL`TVyW5f&yzT{nz@C? z^{gz?E&gbkmW@C|n1RXE9xLMGW+U|lcn*;zFJCXaXCM6Yop(EbsAkTORZhJ1ebQKn z91wpur|LgfiEbRbdl0F6EFJ8;%J2GNUoA`~`vH?h95eHS5!3Eircq>LS=BF@E%|J9 zW@^nC9_n2m;orwn44t72XN3~fV90eu6ufsWE{HUgJ|GRH4tR<{Ld~JMKB>f)8990D z!gOnCS@s^Pn`9vz^|1|t!0Z**1J?#PtA&G`5x7DNyahbp&jT9u0N7qrb4%3h!SGQ8r+ z4tMWmo~HNYjsp8Fhq5@?<2sxd*p6igzE+US#9iN1WIDY8<6>fyyQThNl4|$$aB05m ztIAEQTqj@fa+|)nUtw9hQ8qSi-{rT}cwt`yocs3z37Z}~!9ia^kgemf{X^IkeoxnB z($iYj^gFKXvYdkU0K}%d@05{pjRbLCZ3Kks%RhL`_m-#BM`oziIkKzud625TdXr*h zM0T{oOKmyo(rH9wogLdP^WRR5i}s7|-hwE3nKSLz-J!ZUeBZ*Iuv1HNhj!Re*@Lih zqmNT=DE>P%6fNP;+zfK5i{{LylJ>H8fA5u72Dfw4_@-Xfr^h#i^|J3TdOD9dde4M% zxYnfW5w$Q9UB)}gF~z!LvQ-sDjjg>jOM+VTo||wq=UVH9$MA-G?Wm-%q{~k@UKBG#vUjnQvbp*g$tb?e z%#hnFNish8p#HnEo3%yL!*Rq%VB{vj<=t;cA0PGoVydIaM)Knc*88vJv-^-^By9bE z=Em+uILaKi-tGBbfMHXBCCV$z(v>+p547ZcGS1hznM6&33G!^M)!=|ANZGkPTlm6u zB`ZT#Ug^Xt%W9(!hGEf{Y>h|oynsuOnsznP&z54WR=WTKojFWuE_fEI{D7wB+M|J2`Mx=9Yw+l~4sw9?x#RNYjNYKCjSI60N(_E>|p91RG+LQ>cvvN)8k0z*7`HRrNjc;d7-3fw^~9e#ypZUfb+6B z&2sTSsle@$6pY12H89>|JlPg|Sv%!!oW&n@*~GHxNc3H%ubHQTSZXww455F*q+-`V z5jGkiujg!|$`JmD@C-Yu(d%_LS$luFtv6~uuwRJsf{c>&3|-m&$yOcY5rnPGOViG& zup?hE5J*$EXHcPq@U1n{2n<(m4VB4ea>D~!+>{~@bh$I_o+Z7_ll)~D=v&d_VZiOt zPtvzlWzH^i!?ZwxDr_rGsj7Qdu1&;1qYUISRP4DKslx%tfZZxx7d=s@vb+i0Mx({Z z?F)M|S<|7nhthC{VMfJO+WrGj3STsr#+FZ!tQxk-h3;ulNi}|2XId$g^Lk(3y4r5_ zL9|Ska??rziX9-A)Gg=qdbazDp#|&;$&j~;?5~-c!9Rq?$y`7iGqii@y~xoFX~9Sh zc=3#^{>*m$g#+%~08)ZIu6gYA7EjCX59#~BBdu$|xUg@>t$uSRtm{aBK;(3Hq7u{E zH#881F{E-rO;vlvWNCh1LGL4BX(Vt9e(-0;y4L4> zpU;wa=e7@tV^mBSqVmlTkTz1n(N#_~6rMWE#w!QCKR&+VCt%?CWK(gZH?fmv>OI#9 zDvgxoC-z92zqt5qNW8{X@+UnZ!BZif01_hT-FBqKq>Th8(*r9|QW>`B5vqVkA~1?S zd`%*bFYydKW>9=IRQXBg_Z_$VNVEj|q204*KSP;t=t0*B#N{2CW5e$#WkWP=m1}XCIxae+G~QfC_MrcGcFfRz2BJ z64(l=QKlHRcC82^h<-31zb51Lj6naku)k1kQ5q~{K_Wq_)+O!6%pu0y`7JKKy z8frW`TNLE`S0>JNMDN(;aMSI83!}ngm>zb`qa0mX#QEcF>vNT-cNEXOB2qY>@%x)= z*MX5ox%Ils6LXM47&8|J-f%3-NZur;9l;aM_ql#a^MiM@$)a3GrMuEeZRYvcv5{M| z8Z74zbbN1gy8X3j_j>%F_rA2~?@CH3tT~hRH6;P$!KBKDT@V|#aZCleP-o%ty)4ze zZa$;mg_!!-#&EhJ28yIrZbIz)#`61f^DQY$k1AO?f!&lD-(#gvsqHegyqw_h^Pjv! z!#~6M0Lw^Ac+QNF`RpA|L~Xj!CufI-1a)JgD1 z-E%O%2N-{Eb&RgRJQ%&KlvnW6W@d3Cn(T|Bpwxn%J=R6bcH)2Q~YvC)578M-8Wp%sm)+!vaEuWiHR&GCJ(v<>mGgW z(IoBqk|2uI5KyrIVQ<9QY!YD;5Akz9GE(?p`MRZf6uc(r2?bMID)vf_Dk3wub0X(F zwq`34P&(O|Fif(Gh|P-Z74Qn0L%fP{krH#q`waWF>+~J_V9n>Sy{&9KSp3qDnRTwVlKMu5a8j^ZN){HtiTBaj4qZ#ME?37t%h~V^`Ru!5-&!HLFt7 z-n~&UK9olAa1}%^eSg>1E#O7iElRZomFr!M99IRfQbp!HY7JqoDd)kAd@uXthKJ;y z7u5?k_#8c`+zhHxtZK6^+}Ux7Wn}bUUnKwJOdhLLm( z-j_vN;1(z}NZ}Ihr$0WY@{x9r`JAY^@4mmH{&>dq%&}M3uG*?}Z;D{<;Sp^cUN5JGV&(riOWUg zlM>&Ic4F+j+Ri<Y&WX5CYScmG%M`;!1qz%!jvAJ8=F*vFNzpkcc`@RC;NuRLfk!D6 zM#dHg`zB4w%6p87T?#9m6kL{MWE3u=*xXv4q~vtz{B4dk)YurFY{N>kPS=IZFelo}IUBB;cfEp1_ zV{1CZzzQ(Z*xC)eWTdH{Y8wzYFq1hFpfImZt>U%1%EZs?X3xpye!=4~N7a$jZry;~ zODf~MKCYof$!mE7ah`GNo*XQlgwmRS!-Wq^;}jDSA*OIpuwX?9Y7H26@>SC2GuAm7 z#^x~H#s&1tL9cO#=dsIq3N9%kMs5WCT`!bE$XE=ZpGN@Kj((JM`M}kE=O62CC zr0Jf{f8ANg$OxQT=Jr%r4mHLbj~k6?XlPNuCq{et!$h92&yc`WU}^whomo>g5w46s z3pCV0O!?ZCre6Cp0k^R*BXd@S7I6q|CP#f}JMYX%`1*;Pxt86|-cxgQ>TV24K@tGq z4rO3q(xMT={*;??$6>+5Pooy&hFTBVXSyVB*kwJ{ZB)1HCfhf3@8+a-w*iva&SOL$ z;P?}@1=oUH6k1F{q;Xv#aDJ`*DL}9#i@2^F=U(RgqNq4Bi;8CTT}ZU^`cz1;njmLg z!SDVuL`SakuBp5qCK2wlTaMC6vE}Nto7sp{Kr!{H_}ew|-JZL=HJyiWISXuf>cf~9 z)dPc>08rGvU2M$b=lRLLEd5l(rZN0H?D+cGw%@j>*bBIH7vG@0T?iutm=pSdCcY$q zYhIj?KaI(NQ9*A#Ec_~k(4H*?ZE&c#4K~LqkfZFsgR-56qfZWP8J1i)dw$l7ZDqFi zNnGvtz`6gqX4pGB_Ew_-)X;t4314ARWLgsYa_CJet!pp_C?^#F-~nLl<|Ho&*X)yP zz`zJ;u|`t;%A%jd{e14&Ow|-5spcrQOD>8lDhT){DTH~}0N-t45=OJ15N#|FiRp>* zk8*%2$W*B3hv<>1#w;ow0TJ7d^dCr#T2~)bU@@%s3B>y25womJ7ODSYft0#gjGKjw6EDzwT|f%yre_H60N{WnBlD-zqW9N@XB2kv0b|1#V zhTU`rN$ZA~Gw`8HUS!sz<_?1<{V9MXUPnqL)H5L(txr;7?$yf7ust4bPjvV398iyOQ3ASlVQ7;w?ZTkyPGCq&J!ZZBB-6k%1}X8?*f*UI_}LTjGFCWF zME2f;1)QPlKCW2Xg%JL!xKf%HvK=w#Tr5D*Qm?tpg;pdY_Pyj zkA0TUD=A8>)jV9}#)CjE9Z)@?=PjeN2b_^}T3%JDamGgdhKo3h*5FZ&{c0U@gQ!>vwI~#m$yfdV*AyZ;7sD*60t- zvh$2CPe*4cI8pfKym?jn@UX>(sATxn9yNO#_F$U7wKxNqnj5K!@RpWac#81SK*HM90j(AQ1)HK>$jh^ zK0jb6tbn-Os*l--jBlA_y>|5z^Fd&~2d^S%qw!&;t>fr9yzZ$igLXlqYJ%~QA!#p+ zHvTQfyCuCX*x;GsE@8AnVIh!zLV$P@+lT9Q_Y2b_iMMn zmvGK7$c{Z{z<{-ayq6@;N_Hi^iUB0G@8%U6>Fua3TdQMOw(VF~ghY)WD>QgnINDL3 z_g4N2DO)%6=V$dwcqc(lAFetXrS9EBfJ(l zMDw2A`;OodvLvoV*bH}}M6ONK6fmU5_ zUCA(^584J_xwK&+nS6$f5Rd>Bv{; zG$kzsfK!&5@RG@+r2*u4qiiJv8tkq8fx_bkbuw4bC>sp5_bNciLWfn_iH%O&N=u>f zG!=P}qDlPLs1gC%a_f>ya3X{S=S|4Xu6?cU>Gdq6?kOr^;Mx<&A}Wfj=JObmE5`4l z>ISeslp81x0vTfU+y2yc50R!a5J zP)43ho`oR4=NxNLXW1wro?8{1q#IRi5xrkb7$3LUQPa2_rn2v^uG00svN?FfurS73 zpqAN2sXT)7Hpsudg=Ei@N;%1`v z&G`U5Y0M!WFSMxR7xQs0mw)1l#^!pTKJS$9F7$qBP8F;}u}R8$%*wnrc?{%se|3p_ zL&Hc{$OJr}z?|BAMD3QaP9xAu!l2jNNar6*iGb%`XlTGSlti-{F@c=gRWC z^st$u^H6)^{*61wMN=pK1$&EZ-ji~~0$&=DtsVH*(%;HcpvYe;Y zQNa10f(R+s(I#yQ3e3d2M9JRGS}O($COqu<^3AxFu@3mk`KHHC(X4xiLKLk81>^6PN_Aa0g;Rk z=S8jI@_1&g_Jo%EO)%(#C0AvccavcK!K>vylqdJ?ic`AfXZ2_W?kIn#RN(G<)%cFV zaywvB%b>CUMPT)Iy7=SAz;!j@wbkdKEtgA|E;DEt$U0^>;Y~=73;M}gf9Ik%&0jNs zt%jZ@WOUBA=4k`{BCR_lEiKQ9JR+cPzH`%`JYvM7e-}igoemJ_T&*~j8U)F=+577nN294vDCyp4^j_3d|#81%2{gO=Jsy@<28hc!&1ZZyEc7+?wi$ODEl zBiD0hA9EX!x#;cW4JqLvVJeU@KA^Gb0;=tuW{_C$l}447f|-Vt3H^q1uHe-e#!6w< zhp=X0an;St6mLQxMuq(vZ*Iv6`!4RLo)HK*xIq=XMO$;Wt&|KiF*H%jP-FYx5NiH> z7}}(kAIoQz)Yz)nn?y?+N0M8*epYzYz{8Qd)99@?Ii=C6%$uUml=12k@;O|PU>=kF z0udu>@w(CQDeO*`D8!}A>gqbQ=w(bGdBma{FEV-=nbpm8HuSpYX;Ep|P(Y(~L4i1{ zctM$c(Usl(@cjgwKBM$}C`&*=B0XXpJ}KgN2ld(BJMcby1aLw85vMJIOsI8>QF4=0 zQ1~Ej?+)z!Scp&)CMSYg3_-D`c|m)=1;n~Dn_7#D2~r)C1J(B}Vda}!OZG7+MoBZX zp08^4#|QuQ3(-eEXWzPE#!SJ({kqfB#Et$H&uWKn#>$l4zWXd~s7;jQ#TN#1+mX8rO<=iUt}U56?M{D_7(ik3KQ zVZgmds#)vnJPD_2_3R4s&du*HAjUF>pX=i`S4jy0$#tE8)v4JwK%hL@6wK zd!s(*glDp2s|qEotXg+$>X#^z*XUmiT0ZGj%6ji`VaGldIx|csuTMSg*}r;aN*udO z+8^%OrJZYFmU{B06>oQC{{TKa&u49hcbd_B!TUFoRf8W z>GKDP4W3eMU)63oD0(cFlnBr>aQ9J!t||fyHHU-Kc`F@0!^}yfu`@pou9ezP0+K}C zo}F!l3pb*-)l%!)j1N{rzoevmaDaslUA!})ckaKzpifUZwxyAZvc^( zPCR?N9zB2nwiPo_QG{-Vn7yAJe~o!l!fXUjDBy^_ z#9mc!mp%~rc+{+C{v?|^e&&3F=RIExP!vZh-nT7Z#)DrBf^0lo=}RiII$m~n{@N!6 zfYWrVrF0ZHxGyv0j!nBT@3}kO-F^<*39^>GlaDEeo~HDtOf@AXbk{fRsrcKY6#5xZ z|6gEO|EazcddcVBa+8P!`=3Mn1@I(YFtbM|}+?DK7ov7T#V`S&uVmF>w8jDx7%FdYDEy zb-MJ7w}s0(Xh+w2Rr%E58AuGSnO;w15ON(i*XE$4Y|pIj<^(ME%4eM_eCa+xKcedg zkmxxgDnE!Lb?N#e*eK@-ux021>yfTvQE*s<7{9lCCOgkM@Fb3!pHVs3AV^l#$2
|#{SjuO<>BBf}lVg7m37)cb+x_anpEuGD0 z@@^Ia)AJ8x@&COm{QEO@`Cy0O*t$t`AgF}6Ss4`Fw+&Vlx|ukF*ys5XORd<_s`AS_ zB=|EaPVn~)K5aa1@z+)jop4b}%$VNQ9`K36^C5wHW^EAJ(K_n_hmyI5mIqoB0!@#; zl)KrD4zuu!6<&Jybzy&rWdX%Od)6zv%VdX4TZsep-5?u+rh%8a@sc2J8W0ehKgQ;i zR@)BE3@s{uWd2zdFq^K^@}EH)1{1{ZJc!}(WL zA>Tm-%`lmc@k{JMleciyHIa4RU-?E8`HTtPdekl&=q8tTh^fvi23-=Bi z!o-u{;Mt-`OeE2UQnMJR>6SP=15(!_0eS5?MHx%si;oklS)>Rawcq1A2}wkT)Zse_6p(L;`1$ z?_R@cJ_do2FpOr*$rza$b4`AUl>{6oHMb|IeH0RdJMtfIv7US%5PJNo#ZX7*0YR=y zTVO%_it2fHb8&2J?0pavpUK5h0HNebB=mID<9*torMVT+4>mpe=jq8&REF;LEafgX z%rc0IiA0Mz)^AmMx|TPR0{n>Ss%k$Kg<=MEy#l3C%hVLCb9`Hwxkqw2p``q#CenV< zwq4ufff6pDiaRy(tXltjxTE#`&FJ9!+Hg*45{mo82UE$)2DK}Lf5Q8^_nlpDm^kp< z*nHqYcCT4{t$RIZY63{RFJp$1nKMtyqNZm9xp?!e%-_!@xmxuIt1&0XGzsjj!k4m2 zSwxP-EAyu|bi4=YG+fQ+uw4Y-yb^BQC}`Xa8>#!rCoLf5l*8uX@@$SGwf~!MDtC#X zd|54xKsQW~^0C|a@t3dTp*Ozb`qo)CITje7lPhrasxYo!o051Zr>cA#O~e#JTV&97 zK}S9nZ(6u(pG<9Xh{z*`>nEQkjNhFt_mN#Pe$>zNHvl6}cS?WRfGQagGJ_NV@tnc; zt`UKWKxwyZ#9?VvDR_#P<9!#4g>`$j=%HG_bzRWt+?DV&*SB7+6LWMEVa8BpW zn+h-2{E}a7t)aF+t)rxe3tAbcES5vqe;1{1Zf)y|zT9K>!Mu;65Cyfy%j#NHK=F)!K5b(~Bj zO-4h7(5QvSkGI#*WkteC@`?*?-x;a=miZ3w3v8t_(cZlUh|;Rt@e>M4<|bx6J$+jI z%ToY@M5@85v&(xWy9g`T&Cv$gFkN_Hg4x^#^d?3b<91YlOh`)D^aPbi*f1QKO|2Mt zwd~k9*xDL@7o3zfeehF|)S(o|&<2H6-gQF}lUwOArBi#QI|1cp4PE68W@ZgX!_TN$ zlER|pWBEesAj&tIpwOY7BAXJZvIe$YuKV1ky|iY$AvXjCVAcnQYVR$I$hHZqGf-=o zFxXtLo;;fL(4M`KCAtjF57Y;5#541SO3{eO^L&N_M>HpGVSYo{DQ5G}7-WIFlh}LQnsf8lW|KJ+u z*}~|^!#U`)D(sHlb1fSKJ~U^9)7#jX<#ojZO&XG71Jc{IHGfr0Uy^c_4#_IO8yR;Z9P*$dwKcss;6kt{L=6W zAP}>X-9RIT$gUd_u8&c24XB+VG;!)KCl-6T_^xpswt7N-#ya1ifERAXmXfL;ebyZ3 zEXwP3qUA9~-u4TpRWIGTdgJPu`01x?-s~}%nnW@bz&@V()VHN4Uf*%x5}A_@+F7J! z1pa(Jz|dG1Ls=*n`0To#kaO6QZYI%Mig?qvJ$|#t^LrL|7&Qfl6dl#5Oi(x}`Zsj9 zROFLcJ0{cm!8=l&CJmACjN@?U6VkZbIV^Lw)|HO?Hz+C02{?VBc>bWINl@?Xh8dkhTJ z^?V}|rl!fag7n(kvy{>vm1NR??OWLB>!nvLK!noL@Nd*?85LB@>$ucUl{Y;pEqL{{ zFe$~X_AX(nsjadXaVR`s=o%DugczL@FO}Ek65s!MoP2poUXtGH9TKVX%ceVeEtC<{ ze1sSew3?E^p-+QaMhEro4_xoknhZhQKD%N%|VU!@U~Gpok#Zhv<#soUeVoFF(y zr_`BE$xgU0Lc^OF0MA+igEuaba!T*REb_vJeF}%6Z8gUMFV>U?H)L*97RUFd-c?2# z5Ry{Q(D=#LR&K7WXma~TbBCP^WPRFUiZGaa{aIlqiRxHHk1L*xo#z^ zakYd%(2VY$_VyU|TI)u8=?G@z;FGe#a7vSwtU(>t(95LgYy~ha85r-EkkU7`zDk4q!$u_vvu_j3p%t&U!)G&N_ygnn%+r*@A%eTAQfDY+c9CwL) zW|fATBAOXQ9RcD_9YqY>YFw(n6;d!ld_eecQ*G%rZvfI~7JKW(xU!s*^uwnT1e02UEDreUbEDBlXd9GJID9w zBzCmt{2Bh(H%7YrMaP7(Cec=1h^+W!v~xd8lj_RwK7?F#>$VNq@t3LIhV3BE?NVFE z4y{`@`kM~%!+i?^_RhP4lJ#p@n*Q`87_E#N;p~pHP2T)wyOEw+dfTvWaY;e68pq-* zoc23FOKW|jicUW$dJ7W@tJA_`$DhrWm+al9tm%erc(SWT+oNvee||vUsCVR9-F{(E zDwj}thfBT9WUVY{Y_7g0*o*vG|4PEXZq&;Nc_io5-3mK(@K`W_R4_s*zCG*S1{T|6 z18bLy+`2(Z%+!{eWnT$p%B8THRHcPC!0?Y^R4d%%0<=2(j7PKyx$JvToAxf$?)vE$ zs__|jtqZ2wV$L)6f)-m~oSP2@@)D*Z|H65N{XpPde}6BDYhQl^8|N~e<{5CeI3MC( zqytKZC6qHPJoluQfG8eD(qa2gL=Zl{`DwHDHVz*3_?{oLPE{39qU1)LWG8@KSb#k3 za!{_TQn{7+LJ*u#)EGMH71w-H=29e=8h!8E^TJ~BZ`at(%5#UK>gGlF5inTA-sxqh zgDw-w$G2a)9Y9>4#l}!=&Z1(PwzeM;0>c_6I7=q_rfYRuKWcRX1bhm}Iycqcu-{xd zQ-Z``7E9eH*&Yqb64>8dF`$6O*Y(iyDTeb%_IHJR>D(kI%W@5ON&=>Ar3Hx>caMb1 z;~>Q;NWpI{Tq6hoM<)QF0Jua?61Di>yHVDePfvjBF^fbUJ#jM)ApIl@=$gYp;_h<~ zC|IEh4FGr#(7YWralkEh)wiIkCJ8QINcW?ezc>i4DclYbj84EEaLqUT(%u8f{LA|G z#hf*6;dc7n313|x(7|Df4&F}5ASjV!au))nfr5k?`7%htcei%EPVsf%nH7A?6I% z3zeQff&m_6RQms&PzzEM-Zb;(+-iJ6Hc2T3a?D!%(u8)Qh4rDq2e=y_H+TK@EXzKX zZ{)1AsA)uT?yd(BQ|g*vId2P#zCYNI7ct2JUL>#hFfT~&xAH5n4y}HV3xczrn;^!Z zV4Urkz0Xg1VGivnS(|#dzK(tQ0D4~Q8fd(O$v1-Wx=vm{)paAE!pPs(C6-Eh(W80C zf!XXKopB2LF{50E|Lgk=RWp&SHc)P={&AAa-T*XF?Fc(?F^@~LMx55nkPYoE`v>2D z-o~$NjyezVgP5CB92qTRB6SnXyl557Fz*NZ`*^zdn%!Wy>QWzQ>%qUV&!4ydn^}P7Cw}Ld@t!d{*$7g~ zhcp>gpNQB%?E1v5H%YeaJf&4G___+}y+r=hHQPO4(EcRSh7D`OQj)57f4B&}G2mst zJ@)~FIHZry@nC{BlXZRv)#VdyYs=DtcA!4MfgIGedTcSy`qcAA^HEN>PrVg{NYw+` zhRGY%VQ6oqo#E1pFArdmarBmqz5E=(OXl^%fHL=`A>gvtugAYc+s?p7bc;+xH!81Mvp%Avu`JS6AfIR z&Z!@>^^zYlMH0nMt+n1$aldq+wrzZ$ZFl>p`zf<(Yr#2()8Ol-ki9R$GlObY7u`(m zqG~;s-O0V2YVTrb#Z`;nGsMOd2cB|BN4hM#?{P!k@YHkJs?WKlT*)XL(3-%eOu6sv;ULtVcT*G=Dkq81;sL zf=Jcw_dza`QwZCm1)t1sK2NXm?AS){H!*`>&XQ4umd>hSBb~H>I1U0MMRZxT?4nUC z=*LIK4wp9XugYp>Y@2+6W;@v-v)@WO6v+uy*1s4>5;cDI@k|D6E+bx+-5I`rQa*i; zyzYz9D=+GXr_Dcr*={(R4qIMd{`?b#W=cIpZ`ln0%d7}Od zD1XM&Khw#d+4PSy@yD0?<4XSVr2i}={;Z?^EF=G{qW=UD{?Ck|oXJ^K>HrArDn+D# z5vb`zufPd!PWud#h&DIVnHmsKgi1lDyJ4?QU|*=w&9KprQh5hN0 zUDM=2Av>t}Wc=~_?+pdCTp9M4$aeQZ9)InW{ol|)AN})+-;NvH;(v#f2%P7fLVbHg z@2$T_uHmApVNzWGy9m4BW?G%P8Hsu>5)<;FAX#2~Set$LWrURdKh6vX$~KtRn~s!K zl!m3z^w{36qK9hvlZaw3@Ja_-E;}(jNZoBQy6%%Pj`FXHNoAB z{zH?4DiMbb7qYdgGIKG@xXLwS?zteGFqx2gxRk+EwY@`clHVl{X7~|wGHuCfmmqG0 z*{heiGCiRq-u8aTTeno_kb9#k1F^grrEcJ+?b>}^cd-hOkXi|xysrD)9mnc(s2;2K zJ(LM6ZdK?$40R1i8-ja>fkk%mQnH&pK>?tMJ@i`n9+zyJb-fU!s?YB<#@Z~75Dz}) zr{J;uMXpx$Kz+q;H$snG=Ds9D5vOz8d8o-UQM<*`+@(QB=gr%KhvFl0S>hwy(O0-~ zNe>Byb;r@*xSWlaSMB6hOIJZoc~as5sz{34&L6_Z?fsFl2?ukQK667)V9uZBF73Tx zWgynnz4RkEnUk-Fkwl3$`F0YDhDWH00am6hd#NO0vLO-CB4Tr1FA*$ncyF)ZZO7g< zuGjgb-Y)myMe_pY1YB-y%K9J$>kt0+4NQWuaAyII?MYepJvN#S+%w1Hbiw|JoP|-{YhP>qNN`&1 z(G%5hac^xBy5J4>U-XQB(~OoxRN=MLRw@!ju^)*A$d97g%`(b+;!Acd+|qG@G&Fq0 zj~U(??jC3vx(wJ@mQ>Z5TF+^S;6BersprS9eCQ+}RtYe4{9S~+>o|QSa69tup`3dm zMdx3C^*?T)Fqp5?*F81^kYl#7?XJ1-2? zU@m{ppoP8o_YN^`k3)vub$NKMS}R`TEVly+A)@Lt+aRRE`5lL{ehZn8E{`60tO;0A z#FF9f`Ogy=ty=mi#{StbB&tqFMj38bJ@$oHrcX|J0@FO8Un(J|ZranOgce|0E*f1a}D z4vp;w2rgd=<$#eF$ZI#-Cm0#d>?@h*r^@Ht?CrR|$;T@*7Pq#jxz)dXiMAtGLY6Iv z<#~%)t6Cm*&cNtaFo3Q7W>W^EwGPPtFPnfq=Bcx)pt17WPd+a9pd>oiRZ94=V`nDN zHra>U$*vE6Iuza6Uc7S<_HX#STr8Mn5%$y4pc%85i}j;Tq+4jeB%tt~naDU5k@VXEv+ zRzSa=r7d}P+*fP=aLjl9)Mw1@Yt9IqXVD#pJ9Q~2ni_YTSE4+R`$cd~Ws64%f0DFp!m;S!7D`D;3)- z;d^ch)o{+>;%{(w=@RD8n2o?^_A>`;G<#Ee8QW2ruFcy-Vw7O~4-N&WmjM$$!$>Vd zkpHxibwP{kx#8BK_6rueR!wP>j*iSxFjEvx`s4#uz`u;{!AQC}s_}a4pv<5D+Or$93=+-03&dxO-mp3R8a{jB@L)bDemxU`9Sl}BwivS1NU zE9&=OTd+D1@x52GKsTCL0QzJKOuHfyZA@}wn3KA)V`U%Zy~D9FkA^I-p5pb?^=SK4kebO0YGd8;!&(@JG^+6t`!u8P(s7w!04nlc?@q0KRu>C31Kl ziHx)l1u|dui>6t9Za2s?QNCJ7*ZIlG9mKNBe@ftE$(moGcv`>f?s8iGx)QELZ8)NT z@{a2kk$bqNIKo@K+9u1NV}M=>i{5$Os-tUVVCmXy)F0k^3wUj`)fX9xXExABTG_Wi z=Y$Y(ldM;!7H=QQIYSE&wnqB;`#k>1)p7DI>S2DN+B$F^UpRK$7l?+3MVS*JHf|36 zt9u|p6$+EhtJ2&Ni-!?kT5c+j>WK&MiG{nQ%jZo@?Ao&irv=7H>jy-Jg|t%dYv1VV zTbX;$aYn+Aw2W~*n)^bioH;N%x;81LQF=447+xdWqdL3keHh=R=tR;xSErYhN3iF| zw0(9a-vDhUm(j6VG+z7-Fzb3W{BxZ*o}y(dipgZGOS4ByNxoyhD1IrCs;7BocUs9` zbYCuwvx%h9H7Be5ltzHUlSW{qbO+|s;t0-T+k7Rir>ZF2SRTgm(@^K%c*s09N9d@( z0SLC{8nHh9zm$u=x}gGZzzi`XCOZMajlTDS;5FOqJ}JYRqVpuTFLq*e-hA0 z)YU!jW)8l^9J{TjUMg;OyZ{JzP@$Ic74o`uCa_v(mS4f z;8Qy})qg!Ua8HchU}C~ern2^RkdNe#l)nKADVqM><^25t2voAKR|nZiTsc&79L19q zlL;PA*+1@*&t~vNqze5AOnQ(XqFWVduZsL}1d%5~XmdGQ-nD_1jF|Z!AsH=( zj|=__XKx3-%{ zo%t^UE9Df*^i0?LPpwN`q@0WmR|iJ^yZm=gu>lEkGP2GQt!t&?6ssvS(3*kDvqnb> zA7$oqSN3Tp=hYPgn=K9E=|wJo#L-|F%^zjZmchNT`3k?Hz0ufsRtX+=h1KW3GEziO zRq2#PuH0$SpE#(KzDxh=$NM+Al<*g1UKGqE2o9FtzaX&0T=ecgo0g&#o8YRP$$1IC zA#&(SnPtB_!YTBD)GU0h1gKu~jCA#10OcC}PlesGpLA*O&0z2K$qV&1H&!JN(hI_* z%4XKCdc4Y|dAnXM{z}K^JE8(Ur!w=LJJu0uF3khMc%sFOWn!!cq6HLKoVSzBH z@QB+W`G4iy^9>oKDcFUEOPY=_36~8=706R`Fz3>gE9_t7iYL!KyrPm-?xBGX_S`W4FAT^FYnkMMs*eH;xw9n52 zUE=Y9KH-<+bintF{(CQOZ7CsqB~zS94JKBbUXV>v)2zg;G7Wqb|2E^q&ahrspSBls z0`Fq{#m%S?_R5Kqwk?ZLJYn2svlSxL`|q#YqR#1c`fJ)*9Y$UNA`vw9KcmI}_nJwC z3ML>e+-zV0!@>6`I?<&E`6ejjQ%Nl9n=g>58F6z z@RLHfa)#2Y=dOc<()4^;!7Vc#%{3Ca=dJYW~rrXUfs?Ap}QQC|g+KLX+8v82tIcxn4op9(G*g#PC zSp%_zZuKpShlAP_4XnidNZ2&BmmJGbxX;2E9=US$T1bHNyXNiod$Ro5qsOGU8dz|c zgs~FrVs4=?@0ZYLtnV&WA6bccCdVU(>3RSBUb3kvJbg4dd2bV~al2EzLqAS+dc*g6 zOHK)RrJ+pt==YNsJSKku5NX!15$Ibj%!S`ihrSqjV9)Q#%9`@DDf24_n``fiPO;m+ z8d9BB7tm>6K-$1WJwcMga*2?w;M5zH-rN2h?C_HG;+f`vZ}vNi5lH6j!kK{^?tB-% z^i-7aU1Pgiij%7FQp;aU7ac~rZ_K)p&$%WKrD?k>>%Cv(OU;h)?Np(F+PwtRJ5@_$ z{s|(2{xTf~hF2fyk94pb+)30C;3vuYilG4_Blz*c@NU_$(B!+*@JqiOyrBa{A9Q%{ z=?E>$b@UP*oB?s^bHq&-p>8(aA;s=6ggF5uJd^hyzuO;y{t_npW%|l>&Yq<$`=a%o)P_llSUFapyjg5@2mU5#x4azZSYt4oj;%@RWnF2 zO@pd|vgg`!2)lltCKhjn3f5ohaX6`-3R?SfWp1k#+#nxTg$@5yk6$XdGn)34S3Ox% z&+#1^yy3;^S-_st6VDBm$fvD1;eiY5PRAw>*Wb&0($P9sCKhve-;2BByZ33}_2*P* zO?ejdMo|+*B6E{+mSm);^}WX)!JK^Lg$y7|nje3wMX$JHiYs$V?Gn#K2Qe-t6xUbM zhxR@>l#7-0MOp!Mt^=5OC9zW%`~5<>5|1%39_`t`0E-B3W2O78T`gNN_NNyOpfI)Y zVcDZ){vpPip~q|4EEQkXtYKo8?qBB+;Bx2C38Dtn;Li{Z3~d6Nss;F{65qA{#ACCg zfG=uKYBsjqIPbc_G}!kC;Jd3XZjrh9*hoc=ITbx0=3w>{2H<6^L6NIL_Jc_|L}4CI zjW&Z~KKtvtAT9P~OPu6gq=~uTmq{B5Yoi|cSeSnP?b7|G*cjB0RuOL@JEYsjC-;nV zZnANiI?r+{GA^f=3bC8}@5>u`aHP_*T_8FykZ$jP`&cvT zWr3e`aHun;a|GZSvDkQS4>9`9u?T4`8Zw-}6jI31COmnw40JABfj%tmlP4{807J`A z9xs^;#9O;V41_U1(sLcMy79&fJZPaCJ{);Su-{KtHNo{LQHjPU35S7TjGBRXe)M}A zv+e`go~!Jz8O6gZJ}-DhK1fs)_zk?NH{!F|d@2U&>gV>Gl{{#^P?onI)c9m-^~TgE zxknH46em;*w!y_~%KENuOCQ`~?_>P^xX+4})=moFR!4=}TK4rL-=r1F_msoKagx0|OZ7pa@x@NLhJb3sP%5SuU#62;I5XAXuuGT}`;^G=Klr73iIz-tb?1%C1p zX}MS8{1>2=<$nJcoqt(Q=7Ek*3;#*32Q^pF!K5KSD+Jq$^B}sU*fP@Hp?RjIk{;=I z8LEVYI#&z!A9y;5-^~=(gT+p-PwB|@Qaw1s*PSbJz2drc{yDd=mcDSzx->zmF7}3G z72z}5A`3IOO-*{mP@0GJ9k0OV5tF6+r{nZ3ms{LH7{SU2p2Z;(aR=WCU{KNo^SKG6 z?(~tR$Cpe@>MXcyOV+5_e;+GfRl;>cTIqH01NL%fH4%9m?9HFFROpYwre4}a37m)b zYW$(hy<0;GmDjtGZaJ|+B}Cuqb)7>zit#TXpp-@Y#9)h*Nw*FXYCd{r|ag`t;h^cQ+^al~|_fD-l-l66Bwk?y3cf(s#NIO0i*7i!-cDN~-wAfFdEeX)~P z+~Ig}@f@0WhHgC35YKJtkFFpF%MV;#G_@_Encn^jNG?eNbN7hr3cw|}fazDVZWrOIFN9L) zrdA3Njx?RdKiY7fLR4VKp-*!v^0M~!dGL|NUlULgzP@8~a}m;<+ z`ux&>xme(r5&p6cjNh1i0a0$DZOqj6^2dii5Br3kZe5uBXJq)h4eVlr42>4c&ab)EYZ`0 zoRftfCgbxt_eV*VdJh*gpdhH->mwVH-z+j=8L$=%wq8xs~?C>0M3D zGxSqXkPMQe%Y87xw)8Q%eZReU1&WUBt5~6=&p_NLBy93g#;%qVe`PAwyP_0@7MIAL zf9gBUuYexnX%usj97+IcVJZ2ml#foAAT>I$113^Chl6F^A87w@ z$`@TS=ITZ29%XoIN@gt7YSlEy8$VP)$+S?Teyc~gp6S)NWq-klPw;caI?(Wg$nd=q zPyqhE>hV;))Gsu>^1DAuI?-JF3s~g6UoI}+HlnPxk^RtSrEc1@cHFx3qotZ!TNaUb z`k$k$(9AN^t-6gY2JfX$UaV}?g44%{UoES(0DikbU<3rI-W5*l|HT#=B8~JB5vgB` zee|3_3i9NSrfETQ-ctViRswZ4z=f4zw-4+MNCRNcv4CjaEd0^hEsIg+;avAU1;Fx3oKzPxi}Y(I{$n?g3w=^|QP{PD(Y=vrewjJhxgq1O_}g|W zO(&#N9NtHFai)CH!nKM}3<)%kMh@n+~#Y`Y@+_Tb$R zR&Z+5095az#y^?-B^U`csP^d7YX5bIOc-LD97OYd-Ay{44jKGa9YHJfZ$pn-0kf?M zV?QNOfx<>NZ%J`}hxxwp-SHY(Ncy@1F0G>PM8OjyJGy`PJ`?;oBk|?_3o0Ay9uwbY zAFi(sQ=m$uhH0E1qrrDe+Ddbg^v!-Zayb}#OV%C!gs&+cP7pa*$^>jI2U>q>#rLHL2$|St61&VF3%$hA0`3tZt1xq4? zy>qaBh>>xXLb{>2DH)NdvvxhuLDcn4(?9s}^Om3_LIG^$HrHsgX~0R5c``+5S~<#f z6Yb~r5KN-aSal?sd!3#3$7*PD)W_zSCep1L$@}ll`8kY zDtF-_Qi@PhnGwMG2lKL#i^9#E0>l+j!)ltK!BIE2ytG=FU+ciHqC;iV9Da!_+>0Hv z@_jmK8ALdY*26INc-lPvz1ipseJkIbc8XykVh4F~EK_qh_%WZ@s8w4ZTxvJk3g=(k zEy~o|)y)7NtEJ>o!wR34duBW-3Vt7U6}p-wJFF~mSRWH4!MWHR1^W6jXd7HrpQalY zM=eh#ZP`L4_qkPTpFwWuS3qBVX4sT~w$Q|ajBMp$giB7r2aAH0#1hrBOE)OdiSsL~Yvw6NA4=;qilgFQ86RI0Ka?rFo@f}kjgC1R0gswSp+)*3wR1g+n${}7tr!|Y` zgzu}}D{3O7D}XHY;2cq1-A*A~`FuMf12~(8uyh)K1L^qm&qqG05Df@lgv&{es!(XG zSk7b#i};!$($sevxKNUE>)@IGuYt-W(`VEi#ndti z^xDN={V03kvuu9`=ozrw*7|wt_yP5>0*p<}K z(0CIv-qfQgZ+Xgp0kWJ?s>&vLFs_9UVQgSK3|)Df0$i!Jfi*OnsgZ`B8F=NCI{&_K zeuq^wp`}(pQAmm97B{z_1!)9ArIiJKesUlIX$ZHk4I7w($6g7>t&gZci zZRbgQf9wANRC)huM})j8_ZOgj@Yds;^(pngfLAvSg~c3m-i8-D-bPGS`k!sWcwA)d zmQ?%^v(446%X+j%mT#@_x90GD2L;DFCUr9jthq#Hpmn3u^CNjPo{1$Y%2l{7&?5+A zD-ezMOPE}g^o96Q?&XvG?+WNrRG?udPs1lt>)RJIb%abWlHn;3Y1F(RXHLNwziq%S zj6Avw|D|mo)Ro4fAe1_4E@9#vy<03fnx+?85NT?nD>RL=TTBql`N1OjjzwHfRCz$f z$EB?xIcy%h!u)^%on-a&@W03~@O}BDdO_y8GK5a~zMw>#j^^_s2Ex$4Y2D%QX;%uc zridCszcs)4_5(_;bPJuk+W6u3PdCY~9V2*_Xess&rcNt}Xc4V~VS4LlU?AefDL@Xf znoo%LdccN16O!V80T=0h9BZQ{D8_LoBj`I%7f4HbMFa z_mNf-!LDoiXDIItg?WB_k?+H$63ouNmrPv2pP>_+hy>RR<+W4F zHEGg$HL>x(7-d=v<4+k`$(z(?@nMfL`>pO(7S*a~8hrT_ zJMHwM@MF;_?l*~JYXoQvBC?0k51<_ps@ntoA z#Si7ebw}(H4DFXZDPP~%wIo0>-{h@dFz!a);PJL7-QISB$)$uGBl zmBYy0?ztY%C@v|^!Xj}L{mX@jORpSX&$?P0!H|CQrV~$1n?9O2p_I)3m_}G}kTnxD zQ|qO9!w=Y#>82}jcg7SRtFg$$et=auPidB(w{kIlbhXQ`x!v8t?_9hR{TO;~FD@j# z2Jrw>sORi?=-MTJdH8t{0*CGw4prMJQJ%*H9nLx#ia4cOobzp*>-jRPif*b=uweu6^i3 z0AME(X#*W-+NgTezGAZj*2zz^gF2 zj7K!UmQR#1GhxC@)5vT{*61O%I3+=IBu#CT0}!MGuJqreAk6aSd@IRcX4TXMZitIr zFgZ635ej&btiF>oblc))$N(zhhql=H{n3%puVQck-h;R7sE!D3zqQV{ZqPa%06*WW zA@X@4uf1!pYWGqIJK9!!jPBpPuQUEOH@fG;9c&`ue_lhHWJ2e3#D!B%KRCrH-QAt< zm#9|ZplQ7#08m}M%i)W|q`CG6=!B5W+psR@M-!vddp4)z#DWIt3DhFLYEQXbm%M+q zrcOS3MYp$vsh<+)(5boI^ZD}@*e_LkA(o(fP!r4N`_T)qlgxi?1FLf)OJ@;m>r<-x zWumQg9_fESgli?LZnp2_^zFqSyf<}&+UDbM&Lh@T(eju2l<`Ql+<_TBMMbqGX8+|~ zms;Y_M|8Ol{x;jv!l*m*N8?N6=~`Nsa~dUQ*cEoa#4@m%lperw9-avF_r^caZ=2h; z@1zC@h+xP?<9@*YDK>xDkK{3v>b5hA4t~V$ktzIefL6)`Gjkjh|IPqm-68GF0b$4{ z5GOa-j;^Ewu+_eILSD$giA_@9QW+a2V_wfIrv(06?mQt%G;l}J3v7kFKzBKiwH<=> zSJI&|#6fJx1XTOWsY|V!%$Bvn$XE}=WfzdrP!~xuVAvH1wDCRiwqmhpi()sYR97O~ z=1{PPM>b^qGpv5i`H8i=n1>O;`ij45qFNURRIkN?ZY#+cb-e~i0uya4^fa_2oM8I0 z*kNp&Wl^95??``B*Gr)%NZr{Z;|*K{-d#nnDg&*}K=*xVNdM3uPW>l((vgJkh@kj^ zM(HMd1OA7FLun9)1AOm9PiJ%Xbie1$M{am0-9^<``=2(U?aR!gyqZKrO^&=bC@j^T zKUg;%_&h&`&s|7`CH7@JSDT`cDSvNx8br3R1f_g@tu{BB?(lb0BF4j0aB(g3YcMyA zf`&0_!GNT7RQ#tWlq+$k%GYcCzo_3*sC$Ac7V@++CXH@}2k zdoFNi>pRkjqHMe2gTm6S4uTu+3i$7lc0_kijOu5lIpXR#Fm&AO#?$Dgrg7TF6gHEJ zGXGGjKp)u!%$~Fm|t0TwexPR>I3%PqQDz=e)}?7?D~AZ-|4g0RSR;)=$yv29$63g1u_n`XsUPy zV)DlN_2JnLJn>+VMP4YUjVyZ-U347M2=>GgwMYiWDh*bhC-e{>b)7Mq1N4l@=ztxI zWN~i$#{sbo6wa#^F0|Y%6q7TAaKTYBU}p=A-CA`RE14B@%iJOY>>M}if6mT#eH-NV zaAe|Naf84oQ-`3cj8EKMExkGo1ZC+g@h1-wW7F>nC*V0Zs&7r%8i{D&)eIr8z@y4A zn`^&Uyc%Dvf}1NYWt!(;O(+{_{Lt98!sg*olWw7|xXVJeOo;Orx>@9AMsZ_xv6;=E z_a$@QSxY5=b%|H(E7>^f32z#|g;;e-`J$lK9?b2@c6wp##eeM`^1t`a zyCHrno_->@xr3xTUmU@B{sMmMH2(zzf!C!^o#MDetZ!PK4Ze3!7XKGe?E1Sz_D(5| zPTT5OrBg^=_lYvAV3l}ocZmQx3uSe0Nv^ip_Jo`9r25BzgGQA|8! zttQ&M;ByE}U%#$YrLw3ts z>o{x(?CxAqK`o)RCHeDhTwCv)PjnYFbH@2QNIE@o;Qb4@>l_fZ!;pN@CI#mC2&UY& ztCzoi6AE#a^51PsAJO~|}2&^RrMn^?|^Zm23($xP@TUXD=w*%in^ zH^O2_=0|)g{L^)#+(1=Mp||^U*J};WD>6$R)8k=l9JzIBC94Mcgf`gak{jjUqne2( z+z#l=GpjR6mQ5!A70{dnxgO(_A9eQ8OJf{ zR6~t2@k}&VM)Z|?I~Ky}!1c*xJRwuP=4iLT^R6|OpVq_109^=|p}Rma%g!CV<^#Q> zGZ^XsM><|ITDMJvTqRz*WHsZoGIJf=WhI`SdRI(SpHsLxr>cQUYy+yw{Q#uluSBcc}8~%o%yy`qn$^Qa@@VIfkX{X8qEJ#;UIpI!F2w1DW_A{2)v@ zm>=!xaST$u=~|LYVUBl9kk1K0EBO@C!K2GPm@ahG>J@lyoA+_gWTeb>8FLRxuTtK^ zSJor7Qh=@zk-I@yOE&|v<#i2MvA|M!iKD(y8aKC{c^KY<@C&OF{-*lbw`H2O6TAO; zXI%sxpJ=29%KofSq)0BJwC_wAkTqi`TZ>dut6Cp`1~3D<_{m)yO>m*2zyjsLHbig(Yk7)|34UutbDhuqKWc5!B4ExOKw23A3C8K zFFie|iMyKfgYq?YnPKHK&=z@qtXX?l`7v6j{$f>~k$>o7n2F7e9Tu|Qbm+_T0`g{9 z0|ji~X|qG!J`=gqYS7jGx-ZXXL#(>a4hL?|FMeRoX5#bVl2U#yLvL<^JeB&WQ-b8( zk{uD*!@n6#HeU<&WPL5oo5`!PC?w9fBT^RO>Jp>JRFU#lLC84@Pmo6%am)q!A>G$)GdjFPbCe5j=n5E;~g_) z=oe_^}8esvf=p@$0gJB8QAaRFFcl)^h~Wnp1i z#Rbz!|MNK=Mu7AtHAuTRV+%cLJw4IyjHTtMVA<$Jk`=vWmwq?|MKc7eZG2c6|1g%R zh9)FN2pna_*GzdfnQAZBS3kWj(zw_uqkf-3{Q7RWEBT;i%#Zdjjc`im`zelRg#Bg; zXrG>j@;bwBEQ*U3mzE#ZjQs_C+kWx%`&kpWx6QLjEL4`!&Y<4g7|q<6X8St_1=RtxwZgqZusie=s;04tL5z{ zvTAX32h!z)c(A}{@WAP-3oG!tDVHXja%zcq4*d7n1?hK-F#%~p48Y`;z4A$avE44W zw@=&^sq_Y7^q7Za6gohA*=uJ9>^HfhW0M5ci$Rbf-*IJBYd-c%+QF!ru9pnIZVv`J zgj}x^S2)W_H%!nyqf`zpvo9=s^=4;4_Ek)5e!6cQK(!EkEt5t0x8i35H=8%CRJDEpE5a(=^Tf zk|0rxi~bmCv#I#K%~vn4)2IJ&g#ij;TZ>&`A4lYiE!@wzGk42exZ9s{_7?=?v!L4e zj}>;7n#_Ume3&67xVr13|IBI5t!zQWVL#H@qY5^qNH%l896A5A@qy|MaF|L)J|F4F z3UM+v_0No3+tl{;qNf--&f*(ID?yTafDk=R%f@=GS%$7~VSOjpCfiNMHcZRlc|*dDsc zqM$DF63is@P(%dh9;V?yyckr)AG!X2(;oh#2-F^SDxB0$+%gpdG#6aCZdY_>dPC)#1v ziE>P8r{gx6GQ8nNVvqTeu3kMnwDX z*#g@>Y%7Iik0||Q^OQC|GU*m;LJnz&k`Ey66=f|Y>aVvHHhBFKda!E}XIcfjfp{F`Tt?@}+Bj;A)5%!%9bc*oXE5rR%FoYd9CC9s;{lsc|94b0dXk&7zE9Z9m_>DZPG`19)t2qm^{8Hs z5_;29&anR!;H<;m`){(@A)+tHU={?Q6>Q3N#4K|PgF1QC_QJ=-E}&nR%QF7o(t)=2 zF8tH^?60PO0i^zjXMR?H0Sfdq5LG=B*o(+Kf z*q=Vv(Tk-Ri$15Ty^;1&H`ekzVghmwei;P~5oFXU@@zPMJrt@6lao^ltQ|1z;ruNo zpu-w44o_5Ckq7|~>asSBRJrrOAkKc{RLk=URsk81k37ez{llEQS`OAMUYk99ioF~k zUPg?U-yu=%6v36Ff800mY%pod3)oe`@U;sT>@Z^ExixHf0>`p$%jcSbOK!PKD4!ZU zt$%>O!N&Bm@!f~Runp*n8mEVAqEBx{Ej{S0ElwnidZq2TBHf zOr-Z`v`<`oiQDL;RbpFnaVl9A4-dgw3&g=L-A)y$9XE!r5z{`4==OLJX9I4mCW}uU zgnwQ$vK2@9U}baoHD`CIQ1uTR!P9Isb<5vEe75j#&G#~77xNKux0?5ky}O#xZ5#m`px3@#%vd7 zO=8oeXE@buC+E$v@~1Tp6s(pt`xdnfb4lir-y2k)b5t$dfN#S~L_lbpW#JT;nUR~& zhXfk1?!lzTlxpfahYex(f}mqE2f~tZ;zzpB$cM!lN?$Fry`uOXewlnyj~}H7oj{f! zN0d6+8Cv+fHtmu5v8ej?yTWx803b3(5kHc1?ZFC;o3DnLBJ^6zvi5z5CXOa!4?njY z?1yH|4Qo?6wLdc}F;uobJ_+#6A2&NXm6y9it~_6BM*O;%!0|AoNn(@J`5+YInZopy zj6f2bHHr7S{8i=7LHakc5qy+$4O1Vz1wR@x35D%_os7(ygpa^T7|EOIa7=w|No^jy zra!470R>p38z2X+MA03f+Yds*rtWp`ZCH_3OrXQ&B`rd;E)6}6#~%|K-wvsw4?`7! zuO_rRrROFs2BW4fG+NE-XcezZ$fVAv_%-lRL=D5Q`jW#Wz|8X51@#xd$u~(9fs$h? zaeabj_<7({$Cw|EFA+j^DACIu@0Nu!J%)_3Aaw(3rCGcvy+Zt%Qr?lzRUr&sLh3%; zc9dK4x%c|yE#*j)V@LbX?&dXkHUw3KypoJZQApSXG-#@+8(f5EapjjVHVhySRzs`O zN+l(W^HQ7FI;A`7hcYDxZS^|9%ajh3>s9kIB2LZBp`_ORmW^ERtPy2WBrBb{mrFjO zpC^Kg+bGDl0e1Ezod!QFbSo1JQ@fp~tEBPHJ3{kq^|={-8gc0~Q#wJ7OZH@K%=wcJ z7KAZ7?ZIu%`$p8tF^UE~)Myx#=9Gy*hSA2KK@L=Eb+$}LtMO0y1UZUgwjBy3zQR;} z@g!{HOW#QJC=W63Vp7?ZP;Dy>>Q);fB5TG`m=jsv8C5r@_El?B?i&uxRlT_vwlo8P{Z<^L*(7xE8ejx6-zxiOuUAV z1S2MJpPkyQ?_6q5X(FwCn2*KA+H-NbiDk`&#OqLE{Tv9H(&K(d_}Q>#Yj z{Cv(ucDUl6dhFpsKPF(7xJA33GgQMAo0XjW55(ct4@Fu+kw$LX0~wg7rI6 zULA}%GW-k3+{FF4nYJSm5q54%nH&eP_E1qPcr|`}!jKnT>$|TKYEKJI;pA1KKm$2< z6wgJ*rz*STJ?^JcDfcjmG6hYPZ&s^8(%zKx@_;jE3-b*sE$edF6Yk_WRSp!c z`$g;`w;hHoc)*SxmAM z99LHgD#_*bnuKeY*aRc5^-8?@hV2i1{mvdLv#Dy)n3PCs7yOuft|%3K#>$minuB7w z;_B$#IZUd_j|X@$c1Q5+(Vy0Y<ZC@%x~PYg4CQ{=9HWjR)C;tbgc8Y_BFEW5gxjpLJ+r}< zC1ePGvP9%O@$Lcl&utwcYb5y$3oDkU6gD9_{Y=LhuX|I%SIg3)qLV$o`F+64xsa#x z-Sd<;%tgxA4hHn{Z)Zd+9^q^xw$1C&dwQT}ahf|EmIR`c`G9|I2*#joOka+p233`Z z7Pq<@U+whcEYMnrG9MR)58-|&^xBMcGpxmEs_KAzWlhfGzReMl!8;d)UP{2q<@cZB2qH-5>rWycmDUR$^?5WZXUrUc=S};Qf-O*$ z*OuB77Mog{Le&x5+4 zAp#>H?0$fcjs#8;lw7e0BRkAy*EQy%iShz!kx!H2>ynliOvvJbf>knnn-0XCrvk`Rg{@Hq8>1XVw-;auEs_m7jB+qHQlXh;p#=ZnW#& zu#a{XWU7(YMia)R22NMH&4C4TnfR$)H7d^WvQv*nk|i3Z)^0K>@auXv3Cb47_;ikJ z@-MK^g>y=mEJ!Qo4;i|@lv=Lop3z`Bi@6)+wpM^}EH4_QN^XU)x=JoB>#hp_Nq#(sZkrah{aaKccIZpD$;eC7JegLlq2KUZQRm8|dNUG+0Ym1l9@~e-D zI!y7Ws&Y5G>mSprw+gqdQ5ogLTOl`AD-GU!L1QWts`>;1T{!sQKE#gR2#bHX%Quue zIF%sW#-I7BdLiN+dM8q9-nDN!CTtGHF*+jl(+-chi5Gt5cS#5YmS%-$6 zFPBfb1viJV8^l9=Ao}Co)>on`h8lkeE%rBiF}qx4S}BS+;~q#Yok#IHxH^c&=3<~) zB7nJ5Ecc1K&KG0vJaZ)rWfVkCNM6v)XuIj%NHjr;UUL;-d$L`EE~)P)V%z$RtRBjxmOu=|9(OU@e}J|OGKHV#zSrSBs=_oyoFM1V zUsQQjRKecuWFxP+Epb?7&&l^)&+smCGzSbo#s{6}=_(c)ugttpNLGd#m?(I4F`pFG$}0o#fJSTZncb0l*`x{uS|B6`l3zg=MG~|=oS;%*{1e*92o;XJH0TY6K~m|KexmV?5n1)4^Josi@8_Q)Nm{g{W+CKdD(9zY`&Ov?sngmTWD2K5_vZtGg z`!k+rV}T75ZBPT1&m`qHk7=**myPp1WB2fOC;&~PSL!=dJFKK)lF#~V!5S#El#6|s z3u^us^w@n(hIm7LWOq*&zhY6HnNllS9Qg|<@TgnuZ5a8+mfr}m5?Ww7d+vj9m!z}R z0k=+{dQUIw*fSSGrq85co?idC9@l2@>Gnq)8u`A$%~^!yV}iD5iwIIs3TIO+52?Z+ zXt!^sdsgD2-)b2vJYDV<3$a1QEHbok1}*_tR!{1V4<>OM#Z=|rwW-gGjE5#~CKP`8FqifoER5ENsusLRYnpxdLUv10`y9<3>_1V^m8 zUvto8bo2%O6jI-q2j){nYo zIA;1I!YO6&@HHd;^UIBf5Hvt1>{5+HDpf__{1_2kH+u1|+`imsMJd`O=Ilz#xvoaL z005F}>Y0|rhc%n4K4myJJcMH=Bh|9hUBXx%U`tBm|4CL5AgB+qA95p$bDUbSHi8l< zmmB5w$NZTN6K=e}zuNURLhUGjw#p`ru3%pNw<9xq1ES$hS1P6q>a501ClMje1(B$T zu?HuUlC=*gU52-gK`jJ8SGZK{3b40%@9_i%RygX1564X@!9kXW-dP0f;ewXZTf!)} zr(1@F(S`+-XjQuD=@eGxx`sJqQGIYA%&!F4Ph+6u}?(8BAxHzw!MjI62N=}(284zmu<2XIR(ZFd^k zh48E%=DT8@a6hX2ep|h@u)Ykl8O+xX3Ywyh&!9wPItFkU|sozqEA;nU370#`U&aLTwy3oZgpy(Dz$YWjhardJyY3duxzslEn#hh@--Q7LyiBB{foI@1Q z%MEljl2iHSq`UkN-20gZvVL3ZH`l1dXq~B6Lz3-7BcS+Uw6C=T8VYYSVP0a zGpsESg?3k{EB9Af;Ee6>RM6AzRDGwqNKLOjM)V(KGLaFN^_*J1xR<(-4S&kUDkj8U zU-z+^r?jHlkqQ%UHE%f+5%z8*$?@@-`V(P#Kep{f_xCLs9hzMp-swa>S(S+gz&LI?DO$Mqw*8Kc_o6$%SMR*Rs&M!b?K>?3HaidI zglwf~U^#4Mb{!RVU(3FFSVIGzAEU)Cr2qgZp$~-|(PH0|`40<)hCImYjsc4%?x><4 zu$+v_NmcJnqzbRw#wb$c`2BDwR0@L$No$B{q^9q;U!Lk*q`DeSxUXTWBsEIUA zYY3t~Nh{Sz&1im@-tZB_9x$B^aR`3$IUnKeR7dR%wA8*Knn2VX$w+I;!CMHyC9f-~ zeP9Ftkej4E!MCo#*XHe7r{+qf>5aWi>HUIEvJ*cX9h$JnIK??1Ru+2W?*otxtT>-i zhMw0l)_QV;FBLxjgLmd$*_<@XkO(qBM5LhgMZ)?EWY5n+=2SspIgTwo8obYsXdX$~ zdMxu~_=(a4bUEYt*Ds4(;6U#MMaHkb46?E-k1+QGN;99(;9Fi}Wc1v;1T^!>>WxK& zS_k9Zg^_M=Mu0u$J5qRxS)=tjvi26Z3 zCF|!+f0gc-X1cRGa>;{zWlJ7qtqA%xc$L(CwITs$E zV$aNZOoS_UJs77#Xppi>{?Ja546Sow*s2){6WZxbVbkVq7RlBd2*V%}LPDeD7UF$C zQSB70c8oY-R}6JK%zfS5<>hr}##g8Bm8haXyas3Nu~IG>O;{kLfnp8XmV+Rb;W9PHL zqvqzly*xgx6NkIMfB8fJ_mU1ME;agj=J~aZ8W!t36=3Yz(nV5*Q z)D^aHnohGmHb0%$c!`do7~|mSj;U8rdYSvi+q30yd83z*t&K_+)MF20KffiX!uS0= ziTUXD3WRB2_7e`~+=rg)&x4Y5M#(HTozqcGooQuTh=TWR>rt*wHaTwlBcDF8SQhLn zr$ac3$_QB_Tl{9^)*>}5Qcfg zXpZQfWyb57`|Iw0Z@;Q4O4k&(j;}=4NUKH*ozXLrGWGhHtt(_S2zPUnNbee5P#Lzf z2GvAoMaPkmDFf*vgk#wNAT|Jz3SsIb^0V>;*{%1o!gYKL7pPSdr|#QrZifBP{76X7 zhmK}b&Li{-0}68T5NF<}j<_Xo^KC`oh4Zcu>T~7WK(gGv9s$0O;AIjQPE{WoY06kM zKFJFqC=XmC@1@+IboJ;b>((Y-qRL;THQ%^p#Seh4YS;vO)^pBL7H@zMH(FnaR!oyZc(>9iMg^&j{RgnABh>oO^Dtg1 z>*s+M@bf%0z(4uvw2~6L1toQYQ{s0&)wla#Ot+LAeht&ST}hp)V*m_vwmoa`EF8^v7yemHgK%j(Un;7e_td!;7*0|m-yeYcXZtHkKD>Q*@-r4 z!$1=D`bmIwORe!d42dLUx6zrO9Rx~DH%h#0AZ7=;s+(L+cLZa4T>elkUp>_uMawav_{2@o#h~Bt-MLNLkbULp#pAIj3YDH#TdBOn2gqjiBx}7kMda zJ%?B+A@%-m-HqoF|6dOT%eoX1 z&(dMH(UtpnE&Z@gJtnJR!YlG?MdjD8Nq6t9d~%8!!oON2;R8^=awRFdc;QK$%$nbE z#j?uYG0;YT--<4`u9dN0eV6~#)7jgC4fB~!4M_R{{5tv~OJ?@B%Phn>G9^z7D1kvP0}?wg-?uF7A|*K9vzO4quxL>`Dtlj|bxYdp~oea-#5zYcWo35B6po z%v1No4eIoaF=Lu5FxK#|)<}>X6*pp-{4M(kFYp-3bfM_fj@KR|w`m^Hn*JbaXt{jP zM^Dke#wtmgnZH|wg(#!S9f%G9Q_D&sl2YJhX(o(x-v)T%r4TH{#9t$j4%}km2>y5( zSif;*q^*>fX0(~1%o-!Aao22{A=^OXlkkZG5P&nWeqiRX``^nv2tIxNmh)aMO~ z%o&~EF{mw~r6#9NaXj8&lVUnQv@L#h69f^z9=1x#%Z7p`z7MqIE-`McZFI^@~8CqHgy%0}!78wBY z?4hV?S6XiVm^)aMJz}`0V^Sd#F`{qRZn{}{_aenvQ(KoQ04&$nPzQc>NF0`9f3vNu1i;SrLkY!Q*OEB;Qx74sG*!L_a z;qvYbdL79sI5ugj)HtcL(PG1BfXx5_ixjB0;N0Tkv}-TThFrrqH zvih6IQ+1qxnlrPphHKis!@fZBh{K;YE+8A$8=_k+@NLK?VsWDqtDd5%W=aF+eNFPq zmwniwJEO|OL4ruiD}7}V2z%9nG5)3K7IA- z4PVqTcTBts^%3;3<7VmhBb&l<)Z=JBxCxKmH|cnXH3~V3BhJ_srkOVR@Xg4tS2k!( z*sJtTo`N3dt(TiNp(C+zzq@|DWt|q1r9*0db+UVgly8q~F~S&5Xe-l4lY&f_K@QS# zEUvz%Ima%@bc-0}T`N6@0K}Ttopv-vKP~e!A&?3xC!)w{1H?5r5ktxi{q}^nlV#-s zGPWv&Q{*G%NAYfvb3^(MMAn;H6#=j4e>4d|eLFn0r_sGwhle|NQqsrfN1jV?!U;~eT)4Z0I1fO|O^!e|DanBH$`v+5gv{BqzA|y*G3BKXCGxEUWW%U^~ z@5?HWD4%+lwvx4-uLy%~ex#o^8}B>Qbf+->G!*d3LwkF@%bcP}#1 zcZk`_r$J;99OaiD9p?getjwWD;E1aCoj*Bdjpn%2?kDx>I*mcfk zT}B6&NaIY|pX)Y5xdWmQY~u^d>j}^e28#HxY#0BG8Jst)ma-N6`^h23$c$UT@E}U{ z22O9HF8YQQd50Av~pg&~iOl2mQKy*2kKCO{_+q~`>ZqRI^eeW(gib?d#D?7FU zIUO@XZ%3tXIh`u0gwL8MZbUbXjiV38=IlZ*YYesi1}VyJzmyE|7E+rh z4_Rigd&By494CnRloFtMMFLY`*QpI4j>=xI7eCcEA$t)0*-_Pix0r z%$??GH?6M^+u|$8o&UqAT79?dIEeg;H89P&jr|c6u(`~ca1LBWHv&DR*hXJG^sXN3 zn%}mP$R`#7X&n){H?2+eHjQAh)uy^9O&t-Q91muz)FUo4qfKGCdw*|pVj=gv!x}D6 zf9~CF^Q(2Fx`R@CEs9mv@IgOG(sjA+_ zzb+R8zaRJVNrymuOEN!iZltgEOlM4Hm-Um8M`4#LrQCKNipJdSs#mbfL9)w_><|e$ zco8H0=rs1Thp%>DZr3Vi#=^rM#Ti^(b12Xw`1GlJaRo-|y0FOFT9aw(H#4dHX60I#wLur?1q~{XX)S7n#yXY;5%~#h z&v`n1g3NXd65gl-f2qTanj$?hA_Q?p(EGb}X|`^7(%zmA@4q_EG z7c)>gc6ayT)2t#V-!My!{Y)2^p2u%LF&HCQMaD9;(R!xhHV}i8laI`~bOti_!73td zBa!~Z1gD-ozx>c?mu1mcvV3fpHt;~gPjViA3R*M|&1Pcrqf^&RbE;pjj|CM~UFubp zg=y;ReE$i~$VvTi&!Cq~!f#&A4zg%%#RPoyAtCI+WE+Dw#Jg@l(;jWKc`-DnY^-Ve zq_A>l-n!D&b)SuLpMvws+Q0k_t8EHJnSTs6s}d|{9icT$!@Mip-$z59VHP&Yuk2|o ztI0kHSOS?*X9@Z3wdHopqrzY(W3!Xpw&`R^VcNr-9hTNfOniMTzAwp5xC6333(@Q@ z2hdrW1M6KJh}q8ZeS_U5N7kX|!>Gyshksarm*8 z!AmdYN|p=hbXPMu-^}Sh_@PSnl>^SBpYYAnI<0ZRbgdQfp(W25)0m5|RA^^U_&1PK-dD?`XmQy3SiETJ^dm zsQ4|$*$ZpyV{wb7w@OPrsI0%XO{l7|xnf~pc?ph8vf52Q^!DDjS;l~SqiC0iWI`gY z{CCu4QB4ty%uAZ>Ig-z-yKbMflR7+W8asGW^waZ~MEOl>m5N_35p&>QBZi!8X6qiH zVOLD2-LR?!`Z{`?WnX*9dQu`9@$N}1SCI-$4TFm0O0a~KPdM1!k%q|AD$(q#aZ+6 zED~YfI(IIDdf?eUO@^A8|CKYzqR#pb^0G-;Thz8pq#Dx}KSJ8WzSa=uXG6w}x%=a* zIN{DefL)4d%U2oa!o$fes&LSQJk@V62kl25?EhIkXYoj&GGmC#$V=(TL(4>6I9B?Z z2`{;u6>o?32}hD$?a968vQuqKGu*LsIK)*nJWjL!ZH1^Hnh`$=xAXus+#;)o)`YXj zBV2DN@6_PRnsuigoLinZYe4gN_H6i(*mZ()vypJDh&F!<>k2hM%7t!@I7yByY3AFp z{cRg`r@hHZxQan+Z3uf8w((3pM*?QUrTa%~XZ_p_!>68t|2@(s#-Thf2F`L? zrH&S9>3;#|>OGy&j)*XV%8WC?ze9Ioaez&~Ju5o7EujZX{QZx8+;Rt$Jnw29AaoKg z0q7UIoU@t2o(Q#fLnTT6J}phV2~C}Ta24srBPex+F*~A~y}aMbvwr(`dU084q%XmX z8pzNW@MnIGex8Cm?iQ^&wTy?8DOb_K^t#t)U7apn9=8`J+)#m!9)7J*8fV(naJu-S zxIWLy!Sa)dSxt2HxOtl1gXp}sb>bMNZ*bKSdOioa1XWA@F)nZypD)w4ix;iDCBuX3 z=d9fpn;I$&V}`R9e+LTcr^qOA)J2jBQ|J{MHrU;G7?6&mD5CGAe$crYd7+E09>eFA zY~L@*t^ft9D7X_J%( z`bUq??|$CK4OpIV-%Cf1#>itGXH!j@FVphfmbBs8kYcSd4dEnB%#%HjxxcQR^BxP$ za!Ww{=?s^k2dC?hZF_xRqpa%hjzI{kxmj-)Hf1U}?S1!ksY6#=q9*5s(HqwpQ-&#P zgT%$2P)9SR5~-H1Bo%A`_AcO4g5s&UT}_wMtV(tsYC*uz4rR6y+JZ7Mo06CQCPnTW zPXj5aJ05^G$k6W!cG$B%Ns2f(*vj~UvK`YDoijVn_3&Vf=gVk>6rAo^AM)NLjy>mR zHck}^a!R99WG;6HhU4&R-0$t8$^KULvG@LNC8Ok_VN(U!V76_&GEDMgh+(vn3|(#b z87rhRXE`a0&aGpT_8u@SVugvd&$oqB^6KrdM6ji^#8w-9F>e94PnpEDqDuy7F)$Y> zwHb^V9?IE?pYj*<(VqqG#MR)$-d!nW?TBNf4h06f5K-KzJgy{37iod@q5lB5;J5Uv=O=uDROSE;S%jQ%P;)yYvH?`r2nbtLX!RSQUg$yX8xV@N%XFr zM>T%WtA4|Nx3{83FXFQ_-ikS_m7gYwD1?Ga%%0 zf1imYYm8h(h~cO9iS7(U;E{J;UXx=$!Ay{0kk@xxc?UN4^<_!o#M5u}EXg-#G)S;n z3N8^)+}nWBH>e+-nYrTydY<{ZctOf)`nabd0L0akU`C_5%G_7_vtrMf%J3gR$?UOp zR{HGpw!qRlL?65^p+fq<@@UV;pVG9X@SS21Db`V~#LQ?wEq480tm#r1RbjixoUmvMqu=|o zXM-;hu1sLLF;E9en@3LZTN{dxVl>5@-N3de?{7`-;?_hKNk~%{bxbb6xUvd!wz@(h zqyGk~_+S+UBtv5OZ0=Uj*Zy?QtIUheH=Hm1VUF}{m;36}F8c-%-$YW_GJU2sAiWea zo4%s9xr-=ve8Q4GbMreY=T(i$p;ZgGj|j`Lilhr04x%i5YR(~}WTbOz{U=n(-RtI< zkgAQL;I-t>paTb57q_MUFOfwrJS=+K;%E>NaA-ew8*%dxeQgn+>MeXms#rvV&?R?y zSY=6BV(xM@pS7e{acJT+kBc>cq^lq5HLVT1f+)W!o-|d>u`R66Hl8OjqS0!Y=r#A4DI^=Y zuyVY-(+rP}@v7|Q%}>e+d6zMf?te*DRvbfC3Ml6XfWqfezE-cGh95WENsJMEAQUvv62WKOxS+r{k zcMPi0H?K5mF`sqh2emI-M=*4rv7h!zLO+O>cY*n9)CMRd2n(-SIhtniF4=bVOm776 z+m9T=8R8!%$;rxpqT_S9xY6+%_c}W1hew%{fRhhD#Mw=hm59XUwDPO8ilnh3Cq@i6 zvibBuJxr?O2d|*t|Pgwp&6?v zg6*Z9le6zn8kIdoAkFYgC~fmoGcR+RDSM&~6~goR^3!cyJq^R&$L6QMj~j!$S6J4q z2KtY<#CGs^PhGguS1PVNu|8W3UdatC7n^THRACI*p0!1v8)h(?hhhur7BTgpr}_L| z^&^>v+MuR9^=<31G}DPyQXXfY4^$pWY+5R++)P~BTOJ6+CwR?aj-w+_%8ahc*2T*? zHM(DY=qmgk4dN*9E7;)nJK&8?@;a)unbS*H&9==j93slTCTr#tBbB1{O#~iA78o?f z2B!tE2=^pCbKO947kg@D6@S|#=4{#{$U<9K6+I)_EY3VU;vM94U>2D;?&>))b|cKr z3FC=zx#@~mz_RUrgyK4xZ>Q^12M?_?$S8D#8tA&wQ8TDnwXla}Y122gO^QfF>(n!a z=c(-Pb%eV1Ql%Z{WUzz1@7PRVRwf%v`DYCEuC%b06~Bi~_RP!1+7qw8k6BVKK6LRx z0unz;y;8<9tB2^}4#;a(_L|Z|1+Pi8w(slM5n@s81`^oin(6O^@}DZ##){WMcr{;- zp9u9HvIdG&`D~%xLswMKJfx*NS4BfZP?)jXHYw&M_Kz>U3_;SZU0P?e-Y!UM)>)l1Ea+zd6dP{!*ajPT?fuHznS+ zL%C~aJvj9TC-s5#(fJ9D4H5?JpbTKdZt|xdcLn0gg{-1ZptV!j{b}l^E_FDb~m#Lu=Lryg>t9zD04q z6{0bD5}2G_gLg>#GyInbsTpvHwVf18<^-ngf6_g;n%E&i&MS#DAPNe(Q-abzfMvAy z^5fubTjtE&83#@_tR=_Cc|gdvP!4*&u?}!3@+?6BCUF#M1L?h3T-^k>0q0 z^C>xc-#IWm^6&if+YTf^55lu5QJnW}P&@fvOvUmozsNwOQ_{7V6Ewy@9n&f1T$S9o zjdu;LTI%yu(Rk~=$}mZ;iR2aVdh#i`ZggV2UzkT<2olfU1HMUaty}XjgYgA|`xOWQ z7h)mjB!30{y|1B5OwRNNk7r!z)A>iT!h6MInGlKqKe{03?*{c*Bi)nt*hJXC6zQYm zwphROIUWBfRgF?Ek2p0eHTiJH<_LnrIMzSr$I*(0bHli#zhiV1DO1-vq&R_X0GjX8 z#_!2rSy5|`5X{A%snKvp<5bqFr`J(S?SV_-emc5an#i%+2Ahal`%^XBafv2-Tc@%4 z${?pqlh^az%*~5CcFfKqC<#v*+cQ<1?%5|pyDNI)$5TMT8Cj-EUT>S`<4{X~owmXI zRJlKm7S_hlOHGQfx)S8=TjwPkgaU$eo8ML;z5PR^G>ex;zGzGRWr7O$KUKq?1Y!jD z&?*Zt+((?_*QKDm_HsM8`yna#LY?a4N-3Thv~991buRKTcSu0T3Uo%TaEiB;Nb&@D z&gOy@RIc>KS1Wjeb?6-5CW+x*5ukiL=Rf0lP^y1zNb(f!^?GA&py{d(0oXUA}30O_6D7w8%E*p za-HSD@s;VQe;i8QKZj%O{OMtZ-OD;Pu;q?J~-_c_Kw&6V7$9si@Zorx*H)r z`OCwR6b6vN(r3%2ul$C#i*dZbXXAfzP8wxorKipPwm)cg`&$GcZhnDsi(RcvmOPng z$l(2+wd7Jp#MjZuNyoD_($Be5tWj|0RQ-RlBaevLk?8rN6}Wd{$vj;0-ABO6dothS zKQ}0sLl)V_rU1}I=q~hka^>*0f;tQ0W^QO)E;hEH&|Z#p61!Ks+zEXWq#IK=5x`jo z&wIP=d@sVQquJW6ZTd2Ad;?l=!M5GzkXMl&GoAI*nFW*lv1>_RZ$d^e->nMo(Brb+ zx{P|(*I-_jJuV~Z7;#nMrf^O|*0D+MJG(bs$L4P&5Vjz2GZ`~kQwBfnxEUMZ*8Fn# z^?IC+P3Fy0tIAUkwX)&5+6(N@#C$Iv+oDHi%fl^!Srxj^Ge|iWAj6(&+rv|D%X)mgl z|4#7m=rnuH89e!k0Yg?XYrAl2T6@v7J5}-Qv2y~O8Wc*OWt;84z2f)GQP zZ>=gOl$Gu3G<4NE)+2C;0>U!WTau4$X82jQA;j4BffMfxL*7cf)}X(Pl*vuG7vLvu z)wvb+M*slSAnX@7m6Ik3-a`_9kg9z(F9uGZ^@W!z_}VRp(@{-=T1U+5w@mf32~;*k z52`amkEBQ3juT!gB++SPMSp{8Vpf!4TF}=Gl(abMVUPAdL|!jh>*ga{)a5r#gp$tC z!O!P}7aV_8S*Jwz^C>uep5fjpldG`{a(aY0#wyDVahUZ%`AAoRVi$D&_F=z32qjQo zA$|-eM8;C#`p1HzpNr6_@Q%EAAc{fUzj8-v{C7NUbU|2 zTa=vTKEwP6tn*5~$W8uc6>HWF^&8}Qxn!DKvG}5b8S$j?+h?YhJ~W@tG~@Wb_%(bP z-=Gj1QL6B(@HEWU0rAze#MQ=C7Twl|2q@)kX~1`}Y%2c%fy*f9|L^s0+obZI-J216 z!U7ivx7b;G{AZh4Um(D`3jv;UP7zJ@TlvHs4~k*Q*tI#)j zIPf&V4EZ*CTGNwp479QR^fTGGP~DODN|+jlH~O@lQs& zcE43?U6rx3w!LonsE8V00)^bl7~EU4?xeBFa3)`5hW%~QioPCpDK_7FhDLhTf>e=x z?}!l`PfYPnQnqNCH`rGU2TvgDQ}0{BI4vx>F!Te{`?0RCt^juPUNJt-J71ikhf21NJOjbs|_f;BkPB*pOp!#_j}_J znP0Y^&^2AV$?g6HaHh1~8SsH+GO7&_(E0mc!mKAWLE>`BcNqGpg~i&{cw7-L|NH1e z0Ny#6=8;0J!JTAz65Fyy$CjAP$-bL;scn_PuNY)O-T^bMsH_Z!%Ycbac7bnyc1C6A zCbn2V8^E_sAhJrjNd_>2-&)nIp``XOzbsNE|);1B2#d+%#-PU6j}iJhp#oyTpvV6ldaNZFBzPU7+-9u$v%p~2;>2F!5fr1|3g z^_E2TDV_Cou~Wt+MTN_b&sGExt`c%>!0hv4TQg`SKcyHo-#5T3`?@TEbqMoA6#Nem zmD6(mklVO)vaD1<_C@Pv*Gv2|mtPRfnGJe0}b|k5q z1Cs{N#`j&I^%a@}lmCr}~9-W$0{WjX_!cJvZX8~Qw_Yc6y`Q3ZB)Vm2C`(@Jp zPd#}MIz1{c8SOrWzA~}uZtIF|>hE9geke%vHyhTmXX4Sk&eb)nhT`AT$rPsyesE{4 zN%y_C`eGWgH|GJ3@I0FV=ax)%J4mp4p0Nfg^WSf(&$@p$F3;7>JaS_cic*o=wN4f^uBx8J?|Q+$L_l*hY>T z!$B3|r)EzJe)Sy%a|nXkOx~42tYtOnn^m9%<|FdR_r>wyJ}BB7v~<3V_r!oeu<5Qt zj%WUaA`Q8b#&u2DL^#WO!TNazB6vA1_y$GQ7P3KBV`5~lmgMl)NG@;>db>GrCxuwL zwjrkcZBd9%rx#W*OAT%2z&yHjNRoJdOo*T_ryDbQiYp7P^%d`FT5XHj-G_Ght#AjJ zF^G5Y{t77!OLU#Ok|qEXqycm;SDnh!pm>$_4Oh}lK9J~wh2z+%`e>Td`t>G&E}aZSs&{0Z#r$%QZ< zv(wlYV-xxIAr98{0J`aZgGg1ff;;S7@rXMyR!1ny9ZW6;oWF{LWoyh4X&NFj+Gg83 z=Jb`Bhz9<(dJIN$J@HUP_l$Q52;GP(LrcWZf(Ew>J=ra4DuOCT)igAPV@G>!VtZdi z$f7IQT6EN>i7$-Dg^LPaYXM#LzZa&@yS&O9T_=z^Ul(r9@$^KqS)Xvf2oVC&ou{Fh z6Q*7a?dBqbjAmQ4XpClPmruaUwdKd1(lG)LJ(Go+_5%u{x>{oWT+e{3p##ABNrlpk zs)I)zbUDZ6ISuCn)4^er{{ZD}>Buld+42&P=^aCe?<$7|W&1tsG${%-86);+^5$yyfYe7juH_TDxXbWG!XF zzXn7bt(-lY;ytA=h-;(SXC7ecgTL+@2U))MDnr%GOg!fxQd-Ytuu{HX-M9g=sT4dG z)5HKHyWL-?`E}(9oqi7O`FG+TpF5Lp$#PCi{-Xf3&3Y5ZBDHCFSSf)`*o>6)2S}D( zT!r=tI%jXa);A=~4A=bJare#mgJ1RhB~_j-Zcc^-0(C)1wme(++5(jQ0%5o-)4o!; zE%DLn+e|^A`2C1yR9 zvIT7~*6QZOaX(cKqQgn!IB&}b1O6mvim~5gkqLO$UWBUQ5)gl(6=6TZC)^oHx(>`a z`Ul8IgA66rkdL71J_W_?;&G52tGIuF`AE*>_7e1(KYQHlu26?p1Ahy!djZDg@>YJ^ z^@7goy66j?YqQt2I6AjkBJ$PTr-#vFq&ycVI^RK3?h4pQvyWYzi-1YNYChDf0 z)gRLE7INJb5Q}O<`Q`zrDJMQiSF(?;z*cvgjLVQ?fi{KVRWYiq2oDpwl^} zuFjoNDD;fv<`8)*UR05tmk=TCRkyJ9E$5_4t4>lImo9zlWyoa+>ZAE}?*76LG{>Yg zd3M_k*0!++A(yxy-OFEZ4ZyKE#PI5IOmPlrfq8%2>@B_E3<|!YzFF29b2d!>OMAuZ z*Y8D$U&oU@fM|Jgwz?%7Wj@?&bK_rxn%ZL@Sg7B$#BBiQ|f zB`V1?dA!nfAeyDGVPtWP2neTD*Lf-NQF|#sW}+^2#N44Qe&t>FQO+?grzazmSL`y_ z8dcqK=0Lj&-Mr%^CSIqHnGlj^Uh&iuJ4JT`1C_}?Uu>)H-hRcZaZu)fs2J1NBEE9_ zbbW-!C4W|cs4)%gSmt3V6a}>2(?v7L>e=+tBpg2JXQfD!o&wVw+<$b2qN>7Vr-`eurGB97IVC}b0mi9HSX`|YfRH07<4}UI9h9)TX z%F+>2Uo(QUF4q1QT|rURW)-K?rCZ#zwA3Cdl0KoFi?6I1>G~$w0Lbsd0Vi`D+u{!& zNW!MmXuj9+GYQdT=LHvzR{y8)xQC6<8i2D)amUtuo2UK`@_ecbr#hNJA!^ti(Py$P z+Byx(pap?zkF(dn=oxujy;t2#EI7T5-kqKh*D%@hx&*}5PyXYrtPfT7Y?w9YF=^o?Fo?(N zqhhaPo=+dp?kMNv^sawKHX?NH28}9reA#WgqRMF}Ni}Yla8u`R?R=*Zt?HC_r{Wcse@_7Hh%D7`J1|P#n&INuqrs%Y>z)SM3jzX(Qh%H*biJGGYorh5`ZuQF zm;34vQP1X9d4F6_vU}s^hxP z_9N)(bykNN;`FD>Bt6d3x5>bfVjK5tif*eZQ-_D1H0;N)Y-_yO?FjZ3qz^z7Q>$lJ zSJSo-GM-cFJSS1bN8vB!sJDO3+vgf+%Shj%?!@o(nY~iavE!B3-DqvgG`HYzqh}bc z;a0WK&*ZY6K9X_LoF`D?T|z=a{_(?AAnqSvV&VD``B!^l|7@q#aqQe4O!;5?EGAis zzF64`UMAMGW)ruoZ+$ajGgv7BjB$nSNGp4ov(UI%`eF~yX0HBM zLU)5J{)nuljjV$pMZmHL%}iR)5!VjN`nny9*v6kYlkN^u+Ej`2(!^sv2kE*gEY=UI zJ+_!zY^`&Bb=0_&KllvvX!NtH5wu_rr#9aBdIE zl>o~&pd-cnO_Da>eE%majFcdzFd(yjcJcH_8t^-G-M9<@*d%|%USIa+?K$vp#`;B= zt&9;xFEe{eY%CZ`b%Q#QJi}aO^CBxrazOZ6SW}Jf2Py0IAg$u5C7*dMMBr&ht)A@4 zyZ86w%Z%--#AReIu#gFmjVAXT$J59NLF&Tq+`z;KYTQB-3GAH>eem4QVIWeFU$yeb2!L?#LZ;wWfBJ>8 z^|ii8Y9Jn05_|vYxgZ9FPhBNE3XvdxrB!rg?>XOb6Ntv&|Q(o5iW$M-p@ycFJq^R>{ zONYL@iPQV0RxIe2n6M=c4|?)Y4!`lDx1(S_iH4c9o8mZH`XFqa2S~>^$yz(EyKB_v zgOaE*eOK%q7!;77*eP}HV}|*gfKopZLMr)-Ine9xH8&?M)QRig{W}dUB2FOWNT12p zX;{cRda}~yP>|-&0lo2$qyEgIpqvryrK#*jA&{0SwqSgM(|pJfX?`0$djm_}+g-9N z=$f%w(f&#Kgwxp+-0dup^JEg}OiZYTH!N3OqS|2i`@tWiBVNdUwjP_+&VCHn#&|rhQF>7bA&< z92#G_bD_z5x636Z>7t~J)leY7vhk%hsGHRfMcf~KHELsnoXz2|cWteB`TZVPE{8|?jj*k2{3 zyEv(FF~(fftpLp@ZhJ?aQMqK#!jw*qd|hDtC2|XVQN*`G4)&cJOjk#|@&^LTuMwOjP~fc5NS8=5HRH5m$3fHnN=$We(D;7u%K98z2nT zM8pfHE97uyQHVc%A!B5Cg2W1|4b&YB%I%cIb{}wlm@nFtpPh|rT6D5bB#y)wC`rfj zcEzjm3zr{qG;Y7s6z7h2-b{dWk1@egKhaC(o>oo5B@Hb3Pl`tPy$WAUI7Qf(76~_J zW}FXj#jh!{wa}?k{I9DfHc9_)SN%g`?LxFHXt>Sd?(_5&-te^&EK~T+bglJV%`?_DTtAQx_ zw_=d@G;!-q%6FIwn#RXfEP0@D9vKqk40BR-D|35c{a?tkXYAA=MH{B(;%P^t3%j1b z=(|C^BG%Euo#Hh@k+0lYam2V2=qlIWVdG~^8d>Fd13z_SXja;CCH-$Hknb^B6EGe# zo3Fji3cR-~>Q&TiTHJ4akOhcCy2`$7tb(T30J~hE8ISB&eT} z_w+Cv4b|^f=$Sf{!c_3jHgcm9dpEY{$Tk2p>@c6?n?G9IX3Kk-G2Qz6J~ADi|GVKF zW$)uuCcLwKCns72D{85}d`KAAHmA8S5c^eL_NQpl*q(U_1TZ!+Y2a@=2{VtULPayJ zca6kh0ekYUI%Ya_enIH+;u@{wdu8P@-Ampj2hX(WCw>UM>+tOin_vVo9*&OoS@M3D zk?}TC?;Lo{O2+`nPY~=?W$zaY*5){NZ~g}W6@W-Of*_UZ|HD2=>WnP#WQr4MOY-aMsCz*KN zUcndkZaIaqnq8> z$!zKl*lW#o#`|Zs`Y!I}gqj2LtTVYB=9fO+sVUt(ViWHO`2>#1>GodNUNXIdJ^3^6 zHoLMfyK5dcjH2-beDo+_6Szv6(pyL?KH@wvBu_3XYOuZHmJ`|GjSB!5ZkM^!SoCVQ zF3WbOCCPRt_@_aQH7%8HdNCeO=o_fayiSp{sS)lLaE0WcZh@4?pX!=^B}SeZ4L|nG z#uOlP3!>(JC+;x={FvDGS92!b7Hfqx>gdeZN4kX`D7n7ZF>Q#DneIL-44&N=k0o!b zgbGwnzCleIn=Milg&xxdyN?Cmr+rv&<=>)QPX*2^tkWnF{M8~-FY`bOP0)|r51}9j zw#45@xpX%mD_>DIOE@Y9Xz2rXWhBKoZ z8%^5~B7GxNE++jr?pMS*TPHLq18MAlV{FF41!~luVI&APS)1xFf?hEVyzWljv5L`9 z1K3GX@X$nWwvcAC$&5U2m$(YjEXxmAj(+i0hLXLeqQYLFsQb~Faj(HdXXp9GZ>zj4 zPG9Tl?)L+veoaK&CiUC^@g1DH-FP;D<-@XTmZ0wOVW>jWU$6U1uh`5i#`F1e86C&abp-5+8fd&{H+#EJ! z{%KRa&8^P#Zc2XCzE_YHcS4O8@J8TIrczdR>B?sEc2;E;U@W;PtU9i>nH^c1^dXzB(rtIjuC2`t#w7#wTYNrRz$J0(h=%k);*EonyvRKx8*>s&isyb?e+GQz zy;MDT^j0E1mP~xh#Q|O>@Tk=5ordI_rU_-3T4GN<-SQbNmuHCIw2p=WkbZoUqGrTn z`nfR$bE|-)?_*o3VQvrWn8SiMAjvIH#Nz;?wziF}ff>5CaS=z&mDtUt`Jd#Us`nK7 zp|YdIg%ZfI8m-y_l{#-fGmW<+*R98r|qTl_|LwON2|JP4ITMoMSj6F z>hIwYY~on(aY3;!5J|zQT}D;ud@raBmdC7Pil~ON;;FRBC)7KS&U_O3glKkJT60om zZ;sv-$ab0?LDXUN`}BF)^o$L~!@iah^M3(f_N=YHP#-Xnkin|fqCr%_>3$}RFX|_x z_X9!@Frz)5ELFMdjoa65L<`6AMb*}*zZ8n>qQGT%qHgu==|J1z2;V5mz|%C?1hcO! z+l=k~`#ios%!V@*TuK@`O9)L{enQPRu1nlNZg672dE$$)X8Q-|>I}L}uxm~kaF|G8 z`FZCkg5?tFWJ`>MJw0DhYZJJCXQY zQ%<`yH%r@polIVMllt>A)R!PhfCy-XPsl)zNKBMm@BDI*GiUsYkfNPy=FVARSo5NwA0Z6n-=0Pgd}K zYRidf?%96;Lz)G1tLqZZ1x0S;q?xlj$hsLVSfI3 zcV%MYe%L!tVD80e&Odt0CSUW2>Cf?*^9O$&1c$zd{upMfLbsrd2bBI>6J#T(CHaB3 zYnOdB3VJM*^F@_{g8ONi)D=EzCV$sEKm6jRxH^?WY31JyqzOk`Q_p_f(=*N#Rc^bo z$BNVDjkia1^h5vtct&kEG4a;3vL=3hN?&%x>N=b?zfh&2a+H<6-BLiG!r7fn7c($B z!0YPZO9X+oFa5TMGDEb3$ZaNOGjz5tuXrSxE7)Inx=o0wVt)#rdlrD5NkVP}9m;h+ zMFHa7W2-h*135-2^YT(nsS!ymmGbQRa`mtD1WRu?70Pknc6$0 zeOvvUJ!H`1!k5@56WMrQecY)R^4>kUSa^wmG?~BhFb^#EY9E{-XDZ3#bUogyE@rQ8 zX#++p{&%u85Hh(5A6v>+Tz*hn5wCmf_v@M;P`>t}*ag;S6zp5kFYR)0H)}4Nu0dXC z;flA?1Gnd<;+4#qPjV76fnH+9yCI{dA1b^IlZqT4Wn?pnwf299dGCafUM7VF5eG;wI-TS%k_iOfE8|JdG$g&vwH0nOK8peVK;TokX zTblJ7zvfSo-;VMQ{+xX=@T}i|&}-@6Fw6uQYD>EQ?Wz{(INmxp{-^vu&?084mx}c+ zaw%=%!qKW~nw6m}sb;FFC^w$Hz_ZIv>f^E}9|+8Pdj~)`^mNa{$)0TuSHTWE+~eZF z2C*_d$veyCDiUMTOJ=wILVDx_S0OOGTuD)r7Cok6@Jt~P0$NT23O!VpN)^248^bjAy@nLWGr z<6|7(?e!}NN{p8_ml6@)&{CWPGtKyGJ$jU&0Hpu^*5Kr_C$C;=A=UE#oR4sBtnY4m zc-;ItYBmz1XZF7A@b2JLL{qlsSPJ?qLn31EH--xE2vbK|J@lG8Ase0enp$$Hs{MJz zy*gsYwzlQ8*xGkKE-!AEI;hnPbwE!gKg8;|ob^27a}MUcZWl^1TJTR5ryQK>);t_e zEO_^`(+0zVcl?aIIMbYd_G(Cyk>htzGMh(;4w5(-0xS ziqk=2)Our;UqAf7!{av(!9sN5AaS8T>yC~9(&4t;#~>WbH<-#5Iac2Co$Wjbp2Tx} zJi}N!t&hr!B-`Fk-gSw6t2>~{k}=Rc2ARp;q+(Xj*(xra=Hjjte>q5Rm2BoLWR}It z_{4U=(~dv{x6=FuZYEWSf$27a<$E{6(8lpcYxC!2rD%iR?L}~tZOn9>2$K-OO2v@(EnH~bW`pt)QIUx?rdH0WT1b& zvFX^Lps-GGQ;~WG%_q+m%{?wVyP-XHI1zj88lzIj%amWJ{^=F}VjJ$WNX#F7t#_Z@ zcV!iJQhd$lS3bu7VR9{Cx;w+oOGxftJmLu8{SV|<0v8GpP^#G3&0AVhwm8x_`oo0C zHnOu^gf%_7^Pzc~%@%u-pNg3soO*|tS3=CEI(#woCeaxc2ps@Rj7o8a0pc=X zj>6KGlM<955>rnvce{Q2=>C4W8*5m3Nx0D>wd`^OKoD~QR-9RrO8-Q2ktP%uHO_*L zi+!$61h5>LK{8080ZnMo57;fNX!^T~pI%lGP-OUIV;%O9 zkvB{K)4mP_QtRW{!q6{x(jLafT*c|km-Hesa!ISqK^UF#Isa^f!5913oe39w^k7kA zx%)eP3q~3Jr*_&}R>{cNu-9HPJxKxmb&EZsS1-SE=(l~&B(zwqxUg|w_PD6b{ucH` zdCoAw^V?$v;l<+vMU{UO!U6$Ks2_&k>U-UQED8;sfwmI_*DFdGVsD+e_lxWuDT@63 zaA)7C4wkwLI&-1F?NpYg=dC|TC6;|LfA;z~CyMJqfDrKtmV016{>;?0A66kYLnzx| zZum~S{IrdttHJYL-va1}ZSD5oqRiQ!d>ptRf1sB^!iA;LAI@uk{H?9x-N!)AX!)N3 zkJV$zR!Lbcl7IbygoFC>%&k960a+Lebgo}){#KLcexrt>JmZfr;fr*>z&9?Tgk3Eq z!23LlVXK&v6tXIO>3ZR0L^p%#n4?vWB{}l9j>`D>Zx)9$p?A5`04(AaI8!Ts4@j6C z^M9DO(7`Ol2n`F9MGfciCq`&4J-JjWt!`cv%n8;)9gjGLIo1~TMf15gZZJ@__DF-- z2XEe;Ucp-4$0z614e*Y37LAZn^T$8W4v6d6wV%hYPi?^E24lBnf(U_s}Vc_!P>;BQ~U7 zAU@2B+*Uj7!Vm+r=OyqyKAcj2H6gRcZuaQt-*6c!=^fruB6@43^kF%aH}Xss)>!S? z#VlQ?7NC_!4>hHN#sdG*hFuxiO0IyEWs7a!K1iJZ+yv^f<3R%<_+R7b|3KIuz!Lf* z4$w{*sb03x=DUCUX4rhiI`EsPS3&3Q)==g8S);hyIpN6!27z7%o~{eI*IZiHlP%CS zrfxB|QGSey;W7gwH)sb)K`sFn!g!a*jc;ir|F{LqQ)N(!(Z=WFX4@Hs!7hx?^qH96 zKv3^ZYopx-I;I*A&PzAo)UuRHz6Gi*!B^Ol;8mq~a6T~oJcZSfO2yTNC7@*?YNXHJ zbQ{IYH-VV#SKYrL2QIV<6Zx9@`@ATC?5}ZdyI9e^jEXAbvMDJI3IWS=qiK#aF?bHl z#Nhnkx~pexg`F}zQVm2|L&cOoBb+Ai8m&#A6mDW@qA$`dB*RAzo z?0|gM+Lmw5;@=Wfcwkmr{3iYc$&Ivbi5)bdiov6M`X1(FMO7i?-Fd ztfW29^!^!RaQ>bALoYR=m1-Lpe70H|W>DNf0qcP4`U8UDxDEs_3Smnf73Jo!(~6B_ zh351@?th9`o0xr?TS-~NpaEc8IonDFW7Wb4@VhUb2dr@+n90%XnWk@W;>DJoPtlx? znCIe7+It~7JR=NiVo4NUy4M(uV%^JPWMGP@*ff&As-mxrt>=q#^<@n-%N3yJWeR8}4QT$T z8!>JQ3i$N65Ugs0S&SC_PH#L8oqv9lD##{hB+fs5%3xE|i+HazTU|~dCcB%MvBep3 zs@&hv>9N0+Ehwl!xA5pyOyci{B`RmD2_S)pEJ$h%*fDCw2= z^mgwL>VRZ^T)~}Sx7E?RL4h%ps2QsNK$06!Z!|X#Iu*B?-OF>BO;1WKhFRU9RE|LN1tFVN)wQTpk{9Wi-xIEJQ8KGhm)!P2rf@9mm-nc8qSE!*=u zs5*AumlC~|)c3{D`Dl<1N|i~E$F#T^BPW9P7JX9(CD;D)y~K!owmJfi!rkKG@A?ar72F3ipwhWD#N@V}o* z#HOj(#-_acVx0n>X3h-3TK-K^la>0h15WjX)*b4K|X8qF0AR7wmR+Z z!&EW9Gw?Nx&Th=7%lp%)1g+qvdR=2_X1=CruF->${;RF^!HH?6s(d{c`Z)5(yxO|* z3anWbxu5+fb)HXq?WnXuj9nLOeI!OuK^wmHM7!vKoIFeUA1GS)o$RZ)0JIDh)h)vr zj+rkF0oR7|?UKTqHZ33V*~ptw>39rrr3Ush9&jyU6n9?NlcK@3k?M;%B)8^P1! zjuh~G&}j1g2E>HNTDekx#)#aP?iXKn6krvhNk(3Vng{&RlWikvO#V*`t8Npd@H5oG z+V;joLXXaKzcp>qHMIa`4|2{)%#=r7n>o=fne>(9T=vtRe603%f!Bk&3i^yzP)MJa zib)N=g&ERZD_@wMYj!~_3ZXX-r3W&YZNA>ZY%Z}W8bNFD!mPeX;|I7EIj8)J(8TUX zx+?Rh5#q7Z_oxm2hY$c4ZykBMtm<|cSJVzhB`vq_xXEP0$D?#A+ z3_p?LiY_Lp`7U@J>2c%2{CJMv7wVR@?h6zIT_9#czuejV?E2*~xcB2pXo7sq9J^TJ zB8MDP05}(&oINS)mZ(Q;L$it-O*V!+4Uv6DL$~bTx}EB|rvFCaVNoPBHehDz#UOsy zZk}!tB+Lhr--rXj?{?@^&q0jdvr1iT zuQoTQ7_Kd!-7NW91~N1MlKTG~H5NO77NVh6lI^}t&#V3rj>!!me6xef=j0i8TMfU| z$}%GTtd4sSbL~VdJB`bqyCWfVg{|a*N!uPctp0s>rr}a_IqdN09Xb0)Sb%HgmE(wb zLDt2v8c=7-GsNWIH#O6}biaxR3d<=3|7rhg#4>09oa+k$FiX|Gy!CGnlkx7TK=Daa zN;!}ay~5?)RN%Mg-)+m8HOBz+*t zW#t?trOX>Ln@e^*TwDr$u2i)m?w_5WuHF>4U%mN-J?+}Hn<^+Dvy(f6-l*iH^b-l6 z$gitzVjTh|T3~=!J&w%-_V@{c=TtM6m`dGo%<*D~ySpONB>67OJcpL$yBTn)O_(SH zTp6zAoA1y+W9t6pXOh0+U5`C44M0kth?m7yJEdDS&d${gye$5ueb{6tO>*pwK2KZ4 z%myHGON(RjvP`sYRxn2I$sp6z;NS)(OfA*Z6RiV!(Vaj;jb$WK2r8$npk;B+i9wQY z;~LGKY|zFMQHyDROdm{$#K5BW?Rd`#Y#zU5sKI5lSIe=RoqvC6ucQK{^*vWQrrYYf zv{(Dz!9kvFJ8)Q>3Zv1`pOT5Em$R0P{fN#F5Z|2gGpyu%`Y$0DfcNwB|F=Xcfl($P zs9mW*0U5lBP5S1iw+WY%6#QFnXMSHVxVVJtXsRE>*De(>`D*zbsz}Z`cFN`cGfLEx zaKFgdQ4mpvg902(jP}I}I@+EilAEf^A_Y;}i!z9kz>GiFdE=Zt7!DSF{CP645WSZ~ z7{qBxoO|u`hji(yJ-hdwId{1q$_V_>R|Wpi16DkBXfe8TRr7bKPV9Gmr{&^G3l|^o zV^}}J-T0~8m>J7|AjeX~w;~CE(uq0YKxGN4rl71K@@>utTu8>fZ*d zobs(;ZJ#U>-S(u?I!FAK;qJLZ1 zenR9aVW~F+Dj!2D`G$6e6tUu5;v=SNpWt|o!V%fSAD{P2r)?{oA5hi!FEZIei!8!V zCm{G>H>F(-{x`s~jKYPkDaNKP3^dK~oF6I)(YBIMxAs4mf!!0-#!SJ2e7-v6T&l|@wA!V=9~tDR)K=RQ|@Pfbg?t|R|}89EhV|& z6};=)pyheVQcXWKh8`dpiC%WhYC)BLUct1YXeti6VnAoeRi6IqfVJ}SUjRRAo*sE8 zFgJO*MOZrG$S$NB2O>m$nPjD{Ddb5+&|m)&@&7=jIsaNUj=a0LArPdSPJ|0IomB{l z-x-wPFVBA(i51c|yc^Y^!<)`&AG0X4y53BCFB`7I?mE|I+U^1~WpV4D0hQgF3D(y# zd^E@`FDExou^l_d6vz}nGuv26?@aH^24Vp5U=&N`C*`aV8WxXkRy6(Cu90>ZXP0J{ z6T=*_GF#-m|AXE6whF!&$QhQb_*?COuhR>(ukh`ooKRj4(OV+YX|KF@Eps240v2Oo z3@ZVGkyNe7S`Q&mdnyS8(B7Ni48`65$TGHM1YYDJBLEB#QFj$@?OMNU<>~z{wMB*P zQwoQ{%_L#U-l*R9x;`=#5jI{R4|?Qe@iX)Xw}_Z(o!wL7sD%ER?1Gk0uIq2j>qD-U zpSrKKtTMtQY_{d$RN=!pJF8c!B{|a;Z{|#4zNUH?I_yyflLH%zwwqndkQPQ~L8+w& z3JP40jlRUG>gmx@d8)EdzUmJRnE-=8d$iJv5A!Q?O7c_4t!rq#V`--MHy8!P|8dYA zJN<^Nz;>PL6}!h{>u!yUjL7z1?S?U$A%u9!3&YEjO?0S6T;nx*k~<3QnF8U|V3%t* z?VM$|`f_vXM}xgp%zUvb$Rd*6%0)wNU)!P@WG&;%ZEU_KG5Dq4w2O|MOWQycg_*{X zZ%|)XJm3L5`49A5CwYaqo!oufC$-8;^V4*Fs?ExtaE$hOr&?>teV?9E02Lsby{Sn_ zo|{~`aw#W$T1=3V@4Lsog~M5j%0)8jOz2xz`ylzAj{3LhTi7M7Nw1jd4`P;eDdC>% zeDU4X|07iB^>D?GP(0*OdGpKXbFX0=v*u%-9gpD4pB2X4ES55H{y^&ebqN*pYYic! z_q^td;dW8;2d??(0kMoZ5oxG;MU>c}C1#QgwU2fxX=2AcF)~K1j{X3`k;JFHC})hO z*gqky@X~H^>P&(C@auAR#N2xG^jB&7j?*R=6N{Z$(sr2zXHPHp$1}onrqdnpTlGZ9 z%R6BUMG38+c~TRm!4$J2KM%AIz~zx5eyc5E$}+2<>(?iJZG5g02=-XZt?>1-a=XQ> zB9Q>B^Vs#s$49(84!zerqyaYo6_ef!*UVE(iGyq$`uDGZ$>$f5A&fLbGHx6}x$zBu zvM}D{`wK=`N~b5^mhU}XkzldQ(pVND1$bPK6kA+xxBMjy{;aRT3Xr92{8OhL_4{cv zI2;nPUU?$n$&OelR#8X&qF_E|v3#(`ei|Y=W}e(s)oyGd?9=`DiEwW6tL2_Yiv!~Qa~?|`oE~o( z9dBHJji@fb;)%jvSiGl`;zaYVOKJJ82dbobDD(1QFnv^>#OfOS(tA|#thw4py^_jF zHd1M7_esP0$E9EK5z?HC*Euzu;l;B2;Fz&6 zlhdO5+5);;=KFCaKKkM;ZUV%PR9<`Q@ywbCQ$padZW!J9Qg%(ZoDV8gI(w8rJD9Gf zz$d=MQR+zw>Sm)?``8p+OYy5U3Wd&}x)%W-{{X%vPG}FF(G~>g%w6Sp=hAP@YGZMc z0|Z3b^V7EdM-00fK4zWDy>A)V5vzXd_h|lIhy^0oDn%yu8M@*NO^*~UVC-F;_s^G!nU~WNMY)v}6)ScTU>lHzfI>IT$jlv7?tY-k;;%q>aiSXH zh6_9LA$du@U}m;8>WN+1Miar}`Tg6@HVN;P+GP5KDh?^iz}Ss7uM_y+AGE zqyECkus>QI8YHvaL}9NYpRHYtmd3r&{Z)N;uG*dwAxY!1hvWv`m(Gy9UU1H^I7cC9y1f zq))$oIZTdn--`On%9&3b@?@suAA4vyHbJNlJ-^65XL8pGL5JZ2Ez^(=FqmrAC6yI& zM+ge#v*{9!UZ?0{7NrF@v#nty@yj0?P`q$UbmsQs$kMinvB?y}k>$tno%(@tYU(bG za>6FCQuJHAj>63JcwSktCrSayW}jF2@eno++KL}7X5eJJMgiwXo9ZaASim9Pj@fN^ zWXLrYjoE4Cbv#@c8Ica=+N3sif6*#otXE+HT{t;@X}uv=5$viHL;KBVb%3Sqbj;>= z&dQ}ytieD&%I?*);dlub!&PAEJOpCzDg4-(Q)DrGyV+NvVbjB3^#ml=8sMjE-{QPZ=h$EM(vJx#x-BO9FR5tv;j42zQ@0- z;#inax2_^?d}uh(hdXg%1o>nR$cK)^f!4y<$WDaHcm0nJz9ii-^l7xT>`_p%njXGc zF}Q-@iFpo`7yWEklm0L|Z$cpXH2amDWW$$Wr#GCJ=B&y{?5)80`>B$$pO0A+-1jrS zmuHfJK;7oVCE3{c<9s3AuJw+^E}tD;=Jgms%!4IPOA1>m25C=TKF~A6iG4fA+YLGu z#dv6vNb)a-vsbUoUIERxrG*w>XYSCi| ztn}z+U<1dmF~{nn=O?BnYDo035$H#D&a86CNey+QHuWaX z(V5e&Rh8I9&|zDY&4&6-n|1Wz&=4598;YRcuBWFiYVs_+Hx*$1aSHde@3+Fia|>D*k7JcHL8<^P$%u7a@O4CWp`_g+<<= zPn&j8sMLhJwbbZYnbM1ajopi!2OZ6=Iz z`!jAOdu=B!hItYRqxJgp#3w%HO(quQyv$Q$UCQyr4ffZ@Qo>*7&=^fh(k@rbrJJ7)&s zAC4CJl4>pY-JE%h4m_9KJm6k*A>#=4@3b!`e<9~a!%3IvLKO+d1|~G!UQJ`#%(X{} z*j0@O)o#b(Ksg_L;Mz4KghD&AqlO)3@o-|SQN%CF_p&#aOqSvFeKq-sZ#`}?Yb45v zf=$+Dr$t}aPO4Yv8(WF38f|iV# zAg6RKX=yo!N1vVn;aPX#44f*TeQB4X+AyvDemu)151*Le<@&OkCOt#zCr!G5aUgT( z2&is_#=T&CbdaWGL`2nD`gkMKa#PHZuN`e|mkz%c%SA6=^~|3pZU`zUO>j6ysO^+1 zCO5?%S~&1N#P8X(hpx;2vD|C(rj~rcV#8WmYtTnlm|lBvPN=+o0DWyoiz~szoV*ma zQflk{wyhMx!zCbjc|GjLK|;DvA%1Mkv0kKyek*?YmP=`3NQ}O8 zZLjB|-)b-zjOO`3V41^~=O<6Q>|YcOSWw?K*^@#BF0}D}#rg7oOvJ7&wt?lUsG^Rj zsPJ|Bmv(a&%B_9X739eSuq;O__EY)>X(@tbi<%~p5I*rF{k`H0fwReIZeb%crtP&u z^rS)DcTV>9pWUH^D!%hE7)2%TSNF;=SL|e6@O7H(=H%(w!GPUpx2@eW#{rfN=Z)D@ z#)o_n3jR$BX*(7@6&K}3Qv^5qPxTzW@W(NWJ|018S$=}@xHgxsLOuhgm1d9;W)gUb zqe~t&rSC8R1@<{ZRdmDxw7PB5tl}cKf7^m5@`hQ7Q}mes#?sp8;(wrr)Z+!o`ROnA zo|r5nkbL=N4jmIydYu2n#+Ye*iUGpwR;>YP+C3`C9n)OoX?zo9c_ZhH)D3!hGvmiI z2C^y=ngXS^UUj;(Pn4V~wlEXDfKBan8#<=g}-n@D7RbI;b z4?b;?x;j%q*W>by&N~qw6x3R z9aHwM>>;Jyr}#nX6!DuW3hna$(A=BQbCFeYO5rlrtPtL7?DmRGA|ERXbQDgq!`(kJ zTxZ4%v{LQknlBYgYYbK@Zcok;gz#3>Dirj73@~Xb%8^?;@SKj9*Do?Zyd21$`Zaw7 z_~KJn_HrhzsC_aEBz=RX$rqh_!&VBotjr1B^Q_a9UZT8V3xg=1Kr90-|GrUxp^Jq~ z8qLUXRc5CFR90gCyk9mbMpSRkuW+0vxa2s-S;}Pab+y2x$1IAgLH{+WC=9<`Q_tAJJrlI)rCLO^Nh_7c5Ung-8?L=K?NkGeH*k6*lV z+9#>`hPt8anVym=@hp+cq_Cw$N07Z6C2m85)g9f7lk5IYi^QpD5gHuv-ZW{AI;ILR zmK-i`qYisq$MjLBddE_g*Wy~xjso+7@ParE?z3P+-=WbGZ~kowakt`RnS0JKWPSSt z1LvwV%XkWa7kcOPm-E)0TyOy{k>~INUxE_w*ce=J7)Krcw#b3okXQ z^(~+qaAqatM4>HaJslHn&iEITSPhTOE}JmMd&4m*?)Al7gKCtgUK+3Qsta8~R;HWq z1%u3;yZ3l3XYzzsmjz)+FJ$vK6I zU^tMLXVNDpFTnWc#OW$g39`r;x~S8#QZeihZO_+#fx`&|UE}aur{Zb)Je{tyv(#YL zr&DJB(7xBW;WkQ<(Sk{ax|)+g)Yls4nK;5s`vRsgrQ+E5g+AffY5ESfYq696+0gp9 zmo?{ga$||?xW@kLhO}>HlHB#Ai_}G5$2M#8S-6J65xu9oFz=Ib#pJxo(CT%NOuqE?7iP-5cZ-tluJg;OINwn%>drqe>P! z!T*&9rD8{$@p<46<^dq}FXQ^}DQE#o{rPC~9)6~_L#m)UE%}l6K|Ib-HqF`o=yP%4 zSMyaIjy5pRk25F!q6tSh{n9qSyg$3>>{#H{_94DC_0NQVX#JIDSrbbW&7x2xb&8y2 zf*~+mYTBep-IQtTsX6qr6cy$0i=pDb1K56*oYRt5iW@pdg-?v@HF{nhn|IT5%5^E4 zD*1kN-k^0m>H>}$J|-rB4pZhirUqwmJp@z^;*vR)(^y@CLXW1=Ah8)SZ++=0uLYeP zDChKjJ$RE66Q%;2_th5qOrMEz3Hdcv=ZAPU*j*;o!6T$jH0$>zcZVt|ooH zCo#6(md>uu%v)jkr{FaXM}w#78CdV0W98r#hmuH7-7*{?81lbjLJ+?=IvcBS8uVg2ii3Ch<# zFS$w1{z*a0z)gqW>bK9j@`sCRqRr6;n@z`M2>0=r# zP~hi`@3cMX?Uq0!DxW7?mj>N~Gemk&LpaXDMbbA{DE-r}75~+bP4=z9x1diSJf3v_ zX6fbm$J5BXK|mvXMujt~fw*rr`!pn_1+HfrCw(N~o%ID8L)58pT`@usI&*7DelDmc z=X6-V9aZhQ7$+y(%eu>7Vli|B=r-TQkA0eJ3YKu3oGUrlN-lCqE4?47)}(a1(q=eK zRM%=)dLW5nz#?<@QF};=gx_SoM%9;$r_~FoN z?Tuf{7xp_%ef!=9*{wZ(%P>AU;I#tAZzcLR1d#Ur4K|?9ulbu~Zs?pAldfZhy3OIX zZ?gXb{y;hF`pSGa|E`v0AcfoYpBbx6D^k10)Tcuh4%jKlqA)CYYWn+uUNn#gavsSj z)ihIE>0PVvhH#Q&qT^Uxw!80}X4`JNo|0Bi5K&` z`Oe7lN)&Sa>*coEws_6iYKv1GXNZH8^;ZtvIz0=taNIOL`B>_+j_yMOgwONRU^`pn z4Sh$gd1l@mQPVA5t0=E|saz=Y@g0&$2wpaLHvDPt-Mi9p+nk9&;yN1zTVvL&;3;yd zSl_zJQ+HRK>|yaJqd#Fwq?-=g-`woI&)Kpb2$*6Z*0ZNpZ*x&7{)vXxe@2%t3daN& zCohXSx<|<&7;SPQ0hVuqi0nvltsI-Vh`gB8xz~hwEPlu=HU3K8K;viE&zyv{r(qCq z-t3UtkdOavuxtEyP|Ki@+uQ!Pvu$jyItrCG<4~NXKNAK81kyBxHlnh2ARkPwUYC|u z8o%xSdF%UmL0~3S%QwVM52^8M6*GJl_%7zGq3v%;0pix&vJmno1KUr&vG|;SZNWtr z3Iyv>iOv4xnW9E<2~*jR+LietKZZCceKQ!2l?RV=+E6JvdKHp}rQ{hNhVtsB(c2=z zOEjp({_A^??pF9VwAUy4{k$8l%#FqDwOFrSZYx1Z^PkPOu61d-SO#aFxIlH6>q&JC z3Ct)h6N7p3*jUvTNTten%D6^Fg&o|_$H(eu1@ngTAbOO0-UDa?6?ecBliN|}nra$^dcvGD-hxf0D&t0<8L8E^+M+m6jV*rma zAv@al&tAX_%NvS9TGY!M9oE2;lZNKkOI;n6&8=TU;XKSLaK1RP&_1xcO6F%{*X9>9 zR^BXZ60i-i>Q7Y+tZ~hs-wdu=C1`#8nZY2}darYW=~YvN5gtZSQf_sC*f$o<7JK9Q z???I8NiyNt#D2rR?hvB&<>Zu6Teood7i>n0Ull^Se;1RnEYBDPX7XTeRv|A;)e&-I z%@G!vFb}q53+s)V_RH0|jwH!ALh(z4xh!^6h=?V*M84S`c9$8n|9X_h z5j_0I=4PC}D=LmW%IZ@BOMg)}GdoV_8;owIx%&gm%cl#2EFBl?(_>#{`-Yc@#3B2UcJF5lAch zAzz#S0wtJj@r+mSvBg`$yD{;t)R{D&VuLR4o8q@wN1B`1IgjPm?nUuQQ9c-5&!A#5 z%vY>zbPjGIcIX6UOc4+cNlBsyGFKM%;Tp{~6PloQDCjqwNE45b37u*BT)Co4df{>b zd2WRY8i`T+$d28%j}V7yd;ZMQxIeC|Q0okHuOC)R$KBnjI=N564~@LknCM%MOpySxQQ!k$zW`VU5+%S;7?!WEscP(UNV^u-u6>FXxaRAtcAzOB zy&A@Www$|z%0gvLm3mWd#msSf^}OVJnbI11B$IOx!{_d{&FO)eSW4TEaFSDN8Fiby zh;HVXw~=7(LOA}j7bR0Ee31{y5_bN%jFDG{hwp#W(5jZyD{06STX)d;9@mtK3(RV) zVvJSj@vmH;2T;cN-Av;et5O{cWBa6}r~M?k%(@!3Og?*{CcRGvso_I=92RCu)J?z^ zBWCyq>Xy>RAB;43pUlbD2$sMv{?O4_%7w$FrNIgGj8mp6MhLpGjH(V7j!~6Tcadp5 z@9ONEb{SKUSA+SSywN#v;L8yD&53c>fNNaI#Ne#C6>9#%7zDyh^MQOzD$YpZ=%8J^ z{-YnK29Q9gr*|VBtS(of&?wOmFE#dn@js9)mGr`L3Eo$|<0bu?j*>C_HZC*VTq{#- z;kLcvj?H0DxIZR20nYjTx{M>Sx}I2qIk<2#m^7vd+aWI8+!JU3v$MSuVe(ymD2c&Y zCnv`g&6wq!B4#E1tqkDR*n^B_?~Jcw&smbU8IBG?^j83=hfyI0=tvcnu&cTif;~eL zfO-h8#r3{1flmU5JmoWYYZ$w8TyLU`g6*9Nz&b-xQqk_X-%RSrkF=cj6 z={T7P_2)6M$F8e7<&6=BhUJggEFc^QHTqANcii8iV>Y%KKps?Knt&vPHXtWZvTb5_ zcAq0M!6jXFj5e<_DQd7NOEO&QJ!je$jZM~sx{pfC_W(;H=TR<|LT|UMtY3O=pK4yt z8jL^$|H-G1-tz^!#el-3K_dP+3wJVWQM~Sr%*5z41W`OGX>|ZSZEV19UmSJpYLQ#X z96xw%eL%)dD&%>`H$=KgH2&mLYvE>pIDt>UpP1cw7EedFxV~&@>1X4)3W6(1!kX#R zNuT+@PLa)%SxSTiZU32O2sdfho)5niwZM9qAIJc*`O^2z>b|v>Ffr*SA-vhcWpxoK zZt7g$-!s43yxtaKABnA+n^~$j2B1NqsK&(pRr6I&#m279YIf+x(MH(oz1>2?)6f!U z@za!rq~*G8{nK-e!&zFyn?c5;@uf2uSYG9=hYS#-ki*0C;ctoKXw|_qtDHuYfsV0T zFt780nxwm**u3sW%m9CjoUeSSJIgv1+qimXQc|EIP8_dp_{yQ3P!fu|ts~!^*!$gU zrbXIz)qZuu#$&yQq7fG8hldi7*@Zq@g|CZ=E6JuLfZJKQ_VKhqoTf?lX9~+a4PA(8 zRRZ?eLQYf1TU>G}$>mLMSbAki$vbl5k8^h34bNY~{?dDJNm+SRkK>#IWnM#mcAYQ1If?4zDTr31v<*BY14)YgR|Bw9ho(5BNq-U9U4#{;o@ zE$qTTUzP(E)6Qr)${gY*>u&g3K>QSM=HQ^+7W3X@;a-Bmo;b7e6L5%pT)@lv{oI|= z_w@Ey#VhKCFRIZcPoM6ShL77aw_*Z|*WklQ!*j_WC*HcAGp}}EXNxlm%1`ag0JVMG zZX8I%6({r^yk;Tld8O_D{l&07kS67O0Z;}HSyZRkxzesa`n4DC?x6cEe5Kcr;dK9L zvLid^WP~_p=D^znI2ZQT{@e@15~oja#X-C|y@bkUvxyPcJamZRINz&PB;qb-24%;x z^oPtUeCLQ@DZQ2M1iAbTD5GhgZn(X>iZ7do_Ws|g`&e`ZzAz7?jx(NewxGG>@6@Bq zw;TDV$W%m*-G^;57BHeUd*Ia zfq3V@#55*EWCs_Og@1W?jQjY-&CltkLS$S~;XQAr&(i*=-79u@#LMvBPVVx%ZVd+{ci7R*EVZ#!=o(VxUx8kC~71D=$p}D*)yNX17CEgB}=9kkSE&vUyUt#o8?UMnrFf{4<)l?(zCYO<(m^eYe+)4F z(Xw0>nedAn;C{v^cVV~NMl<0v^k7AMHgeZNqLV|K^xVxRuAy~|N18IkT3uKgE+i`o zJm}UM{#X19 zFUC{H{sSSXKJRolU8M(_I`8vZl)fpLzNK=zxvMZ-XIrbIrHd1SRjFI#JUtpM`d3d2PejWL#3~SIUB4g9~@4KJW)?ES5ceqURU|;YU1B<2AgSNiyU zwq3TfpH&R~o*7ZAXK^DZK8unsi(mCFzM}=rv~0drbQx-_=*A@>V?l7Q)}~v7<8A*p zb}FgbkoYWNVZNM%9iDGx^!1+?WtZvmCSGb8I#(3L+*o)M)z)1U+ef4Q7MYHv_=VtF zV31=W`d#tnqAo0q5NV&wE8`^75~>n%E4|h`%KPV3a`jhn;Jn1tYFjV2|TUx8ha#M4(FoC>W+WF%g_2umd{u6}V z-_AZvqq*54!LySQq{pBNE;6UIKm-Tc1^?1m%EwwP$P}YTqW6~KB&uNdRylu;%D3sO zW~FgKtIm*{x|8GwR7tpLaoK%TXzQ1DknB#H!mKi6l=H2qSYpWR5*Jo$#mC~Acvex9 zo_|f(@A-U263N*wbF10Uc62OA-3}bj8K?0uz+o@7!75O&Q9dF24}~h*`+`*8cW5Be zNAh!-Wa4eyk=Mit$D7_B2+X}aeks`ct@RadLh5N-n6!O-A|_m@kHl`PVSER zlN+sA5#gru@fjg0W%}fM_`}JtWhY8d#)iaQ^@9ZSMEmK^UI~f3z{Z%&4Ru`rm@wkY zXsul4v`ElhukAhLO}I|^M0+$*GNRgnp(LpIKhR7cD|~%SyX~7S-R$6LVk3RYu8UTo zaNH@Zex52eSk=q7tO|?{mq_i0w5xnVYCsCyp&F7~?O8`UxxZ#)eT18iZ#U(ho}c+P zmr=Prjq=%?U&V}c#E^n>qMH|xm3QSDO>!z)2e_1j#sf)kzg>v1e=}rZoag$_sGJiS zK+c#sXZ65Gv%t+%PSyLgC~qH?py8BPob$D<(h+VGn8uzFciS76{F5Q+GV{AGc^x|IN9y^AjkZ2Y07LVa76s(T4}PII@hFl1w0ZvJ=9q981w zTHjo}DzkE0iu8@LNq=D0XndyiGJ24G$yr!lW8(&`{}hWmmeL9^#Xigz_LdS#-Caxb zr{|38ANr9*>e7L@%)Qa{?3rZsAtWXItn)f~q&9o0e@N1L3 zu}m?bY)AqS*K}2~6I|G5#s9fIJ+Ap{pT2ngvp1sdZtuR%Zp+1NW@+%KYXxVM=qZ~% zH(oVN)y?^|C~mq}M@N)1YaH|DFKH0aZnOU4GAqx|6^6ok zwi-X-F(1WkCH_+TO_#Mqu4qNs zLG*wZ1hAlZU+k?r`?^%V_VDfu>m*Ez=9dKJ)?H^?rM2O^Ce^ZD3(ie*Idhp#7Lwaf zs7-1j4PN~4pQmM(O7>7z$jqhgqmnvNBeS9JDCAA5tczSMc)&QjhkyDXLu(8Eykas9 z$d=XZ#Aag%Sp$|=*kX+`?0M_@VwnBnX={DDV?vV)_R3h3I)QXn z7hX9z)Fzgu;Q^A8r_*~nj~UlZy1)%rORo5RL*TRN8ofQ>dM{hHymRBlW#&Do==WDe zWp3uAUU38aSzyyYKqJ}0<6ACIEQqLsod1na3y@dl3<{SIbSF+=R6M;s++Y8`2hM=cJDw~G$F)Ai~H@^$d#aXEB!@hb|>v9b7LjDvcSr85KSb7?&wz zEzsT_#8J)H6=bVAWO!y({LF3E>5(T1Vd~7U*C-P2yoE!z8G*3I?K zu5nO0LRM(@Vvq#s@Xsr%?b!M~qvBS~vkUkK_9Rp0hAQ_{z_i2bMa>#Qj&Y~r5~)i9 zDN*KfgYaBe3&~jpUZ1+rg5BNc7lCS12db*>CBsf7p&yd_Cqq;$*DQ$)V(ltkqq!o5 z!Sq=Ze>m?K>pP^K94<%zJ8k{qtTa;oQ`mnx8;k_s4D;w}BE${OwJ zDJnyw>7_j6mEJRkVcQXCMBS}FZ`5fvvo=FGc$F3vBpqp-w%2GtajyXRf=JXc@U%M{ zBlquV<)l|_cNz{9E%s|X8n$XNKMNOMhb&quZ{mU2BqH810S_&l@*vWc3x8?)VTL6x zK<1bJSgx?TQ)JLk#`i?hCr-?v+GKGS&{%EKs5*V#PfaVaRL+SX&*R%8z`%|75@s9o z^M7_dm^CVyUklRw74Qq4g<(cJGeu7_`Km|8iD)w5J#DK2OxF4N;Q*0jQJ;CMplG_r zki@owK)s{n174f2v%M3*YqQ+NvkhcrBeVa=7N4d3y@nYar4F19a5tG)L1)Y`Eel!_ zbAoRDY610pOJ3bSsZSA5URq0Zs7b&6w z(mQBGy7VTY2+})9C!mmM6ogQum(Z&aDM^4(1VO5F2qiQD=>e3cpuT7M?r-}NOQ$u<ZN0wun5M=}=cgU|P$Xw2aP>4g#Y3N;qHl^PUU>X2h7&dKGJ*&tu2>V0bG@3LxnUQB*@I zZUEp|%|#I&@^}x_UnY8uH2TV1I&I zSW!^$N#zalGPYL62lk_?-VSR{R0E9R8yI5p&QG}4gSXfvnv_|6i|M)jprJ+DuKFN#_p|gavCprkhsT5#C()+tjGy1P z8r-oTIr1%?oUUvIyQ}il0a!(zwucDflFm9TVAs{B0PlVnFlR1n9$Gb!@o|7tD|$dt zlI*I`6+e}j0HN2bPIZ(_;}efIyp+{1R{y*Y&YrYAyV6I*5BEZvY#}nyV56%lq{8Ha zv+FH$hMjWN2leSyOCkq8QAMAab67QinDrtzK%flRz|hNV(-Wq+9d0&)>tNZN_Q_Ta zBXWhSC%OX5l4ERNR*wPu>b7nh(o@?zZWY5*F>hn>W?Q7Jytr|^37axTR?;6E&D{RO zO+qOC^~eJMdmNL`L*3mG6High^B^>f0ys<=2cKxS#Omb!prX9+DOq3@)=&Oz3|G`u z9rWYMPr1j4RqqN3CUdQ6Sw(bulVb-HlzN5H9w^GTahV9*p-bJ4lG7orYO-;S%e>+X zli!kpLMRV>jl)0Gi5EXS;X>nbp5d*A_+yV0R9ti=TN}f;-KYXS4Uu1Fa3_MKPe9{Z z29=%zHoRH0Q}gesg9mV)SZa4C{%_qetCzLN!kBxx<7mxF7YQc;Q8P8Cx?2nS6vO*= zVvH}Z!i^ZEL)6w%Mk&dtH$E1Owq25km7RoRJPGhOO*Bzh+=TG0XUYn#(uVa4jR4y{ zV=wJ0n*WGTWBaE<%`URd!=~CwKP+wZ_zPx;i%63Ef&>EO7}*7l=XajTY;TZ#_*feM z^ahIQ+eHw)GTRPOsbL5;5;P^Z0wvgZX1|be+ zDeZ`*p-Ss|3bpCZw%_o-;1B#cw{Hc zL=|3>iVzFbS^lL>vc?_F<>#U%>rsU10-;~A+F}A4gXU{|9GSx(GQSEn3iseg8c@rq zG~PF0xXuFB(BF>I49R?yorNaG)~kN?)yM@H7@kv3%>+Lg-)G|_;KzwaArVyr(eC2r zyBwwEbnLf6bZ-S*<43Y{Q|gd%%a38GLjoqAh=Z)i#|f20f15qJ_^=)hj&|F{pX2K- zJS`>suh|UV?qa|AA#g9;IlZbNp^dJ<-faT=NPKV7`q>>&Rm44FuaWIhT9;dkTqWl_ z^M_kYcl(IeK;b|VTid!;Sjk=r3HfqvE@`*4;mdQL4Cgb>PR;x*C|t4}HcXYt zf3>~)q!$%J^`yGiP7K3rBa{}hK;p$p_e!ADk9;K>%)f+Z}XM`E&@zTIs6O1(oC;Z z2je7Jp^fVz4j=xK{dJ8CDOvMXXs z;q;CZ74@n+J016n0+M7qM)}@?YqMpqM`e~M)XQQKB`nfr1IoR@iQ)@S_C5{zhZnRT zJtsUFA}TY0Jpw8na*T7LESk}@ad*F{tOhwSx8Nl0QUVdw0vY#ydbo^2e9;dvtX5Dk zu5!7eVjDnhP`^f*!g)~;62whU@|mg_M`rKA1JN+CE4k%wSGiTfbpKoC$(~|-bSMzz z1fPKnmd`Iuo4RpK99N%L*e(qKE=63#aDTzclItXAT`_W1K7R~$>&j=54Gj$QQ7K9)_&oYA$c0 z1wZqttSS}}$<$~6_24Td`&WH!UI&H2=+e;zX^b7rfKWXxe$5jXMyGO}pmKwcY|V?r zOCQdyP)n&p5`Ka9`A@~YYxCYK$?cGa#9zjsu<<+v0G^z^U~-PF2%0ubdMs=4{_(Kt zS))`lS>Nt=Mtv@dIl`0rvBetJ0KCnPqxaEaPoz~{7yozF-j_rW)0yj0Sc~1h1()V% z$f@O!O6cCnX4t?+%vq4Z*~*_sjRD7k9vtimxzIeC&*?bJ5u zAy9HeE7`Z%D&8^`N|g+EXrZX)SRAxLurG!fJ0dIc=Db{=jf2Vz0n~t< z-xe9YqtcI_%_1=qXbgrEIpx%xN%$0Wg|ln|cU@8err*cl8_u@zLX|t3HR2BvzZ|h~ zwydhPDeNG|MoXXoGg)62{t!Xeb&+laQp@Nu{K`gTGPJG2Hsmv!#*6qGKRIIM)u=}u z7TNvNWJndTh0TNx`a`LY z^u`p_s)WXV_5nV+QRcMxbe`XQ=Ud-O9Kq z|GFWQcLBuJJ$1wwhN=tr9gyvjjC%;8GS;BoTYy{ zzRa9HD9F&9P|Q`WdZ0)d&CSg78$Fal*r%RgCn#LgIBwnsqYE0vd@gRftjMqJh1EQ> z!zJW`hwZrA2mU4X8y_;_s0Q83~d{ zr5aSC)3SFI*_qA9rN(0x-X-it7=w3nxMnS~LyY`pf8`-uRl-wr@AlhwEz)%Ie@}Ar zAuS*wA&dSK&6J9x2;rW`GFGp%s9@XMDA3ge8=~Z}t~W@>TX0t8S z+E>)p^PUf1%euy`M{f)kmpvA*g3fBP5QlfGV`{?sIy=c!lguYO=?qj;k0pC$rDZW+ z`bO8AcpYFJ&)9Cd!pG!WGEkO7eB~8y>UloNp3FF92qrIjfk01_<5Lv01vyU?*_u%t z32dNpk^FHlIVW=&{gMQim=9&n_?YQCW83Qs#@{zw&pibCy==Mq zhXY|>a${P$xu3Ce(aoeGKRXoyiUWklp-#1V?ju^zMs$L_3+vr|dFcoA9DN~9^{s1Wp^ zUPj|Pi;1Zj2IAx8Mqq)!R%!UzdF1C->CuNQttyS7Nf9BiGF(bJE=5mo&fT-}v+r)Q z0Xu|O<)tb$2;N^$m)dWB<6%RBh%?`hGRBDw-#vzIm{io z#@#tG)$&Zwt<`ZD&Q{wLuET9?QP7LZzH-mbEAL^@*jxmzrZ;?Ik|2kiclC~a#&&0!+dHPOgg92@5ZeN@Ax(@ zR6GO)6_ma$NkX?@%Cr&k6&C;ynE98ZwNuIYd@avt@|ZV$&CRFK^|b1jUgik-9%4G6 zF!s_}*N0IPTf=VpNH>zEVNI+l1TGgnfPtbCOH6$dGBx{UOcR)Q4X2pCFmU6pc z;y{WhwQ47|ByJ&j7mF=1H{adSYq#CM5-~-+sBWu}SW2l~esl~o0@6}Dov>j3fWhLz z5@)(=1MDQAfNatA=LbVvLUCH@ZHd0%G{B=#+x+NvP* zQs{$Slv!V~WjDU0FexJ(@>>3s~k@i!h13X1R@PZ1~E5w_Ra37^& zZ~A<>zsKFwR&oFeZZsaV@!-(*EiNxEOPtprzbmisag>Bw(VQTTk-Jbz0EE@GQz+xgmLqU zf?`c}Rh(HclwsK5a@((gvF-%HC!c5eq-nn{XlnWv#lBM<#6$#|KJmlg6(ib)GXWkWtwM*Ida;A?eHxDs9?HytHVz9)BY zZN$O{Zhi6GO*ZvPgx)1iJtmN@rh$&72V`X=Nqp+`SuH+1+d|K z7SA5LwS}$XP@l^K7O%?E^70Y@nO2MmM5FdGpjNJC6-nX`>cPduwTpbP(>1c-vTMZ; zv4_!rPGaz5{!&mTuX5e>Qv+cT(#nzfgZk!mkLA*s)T2>taxr%A-{&8acJO}|3m9ZB zN=rylfKJPG33MEi^S|Gb*RCHJNH#NTsJZbyu+?tITrljr|Dt*-he-a!36I+SZ5xUd zf=5iR$c-D8ciu;SB;jucR1tqK3dePC!I!tmPWA~BRlT@$5SQaEt=qQLy8b%#%AC7E z+3(u}yoqSJ!;FedFyo&r1(P z0z>a7zsENr!umLRNx$&N{k$1**Av2qJE@zUC@61AW|7OdF!bG8wrL@bKhikVcD{xD z^9;M7s628gLVeRf!7oay6g%OirfGew{~Uix!stb8*`;xdcR%0ScZL@O7n~C|VLVRL|BT00`I# zy7JQ~u4*Ra^_PDz zl7}Ma|KK=FIZ#+7C$+n(8w(^TU4Is{⪚l4U;M=DJ?8Tq{L-&dWOMw1MYV8NCG28 z&Ue#&>t^BhO%I34R|16BTD_1Ho0A5fHx{8{s3$TpXZpcCBQ&(SsPO~9u_TR$Lig=7wI4D+ zLY0(PC7_nPMB-Jc9O9QxzTD=d&m^*C_6TB4B%iEP0&v{0>JTfPSswSs3^bJ6BP$7V z`0NTfi-l#5g`M^@3meh$9FpLaJJTv;N&Ot4j#;rXtv(;NpC^p#EuC5E$$c>3+w6oR z%4aDn5=LWSpQ(a1b1qvE<0phrQEB;TJRD6z(m_^7!R39D-uIo$tI%svH}JX2y{ru&txq&_9V@{v4QB3dHX6k-bQt)9PBQ1 z9udO#p3(9Hw|{qEk&{zG0-Y1*e{s2w+4vQpq_XF3c)sQhr5%$yZ{CPUaKGq=Rq3l0 zY5D4U7DBY~xV&di$T=rUhVcS3>m!bD3yR7rad^G!KB@H=uCj9k&T}O))%22RUmokq zq_Z0%+?gbn5sWZ3wexP1WghD;MH33IG|1S0_TH{y_ZZCn)DrL59P&k#?1^^$&#WFP z-r=KH>i9v!+cO~jKwui~nLi%4@ZQl6evHNp$4%3klAdSO6%MHzgFqYd^Jo~>u8|9s zUvHp@Sh8X@z-n{1)j({-A|d+vje&Du*yK0;1sWc~P+l-iPVVx_Gd^2dE@gsOsu%HtO!sz z2;>dVu$&fd6G^Ffo(=%1h6n`8UfN^r8oZ|Tw^2A61B*!=;>M70y+qwcYfI?0abr7K zeA0M?bJNz4luJVfts+24LhAoDUDj$+NVgzyV^Uh;(el9ye5wo-9fqv_rL9uaSUOcAKtv4dW9ME!`z5=G~Hts3AiT63>Tr|!y}9G-HJ4p zLkJ?JsU%1#0Kh03^}=zSlgZw>z(hKveJ9lB)1=8r%)CM;$jS{pS3UU%0eHxbW@O29 zVsx?5Ki}M;R=FvTKkMfZx1$r+n33$&XSM~aK0{C|Mof6_WGU37+Ic%GC2n)Ijw>++ zbW+_+!!88IDWc3-Fm)epUQ0-0#NO#=e>@$%?7tia`^di-1lTrz=~rm z|Db<=!C!z<#b*{iL`-|a;Ww&mpI!_J(`T)sY%cH92#a8J>7%ArmS8aty`&@xV1okb z%~C=#J-oe$m5Gjm4!0TCK9Q<}jNKihi!!;=Npks*C6}@&AC?96)jN+&{S?2uHs z?aG{5ceo*a?i}i-(A{X*voD&ex8Py3Vy3c~T?oi4W}RB~J+0Oo7aOUn>Vts z5kh3V99jMWsQZ(yx}>akNwH${x-r+gv%onD&JvH-nJCsl@_-*|f#F%~+{?)Jh&TYYnnYxxsZ zFye!Aomn=72f5(&yjMh7+4b(kraLJ`C%`h-&)(0zx#nfxdjY88figIPURrrKxCT!> zLN&PIEW>*h+9yb_jjVh*D(EMMoYC0PnzIdXdUEQ(1))fhUM?zsuREkv9O5DUp7|ES zxP)Vdo+H%r(!Gw3{vIQe3-lL8+?neGyb776IzJ|vHH4S9ayzqJtj32|@tMh0L3I}& zZ}Awu-{8C6qerhbbWqwSB> zU$yIezomS)^D$)D_UuiNbQAKc?YQxS%8*<2o}TY6y>J6N>(L)9HukK;);!1=VkrZ3 z4UDu6c*KR6%sK(%J5GeM4%S54LC#Y_Ep>D6V@P0BWlGhT!k`78`-sKJuY^a^fXwaf z^CeJp8MqG#l-WNlm&K$EpVCdM!=a+KpFWGbUmJ&>MMIaO>aG1I?J1%FWshziF|)bf zpN0H64P|s~s0)Bc6|PUPO-u$NLBJE$=RRaD%A0FI_rf37o45W)&%e z_;5EQktQF=4J&@`jxYGOqggs$Zw20r2fokkLHKP}ASft2FVIW(^g9JTu6yeQ|2=h7 zUV>s5uucsCc||YCBQAs2FABv2ATBSA48y8A>+`Z7+{m(WAI%O)FMT1Fg=WfPhjhIZ ziePkgr&jIV$^~snRa5^=$$Yxt2-?IKj-6?n`RY~#wWS;^k8+-EQS@xC3&WoV%sH9f~#3F0Iap|_DCY9s3QLJ>kmFJbtcxH>>Yd?b*Z2RI8If>#qnMkIph+>`+(T0 z)iNj7q$gX;&S!cw& z%4Tcm@?K-7?ut0UviQqg4|RxC9269f>2aC-RWS$VUEHIsj$^+=Vd0=1dWK*_r&6 zF{3~S##9|YCKnEc=JL858rXH$ZVX#Kl8;q~%BXrPZu zi09>XiIYK}6{vpH;*zd^aT4?_qQXYZx3h21mRgY?$dtwA_~6F;5KEo~r3J;W)a=w` z#pC3iQ~dGKl)Bf3jV<_B1v!L#5n6J){(p^>h(4;Def0Cjh+pELMlQYSEb;QM9M8hn z#L5`}M7-XbC~f*dUl{fL=pf}$>?BdlQMHe~{h(__$or(jn&Z zQ+H=GLxJ)Bi`OlBGs$Go1EX(xR_T*!YWTxXZRVkh`diC+Q-BcD3tHN*wC65S zeCWLF=!N4cZslpqdG=Wei_@}8wL<(Z$=LhRV||L>dbv9~Nb?dhy(bldybpCLPa}qm z61zb!eawn~4F!iJp&G|LXymdtCfg=0(&rSnN)X;*rG#jzMnwu#U#DW{3Y6>UO2ylf zt!pmjh#Piz5rGUGP%8%J!;8cFd_Mi5!(72b%u(c(Zt9DV`RErNlY~z-u2V_ z#%b>_DXlXi#7B`mdd+!d>aK7?=f|h8hVYWd{Hrmbg&=;L8?kEw;pgM9A>U`u=wD|W zsTDQ;Gz{W>HjfQ#*vSij+q7vXWo>EK?uMKqTa(zA5bqbgbut)5QJ;(s0i35Bu8>TR z6>o39tQr#jO2AN!-=;%uii3=|U#-8In7%$w+%PcnjnlmdoH;TK{ah})j+_V@E}g(~ z{kBwa%A7jOUWwtfWWp47F742IEnO=O1LJRB*|#2fy$T#5M^G!f*3Yi9XHS6me=evn ze4@UYiLXm=;^f4~lTecI^j$}#??mAfCav@?fw!%`1j$KawN!?uFEHAOMF1qoRgogS zrDB%Ne~`Eo1MY6SJRsMTe7yKJgwyXTVWkphrg<1mlXr&8)Ui6VRl|_D7=iHN7v?Ta zBBb_rsD&Omkqt34!{r-2@CkYO@Wa^XxHg&H1}&MW#7k=N=|MWgPcnyg>zZkuoIJdx zX}xRwVTZryb#G;D-5FlKM-y!NW;y+n=1h0B=VkeEcvDk+*CgId!;B3ypDuZ__E=F= zSep;!O2<8$d;6E*8r?88&G zpzT-YC+gwgeV?!2os`NpuZ*o#EPdH@!@`3(0fJ2C56wr zH1#QDH3=V*dVu1><&c8U*7^q4hTA|+sHZ@PLUCHmkfIU?)eBh`Xs-+HJR2m;FBB%j z7eiseDlE*RX22@OGUnX!ShS1lH6a?-6d%v4BT2vxVBJD0gAID!&K?zos)T>VP1Bzz zhWq;(l~U{&Y#H1t%Rbp!P;zT{5wB`IrcHU8?@wFM%3stnOH_Dy?+V0@?!7>NnmIA8 zcy!tL5$ieUtXfbJI3dp?;UF-RSl64cz6o##^&Pdp9zO$9X_Orit46rsyrPvH0Cf?; zHzr??X5a#iW$^?!(DY8994mAxEH?MSz_#LsS7hh%CkiN`-Y0`lrF!+18xG6?YlMBM zy1bq*ApU6+lvP*b#MvV&SHn(1O9F(gfobhBiPP8Hc9p{=8qDsKwr_M*6z7KywbL_# z#UVFl)9OLulq2ZY%dliYAL9(NHQ{Dz>90NPXZ1aMPNAXPQVY*mq#jf!{rX2I>Lm8* z-<>D}VL3S-6_2g!E9K9d7Z4(pXy>(MdhUKv#c30h>AM0oCD1BK;&Oj6gS*-{wTkNr zhym*+?~|X4`;@M?FI>Xuc}D1kOpJqARmFyP10>~Y`ujV$l~UPiG)mB@V*ikW33;!U zYy}XiFzzu`C}JGiKH-g>6D4SRG>+SBfgjI!6nfvMB7#XkC#VI#H(3o9qo$L3ow(^i z8rx-+7y&A_xf&l}nI>q7#D7kq=4zc-17fxB^~JMwmsE(d^jUk0k%%(DwG3D67gfSd zcm*o(_!NupNhaVkexwtjxkp53v!=&x8ntblXAqP)n_9dO&lb18rJgDahY6$?LO$?Rh07N9McK$8E_YMMS8wuOlth`j9O(-1>APL~V z0OfISbE{D{^O1O~Z!0my>7`+6)?S5z&WAczyi}|4eyrQwJS@R65=Umpm3kREQn!!> zt`I0HnO)2b@<+?PMb5H}=ie-W=;ub3q_U=XzjJ*IY0KNX5`{?za(`-}{6`1Bu^0lZ zj}a+YP0#YTmBBnd!YZK-m-jO2cKt-0<(AP7VZ|f?eZGs)X%-kB-pWUBB&5u2tBOiT zcEjlvzxp+ADxA?m%-o}{RF>^v*i!23))y8oadJ=7uP|JIG5zUV+vdPWj=G0c zmv(FgfVd4O!!WGn{_cbu&b1N~LdWXRXd(F-!#LU_?3eXzk&lzMj@)$XuzLHZ`)&^3 zL~_4%c$@hLHFL%<0S+MouXy%f(|-+iI4PL75&$gt}S{M4uP1*8tpbYS8hYyR!ey z3pw?%<`J$K*xEXmm{G`~D)Q!x_7kH3kR+Dp4H3NRlFoHp6;|R^ zu?jDf_uszeM3N${LVcT^A3@GPWc-L=K5Z$U=UzoLc~ar+KT-SAaq-Kxi{OV?7^eG& zhR^|dL7W{GHXw8|``0@kZxp5DdkKY!r= z_yq>uIkn=>rarPuqy%(oT!DJS*XD zWLea5`FEmTTX}fVxxSlZ@hxkzFYuQChLrraCCzQG?e<{#Jyjqn5p*3`eEz$351_Dl zWjKHH$UbutAd5*2$!=b*T3F$jetF8P9r9>l1QJaIWd|`&oxC}DPdwoaUpXFr|NZ*T zb$}V_ZQ6dqx4l5S_)|=u!pfza#5uyFhN;C{thHmtCfzO-NH<@sJi_@8lASnexrPK4 zoAGO03;F-C9g>xioeifb z_s@ES3{4w%YP~Qc`CjU$yX%I-P^+_D!8#eFHpZOEUj5))|*k&7(Sc{}0w>qxA0)GCQB|BZ2z|X+POkyJV z1Ua+!JaIbW4BV)1HJMv$p1ue7dwfCuN(NFxRcAp|SfUqgAu=NG<1#Lb@J5mvl7DSX zZBWe6`GZ6%JbI@({~Q z{B(GvYze}vMqsp^!9BGgksAT3J<|G*c~9G3ycC@O3{*o#J#F`ldIt8(j@z;bY?_>$ z;<#~xuk|bWzB{i2CCM(RG3mb(-T(T((>Z7i7ijMhm!MQ7{t?wUtkI||9^}W3>;>2> z_IcI<$e%F{6UK_&&z0Zl2hQwGT5Hk{s~m;uymZQ$;loYW-&OhOBiKMKbHhek?>jJq z-dOCeWN@pBD0`HoehY77bffg0H$s+WQoDj-Pz zm&SJfd2jGh8LL7|Tl*~OuuyfSv$*2Mhi-DtLF=QGnf1))!>_H(7Rq_oY4i=u^40?* zK|mE&{ZY+&j)})B%Yx!K_exZdG5&6U^kun}TD8KC%cP`Tib8G}3bqpboPvSc$4O;W zuSasRi1NULDY@VQVi}~W-73IDy!C*Qm$)1he3mfl(*uLAe z!uV-T-!0>2YdB4h}NX;-L0U`K1QV zSjX9rDe;uK65$>Mk&M7Dv;k9aaaY^(-4d0doQW{Et$eQLiyf6W{)F4wbT7?zP|>+8 z6DoS+NLyQ6&Tn#Y5Hq#D`u3QklU2c+on8CtOc;VE=0isa2`m)Yn`8gG^vki$9;eS% zE4;lhyZ+H5n1TU@`PF0u9#wvCXg%eJnU_@DKp5Zai_r0bSrIwA+-usT2ld4lvoCHE z(JLf@GT`+Lo-LJ5t{KoK^dBB6jY!i}Hss#cK!Qf)oKN?hw+8_*A=CEGYEE5}y$lzJ1-v`IcD1IPcZFpE_S~c+$=P7EBn!q>agJJMxy# zhV9n2u65p~oqzm*)OoaiyE7YIHgWn6k;`_Lb)kcl(U+; zwSdL28j?U#U{()PTgHhWP z79O~%O#>q63ss>*lm34Kinn%FNsE;gm;J!EUd<*;ZU8y^?p^vttp2=66U^5;Aq#dqU3h8cs+kDgARZC72YY4DN$RB`=NMvV`0 zma(LmJcK(Sl%8Y3tNB}>0z7l##6ZdgI#^y4gdL1h><&8m0!N4DUso&nqE;c{{?|vX z?xzr@AQ%?Es%re(7y6$xkmpo3;zOxe;F25dbAxT# zNd-Tsc7SpU{!I$Ynt+1T(csfd+n$PTKfYq+e>fN5l_yFJdygt3gChnI?S-w%uN>rj zueC&|*7B)9>B@CggJtW?yLAzkR1Jbu;E)7$;+G+ zX*c|~@|S(!TCXQ{eszQp@s-6kB)z1?)9#A!`_IN_v4fsBzzZAPpNcD%srXf(7pWR( z+;qHzEm9_`-pGgAITR-(Ss3Vf4tW)ONz&+gJ+SL=?cHLxo0d#-;1au&bDPQD5w)g#5rj#GEqxqCf@o&bKv>HSnj7XRM-s zeeVD1U5ck_cSFxd#(<0MO@SOEX2F?Ri`ZYe6z|uw*R`fZg=XQTF+2(<(0@cR-*!GX zFY+PpZa%Vd=bjnKi>a4wIdzaN_*hhbR9#cXavag?hHd96D@sqXE2uA*77L4V;6gQ%%su$h?c4RbBcMxHe0A?JEL^KctEZO>+#^eZM>~+HT=>)V z_}3oG?%~B%o=jd|@{X`CU#$7Q3sad}{IO+M;Wv}ZVY6;K zb1ja>GH)#JW>A}~{5DU4JK>l`T}W$JB&ek=XPC(^U%wv|gqm$%l6&U*!kXwwaK^Ni z7#NjRH{I&<-lo{KkT1`RdH)hmP)t(xCUGYh9Vki7kPl#1SZ z1$O(NMIDs5Q{z=CD_1^kXB}0H9?ykyEUgY`0~N!~8-1gCG+MnO`Q;&%&Q12{ZVO^j z5h|D|%KWa3V0O>#@B(H)>meDE_=iS8OXgLSjSt+ z%6Rsd9z5L-Waxth|GQ-Vqo@|PFN#}onV;G$^rR3#K*3&7nI*9OCn2G#bO4Ik9rVfO zb3Ys2C<{tG#*8$YUCO#?aNEj=e~DJ$dADM2@=yWqdt>jCznTeuzO(m?Vq=Q2Pra|u z**z`6bRXQmpG+7ZLO3QjN<4Mr4?v1u$7-VWc_)sFF%n29?go>Uu;@Y4TyIkYuOw-2 z47pQdA58L}2krL}$ZhJZ*l>$WWuG(qP}8H(vDeN_)IG2+50CH-C0mJqJrBDw^J`ib zIVIF~&dmDNY)%Am{l*Rc?JW6k0rU>nAiUR4LFF0bT%_bdTj#s)<|1-tmf#T!pSq^= zDTYtYnnFXr^uAf_fylI^vKv))$b}V7BCmWxeh9b%4W8X@y><;!HL@3lR|$O#b@uVMbhh>H zUqI?Tu)A3z=Cz!#$2Bb6+as~A$Do5%AAakMQ@#yxEaYRM1;zUaI<(xH4)uEe>%6S> z>ZvuO*BdSy6RyS_b|?BBd#(<-w!B>9@bj^3>AfUn;b#u7x`h&@M%F;vDgU6v{^Lhl zGS8exvnN9Wg60p45G{e>>1P4>DbojN^9Kt${oZ z^hM6;_~_+}9EX>oU;kl6fmslp{0OqMt@UFI`y%Z-99=co_1JR9y{C+LKEYf-@aI@2 zO{TSZB@!4CukrSScg7v zEif#DEq#MqSFw+d1U^2I$0ZLb4M}#!&uOON!-;;$!^N!hNRF-*h*F<^w$`u5^s0Fk z3U_~x78&md1uV3 zppRgy6|hZ^k{mpzew(OdRUXVr<5d$JQ&UkctrP>`pm2jVUc`@v@pdzsl}ilB+7G#o zr*TRQ?>H+6Sk9G&nKxY6JS&cF?gbL2UAQ8ywg&A(t>1oyL(`1G|sOI11+n>Vw zb;q5|v%Ew+)c)3!A+?~VF~>GP{aVx>TKqxMwa_EAvIo#9Mfo1Qwb^P_34D($J3dEl zJSBth-v3PXo4)6N-)KY{rsmwVz->WO3Ikl40wFujm8l9*Gs8RD3M$(i z6(Qx0W6IJ))}ipvwgVn0v!;ojo|c_rM~dOz+w3wKrQ|RFCc~h3qKuu#P~O&!JpIZy znrcFVA@U0GX_uK+dbyr7_wpiymM<8Cdh&{naC36r_nS;-tJ5>jW-3b|d31u@M0^51 zzW-+J<5h(Ad^|Y^B7ZZsS{5-G^n5$+yH7i~0(CTHF|r{0Rg>FPZlhb6&;d{G*bwsX zWn^~z>-s@?8zqN&J;sKg4|e$lA2a-V&$Z~jvZ)eWHf%(&xgeD@@cvQBL`0X@iNVF< z>fp4a#*6vfjmj^MNho_Z_O*Fwa#bIq7F5556ePL-eSXR<&Y$SJ%q^tAry#fmpD!l& zw=&(GokIJ4B@fnH1Xn=odjwe<`B2Qw^#lY;udimjR$DcmE^y`>K~R?r?tcJ%5RqL+ zS|ays0rfWK9gFX6B7b_{->?5)p9J>x77_9{3>4m+6oV@Kq!-Bdn+Ekwog#&FC2u+T zkFH}1H#n|E_ok6w2koY@+`XhIz+IeB!yEIA=U*C|5!_B?(5Jl?J9($V-0!$8<0rS`W8Z{R!cr!Y&s*VpW5V)pC($g zDm)E*c6omis7|ckSw`)&xnGgm3AN7k^QCVLyls=WXe-l3NWC2U*T?pM(L4F= zWBu72i5IVNWwnt$FM$1x2qepbR_AtUkE+PI$*p{*yCWyYI%|yiQ@31ifq8xcY4j`*g^x~PA}eQs6GPLscI5W!ko`x6?9<9h{dZNEG}qgD zg=Md9`<~{XFd7{F(~1k+Qo{9C#8tyH&(1H(w@N8jHU;!2gZvu?Y}+I6uRpDY z{U%2L*A~xPNhVXbLz_1TmHILU0E%4c2?#}CX^u={whfsGq8T8^OGf<&)8~bQsD0?deLQv!XgXC^E$7P0F5ptS{ z*UF}M$2GmZ_xp$C}@Snjx z-UvI5aMEVloul^q#SfeKTZ9AP(|t3=f-}&rQweV8$YXD^UvVCyx}Y=5@)jWMUXj@# zr5Z6q%F8&O>T;^OZF8I^W?%AW)OG&z{+#bhAqrXE7;^!c`BS* zQ-9ldwFwZZ-(xUu&Z^sdacYidNT`dVmKibo-qObRNd0Wb^eM}edzb0{X|9uzDfROH z^HcuIpp)~krlHLpIB~cL|8Ndxx{)4OJx38zN=UlilGo5FhL0UI^p95}w>{Q*L_e#J z%*SNl8}{8VZ_JeO7 z$D(^pdc}NS;7Y6uB=?w)U-Qv)n z<4oTfbr{TCnr2TbpGHl=R$fMl3P1ig`JoFK4^eL@KEe70msv$>0QBqWObSmdWtJ4l zc?bV>a&?`2V$6Rux59jU7SS3J$+M}N0otX6mme6gJ}T)^&IwixJAW{D`zp-3NLq~y(|*87ub~gW=$CW=N(TGj&ke9NE>&?zcw81#(PL|s79o%5 z80#Qs)uC42_T(>nIcOs5-=l=nri|GVRUEe%w`h2hQpE{B{lM@4Jt_2Gd-s3%xY5%l zH{FZEXPnC=cwEmtKB2hCA@VS}znVN+_pl(^P8x$B#XxqGJs0vvO2j1xWol|Fg(rr0 zB~_c}sYqKoWSvw8XhyWv9**<&H(UbqdxTd8P!k=Qt zCr3|sdur1>hstW4sVIQozTnNchqLBhZ4JcVj;8wxDS&B5l<|G$xp+Pl`YDFuN!Q8S zAZ$?7I7D?et#Iy@{Ro{+KJy((@M^H_Om--@EVm-#xVEH`BscrXo6V(h6=O~D#p9X^ zUkpmbh$3n|>c=5zL64wc(ghMw^^xoJNn2f%qcC#ICLj%M795P#N27opFb!Ry2Emts z^bBOH^p2Z7&nB@%r{WrL(d5HrD`i*ndwhFY$sYhZ2_>q5OO#Dh@@iK~-(Vz)YJ7OG zu{mG+v~-0&)wpx($MTad8f!)I)L=8ltxRnzgN_%=L7O+d6MPIbnLfNPhX_|+{^|9S zL!gO{-0dk`L$visb5t%B5hYSGHF@eV&1UQJ)_dfZ>Z?wNz7fgsamc9qIXxbmKepi+ z=pN-0STUKdY|TC^h}71J^rJ16Yfsy(BP(V>DSac6R2R8?JaR%bT zv-X@5e(wzDG6E@4{O?a@(VTXf-h1yJSP;sauvue017S#Z`_m@5=73YdYq6b&ESyr= zxBVdg^~T#aJ?$?*4|Y~rSu9&@Ty~T*XffmI&Ck1`^fZ0Mu5kV-n+G$z(>76eviN%5}3aQAZzN+eVkalbviG7%7ngAZlIE zJtYlXdCg4&1NnzgY8XED*U=Z^)Gwu9+?3bwEpN2hdepofv3WKZVXe!g!KSn0+zW7? z(UCL5x*aLS3r{p_PRh$FgXL$iu*zZu5&1IY2hUtnkP#OgEadJ%F(U{k_4BwUDp$6M zQ(ZhUa?H2eeP{LX0}s>X>5j9axlH)M*_(&#?txlbAPy3@YlsW84eF^a{e>TlCP%)OOT7x5Xcm6bbP0c!fV2knm_2Z;r5M}rD;Dh z`vyM?Dk-TlP$KU=YCVVSgEMQ*xuAnX6d+*|%N`Tud>Lk0t3grL&k z7Z86VFfx0Hf_a4E*hnb_(QCi!x^w*p=eb+E zee7|3_Ibza`K-E&4QR^Bu+X!(RaVe4CgyF2Q6SVu63pF;_-sX%ora8!0qFfLl< zgUNPl5K$z0BmmaCrYf;%Nd-Qe9}5Aph(be6h!%z=t?nwGmE^mnpE7aNCKE%1V5uLZ zI=(47Ras-*u#oD&e9YWS9Fftn*?o)8u@aAw;tHHr>0r277h1p@sY9C@%xXI ze=}(doerIZ>*&o)iZ|KpKOuN!`F*jnobIRP0VMP%fY3qLE+0`HQ&6=X7*>3DQ+lihws20$Sh>cv5!oJLW4P@t zm9Qz$A26sPUTHR^6I8#eO5qR2mMmK6r<&=BFs3)C3-&1d=&(`#M9W*pmx5S^cs_-9 zP3+0ca#O53yiVT2;}y;FO7IqiC0VX89B&?A4U~zvDj)xbRm7XHSt5~uyKWQL1{QH^ z(hzidb&91geji4x5z@EMLD8yh7(1y@2WVEza6>;YVpI!S?KfPaHIWv^o6-B`k6&4) zMklc!0Dx?MKusdLecPZ&y5l^0jVZN}@KNx^tC>>zeAbXf_y1n(P0_0DLXwWJP7{i( zb~8*CF*1LD1m&h{Nh_j1P0{WfvGzjb-3~(lSLokX?@Mj(O4$aNG}zUq;xMI(458GU znHjVZ6WTmds8E1N;sfNkcP3)|Iho-y<$PBCkv7gu>rqYG&kRLtuGP_>XE`9JfR3yM z=OakY4nJk&)VNbP0-Xp|Zdy3rG02>>7^S+Otmw}3)9Bf9?R~y=e~93@@^WB*md0l-sn2cVrKBOk^Wldc4jcW zaL@4Y7}ocuQk-iC6s9{njvZb5ZD^>#Wppws)< zb#}ylp@j^%%eM6EN!Z`f&^Mg_MI)x1KK7eXBHu&bZfjzq66ev*UExtFL}|cj?0=K&Xnu(L zep0*^vvcRxvNkkmDoMkAYj5^^geGy;%JeQUUGw3OTA1C6)a@f;@}M86F>?jUzcqq| zYPjRL;u6!9uowc(-|yVwaM*~@95{a8Ky=~NQ)1^}%$Pz1Lxf#`l@=OhGyLIZr%ny@ zduKPt)%5C~%_|&bvw5rlqQ>IhooG-i*(a=UfR9m@vnJJ9f!NlO&HCs8QphoZV7e^dj`y$7R+r z@;Xe9p*fmvq)wA*3sQ}(m|XTGDr3z_i%MwE+KDOYaSLJLC)0R8Oox7U`(`je(sw6u z&xO`~Vz$`e!o=gLY-p|ME7ih^MA`OuBnce~@ryH+R}u%l<5S>J80yx0Ut{tKYhfju zURsU&@>@eiiMk{spm^`WHOaMjs+7JrEJmfzCa~|T;CPy@%SM|~;nJd3Sr2z|gNI0N z{m@KQuuM_FxKfMqyZEU2Ntgw6si%OvjkPZnZyr%@mK#uv_9}kLD~vM-|VpJ%-pL%71(KtjgWvXW4R9 zi<-F&gpJ&$0b5Z{3a{Xb+By1YAjpXINMQFwxpsC}tMX)Y;1bcY=mD0weT)gX|6yJt z1JidVkU1nhwtTMUzL@z{Oxk?vIR?J#R)&S-Xg=R#MDsMJM8~%rtWbSryw?7r-G$K4 zEfH!&usuG8HHV}#=+jJe;|2qMrPN69J*)e>P1`uD!YUhCTzr22>=L1NqA~gwYQ4weYLr>3sB{sV6p^J+G>~fvfoc>Gb^U3Fk|J;=0 z6veQ#EZbiWFKub?npJln+C!lK0T^6L%Bx=AE%3}c^|_HKAy@@VVgYcj^$B##fHW`b zJo(z%t)O3mEDidn(+AR5}>L2WTM{?}FEZ7Mve%HTqS(aE^URqcyjV>-|?R+Cu<%t}LRUXMv z2y=%>WiHOhv`Taj7)eHP!^?4PM=o4`S=e#xrIV7U_lrCwsDal#uv`8mJ$ZBUB&$3~xka6(wEM;ONmo~@eeOIPX0Q=W5rzD-5?tSPy| z^qVf(Yl1O50#QtA;K*Wx4*U&%W^e)C^-cUH;%UhP9TjmJ{dlj)g7h4N?(d`WKi^za zcR1@TB8hWdbWK%TUR)pWcz4x<%gs4q=WT~vF>`2)U*IW-i9@AaCUE&&%g7O*va|fs z{K1k8{6xG66=K^-BRzhrP&Pi{x1{E4Oj(|x+EtQ70@8F+vfb0>!ra4idh~Yi3Yz5h z$?trwXmJHpz>iQ6m=5)yH*A=rVYDH;w5|Rn3Yj+CYjfXR3RCdwwOausYLC<{D0I;K zD6i9=ZB<~0PTNZ=1zXi=ZWm+ruvm@;PAT5Kmk!F20#TB_T7Gm7FWaA;>&?%Xd!O5Y zMRiJdQ%20#52=J5%MwcZ$GnQ0TBO+`l;mB2{#%#W>~5kyqS+nsg>0{-1u@;|7eWWW zO7tc>#ohScJ|+_3M%_f|;6g7$iraLc4Nm^iXfRb7&+>t&fx*Dj+bF4FT#U`CU2t&i zz`j!mii^R`h98;@u8ksF2eeK?#Ioz{#e+C`sh7tCDD$5)l_Gihv8(h}6SLkKyydo4 zO&b*tl}v0_y;e(QX|E2^FWwjDq0U;J@QVn_jvNKXKsd3uDao~+J#hL?bb8*83XgmJ zjI;Da%5yH>ORw|y^SQRkL&1|FTUI0vj-8r4uHME&mF!82W{3~(YJ+P@+eLn>PfYeG zlO**-`OuVM+HB(Mam=Qc$do5ZN-hMvhDGn=rvU+~5v6`m(XBfhZq;BR&b*EI4z_%DXKAXGoHWjV zfQnA5fa-d(oYjJ-N5xtmO8&pRAeDNS`S;Bbd2j!PwLFkNxM)hy%L+;rT<6X!TH3#9 zMv@DF^S;V%I&A59aFc3HDfUNtgggrQ?D;tbJ7N3Ln`<13GQ;aHWN~r0NT>W=msXXH zP;d`_YufSH>!e+TbvR>~`Kj~GQX$kP7{q=EJ2*m{J zRp|jH;S~P?N^)hhu%?95=PsydF8QL;WL!?0KsQJD0O$ee1wFWqm^k50VEu5Rk2NLU zZ!jPJ%V5N}l6Wg(Az{-`-fwg04cBw`&RhFg8E#D%qH}5R#zhYgUOgGor|iQg8=GO1 za=;sPGJPHIsF7{B?&P8H$4hygld+gn?2KaGp(x1SOnfj<_H%Qkqx+(duW%17iYSpz zc%*6D|JlS1>JwN!b&`5w5KX!MJ0*j^vwu5dVxpRZsT+ZqZvv9jI(e}*5KJc(?f8PoUrn;yIL1<`PIyV#-S73{aVp5*7OJX{Y#|Qm3QO ztb7a0L~t-#M81b9S8#G5@gKmstPM)RuY}{XqADK>KasL4aZ$PJJ8nKum*j6Km2*uV z!199lY>RACD2?$(&;3PD2P%%}GgqRP$;c7mgoxIjL?ERO;R6LLaeU9A@VKta@LpK% za2tAn4Sd7CY?|LwB)qGyfg$e+C$xeAq3KNWYs7xq2{lM<;4m6vm|Rl!PJ3tXuxjtR zzMp$pulvdX2+!ZQnW(O|hU^nK3b$DdFd#y&&w64Cxu6CzE2_4^j*Kqa$uGoivL&p5 z+Kvm-B?xl*H|3(g?j-z-bIQ*v0Vd6tXqHt?1R^?Jjc8;GvNCn-fntl!MnbvWl9Yr@ z-ysbs$KoUn`#00#`U#%Z%+w4@g)@>ygPpygy%Mn4bpQ|*Wk9Ym!GhZYnv}Sl+hCe~ zKPk@ljWEGI2@t4KfD`Djxe%Y@C%8~BNz|V+Tnr5J$+px(r0;?sknf3#%jqmjgL#4$ z_&EMBIXBC%8iLrlsSBC4FZFz9*tw{mS*eo2J&OiiYjT`x*?eODN@R+8m@Nau+K24E zT?v+(GV-xhNhTH*Cekj-$k^Gt2-BW&a!abETQM07$y2|N5sVn7dgr#7O17_=bH}`# zm+3#{K$|oarW(y}9_V@m=g4IVc{ABTcvL2K{geSt?N7IcO^T#1pViErR!;|#b6b-t zQL*^qkC~IG|3azl_#=XqLPIl{CTg|4VuEG`Ya@i~EYUw+db4`l&JYYaas60LU6&A+h zIJ!jU9{%)>V;3TVP#}TZo(Is(L2Y_z3KwZaU$It~c)irI+mpXFHUtK}OB3jVzb9&> zI&-~L%!+yY<;;eM7}i<4cwaCl>5(nR_rZ_KAa|-tY-nRbDJ9&(S4$Xc@3P*#$w8E% zi5roNYOYka*^FnQ;!(RbCJ<$(AkgBm6oYV|HnngIvo5c;Dg|$qiEn_56p7hZe<5CFluu}KGgIt)ce187ID1mP7$%$g zV9KU7?KtaGN(OF}V}uZw3((gB0+h&=0E+{p_^-!%HCYA_){OG?MA^qR6{ zl=F_(%h_N@oXzTI&+|)p#tV^8EgGP4#ZnyzlhQOSGq_0V>Of zHe$-o*$X2X!Em6{?FpflR}dL8)?RGT!IrHGp+v5%tfrsx(8kDn1WzAQFn zpH>iPKXoow^1loar@8s`_eNzoDp>DUl!RI?ZU`V>FxN(Yxp*7<*+h8tM@aJ)*}3S? zjW6Wt$(Z@kPKURNOyMDZW1(E~fC<9aLF{PM@^(peyM2ucED338Vx_2SLplChE{h1v z-VdT)!nKIf7dDe8DNBXX;_9xUf;A7pGlql6);s(*hU7@<2tj2k0PQa1=IO=My)%Pa zr}>w|?gBN_{?l=H$v<9RIOGlnRV9@5OZdzx%zOH3GSO4LQsKNcjh&R3I!&!U0k1wi z6#b57HG8r)&+hG12g-=tY*P?O%66H|*4n~Vh|ebQSMN2rpSSXSRnUJIkVJi(b5$W> zo>O3rsYjjzlIey{ReFt|HXSaN^?TWM)nJY!TvAXG>>2aDgZnD%qKzU#X+`~l zM5rOoa#!(C=|w?tRNm84n40i@FiOi;s7WrPH7JF4Obvp!GBMK86SuHC>@i|sM2!d{ zpAJN#R*e9FwKP^aFBMUeD0+1A;zqMhVC(eowB*LQ|G{P+M_EjK$KUN<9+hDpV-FRR zy1%JGTlOJclZ)P|x_kALdZDpD<&=Y^s=F^Nf9^rNwg$rp;-7umf^;aT&hP@yy%$Oe zZSL!fV(~Y%2mAH_dzjvIt(Po_hvDr+uN%4}_$9QWQW(2LUSS9mC3WYVe+Ijwd`$Gw z84a!Vxkfy$fqG}x`($o!Z#j!qlmk~dg?tiH_qo(K2NOnVhbKE3D!tR`_H1UY@g_@^ znL?<%JgPg9gNfv&&EUQL0oo9@QHtL%FMf8BU*;HYj)=y7Y?S+QN5b;=b83&LOiVV+ zAnKlP3L6ShlGn07{R3ztY6|t?&l=%^rt0)4R80co^&PhnWR^TVm;6Dupa?bS7AA1_ z6#@F*z|?%FUEi3*kV*==_u_v^LU`_h;(+tM15Ek1z?)FxZPw;mdr|3K66x~3h5iw* zfiPIqecf>&Y<^_$3f-**2q+FrCI#9_WI*Mr(LtdfT)vdrz5&DWW^Gm|LBG|_Yp+{r zU8k6>cF%jm15`)h1~g*>1kEARrpBzH&|z~H=S-p+bG5=(I>+jB2sGScU`s-ArYkGA zmzFyiDyY48TVPf`WEi5P$S>t!#Zwsq3ly<+do#zt%C7mpwq_FwlQQ*c1yp!dF0vKH7; z3*B_G(`*ST7jITjt;mi@S8(S0b@R~o=NoQfp_aCRfzwR-D0dYaf7AXEEVpS=&+<%9 zhNt%Msm)IqKEvTgPGnBJ!@3BGjtY0*3va9bsR(zvco&A97;K`A zdN8xsItY?bW_};V;;xeHp<+;sMS4$jDK1IeY%{r!RCCW&Jv}yZ8e0p_kr`7pbQ6C4 zC9tQt<~inq_nrAXzjuSVs+FbkJU_KMC&Lo$#ULZ4C4XV83l6FBQsmdOAld8L5k#Q^ zH2dO|>zBNz&1CB@rI2jHzm0!WK-GBu2u%D;4{G?~XX;+YBr(pOmp073Gohh!wA` z!qh2|0*oGJ^hu?xw(K1atr$NRuisrO#%ASR4bxILDxz@ zF==Wc7@dk#aiqI}tGm!9doz0r8s5s9pVOA+idKGZeO|yL5rA~ycUs}*%LbB4H7VAE zw2>7z%<$e#JU;ovPfD5RKweRuu&>rlC%iEz8>!W37=w^K^T#gMUK_g|otGZXCf1<6 zT^b5`WHSMh8mZ%>0?KStRoAwixd&wB{R6x}^{eQcV7WvvD}!vB8b@?`nkc+D7jMEsiS;rT|e}M_4H3U%bZnDaJCt z6l<+7HEQ|YJ&QVeAV@8A!8d3`g%i?+9dBZI{Vg!ezG_d};`$^`A*JDeZPx#-pU3B^ zi^Q%)&V>lX*i)-vG$R9=hV6 zb~a73xJPQ+5c_<>?g#G%elm;H?*{Tbf=`98Uu*nCDUu--7{S0$GzHLSZorW5S(|aZ z*@~2iRzLae216$Cvqu?fUU@Fids@?!E8HlqLY}E=`K83C=U%bq{paL9wNia!b0Z~h z8K08I%4Q5T^6nJayN<2Nv=J3My&6PyKgwM8W^zaXUP8P_fS>h^?*{KEZ52V{tL$un zd&#sSYB4bGL*f;^1eI<>?mUe#r;#kFUWx8u-YsEfHF2HF+R#VS&AcY%5p@8ZyVt ztdWEBaEaP7mi-vRn#nd2_eLz1Az@Ws$k{hbYdScQ!*9WHoQe=-4G$vBEXw4~La|UM z*RZa>7kM^?UgKq;KoM{7855s^j}JR9#jv=q1HNg2s7cZw)MPzFVYMr~6H3V=pCoT+ z2#!-^^((fcMeid9U(j`i6S}5O@Jm_w#$=^VJF~HYtl$ljgMu%AiB{YAM^L#Jo3#HhL{GGCxQtOaUPKVkPMx{=P2f$t1F=~r_x9F*)7VO00nwm-rHU=V z;MaR{&30$nl5+2S+#vDCwliFVw($HZe-EfZV7qr$r9C05tTVn}Y_R`jkd0I#0LT|7 zFd24R_J`m6=+tacQ)w>hsB)juJ%Oxbe(X5ner1`v&1XjkUQvS0MM>^5yDZ*4F{YHX zmC)wwSeRZs>%xkPZOHdzt=k|1ruC=5w4&29&t29)vRGF7iF;*PYM?gaEP7x1&?`l$ zKahE*g`F?v_$gtMFf%qfurhS3%eLgeGtGoiW^BM(RLjA4oawZ^o|XvN7&Ht&N}J~I zF!=|l(nN+MvMDg{$-I)Fuyy8RF~~h*78ZvK7fJ$a-ZJxMjh^ybocy4c4nt6BWisPl zlRv;Uvsry)0^R$&uD54iAme<0hG%%^M*59Z_$jb}uTaqW|%IstteIti;4+3OS z6QmPrhU8)`J-%|vhE$Rf7oA;94fAHA9f-=n1Gu-yqDsz#kn~N}briQz@e+PJ(4?_q z&qP&j*|WJ~S9)))lVVuV>Tpm{*@TDr(~&1<)u7|jdvP{-XC*zqW>I zNtSb_Nmdo;e6$1fgR~>mJyer#gs$D1_fBoL^Lp{NVbtbeaBTi8zhj_&Dn4T3i?TY( zh;0ZcG(!v_EY+0-h_BhqVn56?Ma9T|NaP(OA@$y+^c5_$!F-zA4Zj=@jLF)1v@8Yq z7Qj63ITXLzh*8u^7IXl1>C5{Kko^_%0MZf@UfE_17LsJNTY!ZSp6Sq2;;~Pq5>MM8 zEGSh0lIrDDd}Bfu78H@)X-^vNm^AT1=T6l%DkI9|Q@QJNSbLRwAlnqy5Vpp#c(*NY z@L|@nUxWce&Vv=^E3-_L8;xLH6!PXa|M?fsq*dK~(pP5D-Co3ZeH>9#Ym6mS0Le`V ztSgvMWZJFT^EEQjqtJwY6%1SqQ;1!|)bDfT3*I5pe@{92%naJYOVTUHi(g8xPncS1 z>CPi{KnShQ+Kd>1HO8U!2gYvVt}h6hWA}GTr&FHoScxQJ?}F9eStp^LC*8mS0VuMb-#5#1Qkjnt``n0A=d%2 zS2w%MHgzQ?Mx$O=OdgT>RzP;XDl>9g4m|!`k9#UHmRT(g4I|-g#CzXgs~1#+(h2+& z;1lfN17SdgDy)J1W|&-7^ZSo)khqoO<68PgXY>b=_^%)V`?dqM@97jf2#~uT_>A~+ z;pB3}EeM?Iqu@=J|pq5=94qQ4>_w(j==RGYBN zo-bVSmG?URT^y4-S|qh@L@viutwR#M#-U1@^Os{>*|H_*yp%**y)fsotSrmT7%{&? z*nalA5MzX6Blx+`Y#Z%(RShyQ?}wq#!+qy|0pSKsBX`fj zcVTT-GsNOJZ0q#?fv&bo{5zHv;+kjMg!h zI+V_;5&N~Y1I{}F`#R{fv$m=q-l_8?zRg5;=Z6Nt5gQ(5OiZNQ;rKDlgVh~p7G{=D zbAy@&5RAP7Q~NBTYfX0~nS7UP#p7OCQiD~OR&c=)H82I)L(4nG;Fy)~h+(&h8!5l% z3B7*pETdHnSO932$tGrv(e%wzcipjC#7QRpEq72afYxlvocXvm(e$7@^4LP z?a4zu+=gr#zT3Wz+4s5#n<_G$wdb_5=YiQQB8^1(4j8?XQYn3CZzc+J?6~CrzghZ! z?mJNFL_d6(z;;I1@3{glnlNea#PGKss4zVT}-_E)ca;AzsQA7E)6C@XLUXt#>*- zA1%W-(<@TTk@vty6E8j;!M*Ap_N4$%{F+C4g*s&c3LBkhk4M+?c>*s`X#5-e4tw&a^w_xh;=?4&l zPAdJtv@IQ2c`Mu(*LCeo`&?_<45YLq>$;cpz@2&m86Y4~=ef&YhFSWUZ|H$wvxVmF zgsxuelIj=)N$)?P=n!s(lzhS(`;3aKT<2k=4%uTJ|+G@HG>90I`+ckS8pc}`>kv(QCma4yKDU=pz?C%f$d1Y za`d)HWxgHXshPP3(64o&&{-eAv=W^E;~EmjU}2yFMWY(xkp{|Q={)`mFo@5$$5+K& z!NQtJoo2JicZHkBhKD(?NO2>(yb6v!7hq_YxVYljIO9HrXYXdi> zHuRrEhgow#wVNBq^7n3mRweg#SSB8Q3FACqb}bo?qE>1&X{~^8efK+j!?Gx+{?@jEu#Cv(UQJ_FfDewgd?>`wiZYoZQ6pk_x+CG z=Zc1JyA0+d`%p2T!8_+HhQ(a2rPD7A{)`D-iAbJ`6 z`tc9oPya276;YC3X@Bz%Q`O-bMBtpa8CLW%k^eX(Y0%^@1XH;gm!9rXvBb$J21m)C zN;9S&3LHtfHtW_@!s{EBe8A*I_%thCRpjsr$70vq;l9lP?OKb#@gfx{Kd;;p6*Y|c z%Bw*UyF~v3sDGB-8aR2P<+nN2d$UX!7`G){S&5P8xqH{s7!7AKjjaY%`8W>-A@ufy}E^uJU%wj4Z%wCoHd0EIX?1W z(SO5Yh8MzU7&Y-e40aZGB12J+&myCa*gtaa3uuG-kZ?E^R$XKA@70;d1A4x#=A(k$ ztCzEM14gNSK;-{)*JLl*F_cY%Vz4#4*|3o*wI&rj?XY$4C?kXI#~l@(2^m%HPw>l^ zuvy~Wl5ye_+;8KsSw+jinx-1>%;~gf^sF6+$Q#|Qk>+Q!P4A?m9&9un?X30Cyb^1k zhq68%D~w*&VsLVRAqC@PBLKrI0059fvzYjDXh%F$BI|FrHc(X&kz#tdF8)6FoU*HD zpRA|BuhS`c!FE=&Y0*v4qD|kRHl+^cVO{0Zieolo(fDls{-g}IJXrI$(EKL9SxI|4 zLrZ>Gxd-$4RlnaXI?`OsWgX(FMVQcWc{F=1U)bgHX|hMHnM?tmJbM~#J2>E>`sUg{ zfW^|?x(ehM$LCH}P za6BRL>q+2HrSwU@1#xe-#j~KIIPODjnhRPygiIX-irKsjV!yF(CaVKh?TX2-z?_~* zhiF%T4uEX8Ksk%5pU3zbe_=BYDTh>J_{_e+KLGpGKY;1<&0{{N{oi;U6K>1 zeq7c3+R~l1=-V1>6a=-KC&y&OgaRcM&ZJHEaJS3~Z-a$aO2CCz(TU?$$~5non4Ry# z{C*7434kD6Uu|Be%#>Pyw>`>9g^_(fQ!6FL7cgs6$SELeEuK9(<$|esQ~{i)bj%AG zyrwVZ9MbF`MnzLQy;RTwX|&gRE+6XVfv$l*P=5cBW7+o?LFyv^KYDtMxYmxkE7yCo z1e`E-QRWGx_tuomJ70dKW~~xXUKoq_jPA4K^h>R3A9LvkxIqik^Y#RFC#TX-o(a7? zzYe|OV;4}tL#W?xrnOs84?>4al;$gGk=$BySyg5WH|(j)7=jCR@EW;dSS z!mO>|JZ*SUdPrXoPeH5-m3IKU$}RUhtD$d#xWn|XHTnB`Do*C>I|5G$p^Bqfq?pT- zyy{oJouIrVHmQ@3EX6Vvx&g;C$15y+`N4v;q4US`?hd)ejx+5Y%)g;@nZ^e5J}H7OmK^#?@$)Dh&H z#niY3>WpXtAUt7)Be@z9M2Q<4olDI2E*aGh>vqF}FuPa1!Qpobj=`WbCGM$dLNgQ* zu4jqaNNm^=tng%FD0G(yh0UioCFwF-R=BSemr_n@j+Lkzv>NPCuqPKSwHgnA;wQ+^ zb=#FH@j&Bk5R>3G+fI`zG%06C@8QPol(x^u0wB+QE>Q#flid8LcH&<`@gGr=Q3XRg zPv)tZ4yD?R*rGJGUNF2py>P0-#by84SoD0edCk&7@(CTUbmR*@9IF+vL+K*pU zzW;E8<*4F;kS*5WDMXNabM{i@XB%;F;BQD*M|k*#;{+0vI^C7w2~etj4cS1k`f|4_%a2W+qU0Bf51S8z^X z&$ZCrIp*LI`#*Ka5U-+=uCe_Ygl?FVg+xxLtZYNU2z9=JSmx@6O2i&=oSB-ZA*5jO z^!?w|nNyq0oeZKqDK0pdeITv|^&Jgl3DQ}VS1DK6;=SuS$)$*Hb7-TwfcKt2j72Vo0P1~X1R6OK=2zi68`L&r?O8Kz^4O)^ z*UQ8N`*L7$HJCOgi(a`kjqg1K1I^H##6$VDQs!t#IsEU#KwjB~^G(oi*^j3Tc=tMR zNv9JbH6@--xXb^bC+Rlj>t#iFarPs#76nw_Jzq)yz-A-JSD@g;nu-c&a-#Fuc31q5 z$3Flmj$ye1f8M_kejZhH9tXc>0LmnKOkY@ulVp&cGzav{Vb^^u0Vc|`Su@wrQa^JOWTmYK3T+Hl}1BR zVupaAn^^U|fJXW8tHwvk7o)s9g-a%G6TJ^CuGSbswf8%#WOZzPH4^GvY z&5=fBEE=^5t-#LW8VXUBH+z)tb9%*7c+5u0QIDBLYFQU$9WkVqauImIx%bc0p4(xQ z(PnM0K6Nwk78INyMxTSH#x-DNKy_;)oi( zS56mI{gZKN@t|o!gMa(Yqc_FO7$s!O&@@YJvBZcsH|LD3Vz9@L;PPg(84YvXo<}Ai zQ~I|McW;YIxeD9dMm_TR&OmR~EwSa=V$VvhCH>qkv6^EQG@qBiw2IORjZIJNO&{jl2NYzTYbt#SW zKW4EueH>Obg=>s;_$-7cJPq>bErpFBGpkeTvqNp0NPaT7%K0be)@H@FQ&AhV3;o@i zS~#F`Qd~p!U~CQhFyBz<)UXaU{n`BwQC3QPmYAJ!;u|(j%8O%kq7i_HR_R*9Wq?Vs%^6*# zt-FD8pJF2B{)~kTUqF_OJ&nu?hiL+5z0W?bcty{<`$qP?&Jb&mY406r5#n=YXWOMs zsGYyQ_bem*vih+bO*+?=;mG9JZ-1GEl)2+s-^nE!JLQ!J7L{YX{G=`(c>kfT2=I*Qd7&!~%b3G_y1EANx#T-07Z~Bs2K3nO=6MH=jOdQOC4*sth`c`UGQXv5sy#L zX4GK2;E+-jvl4varzuGks{g1|-HJW_=v@>`C`;6X^P+!%>L2g_0m><}4y#Tc=3* zi2=@HxyCYNy|}Eb2t_%GpUtZ5B}?axUsFD3(WgJ{Z!n>PXKPLQI7KsPOx?VuT%dGE zxp6wa_`Qi;QNb&JQ%SUC_tu!rR`1w0pS~lgLIPp2y@8Q$?S8ya9% z=bAtootI2fJ592!xO|X_2aU}oQMABi8oR6>1SUdtmj5rl3#T?hT;|*=PSh!3oN;KC zN`N|1e(XVT!LjaTgG$!3CS23yv)KBE_mvL^r%kljlh>UPa!o!mOUA~};d~ibx6WJ8 zsTuFj-Qp7`#vk)Leo7kJ`AYg5y`Z~Giv8Qw#NWsM4=`(pd~_le-XE|}B>n@?=+Y-5 zxd@i;a2M)RjqbSyM$)IhoxR@H>u)Xa;L?+|f-<5Qel*0PW<5)=6JNd}6t%5^tj);( ziI+UJk^xuf>Pbket*U`B@l}T1tRfSNw(tS2-Y!STx>*4 z$MBri5T_m&#^2cRx052FEU%(M2gy@&Aj_ub4F zO*YJnPS+O8<(2MEq#cxj`_CG#JaDE|*_gqR77pc6I@#BiSlN?O32YE;`mBk8zIto$ zj`-SP!HoSitY;WSW9R`tEeznU+HBK%x~6wGB^#Y6%Ou3~$ZQW%6=s?=eLMB9RK|HR z*Yg6A-@T^cH}J3TPzpA%(bQ#>VFF~&#!=mCv+tmi{F0u2dFp2f4-#7rT{ZFk=HsYkgaEd zNv;H%FVQ+aGr^4PsE@fVGrWIX^461`{Xm>!N>Pk?Z4IdCk9Zlpv1#{sfY=nROqYMK zz!9?aPnKz|x0Jo~hpBnL=&mTvDwl!^=gGL_&HCO_Bq{)KizopA$r;6~z&p(|Y_b9N)kP+O7h50h} z$l6s(W!jP}xI!RF^-k#AypS*NddHP;U!`PdV&pl|HS3W}v$o8Q%6ftXKI7fch6P^o zE-%B2*y^!E9;q3pF=Oax6I97XE+LiFE){T^UX_I%wP0uI_lvVqG-GRiz-7d{yAa}w z{I-Fbq7!26V?oY#=G&EYY>BG`=U)7rwb`z84hp3J-HZl|JtZ=Tce(ZFa~g>5$dl`t zij@mC%I?vs6`-FH9G5uT`7}P5JNMu5g{$lHlj8B-zF;6=%rN|ca7=6vY z^zfKyPR!I7I7m}<1LPe+FPM2xgcwVvtrXpeZ9^VED3MA~@)c%n1gASuINu=)u?EHB zaF+H0QnThVpUrbG_5rPfu>eM@p+Fb}6QB}3UQulkD0P*yO zX?;fZPM*!9G`sLLq!&Et(otscP}u0i1@z%`{O5=J```ZD0yWTyW$o+EW3Z{{sq-j$ z5v-L=O`fdo)I?7*5#(55c7V`h?~B##zSkI` z?@RbRk^cM7tr!(g2z#fgTjcywMn1JzyGq3G?|u|wKhSk6_XXC&FuBbT7hDvFjXfHb zPS%wi%q&1z?lVnx4CL^EQdW@D=6wF}@eZ* z>t`rR!L&Aw&(kD}Ki7Yxhgt?E9$_DY*4Wt+XoX7yVI|TVtzBe_&nsog=Tjlp_1h*A zncBwO3S1NLJ=F4N*gZXQZkXbF|AVj$Efd(#{Tlt`Ti~G|6)2VXw4}iVDrY*iT^Z-` zUQ`113z#+q>T|p=9Es+k14L3<0lO2ot(~{XKF;s@6T2$vFKeyyzvzNLVV}<+t^Wa7 ztir20K`3n%6lM906?umJ3*;SA?%EFFx0-rnE!TyXd*wS2eve*@@KtdDhaZgJc3e&(x0dxf4-HyR0I!z(M2w*3~JQo4ek zQ2jBEvMT5iyWpLFTV!=1j@@dvm)WeA#0EZCm7_R?LKd7lYTWKfQBqm|H+)#g_=kes z(gM3=&wl_Qo$O~w9Y`}*Uds#r=1-+LcPsGTi9Qc_R$ZzIV)I%KaxAdWNwdH^+0YG| znYN_<8O!_w(!uh0-+bhcCnT(-_W)Nww5QJDo%}itnwh~P|7<_{07RT<-Tm=$eg`8V z)Gv`A8~^jhv{A}g_qnmxSPW5k-mqm3T6q*UWiH3vC{hvC5Tqvn%bB;cq4SIYKK!=x z;|;eL96ndBz;$JDJKgCo;VMDpjThp>?kiiRx|Ze)Tca6fZAx5YY$rY2B5{!yJ3^6+ zn`q>rvrx3XY?A&IeGQ2HdO4l+eSLAPg;$lqBvE?%4apXJ`1WUGSW{gyvZQCl9z_lL z-kqA`5M4L-tQSpuflIT65O1KTZ+dtPw&`*^Rt5612>G<+?8)@;$V7HLfDO_KrKipF zeQUz5RU^0t4MbJGjhA>eGM^9bKiY%<0%<{8P4)4N41ebMKC&P@qV62`ZEe4rIe$OD z^p@fa&8fpGC3OCjl{0+0Agig+C*2OGO-HE=4f0SFNBqSun~!aa=1ZsG-bLlL4RsL4 zH1qZolRm(LbG>}i_ksvM<{Ntl%0n*gngqisY`bH{WVYD+KylO5LZ&;pHfZP-xV|q~ zrFvEC#`-n-K>A*P2vt2oX2%p)e<>#x7Ahfket`2ugL{Mh;~oS@Q|G<13(oNc$WAfe z4xD97vvr^Goo1>(BwbzH-LL%zpbHrJVOSWs-z}}!>w*g|t_A=p1NDR!5 z3K)FZPh%d&dn(S|u$WJzzr_6r`i@{IX?)QxjQuK9GQX6)%o9J&n861<@I|V+f!#dS zC>9F^AfNMbPco$hvKDdjaBtiyeG4kxqEqhNhEpT7$YPA)(VF2C1IXzcJoUwA0+YE) z+PvKR&usqR*^SM4mH?u+Cds|Bm_PI${VNJtmyu}MRWM&VCV{}V=E5p6IrWTk0*>0> zc#S)V#HvJGi@N0%HQSVz#uayHU5)9SSuSzQnKaRRe8giEdeqM7caaDNX2{DYa*mxE z>s)eAUN|e-aAa#0*5DflXgwtK4_bM`&hU~Gucv`5&1DASGB>rkNFIv8?gcJgX_E4p z95acvbxc&CPY403!W{?y8>Da&0cm?Y=Ig2%=3qZkRm#t6ehV0QBFi^fdt&bVYw!Od z?!EuneBbzQYJ}FTRuLkt)kWqU_3z?kZ zHp}@kw{UK&u-;T1vIkq!SPvVS@XXMxv_98U0q?J=@vdK6fBt^Y&E2EUCa#<^5&!t= zkSS+JGX=$Ez|u$N#)N-r9N&s7H7kY9=SKWv|3{HSCxE82-TWlW)k-}#!V~g)KzTUQ z_n5~U#(CV!lLRap#fF~U5Fh^&MxHwr0yxKEaO)p5{+K9W4&zt``i z=5@nrbgPkIJ)TdMeMP&w{{D~6y~Jr{z(=gpajOx`SM-A;9y3Z*#$ntT8#aCioK6H_ zaShh@g zm%gY{2`b)k$l9+R*`5d_MKZ4N8X5Z5f;Iw4q)0 zWl+i_mABpTTGY_jS#)0wEt}MzW||0D@O0i=kBk>y>(K?}54avBL=u7Bfh9e!V6L_< zo18cm)xRrYor7ttn=mCR_~ulUHTw))_jBM{ZcbZBqVMB?*VernF;JcU;F)mzLfhaT+HvL>#2Z4ztzs>N|vl6B%&*jX`#oT$->9G1ALX?BI z_%rDBR@XGiF#IaeKmdKtQsU+z-f3ViuO~*HasDk5nj7Het%(y~>?Pl0K4-`EvV^=J zA*zI$AQ}~TP|1)iU?dP!=t`&fW8+%kgF0oRcuBzzMRwUOhZZt7Ef-1dViAWTwZJ~^ zx-qL*;@#QmWajUIjmGrmzPZa2#?u>o zkV+RHe6a9Aks$JJ5Hz6(KvHhnM-^mPxxJfyC|+5uA?qlYXCJw88}y}Fcan)%2d@ar zbmg+FAfcQrqDD+d!;IaWCHFk_ZZ&yR-R{0}4VcM$1MYh4Usq#y{MQ6vftEe$M!?(wT0WB)9jC+h4z&qk>A| zup)iEI>M|456Ln**2e?r6cg*BJFIGhj;HCer;Xi71_%M#Tf`EqRYg1(NmiQ)+0g5= z_jI*!UP6aXV1%hF|3qWDoQ$%tM(j%7#E&yNO27ta&3o*K*R{IHdAac!ud=F{>3J(`>XY?Sm*N)EoVo>S&5 z8V%wMXHDFbqrSSBntyM5p_(c}w8w7?L0jdiDlhebLt)OkSX>3gPRi!K2E2-dR^Ei5 zY5eK<{omsbr#HW`Qa5fC8VDO`#98%f_k(r$qEXgn^va?`+0=6DmIeNpuhR^5j1Gvx zCSy~p!T?3!+IjqJ!LPx2*Mq1(D^#Nq|Ds_rVG-8YI#C@@1o{s*u z-+=pp$3_gF>pK_~;8T-E44*!A$SD zVW?*Wn$sV@L0Jm^`lSYzX`!oj9%89yY57FVNJ`99m}9m8P-d&bI~d;{L`Ua8QDa0{oXUT;lIbz# z_StLNec09A z#_B478qT@!KZ;M(?Uzib8y6Jy|D%A(tl^3xb5DDopMjNXzSJ|nTJ(XZBVeq#{+ZZI zG2kjg_?=ghj7Bus=4RHI{4{LDK@yYbFNjboot<0yne1h?)lDf1;X)vGZK{K~Q$-)d z@+u7XhBe62|F&1W2!^zR`hhB!4wrNI+s(!6isB^q^wxWwUFF5QNb5 zD!_*Pa~2VOJW$HH5YSBd$J#K|F(R@*vpe$G(p>MPZ4kS6@#ii~Lk0e;4e#xuvo$&- zxb>;;k6%J)LJ0IwNN3c@1bKf{v*-@SjpHlJcW=kMs5UXt>mZ0dYikN5A^iV-Qw6Gz zEWa4xu6H@DIUP!!f7|;AnECW*>NDXnt5HGpy776x^v$4!ZF?^P=qN2E!$?^`O<}t< z4x+^Q=PKwCRS(p{Q*I5JWVdgNuYyRMoE`sOWKpNUS2Er5M#0Z+*1o-TD)=7->8H=K z^ZnT7=vOg@q2u5weq@pisA@s30tAih#jX6;)9hhJl!9%-%L1sKuwI}qsLK?N`QluU zGzE>imd1Ei10!u+aMe<}#+1$CT6gU4zeO_NbTn!GQKas_><0%x2yeWJPdif8SO!1k zcVNIvLhk_R0VtU=>l6#2FrWmVz5n_*`PKbv1|<@DlG8WvLy!Z^ zwZ9?>Oe!2g6koKdh>?^hk`*JG0i-&iZ=0hXx)yA&{J?n*Lj-+$w*Tfelh)MgsbMO0>T*GH9u zSZdF~dFfrqD-^t}RUa0RHXj&dDZ~0d3i|1;_)p1_uX4S4Jq?}DooRP83(VGxS^`M0 zFUEEAS|L^A6?06oztS282xkn3(4=>CinSXs=p}3D5B;85+b=3^%*F}sZArU~lT7tO z3n7G_8E6coU@L-Lm*a(~NDcP^Zm=|sSRZ2}!<0=6~dqutb(;_vuQZK~OyO;#Fb`BE} zK8sW47?Wo+?GJj}oZQr}cHcgAfniw$@m%pt-v{eN^TqY_vg|mu99K=;aND8JMijF3 zn*<{qPxMzHFIKf^rpqBB`nrGY`O|(%s()|^6^Yi_ShxA1W1h6Z8_9nN5lLL}^HFAL z=b)hG6bGUwIX4pn{*lQ+!I!Eeu?FRUiT>6jPu$jtoR_x|((1%1Lys_1u09-jG8Chc zHLtXV1sa%VDsa|T;~ycm`NznobDO#4#c{LKgAR0mKJH~vJFoXyFYrJm)&BIH%yGQ> z40{GdPa4Csto4#2 zlq4Y?xFgMiKSSDCh6v_H*Ujplg;k{- zO-anKjd$c2CU(Az_T4|B=zZv9k)mt3%%GeTsMMC{+tV<{zv|kTCWcn>)?(HEz9i(U z+iDY`YGr(Dbc(%|3(xLeYYcu8a)FDS#IvHtp+P{s3Z_EsZ7bhYoY$e-7!H0-ba;aK zy#=}?nnKc`M;GH9g=w%la$$&|9FVCPBBrBtQ=5OeB}p5Whx-s-Yz}+p`tN@f%wNvyaHBj| z+F^Hg8n4_SIw?0NAzO2dw$Ocsq`&%Tdd>Cc!P}}Zf>o*wzur`RCROmB9ev=DZzvM+ziX#`A@H~t~mxWmilM3%;*A0*F@m;a!{29wV99o&7kMe^syIGOqzkBxarmK-s?c_i%P{mGTHrii zT-0@dkJWoVpeKlOj@m)_4U{;0<=f!>*}qpx&+!lpE^?Ny$$ayf(=DDyHK8AcNt<$d zK%yzj%M)fq*Lmx9ZP}oTEdMezc9F)J5Gpq>U1g7($h0EWlRs9lzF*$}8#-o?9F+fOu(Y7OcUSNQvy{9~GfdzFx*G$iR4?FAm|mfa3s+X_MBo<;`z4)#)s-vE zBInj71A0UmOM;j{Pi-}G?aL>A;V)P`!lN$0Q@i8Gv*)(@)1MlxAMm-}7`L?!{lvNC z=!sSMnHcjq5|RHPL!zpJfC zK~)P%wSLur$UG$l2w$if8StRp=C1E9$^2N*#m+$<*sZn>AeLhfSE!tiZ;}fu2XI-u zfyFb`Zuh`|DeVJ|%iY-(<}*-#LkKnGEnst?vWbwYJ!X3R%jnV}A=G;0(chV4m;GC> ztd7CjppQI{R?*=A=j`~R8C@dCGkP+BmTn$xxk{fnY@lblu^WFZb<^j>*UnwAkv5Uw z(@|CVMZtjyqDjqJsO{pp4YL07PfzwYIr7K3jHg-W@)V!JVC0k}mqEVWOzspTko7j9 zYhYU}g6c`*JbV!)xbOd!0v)_SyW+SOPtEG*9O(fQ3_v0)cD_E?c!;lh@5%K1Vd47< zez7>TIH{EY0?)?z2(?I?Pd79m zgZz$hAEp^xEb9iYcJ*#51S{W*1C{mOnJ-a~cZ*Y)|38OO*3s-+e+D+5)s_L&_fMew zb*M~4j%IZd}(N>r9FBtG^h=imj~4Z<;LaD{i_DPL4o(*chdUgtj4NVkKG-Z-K*V0 z=%E>?T6&4ctI&Jp1>z5y32^cG_s?ElCwBz_J->tB59R(0YY&-3pL}e4b#mj|=GeM~ zNape3m_K5yKzMmvDM^!(JYvG4%*{gGEycK1sVNSV@r z&QO&ulbgaO0{*wBX6G6C>lG?`LKbjQkYdyAz>1OM?1eV@tM9L&RQ%&8E;oKBczV8; zsP@Fv{hnM{rU^6kf*hY@PX7K3s0kNv`c~tOv#%LKzQ){t#=9rO1;6l96(@;`wn;wz}i825yQ-6MAA z32bQAy=?5v-9U$sveBj-%^JN~$LkqUmCfy&6pZswpND=bOzr%h_%qxwFt&xCM~=*t z)ypfS-pGAel>e!^XHOzS3+_OMjQE>J)N}1v7rE|~_c**An#*{`$LDFYr?N;!pB3y@ zKJ&k9JJV%U6SWxCG`SJLFq2q@QjPFKG12wH?IO^W=eedQ+tUKr67OYAVT`ni0*9xy zWb@7t0z4qpyNXNXVGGR9ePqo!N{W7l9FwtzvE40M-@MOxBcew}wcQ6i;HMI(83K9- z51q(#%-%0V=zSzG)sV~>?{J0QqfWuwW(7QH2cGVs#zF0NAWtaLmU~{(_O5?d#r3Lj zNNZyatnC+(XWwT<diw1Z-JmTs&?7*2>L-$ z9|AS)gW(GVif0rh<6d!|gqbegDooOyRqxwnGwmbER?WIcanBNEseU$K`IEro(=JnY zU4>lFtwBv|tbdE{Z%>;|Wi1t_qz!}>l(_NBIzDVvZ#$advP}l^|Dh4HN~h1Q9VQB0 z1J7-@r1pGL4eS?btgRzkXCS0#D)PdfpsJ(4>;`?|8d3W4%a(N>dvj_n8ar!Yyx;3) z@7l#-7c8{{xeKC*m~mWzrXI8=X-x5<>K?2Bc%Id%K&7(Rv!w}^gjxp z5=B$_cn99QG)NQrMeQSuUrMzCadF;%uadLElY{dHXoFJm3sl?7{(GGGxxk=_sBPu zVhflV06}F@XeO*~pm}X{!Se{QiEv8q9c(Ng>RE_XJI9j$N1?lsaj92Wdvh*nT&j0; zKvUSJ^KRb5Evio~+Z1~|c~^oD2>fjNnI?#)($D5iNH_x9=G-`9Ot1v!qpZZW?B$?L zE_5QjbbJOS4-B43ckd*dfaKGztvo7WF z>3w%~B!8;0w6s3MbBw*uVv7uA#~Lt*h)W{xd2lgnn@~z^UMnATXw*j3wwRflX$4Eg z#=ZHRO!ihRQvAK4ZChG_dfs3YP+JXf)Qi!aVEB#K|E|&7Z|3?%%S0_SoF(@sFzfpB z$EK@JIsvrzu)3@PK0HU}8xBpKEn$7!`cawin0H&qcd(lk0B)LnQuc8na6fh*PIu0+ z!_-$(UKtGNAp6!%gJ|8CsUU#_xuLjiRMkmiygzne8%u#Z7P0lq$*H@R*VNYj%10%_ry4{zQGkP^l`mM6%4b@ibc5cXb@h)kS}44vAm z)9v51bZN2P70LH@QpqoNED&N%;Azs|;H$(PndFNMJ~(|=OYRx1Js?*|$S)$YA}Py7 z`eGpjjpcahjUBjRll;!(saoMIBiroa*x8L7N14#)9m8X^2Z4Jnf!8uZ9HK>47?ZT9 z_!p>IWb$?b^yflVt^AcJ}qY%3psK?ns=OJ5-oiTI0P3&xIMuO|f^~z3tcja$=o}boyCUO!+nKqfNvh z0TJh-!_AOL8r8BUQ+?cLp8N8ix(QAXGoG5BmtQ0Ux+?(&=EXsfBuj?42+>%*R&QO$-U6Fjk& z{wrtAVQmL4abx2*QYGqyWW5^dG(fB^M54GR-{(K7q7%)|H6vpeT*C|>thVl_CF*+C z16woIg@9VQLRHU9ET96X`Cb8Se?K|!FR5($^H8MW;!#{}{D&ENKeOnxKiA%OG8-AH z51FFVa`aL*&Kssb-foThq50fj-1A(~1u5H}*(Ch;u5cY4&8V}eHWh<;<~Zu{iUM?9 zOsITOcY*;pCp9`bV-c-%C-TQm*?OyL)j(-KavqDdx>`W8dJrx5f_W~+9BawJ$pc`k zzu5BD?c_`6+ULC=Kd#$(LZUUB7EBP^OJI8RhHbeLs|fsnzZh$cBqjHiLf<pbaiIc>$hqJYc0+}(HD+5 ze*k7ux$&OCL@wz9&8Rxv6+P;+)(c#yE}Ge7m_;2x zPRl$#KdQ-KL~1jg*hYm{BfB?N#&W6$k8osP+%Z+p^a5`BqmD zn${fauM&_%z$~mbJ(KNZ))G!JP3uPr*P&@mh{m10(D#vy4qQ}LBP$dX{|DJjeRadH zuC#p5tu_-D;4#*8f8rSr?8p5(*21m`FB{12Fw=!5PYM#o1$IV53;Kgm zw01x4udn)Prbs5i?urC8BY9Q_tX&(_1am72lQME7`VLz2D&gWZjRT9AU^xnDVJ9=G{~)KSECA$`xFL|b80*TDhoyjaONxw1dNzy&=?W${W;T}_ zRh}!io}RGUAOlA5Rx2Ta!Z8J6du&qV0lR~Dtd?cm!mPfm zaL7>djU0PJ4SDK*EzT}^L&~q!?)l4c_Ewwojj86yyH3w6+aUzXL_k){3$)GO{&!%H zxlk=D^Q>=uy=wU&H{Lr)Q5M~)0PmpVo7d4RHg_*ib<=eoM6NF8uak$KN!=)aSP;nX z3@s3fjTaG~^X8x$q+?JW8%vBdbHDo`>Y@no85GPM{)+DRFfb?L<-ea_RJg$tl;ON2 zpCPYp58Gy`eRDa=4Wkp>?LE!TJ~4ldx49c2T%05wbK68u*qT#HqD#fkjtJ*~#sazh zy|-ybt*ty1Os2v%ziawsf32TI1*)~@;PO*|_SO8hyO7NZ$urh-yk z9@PBoR9Kn930vLrsImUlFuQvr?OaylIC<>nmkNOpfwviCH(=nXa00gdiJ?P#@lUX@r?E92D(8AJ_o^}-)FRJw7_Tj)Lj zec&EE$bWanvt$Em^(OE|Bwe!0t8NTD&qtnnnaviLXB5N;w(FUqr7db(xK3q1-vaO= zM?(AzzVz2^hG&;lTsa4Wp&gfX{`}4G?BT$zu^{UcYb?VJstTm61NR!IouawD49B1^ z&<*+l^vgeNrWt_!dt&n+UD1Bv=E%5nyUbo_FS-Z)XVd%1goo#aKDW$Nkz)u?$JjpQ z?|f=3d@V>n?$h`NW6@A4;)O`{rnar&L~YBRk{+kHISXFypgo1Tl;>!A?00!?}LD{U|+$_kfde`8(xazIB zgqLMeR+I38)UG>n9~XeR5idz9Os8SURORe5@5#EE;!>}aBVu(@i10+oi<#Cc+1*|- zvem*wgj^bMcEVcjn%??gCQO>JV02=%(aWG;3_Rj@h=PL}X_)Y1r+PdE?g8xC6)`dM znw&4=Q4u1t0EoH5XN5~Pxq}+A{=H_pU{ZS7o1DKJH%7YZ-jXikRWDpr>>s7^_~*Xx z^A4ZocFL2PD=%?d#X#6b2x2X+TJ^y-;1g6cH0YGxK+J5M+O{2#>C%>~qBdnx0amRc)b7%#n$=QNwGgc>ZV_Snwf9u4vyP$wM^ZEd6Aodt6(w2s8 ziVEfGwU&}n(~ohT5r+^Mg&xz<=Mtj`x;o|W|z1^e}X49HN@0E0V|)?y7m6Qhg) z*fo5ZNI2;iP{mvFDS%aU$Z-s50Gs+S`CFiliZLX zc-fBVrxO2-qJs|M5w0Ww1I8F}spup3HT&Sj})KEY~AWxezH>Hck5z zQE_^q8c>^2z35$nNy^AT=sDqJ9D#3nz!tsmHyRJJNhH15yh= zjy3)&^fgfGPd~C^9`s0~%eQ=#oP^$c!eCbSqj%GRi94}f3YMHTkC{jLN)^4UCyP1vB|khV$h)6a~vRh4R=Gl{r79e ztwYsq-B&SiMp9Z@0Vr+X+e7%x!s$Y{VUWMdbXL7%?U}n>US0{d&tI&cG%6{t6Y`O6 zaDy+T0u;|3Hxdzyn`^qrzbRdkd&*nou0D5A;)(0fQ%vcUHd)JT_vwQ={%V(M>4Vz8 zVJ>=md~zKQr95bmRckge zxZhihdpQI=-=rjipOJ(ckRpHk(y02})0i}RYd%Z2m|N_h7k`2=5O1r;*PcB=0GssJ zr@hM&_Go3@k{4dT;H&EVS$Z}Ss6MW}cfUYY$D>^)1~>H-wI?IiQ-R97m-DE7QGc3mWA}}Ds$V&FV4rMF6G>Rbx0Ud5Jj!SV@gKccPfB3p}~uN@Bw8RNVSnbW(&8 z`Wow~JYw2_k5hh_p8ET0&1c-m{FTxA*iTDVMvfH^L@tm`MU?tj)7DN8Y#Vp7F=2-xl#GA zt9vH!vQi6d(GPcJ2;(bzkz=kV zgf3xEZ=kSw?n4!i=%IjbJifv#cOEw0VMe@OAnWXiDX241g}T=?Y|8;iw8j6NzRD(# z>o|5ZR%bRi1hHKAK6dVL)JAzPfn0eU{MP6MOPFQPQKM#XqF|d<+-^m|ysm(fCW+RQ z`_;X#@R#c*bvqAgWW53z9r%y^Z_$4;q4DsRH}Bb>osinG7wG^uKp~on!_VX`kxP+? zP}*FBb$8*;k`6tS8|exIdJ4I5U*}+^9z1Ue@o|w6-f{_CK*FRdA{6fW$!1~Lvx<=9 zvwJxIBXS%tr202b4LA>-cKHXHd{Ey+h_G*1%}5073LN~o#;rvN1UfLN_4oB!rzRmK zHE!%fBI!+96F=5F{EAkoc-*Z|+G9bK1V#jB51qcX`9z(i9}XEHIDGug*a{Ll{n-eX zd-ensnYjvuR*ZmEN1Eo^)-?0>#?GS2KVMYn0L?tnZzz9yv4+393NuM)#n8OtRA#{1 z)mSEo1?MGd?XD?3tY39#<7f5Djrx{5g`E(#D*2@+rQRmkM`LoEqL(l6ZSw$igcd({ z;KCcWJvIO6DNp=3`=wN&msD!H{NdsayZWE)v!q)*YjQZsDC}Jkn2^Vb#m;MYF!F}4 zwjpxxQ*2zL-+7_5?XZG2Lk~-c19dfA(XaEckIx&$Er(`;!<8k2o`hwYAz~0GQZVv- zh@*-r;4C5a{GnKK@D6GeddJkk-IB*wsDsRLi!1%${5345U^EAZwNiNWhJsh|4b{Up z@%}H(BV%hD+WGgc^VrgES{e`y45aqlsfWjV#C?(%4q22OAxY!n+V}Du4Q3L5-o~62 za$jZUzQ2%>QQ_v6CYP+v_leJTpaMkAt3y9h#gsBFjrWM^a~;2FHg*doMQtilfB_=x zU$d!loyz3~eNgH3@nk}YYH2d1qEs4?4_t3pC822a(k3tb9BS(F^Q*^<-#c~>ZXaNu z^+z)}F7wOC6n`-!&D4(H_MS`P;-vEHj{4N09IhnEW(4{;D{(*5f@p2gONg#b8vUN& zOX(!3$G1#FjXsfba|lc(-FTsKk~lH?!x9UXm!Swh{;MU>1QeFSn{PZw%j#v>WV5!^ zBWn>+f`LzB+>nuBI|o6bvBKT~zW1Cb_jZ1$(vJRGwJnMrm-iNk5f$z5$+_+s^DZ6& zO7PRCQ}XFefxKRyO90;)JDqe}AdyNvk|aWoC$y)vA8OWC%tNm$`vQ9$4Iqm1R%Z$z z1)5_12JrM$IIA)WC!+HQ{XTOkzKrrytgo55$_OB{j=QEAyUaFeJuF-vh1t|fG3GZ8 zJlW28uic)HIKy4k%rAYW*p4C-FM06e^|?FF1NWPXAME`|(>gXzybfKoFU&zR-wiu`4dK zKt0j8J{>y{bw9ywiH93=JMVY9=V$IiAj1%UT3omD#g$Rc#J6;eee12egJ9aMrg5K3 z)@3B4P(WjkO)%wrAGPG9UH6IIOhCSV!#HD7wEp-+pQWw&YMOlQZiwG6ht&290q;vN$Mn(VQlqzYC+p*89s&KS;rgjQSTKonOORj`z8nkGU2z{eQFWdJr z)}HreWPb{zce=!(tbTO7^R$oq05JF$-tK5;(d=$_kdc9R^ye{p+JL;Nv6Qz?VTNQ_`TAzP ztW@Q*B1aJ+3feKzwN?0*FJ1O#GD&TKG9UR1I7n{s4|pNm??Ar*0CqT!JlL#DooJys zWW)y~fE0ZQAy9=J6RUEGHXy*}tEKqwL_^4<*}GP4^jshNy5f)x2LDS9Z3xY*^(Npi zH8uWNO}W(URlPX~-2OSJINi&?ryJu|(uT1bybs&0!h57navpF#fB-QD?g=5Og`U1s z0W?iVRA7GmO&`;$ij_67#dcmT_&WdPqd-H+6|=FZ1B-xEtZ;$65WV$nZVtQf!r1+O zn?0Eqbi%d$wX2u-=F2rhtAUaY%cmP9cRy%J?kav%ZCGKT!pd!PC+Po+NM-zzJHQWb z&p@S`I#TtfgB*SB*{>LlUed(7>e0kBjULuDn!HdJZJ<@=n~#|a&&y** zytJsOtXEX=XN~arHKWW5zf<=X0CHlYTM=#qPgVb%q>n8OANw;@?G(#pfs@OV%^l@H zVn*6G{dokhwh!)Om!keQA09$VL^I!^1Lo@a*5mQIfi06KSay=e#Q-)<9vmkZyv5}J zE=#}!qpX-hT!I5{@Ysq=<=1F$i(G0OnXxq3ZOnS*6p9@D+ETRS1}RFt?Z#TR@6bV= z+XIold3YKp%*!z@W5aOn%2j)fKSK`jjjlWVfsPR;=2(v61q|KO$)&jLSO-m7 zJOc#_9B7IbRNs@rCgR*X(!ei|d)*hg7W-D2U)YOi%IsF{fmZq$WxD8sPq5XX#xw#nlh2#%&4_!4I)dBcG z6%IWwr`+hDhc^C*qll7{ zv`(HIU!@Gi2HR1e^|uZ_CveTp-4zV||4EDge|;>2g zJE}XNzxX|&i(UM_P&AzS25Z?d5B|63Z?b@Q-q41|Kbjr6hMX< zk#R4;mX^NsDsD58D`;{NYd;7Si*;(oQBcZq@+Y*P$fz|7mNb6AmXMY3t>*8#U$}i* zLS?jTGlG8tf3Ogga+7SGD^tZK=Za4woy?}CS;|jz7#MNH4Yh;6XX9Kb82$k0BVhWO z!Mj=pMr6ldIr9qyiANgl9N7oLD(%YC6~3ST@{~RgQt91z+R4qmv!v~OoibsCgisGmsUEko(DO^2~*?Q!t+Mal~L*vfH@B3CWgfD{BzyAz-417E`nQBX{ zh}jChX;rb>)xzsLyGhl$|HfOn{}H^6Ol8G2OhHA#)Xi(i^4!{fDk_DH%|xb~8uu<< zi%qFDRQ7dqNkp$g_};A&>0~*%X|E`J9}XN8fgkQ%Z9Rrn){%Sq|E@jNoWmt$N=*Gr znIdI5#p_rt=M*kDr~Do@Ri5wt=cz2ZLcz`A+HlUbehP^6Kz+ty90tE>tC;jcs@U7{JlBw|teLJ^bWtj#BZ1+}EzYpz)SS|Hj56&6| zx9?Ij!Kq_gtc52sZPhDwR1IuZjk~yyPgtV~drAe_;GV6=%o3OwEd#l z^V+tOtypjt>P;;LE1Jujt3CK4K>{lW4EvbD-m#oK86{Pw&Bj52`>xE6`+GhNQ zbdgW({F>+yvUC!0nI7SbIgiYLe3Z^E+pTMU=^2-n`BoQrCk9UkD-|lrMrz7_f9Mn! zdIb4x>cPYM7}+i1lgcKpcl@00lZ$BO`JaC9n|rNv{wL}`w9Ckw%U-#DeMp!(l^b`* zY#Zd~`D4cV%DC6A1IhAM7a;DPA5&iaxJi+iX0$} zuIqZ4gK3(!WsS1W7IaE+IG$@Q>%rrA16@Zq>ZP;PK*F7h?~zVToy|Vwij#tdi;WT@nqs8 zv~92Gt7P&R;fC{7BNlg64lYp}V({`^ab%JQIxK5uF)7`(sp-HC{c*I*tU9T@2jhRI+IWJXR75&Smv=r0kh;lIAacmbefBvd0vH28Z2^Rca?NU??Vi^a zl~0FEImqk`m708x=i4hubNnlSkJv&LI0^&?kUnyx?I2&6PLuYvF7s#8x+*K z_I{^*MWUUWQ<#*Y)9+-hsR#kNlkb3fDi(-i?@~K4ZXO}b` z##--@Gpq6pLS8Oug6wvx31&Q%sqf;p+Fx1|~ z)w^jaJv9Trr}VdTL!znpKQkSon{|&}P6gBjn3BkIE!D(6A**$0ajeF(2$_0Sl|c&5 zL#7q*Kk2j{Qu-|x3jQM{Q?6_7wznkPMoy!BNfx%+A$iyqH69v?7c=%4L5=_J;3yX& zdavg4t+{JPvk4MxP8z~b7kI?g8W2lr@xDWV%`vA#T15=t- zO0BEQs-PG%?Ta=rUOXWx*Vj`;a4uY7eB`qplv{ejgFHn(D}G*DT$WVE<;Nyp-}vj_ zy&0j`ip-MWWT#NbV$R(ygnK|w?zmo&9}nA}6p!BmBQ?u}Uq|oICz|PJ8({WEVrr9% zu~AHEfP?pGWVBfOudmO~C#br4d(ooi{ya7EEp5rJX8S}h?-*-${se}@`RkG{Jk3Qi zSc3GUygJK5x1Dou{jE3;PbWQc*r@T}Ly8D0tI=*r@7}(?rAXTGFizUaf~a&0q>Ig5 z@xm)hZYj2&rxVNIj{H0q>e!t7I9JS9 zX)U6==LGq_W5C@yZdjJGkG5!(hYiVPo_!Mf43V+aZ^0MDpN1)st)CuZVsz~tdVW{B z4nJHU2QPd`%7EcEb-78aQZ*BXy`%vvRVu&RKuZNRsKclnuhl-5$83h^Fg>;$||%hh@TeY%O73uAyH{zZKT$Dn-Su_Z{>?23~Y#V1l2Bc8CZ|=2Ln%VM5yVERrZYSRWJcZ(C_Fz%^s_f{Rk`W=PA3n4O*mFO>S)>0$Wy4Bar z%kkCaRY~?m&u6fou_Q$wh*3AU4-K{Zw`1O1srXF&ovQ^IJlo%IA{%s0|ExGne`%x> zAu&anPmDdjbiwP6AJRpCFfgEtU=}=@7h)Erp$3qJ4|H91!5(D&eqHxmjz_FAk5Xsq zu}A5!Ig9It?ycF|^53jUw$^^+x*GJTZ|Y!J2{uqVD^>{hl-kED0oS>G$%M~J`ehJM zz18~Mvtd*roU0@x+hJL@2kuVEP0#)32KcM9mC{=7`h$C(R>X^vETg+9!KPlwZxxPN z1W$CvwSwl+;mrZg;L)2>;-jhoxoJt-ITVd?C|zyN#m_fb&k4iJI+mWIHai)67DhJr zX1~$sJ*-muJv&F|tl1M8xILsfgAZeLk|J0=tJN+_{fe>1zutR88AnP0Q4P>YlLF0h z>ayLO*h_2Q=SM3sTV88w`Y16J@cY+AavFApwex5gef#M~8CX373*9F0*y3T^5Fnz+ z_f-q`!k$O)ZM zNv1gj#lj&$>00W;@sw9+yY#u1AWR-)92Sf=&`I_Lsr5(S+U zDQ4X)UpVMvX@GP|`8VQs!T(XbCg|L=gl@afK-O62o2(*V?ohb|+FDeT2e7LDqqstL zyA#8Hl_O&=J2vqvWn9ntnd~uclSsW9N#w|8da=0Zq#yp*2(% z^ktz5R?f4qTmyiI=^0?5U2N}YP*x(B<~xEu`|>g*h3m)*#YjZi738Pw2&gyhXb^w6 zzrBkHel9nIG62=fLA{~LXmMXI-+my9ti#)}J}$(kB9Eyr3i~=`&wEJt@a!M;^?2=# zX_1uC<1|K?Cwd;4=e#1SCJG7>`ow?mUpaSIOt{h`=<$v|M)pL#wzHbGnWi(fQ~qPL zcOac#@J0F+1#h&XO%sc}{9Icf{?qMP<%dZ1ui~O%%}$)keRSeTvEgZb={ETRuW~P| z&xE+ikMp$8At&99dwe@KM6@OXso+2)J@se`9M^WQ@7RSF#!5Br2(=RMfL%6HANe&` zDT{25Pk*XlGFN^p#2T#qPFyQ<950n$-tK3>a8VJ~D>t$|;brcoRfJRs#Z+gAHBH#y zkBxOkFcXb~enTlKJU+)E#bakN))f<{(Lob}sU7>%-NHFJ?k!b4`Y)G*V2#`?UiZ0l ztgha@TZG6i$VW>P7(^?@5-S;KYjYzgyxZY3z;LeC&Q@+;L3at{c|bSrTs zpPEYLGH!ABq*F$4)5%hBFW8F;a}JkkPmAoEyXjdx3om%TxSAwyq|@hf@>O9E&_g;v zKO()hT2sw8uQr)a*1avp2b5&IP4St2_GBo7&T%OGe&~)wQENNvG)wBMoZi8lV0O~?)h8yb=}YJj~@R>&X?D5 zo;g1Ia~{Y0og_iShEIRqPTsy4ez5BZEFF0qbOGpzaxIa#o`+A5C!^e3fZa(){*Ei^g8EE%liyNS$gIC6?YQyQ3|Co=k=Zd* zEqu+j)KwtV$F8^uHo7#WN<-R_#)67}3>LRA+d4v4H<{=A=!Q*T8!B^80Ud)puTJAr zFAAjR1+L3%Rh=6&8Cei^(Xgb*YQ|O1Rd?!d7pZmlVg)A7LOY@deR%>$Cy^l!L`c%Vm$Ajq`Z6;ww8Fsz{F%ieM2n( zt_uI;?i*;5WkcchV+>f1(p8Z+K~{v+SUpgj6MRH(~hT+l%7TxQc*~p3jbslq=zSZUf%(ThJq1Ew0~~UtCIBM-Y<`Lhjj8 zobe@hBH-obpJaIrm4ZlVmUYwusJ&-)^MLCFrjuAq3f}HZA>u6{dN1zp@Z|Tt!QRh#ZDVxANL?I1mMTGIQ4^MkEbVTjy z4X7I`M;ASU586FJJ&9;PhI?f5B;ccG^KvrgQk7Mr1Z2@S(K2-&J4IVYY?Oj%>?`-r zjo~}hTApE@oPE+M`n7j5ZfKK|A7v0emg-F(B}amFfX=9N+;b}}eOJQmBJ3FOQrrQ- z4#F-jC_l{az?Vb^c=ULP&QKD?jao5LkYT@#1Dc1@T?J;wIRK~fFrdQgZ3j<8)u+cP&=SK=1e zg5OI3(#iA$gwh7+9x0FeyKZq#K7~@76I{hZ@kZmi*SSbQ7oyfOeD8sn6OSUuQQ?~t z46F>Z?Ub#zrD8XjeU%Rkjo_L*n| zt1dm*08E;*+1f~}MJ2vLOKTjZF!H(8ZYs7yDb0NJi-g_$Tf)CS%Y%99s&U-y)I!ix zS2(h`p0EY=IlU$eT~Z!}uEV8Gp+Xf|^{lLPnXf8+9qAujP)ny63`0K+yU&e1$>a+r z^fCPO19F}W)G3`R(( z;QH)gsHnO8z-qAzud{YeK+RfV#-Th#O&(PZCylq&JJ)OvyMx!S7qR<4M($-(ZBCi0 z%n8&%*0_o)(Z&l^M;Z4&ozRq$qP~--4XJUQBj&MBc7y#JRqTwLs^XRUnAl15tJ~x0 z(=hvTM68_9+&&_5@#ZTKNZ08OfUY?I;rP*-QBHS56;lK2C5EJoW63J_weFfE2KvF= zzWUe7^7@!FBFQbd<0Q~P{)F-BE&)ZX=7#JZbt8N6r%=5qC^LpGA3kQ6TiiIaW!`*I zQQ>*4^&#m^Lw;y86-7g3vXf$k8E=ELx`6Fb_i%n?vCl4U*qybs`rjLU4PVy7_Avhd2o5lT*d+VNqMYsGl0Z*VCseqVoCP@2d0(-Z}Z6o5C6T zi~Hh{>vOVmKAWr;sgxV$LiC_ohA~6E=2pb&uOdQ2Od^@MZ0t%4a4EU9ckn7?Y&2PU z1y+rF@}uGrJoHbpTsfg>$!BE^R#3TpgLv|a=u+Iwpo`}oiPdN+*OtTj+g0dXwWB5{ zV)y4#0TM7_BsqbM8i8j?ws^mk0(P{=+T~G2I6MYlV2#)w(gx4dk_Cc6bcxkN?<^X0 z1InrzoCk=*IsVGpcXqhu%M@CX3yzKy0o}b~*f87eAM*ASXlKmR?aQ}KW+3_EBUcV3 zWJ76|X?RH6Kb3A#8sQYFiFKB?X`NNujwQ3-YcFFQvv=Km&TZ{aXWz2N6r8jlA^S4) zEi@F;W7f2M`I~T0Sj>j;s$78ua7 z6vTSJY-uygkN88#QujKB)l*C6e9{%xlRGi82`sy4zXKS`8V~Ms;%7L|TG>xWqH9=pqh&rKk}@b}o9*KDEMxW{N1NMC`PAtLA< zW^j*>)VgA&txOe_6DcxrbeE}@-|VO;nmd-C#3z5?_7d2 z?QU-pbd3F5yPr+L`KtUx!^#&<$zBfsNydF2Xw^uU0Yr&DQnN3`nOg809dibJP+FvI z6LQ_D8}#@@CpP~U&7KASsNZz@hUQPQ=hS!5Ope>HG6Ayj%Ok#6AnSpDL@!Y& zXS4W7Ox70%a-dYS^ zqB@vr7~z{PO8KDMUE2fzu)pd{g<N)*< zd(*+V$L(w{T-bfLkH99aeoDXi3`BlN0=~bbQ}ZLkDJab;VoI{bnA51v`}jJpk6ZH4 zHGE$tgqr6*8JWjYS8mHrrO*pJ0aT~stjUbGfUr@<@`qySLF4yhVII%;aY%n3ha*;w(YIXPJ8th-u)fiw;V65;`J^9YWYGzgFD+cK|E!f`c zNl(=UVdTS)BWzk3j_|2%5??BigA)>ul}k5UZk826A|@4X%Jff%xXX9!(vseOb9k*! z90!TzqpkMRHVpOD9)I#zRcm7DZEcTR^f-I|HQ~8eHmz47<#PTs^4R#sqP52Ld`LuL zl*f&Z-zI2Q$_KEx+{x%VtJD0A<&X*&2=1H#nLi zlrAZLx49$RIr>q}KxfjzyR96N%(7s!Oy8SbLBsEwP#33I2$f>S>w-ja9tP1-!?u~_ z)~@Fty*!daH$y^`zPL2bLyb+!D>(r501r8##f&$k?H|^mmuWEdT<`o}YqZz%i%5i{i+4&RR(o}}D z*tpYhRHysK8>jh^T%L{w?y+)pmqwG1hU1pyRX3^HUyzPhv0RiorIyVrm}6YtsJ=cQ z=9h~N@ZMZPG*p%ek$S*A=rMQO3zs9tY9jtnI=wj4IY*wDGxlcc>T{E4;b{92@1kZs zNVXd7(IJ3%*99s_$ze<8?jEX_OF~-6CPIVw8rJk)V`VAhr>mZzgMw;_kIIQ>cnhe` zr}qN@g`*4h)NajfB4Gs5dFRV?$#oCILC?Bhg>O^Wo42R;))iB>v-f^{760t*_y7#^@~+<Q;esgS2_=&fR;}1m{69 zxU+qP4qriHl3VNWsjEQ9wE$Ubva8PeqzFy*v;3IrH27BUGS5t=!1N7yMeHQz;=_tI z@C&rGcP(E1%2wdxh0>LDg>UV^G6)HQIrHtD_kh)QbbrwI9%=a%_d9Z&qsdQ#?5lA~ z-z+ZuI`F;t9VSyzw!Db&&puv14zzWJbb5X0co11PD5Z3u z&KVLK&=0JYA|I>MaB1`Kt9@PrX|10;@KZnys-f7bVIy>464&&D*6tP3vLMkc`zsU;3%{y81=dkklkje0z z*ZhnG*{C^dLVgyueKZ_V->c0@#l2wjX?f{Muw4Gm#bZnRLbgC{T9C1S zjq>9ytxUHBNh7ztfa+H(z7aDw*j^u9+YHqRuEDu_EI-|S1P@DpVN(j&z6m@)jQD~)`{eSh5ep>g zeH(K98>LDw7NqCl_Be=@BQA-~p=2fCDQIzuw8i*V9@Xj8&v&lFM}Fh6ZL?KSsPZ}! zV1GWr&8GVctvjhSmRH-%L!gFRG0rn-#ckswp6_+|@6$Az`6{&wAXY-Jh(1#0yrrxs z4E0|z9(%gr$?p~^;}06u)3_X_CuaHyhFPJ}=6 zP?a@~p>x+dlLEpRe=}ZZ_OROS!d3 zrZvj+@6sr&Y(n(zDGEbQoLrMGmUV0$<7K6*R44_#%;1U;};y9uQFqTG7V z>-{0^Np3O;CG)>MB;B-wo*P4^zq4J}O_nOc8#YXv9k~G~27Jk(XP_RNuHB z6PLqoEB!MDuuKj-IV;-AfqJJ?Gh(|}2)ij8L8-<+)+;zKJO7sL0d6!r!qal3h0a}4 zyMt@}UO5++Cy8-S8$o%sYC@=a)CgQ}9L+f`=B{F_&u7s+2vcS^dz7-da7rSNGc9OH zEE}C+9+$Ikev?{{3)d`Ss7NzKo7R5=zH-YWmGS?$5!Oq3|MI~QEa)aAa@+5yC4~#_ zrS&J7v?A$5&H}!b3j5Dkz5m%cfmhJLqX0Y_;#frp@3VpD!ap(uF$t02tr1z6S3Od% zKdEY*QV2$|hyvkTT!xi)42(+;RHC(`jDIiGcQk44jARB9HbyjI^Ro`5m|MvKD zwt+2nKGDf@1_cBfO&EEb3aK!mcOHKc;FE4N!-qG=Q+r8^%Ce5o3s5a?4&|P_DLaX{ zO=v*(XFQvtW!4mqJZpSB=^#O>NLNWnPE=uC>9W1m2`P7e`IfuzFIof?5{7ny%(^Cp zu91g>u@sqv$wq~&NwTFia>_g7XBIB4EC3=HKWSYu0eXgTH9|*K1sXG6(6T%j1=Gfj zNYJplUu@5v!@H(qZkNAlYraCvFZXim&{uk@;Wb5ZjRI9j^z`Y?OQcrj?F;Zm9i(*MZCh zGKd-#OocM^pQCm_V9D;u4`u7B8n89fjhmN!$Bk5jo8z6R2i;$t@Py6d&!271)RzLD z#-fb2E9HJ{t{&LSJw<0_?dh^pec_m=RJbsz>KO_O^D>jO+HEV#kylK3@?*!xp6K$PCTG2(-wQebD%Z5W zd4`xACNxYT?>_@**LojVOh2mHN2iEgjW? zhwrAr_Qjzf=AoTr+VDGTo;h=W;2WvQD}B*iJ2jNdK7aW13wa@@iAU)iSskIenRoc5 z`n-QGG`NOvTW=u98J9jlwUmbuvfI-C2k<1{f!=fL*kaD1Mm z%Sl(!R|%^PwNbcKzzf4b)_Y$HHg(t)YlPZp)4z=!-H!YJIy1EU99WQ87+>GFo@3od z^ZinRtFoh4yESNy;`F~W??3N}f6x3sqZz-~`CqRyw0&p$`u+FQv$hoE=frsmjEoMu z=ReOXyNDNJTNDV-p3Og%ppDOvgbw@<`-R`q|JTz0y&At)<9|Lj|7)#VCg$ol4|!JJ z^KfHM=IQ(5uEYNFpXPr4^^O0r>BjGwe;d;OSws4*&%bT(w+;Tb!T+;m_ir2gZG*pU z@c)SoLd}6yqSsp_@@2O)&Nif9eU#=VmBT59BXruL@Ej8@_HfX;JWmO->wj~vvduWM zrGen3qDBVHhN@cjp1NBwBG>aTWkVJILv~Gb^C~wk4mx!rJUT75jBlQ7UP)7MCMX4F z_8#&=Pp2;So)GUX1kt#hkbC^VXq_%RW>*ZceC>+;aXK14Vttc)rv78l(XG1Q|M+`( zek;XqQ~2#Ee*4GYQQ>#c{GBTNPLO`5g}<}r-?hT;3h8$N`MYfX-7NS|TO^<=5Qqqg z8rQgf`(4|%`cvh=mG>&%TLH($N%e{_&#j!`N@hRCdHLwKl^=B!j3qzg9xr}fb@a59 z2kJMz`1=O%%bY-?ZFT`WLz#y%mKG;dOJDLp_TkybsiOw0R5A9opX`%8rRR9i&FJwD*t-ZkRBMouQ)>dmQ8srilFx^6kNQt) zLCT+`Lj_+IqYcy^(ZKspGRH?O z{8~#D_37Jb3+Lx18Ls?xL9j_>-u)$)X0^6$)E-)mk8S(=I- zm3Ga5qldi8>*r3O${JQ0B6&HiBDRo%fTuKkzO6b{T93vs&$cKkc8wVBQIITG^5YQ?yft7P>Fj=IkpQjSZQrl4rO_j$m}Ah2;C~ zS{|OL>^ta(E|c23ul2WoNZXedV8-4T*?gBWXYnnzu}W+03P_h<*Dr-won>hc2xoCyT5u47{aYlfO*1>lPP}kC3H3&U*op8-njY%fIuDXWXBxVNvwQQMT3m_0-G7^&j=LZ%aC4e)Sd|pN72eQZ&YI5T66=ymxEx-~i?>Rqz+7mhsfLdh#!iJbmQZPsrq!h!S&nJzxp_#SIn^au z_eIdvI-O6Ezf7{h`BUZ)7re>XX~xS`zFtoj=auw{*B0v|*>vEjxOwYj)@KfDs$w|) z3&PD`mF@7vKv#2WJ7;;;&9BFtjb@&MaKl-{;$Cie8II5ibe3-`X)~SM{_#q@Rz~`TyZ)5I}4i#XKkK`$nsd^P+vL#gM$^Hi6Is_~Y@@FHh{v zM#!kS6viBuBeiEvrU0(kyFM`ug*nqtce)j>>s!1R$~^M~tv3&S?pvo3yQOmqG1OI= zuqJsBVBAj7s{$__!MEG38m{&Ajjt+lp5qmQm&MaD-*|ExT#}vTESx2M<>u~ePYXdO zcuD99z==y7AdV~KvONrr)P2!IW28XDoNZH5DW|113lKO&7+O>wWE8#Hc+;Qj)09Of zuR%^}JQb95jOBJtCc1&US3;EcMXRpEFdF1GjfXZBy}Cmxn{lHYZgz^y*lGzs3`^`0Cn z-Y6^y`m6SBuGz#`&e!z>11a5oZp;|69EH%5JxKje4bKLniD%BH$lLQrpW@*nfxtam z<$H<4?huwyKf7U1H7*Xn17Pt91=eQ-#py^CG%i}NF&$!G&3ni!%qn9o=BY931Zf2N z^3pgh%h-#;)dlqaRP? z5SbjOe-hl}oI7Z%33+x3DT7ImPbD8R%Xa#GeklGjwb_>|Zufciv)+26;8WdEhUo0* z>H)_8GBsd(?E;T?^TFWi&jF(*^4*m+fT4==ayK(@JPXZWO%8RsLjFki4X;LZXyuMh z`Ifw0r{Tls@Um|zwDl=h8>nQF*>Rp46oH}izw`*@0r%%9r}cI6?-|dPR2(sVb~di! z7Ard#X?G|)Od>^Oplu#@T#j6gbwVd41_cUUK+_4aw}D zG>q5HmpmbUFxD9Rq>DyZo#vW|&Pz5;bQkLaY*1VuDLdjWJ#^vGgYKnF0=aMRJ>>qpi74LMPR(%=S=Zd64-~WRnzA0Tp#>El|U&rwvJQNs(~S(A;V3SNU8w$(Q`e8$3x+!?6t)lep?FI3|^;4FV3L ztc-4m)}YKbcNc&`+S!L>e63}jmiiLyGXYosB2J*LR}xah&ZyxltG-#^vu(d;Kk)rL zPIFF*Az8G!kuxqc(i%`YC%c~0g8Dsp18!I-xBT5;xvv>$gX(A2QWl^$hHSCGK(p=W zDuD_$dCKW#UIC!9o5l_0U2Op4dl_Gq%+J~=K|Ik9NQcBfISDcS%|?LnBv2LO8Lw31 zXVEp|&-UZ)-Z=7Ry1=Y(lWf^ior66&Hg<_pW(GEQrsgEvS8)cLaT*&pd14pV{sQJJ zr;wojDoKw%uy>Gj?*v6!H{Vv3>Q5qVxoG^H$Of|PUP*ZdR^iPpGTR(7n~+r|t+nP~ zw*I$qbpd)(zM-a5HBK~q@&~xEs_xj=0s_V`fL?B>s^KI2Mr_(p9i8bHoPBpw&-e^M z09Z<+GlWU0q;dAvwXQw<33HQ=EP^?43aDzDLP^OIJ_YzuVDC@gX!7g@+|ODRChX_& zQ2{9fAy=Sw60E-9cL+rK%Xz`-iLO6Pi;JqYUZ6WE%AUvn@$QLd50;{uh)-B*k+F&F zA9)dDpE+T4RgH*&dYa&@oKGM%5befR!yD$!rjOY+iMd&>Yx9EUy_qoffvDjvhh;oF zZ5V?2!xmG~=1Hn)IURD@`R!0C(p!gpz{$>2)oeo*%fY6!=qEJiS`WWm%YzHhBtcEp zZNvK{eFjNsa3{N&)Ak217^_v9SzXR0XRKA3nb8sA08j%tryay?jFijWK=aL7<32-#<#dH#zNHlbqBVrMY_ z5wvJ6&?j`!7dqO-hP)GexE#nLsgecFgmFcu8lIkY6wPDgin|P&>1M>n)Xw}_Km$uwsZoO zVhV3$Sa(0sL^TZ69=#uv^09RDm)G5bcxx}iFPDHhEzbU!l%YMYV(ql_tERsU;I9bF zHEG1NtrvqW0Y3Rvn11#WO5S{{(#{Vw^Rw2S=2_D6xegS~v_(mYCQtsNwl~t7A&YgU zy3PnYyFjnQhiTdSv@Y22q@J7HFRxTTm`-72fMOiB?&U-EC#@vo!Zb&Xbrz3~^;otS z@XYDtIj9vGCj~R=i)=|I`lI(i&O|q^hNkTypp|b%vVOxon)JIdyf2773``kI*`p8M z%)Wzb9Gk0EwjAZx?G9LG^Jx?nx8V%|u&USZqJ4mEqwA>0JJ!JlMo zm&!{+18|)^*(i|G)#gDDp1<2OaqDm{pWGxG3oh z6)%vSPpLDC9e=ocD)(Z(mm_;wKHh|UT_VE4_}uWQaV*8Ywoz*fY^ue*h0J|-s0BOd zQH*~W&Mm>2UKx6nQx6q18rwYkA?{vpRrVw^+oB7%+S98z?J?&mBY7aIIQ@8tpY4}A zhrLrqxLlKCrtV|YVtXnLlcCLxlD8xLNv2WBPGV!($@4nNM6p_2ab8K2>qYGi?+azm z4c3uV%Eya|K-Dmb9yc}KCTdvuY&$NBcZ-}pk8R%TcY$`Y`T3AlNWis>{zH-iM4pTU z5W4f(7;As9LvRL~(+WbzsMts))xCALE!Ng7OyW|!@ZHC)l}BMSAFGVd>`%R2-^Jfrrx$5?AAGNKEM(s_ zPIk;L+~kDFmmW2gqvnL!=2j>TU+B&M=zTtQxWt%7nwDp~qO`aG0k1_mE*6JMYuv4s z0aVziYDFo8kY(jY+(@21GbYxW6(%_cWo$*g%~lu4xuJ2Za1L|miXpNl++Rs&J9vMT za&+XCfHhF&xN#s}(|rR<2Voie3zi7W9}+}Tzyxy1y>RJS@bg_QGy?~eDJ{k<FEXO9?WbV#u~ma!SedsDWZbgh5)>^u@;>sLs%Rsxp$ zn?HD6fUM&_y8R*A*c(EZ`S>* zzYL;Mh3a^(G@MuLsn|qv$U{O&R^WC(EBzx$S_>Pmq%$9J^ZUaViRTE%MIl`~93Yy$vlP!Kh#w)*mw% zcZ6kIRBbt5h^Lk%Ii+$*GH1PpmR2M0 zOcFgvDhd7dur%e{iH|2;cC?KcS0whYwG()9Y5XkGsYYox@Og zD?KI4_!kz!za7-+l1D=^g$iCSED%6bECUbnj~wEkWLN$oM(1bA7SBJ}5S-_{ipT%> zEbvF((eAy{?Sgk5n05@E0EyXLd;oqoQw<|kx24rcd(P%KE+tz_XQ!YFBa`pin@{aM ztqtr@Au@)UW5J?l=zVDGL>qEL%|aAlxtEG%<&Rr~$qz64)qfTSTz`#Qek*NjdKQli z`my_{zxeH+Wc3ve_kndcCfOa6X`sBFN=0`iEf5-|pUS_Yq{ zGp&>C0r3}ZIO{a3si0>Hd#ynRZO88AO_Ml74Sp2B0Igv= zh-KcFoff2PUzxg4Y9Y$F@km$I^(dn1;n{*_@E7hx&3U1X+O$0vj7Hu3v}5lXm2juP zzm$ak;RA53=+hSaO^qOc`iKX8WwGNIiPDdcbM|sZ3?@8nFj`~y?AN5?RP_`eE%Np` zGEj{nZpht}3+rcxgy?c{-1p{MZaiw`7_$yByd zS_CrhB*GV|NnwR)>#gJSaDdtZd_V;LQV{S?1}e3o?CEB1}q)Q@kvRdUSkl@@Y|p6yu% zlsZ~`zVtICCh56w-`}#^P$vIEcT{6GqaJnanSamqRY)G+=jhZ5i{xC4w7>M!NLy+7 zqpkTzyrqGS(Z6ztzmBl$GgKsCQs$w3kY<%f5jrbU!2O4?{nxRNql*vbCFJ#{=pBSQO)?qF*WpBGT8{pL0~AK?pBX$lKjUy}_|F?RZF*?U!)z)!-d(W}RvV z!`k>i$;MR9zQ`<;BR{H7-}b%PhgW7~A6^f1X!*RaxGna~!0A_l%w=>GRSe5?B`n{` zM2`oS1uGyEn!c}=f(0Xr{V&jL)!+V56qT3Q?NVd|k|&GGy=XaEPjdFU2w$~w)hV$X zH{S%pd;JO`I^vX_x;_uke|Cptw9NA~Px1Wl=p$Jh_yIV|g)mZEd5J!)UKgOZldW%T ze208|aFOD}n~nlHM~Z4m4?%wHT%8y2?|zsnXUn4=^K(GTMki?8eXI>#yTM5oq-{rx zloNXPjE!cXt%z(`jY~x(*@Yq3wFb{NFY5Mc0v+16f2#!H!u#rB@uj&GOu2QZ8NEdU z3DAtxU-150G4Pj)fRe4T5J6Y6xm8i{`qqV8EL_jT?ggv4R`<=S`) zzfFuC!L`{3S%|BfDi;RzOja9Q4%clO#W%Of`*Nbm6gt{vhCP|V(ho-@v&)qo%bz9J zUb=V@&4qlxS9_YIm37M4Ddw5A5<;a*D;z`Ol>c{wLF(*f`;@35IhxnX!EXTs+X$CzRr@#>uF#PpS9^r1dYZs85 z^69bCNuFZ#L3&S%namnK@=jN(+Ulx%@eP zYs>N}v70w-qTs4wnD60xb>H|;%F>ASe`)J*bKsi`k>o>sl#K0fxq>X$J``AK$qE!P z*yofasK0O%oGDhYfQ_@i>3tRHTe9%}=o%{@oLT4k48NPBC&zfgqF*S(%L>`QhttUb z<3GuSvB3wgS@OF(|KBF#5@K}Mwkcc`db;2&p^_qK+UtZDC6G(P0 z@wLuoYvC67%1hfSB<|jv3yD&!kltriW$|<8LR#$0jyq@n*=In!`MoQeWfCKE=Qi+E+aHfhDKLo)9c z-He;YEs`d=F-BYd?BAtkvTNmfZc3%CQ5)*B(2IVaPL5sSi|1vevnlgBfz=EI;7tEd?I!fo&T7$Vib8z#D zrGawNJho<9e296wb%t9GeG<}H{QLonTvMl+YplvvswdMYO<43<*FDhF&$=%W!#k%E zlU=(G-n%lMx(RPpNSL_+bx!A=NYfqE#j+>_V1g-?HvGQst(Ik~z(~N;+AZmtIce?F zI>Rdy%0WW_^J*!|7NKK`$Zhhqky&X0!FZ{ND|7{m{EuMf7n5kNl8ohjT zuY;Jvs4ZLQH@k8CipR&fO;IBqcc+rd5?k?oF6CEUv^Nx2YuNX2nD6UsOxe(hEYj&Dv2MVpwy;shEwuFu&0?C;DLKbTJU@)X_W^8hC0>%% zpKmY@qlUpEe|FB4m<3B$|1?&d`Czw&uAmWb&4siI!bH?=-cfV=S-}& z8+mB0=LlKQX6Jlx5nS%zUsOAt14yNV%G2z-N_QM3#1zS+o+X_t5~Mm&#-UWRE~jv~ zYC}$1El0x({^z%8C9%7$zxRV3Vu8=U=`G?h@=4&YuZP61>i%z zv#p#CsYG^fyZ&tQFZf#cVG^L;ES)on)^|B~IPI@sRIw-#OWE+rOA*L6Vj$WeJWiGC zB{^Qo@Lfiv)o_ZA>pn3xt{B4eFt7 z-sl_Eq#*`wRpoDOb8>!AUl3zNP3;IK$+<7(SYP<^d1bVSuvJlK_d`U=tzxg5Ao9*N zvnu;M;cM`|K3_bKfK&S;7dBasFF{mq>&9bc*c**xA@dEEoj z<;FC)02AbJPgtsQ5bvsESyopzzUAZ)S_T(}n-}CGF z1Z~mr<2iLpiOde_*ss&(W_=%cI0isZ!J8MU;FGOlKIYa@V^fGK+_6mvl>ash@CPo5 zyz>*jS!KeNE}-&g{v9@H8?5hcckw!#G;oE#ijP-HnuJ*yk&;EGSpsAFA?-CTa>Y?n zl;98DyQX8#q09Hti<`yX?39-t_e_*a{%p7tcS9LK>Xnr#EM-N8Sef|E@Am!b0 z;Yqe$ZO0gqeYUb=4d((^C9mPnh=<2|rQ!@COiIOMGF>K%Oq`%$93C8IMig;n<9jk^Zhg&Un^Qxik*{|8`2oCg_oX{E z-NVPeHC-2Cil~FPt|MI}Vd!U48wY|JKSY0H?o z2uZb3nfncsl4|0dh3^HbC{6`=Ja}%|X9}-asJZ6B+m=i(a`MyOgTGp3>}6MzmhBDU zGKie;uS10QO72R?>DcIaX0)wevEek>$XQ&E8;NTth35di8LAHi`jI`tQvDaRT|A*V zH%apw8;z|;&AOUv65IXnHiGGrcgGE^&YU*=<;P2*a`s=ma%~25?9Xp4aD9vQz4ma% z>)VCw^dbb)3JL#`DLVQ~$$rB*C%{D~iQ7`x{7QCOglmXy>>^Dct8rT4B>1k6PH~O4i%D3DFIW&v8}N8)zIfa#slVw{PLt+jP^l-&B!@@)OSUs<*CEtN3PB*` z*-8wOFXd)1Ad^MmM>h-ON8dIU5n_bD*l)n}4G@JqFEn5C0s#WBccJ1kI z(pMC19W|%7cQ-cDB|Xc{JF!fskq?KAw}(y~#RU zA*m~>_Q*&qyte$gB)MV*eJ^Mvu&S{?O#DN|j zKhaRTFsT4QQC5rZIw?qp@6d1zKb5@^t}pqk*oJKry$dAY*Z@>Z>!w!&? zUaErr@XeB->En!)JZatXsNEsEKLxfb6OpAF>w58)YlS}~XvZ?9EWsxIF0c5U74qm= zLV(Q#TiJ+X>h2CJ9oT{|k=V~Z^jv>8!3&S=MTy-h;1D%-7G@HU9=PUBl_|-+k59yXBPf&$7fvq zEUL=zB~qk#T!Be|5KD;3N-k@=g}9rr+KteLN z7D$`yGJvFpXPb|`JB~;l2!Ub8sHFnVRR&=;@QEol-5yRrjGE&53(J4jq^s2=^qh>*-K;0zWp?DSI~6S96}x!zpiv!9x~ zQGE*$f@Onul<(?UNlxJ58?GN_btq~jWb4C7BnOo|jI)uL++Ngr0~XCZxYJPHiUn<{ z`pQlE9VQ-ESP$d`#!=?NPTMlsBy#e`rjOzd+oUj@wuik>Ipo_fZmjg?>7d5Vg9rSL zT^2xd)^+&kA!+yQrG%L9UrEsID3JT5AER#8lu4v4D2SIvq4)0G7R+XkK)?T!rx+7F z@|20x_;<#^T{}wo5HWh@o34ptxXW)wp_cmP#F)9Z@9+AW3KR;AdXxkzyK{_%~CpZnU6cx$p+5M`uX^Ui)cizu_^ z4obgUkx4T3+K+NJ%V6uU;kFnfl>Fl@eYe&*5B?l>{eZGZ-&OY&n@ISSo{E=sMd!!1 zE>wu3ll9E%C+cTWbn6R_`3tl=JI<_Eu0--n-n@EAMnU!fSc0n3geExkaW6JD@Bc5- zzJjgE_758c0i{F*Y0;rbDjfq9kuGW2z#_*OAtNVBC?POvz_%Mlxr=-;*cDabzczVKoOk%a=ptlrM&HU|dFV zfjrdCN7lRcc6RNvjq@}jkBZ+N!98J`8v_EVSN-vuq3Uby>&?LXD9!(=~Kk7`)o%uFnmyN zWBzr&X=dk#WZH)uic|?E9cF}`@hz$a^PSXps0f#P2xvTzuS1*ydm*?JL#*L#%(;0A z(UdZ+%c}AK>2&OK-5GTV{0^5M?}?*Rc|^^Yg#=Mi*QjVhzDd?J@tz#kAi4s;&CIIg zMXetX$dz5kQ=DsqRBxt3$}1+YuRW3BmwVf(bC!Ed0Ju52be88|8pxTM`p+*x7Nt-Y zJ~=6=U#4|z*?x^V$6oaS|CoIhnsptg?Qm;Jw(L&hprgFA?^GrUYudNCEXCp|itYCVPS%$DCeB!9&+PzRvY=FHieohg3jI z*%E@+%S5-<<|plO`ra+JKX;NJuauXRWz{?%%w%rtyp;G+utRjNl0$*;_q{$ZrcvagJ%DhQ=#1?<-t@e17cQngMXXZDl9?XW}oL$_D@EJuE;n=tlhmipg>B5ft> z?afFXQF`Ao+_+rgluE9InQ3j~$M`!eZ0&eAgv?CZ=4*3vkcjf$MWC$?EgF`TPF*+HFzTNl|tGbt%U#Hx^M_? zMT=+pkH3!j@bmJ5sAL*;qkv^acj`GgXWQ9~(y!z&=V<)$KD6n*>Cc(}hx3+$Ct>-x z*f+-;x@7x`kRo4~-Z>NlVwTGvbLuPb;~79iecH;zSl95rh3&ps`%V2-lvQ|5EMK2+ zuz)!azy@A4>f4lgGV}=60u?Q0h`V1(v+0Sz|9JO)2O5!b+rZlxJ~U=F2i7csw;Xip z*E__!Psjt#a}-|1$><(DY>~T#i}J&53M8b8P3D$heK#+jJt#`Apdx(%9p81vrTLrW zpzMOuw%}kLnncgbZ1Q;bxr)@6@wb)BEPf=mvg;f3t`?@(%Bq%kWS|nIr8<2@z&$@8 zE-b~{xal1DF&>r+(aF!pjz2w7-l6f{1<00#=FlzBlUjd)X23_z&ZA2OUO6Mp>sR{EO|C zXO?}?d^AiS9!08cclS0h5g7er9Q_sG7pcO^?trb5Xi>oYlk%os;tIU5Xny6sD%@Lz z^#Dogb|Z%Z$~B{V>_MWZ37KwJ0Z-6QTaT>T-mN# zip+yA5LM4&=-aqWnB=}q;xZ#c6j|-LoV^#h(sD}^4^1Jqq82o1{R&G;(rYxihNU+Y zgXwkFBPW%==i_>0S8ph8Htdd5_c6p}AC0f;{+%CrLnW!SeC&x=`;3(M73JtC^D1l?&FEeI5zg~I z!xvahI7uI4)>bi?SQB@my{x!uVi}U;Qs*iKcYzG&$0ThWm7hB zXBRgI5i^uSiUxjVNU!xVjoR?Cul5JBLfTh4|2t#`ZZ{!d*_v%DZQ|DPNosys5$36I zC^%m{QH1G|w=H2i^r~QJnKH~yr1WU2ydb;GU;#EADVS7>0x6Nitp9O_qcWZ8Zat@` zoQ*208z6SzJ^RTO%jrjfWxc%PJP(qBuUdpB zH5`!$HB-CbBg6H=3$g7l%aq zua=AYuaN!>iYvjT|Ix^ z(KpKdvZH3TJEb`Gk{!zgyq)!C)=8Z(En-u>LM7lfo$M^>4v90Im?ac9e*5;9ULJnc z){;a8~`asFi_xZa_+)So9Z2E z@9%Av_=?r5Dqx|gZ(n*mDsyvcHE$(aOmoVVvu!EvhWb5aPfA1tFyD1T|4Z}osC!gi z40Ez|C3mHGkX78r+}KTa4=}H|HY{K_%I5SedfbXX^$0V&Ue(m$++=1+LH9?5YuvX- zpZO^s(5vqnA#7<5N>SGHprRKx@Rrchi;oTM9ymhX2gtfF55sHzd}^0qqAtxnfKv{o zEVl%j#gd`-veHv-W^3)gwblI8?;h&JriF*Tb+gZZ8BBzA;artOD{j|slzyvnp?}Yu zU9oe&QgM56mm!?qLSJ@HCzQnt8;kwPkM1Xm?ey!FVS>4K;OxhfMkC_&f(oh`oz8U+ z@vpJKAR=u^)+_g)`xU}D3}GAI-;(RUm$EB<)us;4@Skd^bCp)RD@CRzwnr)Me`1F# zUEZ_!df_+fqm2W+pYj*5n13oli$(&nuiA)9%c?1HEv`3G-9Orw8F!w0tLyqVlFCnJ zE3I75T(3RkZIRP7s6fiI9>@@vxc0YsN5G3t6JJ;id$5aW%r6V0H}eMEVB|v;fm~ z`z4ckvRAF*luXZ7ds?S z8(IwhF#Hn6FR;C^coV!yuG_BDo0u@2KOV~FDRssxQI<2RPzsnu>|l%%wZ!hamI=I5 z-kYGWy~E%tOB6N$OD0LXI3-PA3&%bDTS(sHNS7208QlGPkEf=|ggtulW-~Z%_CBsx z(tN04C?MQ}b_+a(=j?j?Xl~d~BijF<@0w-JL6kcC`GAl46U5RX=VJ8Elr{&< z{+{>jM70Oava~c~zs4hxn`%UyF0(G8*;-Rwg4ZfOhlW54!z=m ziiP<2>s%@RLYSE5_WJbF8SeB7=ecfpn*Z_5m70V&uKlHK4a_GVe3b`rJ~wR+zNdWw z^Tc_IXBWvHs1|KyT#sGr7}Pn)rHnXTh{|#nwX!_%BUhm5=(&8(uPh5hING^Bkmq4*iP;lkx8h2j|56_2lVxHv zyc09p-$$y0y&&2Dv9RE5Gfr>tHYVRKWFfrrz%#jKFegqsCgQ*RBE{Umht{%8qZAO5 zP@+ELGEn{CVXch~TS+-X&5+aXxQ(9L!SnE!rfXDcjc3ms*5iP8(~%53>34`hwTkLC zi)uA^U#ao9{{AQ48mCTRFo5a1_z_^HcAY&Myh0(|jP znet?U7`2IZQGD`Q;b9D^e+iy31?63q&DWR<;7ycY7AUZTa#F|9U60c|iiT2r-0~o6Jd%UHAY_<8#jx2*Pv{>;4M?HoTtxUw9iV?o0CY@)Q_fE*da1m%4>ijdBec0~;ETCeYE zx)*k0O;6th|IRtz;H>YDen6D2DqKgwtYHr#ngJYbS5k$< z$L|mq^kOf4dxYiWQFbM3zbgdR{l1wdviuRs{Au5FhlP&yc_`yEee2;QO2M~Xj_tw; zW%oUYs11Reyd?AP09zVp&B?c(-ooj^{DRPZ==a$Y4|&jUv7KYL8|o&sr)ejD*ao#9 zYh5cZi@zSwNZ?2T%21r&wU9#Igm1B|vy8|7t@E{tlk!3s7a03)_#gQ$SX~LaqUs}d z)+>6?tp>Ot*LMBGy)xESI-V`_odE|la?fU_LgW9H8%ae-j$k2bwD!37TO)~AI z7q3Bq6~lOnbRlJiL)GmX_g_U=(0AWyI8nG1oD}vwlUggPV^g^P{P}nD(8K5OaCCK# zox$dat)0dF$I0BF_M7Nw)FI7YLdv7?ngjS9qI?*ki94HABIko12e}{i3zn6-d5DWg zGQ7@QT>M9`I z1(_2W1PIq%gI*D!_GsU1Z5C5f7nS=`t-Nit@#pK0C$a5R3FbD{@By|Qd*>P*RGCYn zg*q0vne|R9kwS_P5trhZI_jFgAs#9BymV>dZ;&%8#t?-PGWNSH%%^ltHn^cO%}WU} z!I2a7e^bt-3tLQVFqDQ(Q?Cy$3Wd7a(ZCK~)jivgtVcckK4&7kAp zEeEj87|;aQXHnp8^!^u(tBWi5|e1G`%X6{Pk`Vc>2_ z_p<3@|7`Lp;pAB**QEoPW8%YX$9Jk+{P3J)On5t%rF&eEEj+h%jpbHiUCmGowsWJ7 zZUZeken)SB1%0t4Fea;2IEGE5JKn#V#?ZRRvpl~%)$|Y|_*0a!^%JsHBD5v4Nj+~* z=scv_u6z0;8L;f!7bf~C<=ctVE&9AekFd|N}FlEyK_#F;kr&AKrKMP_B!it`BF0YPqvE5dU|t2%c^B!-A{^Xnfzq}xxgsHpl{4$1W0!5!b?}5*k4ozb2h+CDqgsx>)J)iI zik~YH@DVN+n9i$f7_+Z*k(s~XodPSNmmu2@@%FcklIvN-yuw*>-9DO8z69ipJ8FaO zv-YTx*R`hYF$}k;Hwyl&t*l2F7L|eBWPFEbzOc_yqg(vgq(Ky zD(ukJI%R-ladUTny+R;wkeX0wMiVnb@WptfN6PI1O-uM3VW^BHf9!TTq{#tQ_;BGA z;Qzl{D~Xqza;fg3*n-Kiv^19#K%VD3JHaOEB7xx-WYt)l3Sz@LT%2EsE* z6iXo-J-a@7B3!!7F1_Z|Z1DnRHg2iWJe$=#9^Uc^`SiSE!p`#crst)dqT(!~_@|FW zQ96ynf#uW-6Pt1P9z3vA?PN{w!|%BMXqD>bWEmSnZU4n*>9kFF<~C4K%x=@QxNfS-W4^lX5)gk9j`1*eA_ z%~yn9;S-sjHLBnRu;~`}JEJUX!87<{o`?!nuJzH(Rg69jceYl%XL+v4?H^+de$i{a z5wGJS36K=L8PXGCf%-N@7L`{of-Efhp<~s}6&WQkyPhK`?cF+ox5f##Eox7!%9f^^ zo?u*mKXmwpT)UcrIZ#m@TN-wkrWt8`?$9f@KH)p?4Tn(iJ+FXIGtG5XgpRny{SdqF z-O@Y9&^7Gu!Ja*si`^mRv$oa~GBUFSj>BMvSBA4~Y-g?8djiH7qg<%nq%?aP21)j+ z_i#a&{+S(F?+Kf|cg(e+&2ojNN|Ezdp(9CQjhUVgZR{POFb&QW!Xz;i0UO@n=LKz; zl3s6>3Jrw4*K%;??px`-r4^r1$T~nNbttIBY;KB1W;F?!k@BE3R4vE5Ytf~Rkk;ft zfXVdu*vt{Gv4MNt?Vh!S!FxAJLB~$rHs;ko9CC%nhxmRFy1h3VI66zi^6NJl#V zPn*KU=dKc71X}IcN0n66`Lb0hcT;`7en#*YvW)L^UXfXVfw$8)IJ%I#I8bl1MRbH^ z@|VJ!2GjmNxWdFV z?MIgDe7FY@m#MwZbnJb4Q;)QL-_iOa3W-Wgh7bRxc|K`7O-1**0xXMNM_zVqXry94 zQQl~0KFIc6t*$C>>^t#;C{3Q=vb+b5t@K0FP*4Aw?lJZWpBlm#78l%^EPYk zAJFl{*&db73S<;{<}{hRiq`DD#6D3B{HO+K zhVNp9DcMtAs0M(`J+-!t+gHC}wC}S@Fc8U2n001B&S#WC-^rfr7Eoq)w zl8u^m4?F7Hyn`P#76j_520LVT^4MevUBnv$d||a0Z^|Kg0WniO#*0T?9gV9%0cZNJ zQ~{ITZpr~9Bi|gXF)Lp*&hNq5(5zz%Bnr%QL?r)*pDdX$TAdx%zAap0bBAY0zPuAN z&YJH7_CEnr=IfPk6YghB?gigx;gh*gs^ifV{P3=T%CU6#;{fS^q#1^rGoi|^mFZ`f z7i{F@!rKE|a0>3YoLw``M=4F6-vxZbR?T4WN%v2bh`O@leo>~K){R24SQywuZ5y+g zEg(bc%IgOs4>*j_3CZK_7KR*#vSUMZ;Qvh-_>$InvWf}A< z@5!m6_Npn~eu=`8{C4O$gQLpFFC3Mw7&@Nm0{)XAC8~VE+Ln@SpEl|*Bf!dJu;-@4 zP>rm+%c*kybIAP*rGAG)|M38?&zJXpX|2U-zE=PN{(+fg=v#pW^2Kjke>Rb9j$P5N zr8fNMX<58zHKptVDCZ-pS@n(v?#sD}aA_mxKG(&ZhduGb#`{21N!`EHkOVf_V}m{7 zhJO0pv?vjGP*gIEZuOc@Hel&r8q2|z<`h-Zel($thKu&nf3^>Vn;k&juP!i^Br0~l z<)!t`>_Z7s6yO@vd-udq*ysET&=7L?R^i2Wl_8AOd2`6T&R~+A`N9;YLPylL=x$Gy zhrZuEWEZmENYR^;AdjA!f46{t93LMMNi3b~0Xqw=uHVEDKWRC3CX~LCX#Ss@pQ=&( z|CA@5IepB;Rb3opTv&4aUx$##an9J+&Rb75w=ITJas&m#1&XI49V|Fma>m-Gj%RUJ zjd{GoG_AJ<4nqX{wxQI46#C}uYhYBWU8KH)q=%hjqdw<`hn3`gXp1B~?9apW0G*P2 zB-bn15jU@zf)NCgmP#0?_U8@2TDF)9am3i3S5nv)q*CasE7|Xuv@MMBybXvpajza> zl@f5a?2)&rTCsCKyGgIl5F?(Y)inug{g33lXV+&0VSxT8Dsuit%mQ-ald;kMuLLeD2qh zEZ$XR#haQw`?HbqcP#;PTdAj)=Dy_%&L00NiW0#+6m=mqMhUd)Q?dMYz{??I>*uM~ zs?i{@`$2&=9K*N}`PCACjn@vJO@`%%B9U34imyW-_pZ3C@{F}zv9|Wj`c}@XF?NiG znwUzvLWl;Y_B}b*jOhhfh*gDk2I>n5;?ibHPYKKz7~N>w`t312={ zKsRJtQB6}tIUr7F*Rn;JdP#Y zjIiwmuos}8&?9}4VR6iN83X>LQ|SuLGZ_snqzr77-q*5qu-nBPg1yB z!NOD?P_+#9Y_bG)D;324Fj?JnXq_SWsV}hGxVu#4FQwxfWMjq|0=W%Vc1^X1T9F93jORDDQG|DW>Da9=;^`uZ2x3*o%GLec{RQkMn;% z-d=i3_1M%N^;z;n7pP5#_sR14z}YoSJ~Z~euGf4xz#Gi8=Gi*{Vq7BH&JX7H;V?hr z>gu6ioOkjdRlfNxwoV9GXv0-N=mSMeFPGL&;8J@Iv#bK(>*a-9v&IT#3v!uz4Z zP^$;i+=&oa28{-+bwsY`LxoleV8&Vb3~Y~vajy6&gIrTpNh6`Q5~91lq5RbUs~~N| z6&tdPd-^#oLEi4F8HS(NJ$yi}Ri`V6U$OJ1Hh{$CZPSN@X3n#;0aT<5Y+cEl9K27&|W(y!`9wQnKBNht0OHUbJ^b-R#c6Xk$TP`q3c#xqv-9<_-I$ zKuv zoo<$G9AlC0pxJ_e_k{W#jj&7nd%GrOM|u^`#Sh_yN%&3ujL1A3LDx)DsX;D(H%>%_ zA^Ee7I_wi~k&qD(RJ*MFgv1BiryfivBfa~wBcVO@GsTsLx2eeiw2(^kF;0uTsSZ{Dnjg5nw zSJY=~Y~DOZItUZl3;Lk<0@rofu|v=fE&oLi z&;KA9ff@U1!#tl=6p2O4U7AHdk|<)z}!x5#1rPx|EH+a}>= z;t;;dndqyi@264XVq+|(ov71ct0t@PLcc((b8S|jun8DD~lZnO8hmH%AszxTDnP zjjtu>>mzj}B`*jilUBpAc+f_5R^(<0c0$Sw4UDzu8V+~reGn4gJ=K_hr&6kkW@%3A z>GOJ*i|SLd^7A8<rtMsxWY-I*mPrI~g z4tiRQh62FvYUVL4)RQ1R!E5v1Nw_)pJZ8i*0CLBDHQb~Y|7`n}9#oHas`C5vt5VTo zSdy-;o>*@|$XKV2L>!;=Q{gxcv%qKB(LDD$FcQ@-C|SC<4oHQC+1fa619wS#D&w1? zGjF9^V*j(TR!r_-!T%f97Hpwz#%};T-t*R9@$~i!S=4&ESjJoS$Z)7)4u{AqE?0K1 znMfrq`TvR>i8C}BWN2&|_PU#M;@{~-6Y^l9g%-}jQse}9IrY3hdOZhi^(CFRMd*dp z?(5fHE7bDw06;c4Tj!OCz&dtE!dnBa#Rw4mq@6()JzAVK)`^&+h_F-}+-)9Z|#^bO-1_rig z<@c(L`O|-9@fIABNqP{Xn98`7uJMyFS&R;0XelAnQ{o9vO1XzmMDBdt_Z<)CN!};u zB{Rn{&hw;WcL|xj}_U&?5JzRx4 z)=y7rH;J)bURMbZZ}7g`L+8w;cqP{%8C0fDVX<-l_HE+qL-;-mla~=O?G)b}e3gHe z=Dl9+;nxBbs?O!2X`vkbAzYcs9&9WwJGSAg`kQOxQlh`d?K=-Vsk_=AdOs_^e21Mx zyN}8jcr}ij4r%jQirr_ME|n#yQjOdW8L0xRw>e;$!fe_n--r zi1@?Is%~jz2rI1M>Cm^8C7-0E$a0M0MR?Xj!3pg;M9&24dpgnQX@ zoAv&HN@OjWi=J29>1CBa@}!B4znO7IDSK!B&_idhUXPbQ5r62NRc-QOyfru1tS_Oa zVED;((dthi`xl$Y6tD}Y*pQuO(=%{=Spm+hxthy*kxM|kDWz+OE@?S-dG3u?^Mm2c znpw2FjZd}x#O?1FKvUmen34W?%a^KF`Q{9hRsL#W6RkQVXFv#N{`f0@|AWIWJ|)Xq83aSk zfJAq310CR5u*d7(!>$H1$oP%uJU^Xt`AI0b$lZ6zVFE_QlzVo+UC|3ZlS!d`N+`Zx z%U9dGoQC9`u(P;NQ`m&5&5B3vP3AppCVZ3ZYuj-`yP=99sW&Ol15zu>&2e_PdHC8b zJ3D@XTr`sLzz6_ShiVz$Tn-sB_A_=azt&hI0j;xRsDP&1m13~?9Sgq8^oA+{2z$B) zSw+5(RK>Fw0U0H3$+)0~Im{X#A{hfhfgaiS##T{yeF zx=_D!*1SojK_{}1icXQa%NmanFEhOj}?-$`?&clcm1wSQ>@yCcynCmrb$ z5}E`3HY8u(S{^2-%iY=auZe=ACP!-UsI9?Jhw4xkP7eh^J0@2gZyt`y+Eif-{??gm}mDNm-|Bz(w{zJ8x3dqU+-Z#?bCwTG!wUaM1 zNygvF!;L=z@)M)qRwi0k+?e>ye-PCfKgy4Hpk3&Gr_R>~!0Jq9#2KR38@~s+Sm4|S!g%hJ)UP#@w=dBzvQ_>h2fVz zGnfx9cfeRDau}OZyHg1H%%6MKXSW!8dh4(o+{!&i z5Fqf*_|i^PcGXC?WE;SiR_0H1cDKge){J~q0nS&o&2BWKfItq-xGo#t>Ol%fx;ii2`09{4Z z2I?2%MZs(t0XkES4prZYE}UbL*lNB#<i4L<*a1dzHA4ob+cA-YLf|D zn>*{BA6omRQ0CSzgSK^@@xki>pS07fDk^85=!%ZmY&t!*k*xeYq_X*NPF41a)(Izx4+Bf>e;MGOrPq>x32`X)hz1>sJ{Y^Qw+{(N!IuAF|h8(pF zvYhICYOC>#^O7U6*>g$M5!n(q^Pun8A{+evOmfUEVep=Elbx7|Q`AhGr&KUMa^tc} zqTlPA$YTs@AZlx$_}tmvQY}%Az4=t$cQ1_j=B)?)7M+ZoP5)9lDofE|M0g{ z&*oUkHm9Aj6MCpvB6(U2-c_g<815m}m9OX!z{oIK#wa{K;CyDRv8gI0nOr*#dRvvB zY0RN`7YX-p=Z{(Bd%_2#E+C-tKjUiCPU7me3=dt*M!d#R0nP>0vrP3O4ZRx!Dk04; z4dT4Dg7)}gu9*JO0srmvH4dmz8!^c#m;Hs}tOY4QFdMm(Qu~;JHe2QQ$=Xd1pj=n! zRt*_v1>Uh@__Cww<(BMY-R|wLCcQKe%|~A9T}A5oyZc2|)z~G0?>y?=|tQ4p6yH?uj*d4Oh5eeuYHIIF{ zPgyP(95I4b%)6gW*`-o8XYXQ7+_k;jB-_i2Jy|#BwB;Xj#?EWb4tq+8S&zVRGrOT! zw}q!*_)sn5^Y~}uHZQtqHcNWKRj5Tupatq*lsW>3I*Ug1M*c9V@=EjxlL0bnGdsL8LH zM2PO{Mvl3ZH`zMFRQYeQ6&I(>rBfx=8+RUGvAiDIQ*x}W7mJlKoP&zO&^JD{;-Nmk zdWDjiMcyg)-8C<7dfkq9%VQleP>^Ae%QD%5n|;dKZ6pnpHa~^WuS~AlcG7X7CNNj>TyR|5sr~0Ia!d|eLdekS_UT^$Ujy3a zd8PIp^^GUg;7R-0lbOoES4OqpP@6801+MIuHGke4de^?E20}=cM7;i4R)a6&xMHE1 zxJW51K)>Zbxpg83NV#?wS<}Ll;yaVsQOECUzpAmC31R({DNmDo#z+i>IGe6xLOhYv+ph=9l38D3VpGJ z)I_!$Izk)Sdg8@(qoS&RrX@z%CkRh^2(LHm@O5b#xqKCp2hR3s_e`= z1Yg(E&ZPZm@#!vQr!I>>S1X}{;LD@`BplsPnr^`8mXT%hrrVQo{-b2T0d?N0%DRs8 zGQp5D%<93GBM+kLruF)n#M$5m6~)3qheqr18`!3$3L2!~!AgtiA6?h1Shwt4BJ6+~ z&&0^2@6C^Upd&4n0C?)JX1jLNfVu87TyHySXA>%!5jPklyNgBC-$x+{w>tjn!ZWY2hC;wL*1qkT|$|? zUGQpQwv-ati{aKSZC&w@gA5;=P+b~^PVWeLzJ2}%MwJ7KPhE>rokWodKcxuCz%12#t764B@m%z0Pp$sRAiUy);#7&kuQ=tGl_1=2V3c+5+Rr^@ zpp8=Da3YdPlC!(1vz1@bJ^4RZ3v$r~lcw^zSz=jtp&+Bfh68*5dxF!(dxs%Oze_VN zuwwr8-5tKh560j_VJ~3;f15Eco)54j-N(S;A+gMeG*!|(jaMIl&RK;Ps-_}e_-*Dx zp9d;}BnrP0idK;EsU0(sMmza&_HnTe`ycjvctH*zVY4J&)vDIaxmliP&a*q0A_K2Y z@y{yggT;-P`r4EldzeG>yqg0*=2mXJa3S6QUHy2j;^;UdFMbOE-9PPb%zI_bUqyzu z$Z?Jwb-hovsORxEc~|mzCLwthRV$y+)wHUZ_}Ft)NwIiJ#_eC4Z8enjzXne{InBUb!G<864v2s+oLdtlG!Jw~+SP+A>FxK^7Ae)|L}(_ZX*9SMj8pg!?v5G$Oe+j82#-B@w!< zJ^y6zqCGve?vUo#OAweR8W;TjM2?d`c^7`=I0`88P3d=k5thV~n#Law6&izA0Daqc zTc1*sMnY$6Vv|S}g$u@YL-IeF{A`_b90+%S^Gs0(YnHyBf@I}&oo2(axJgQ(GLzha zh|rgm5y@Wx_7XSb^7rRDX0&txLhpX0l)ICja+nxdcdc4Vj3@R zEMv{*n28BJm{N-6^G60XO+NCt%I`BX+%IVvLEMx_6wVs0qt>$*_--huRwM+g7WK25 z$RBoiDBrV7gduS~kgCiso!?~=Sl~=bj3?V0A^UDfZ|_D^Hn#~iE*RxTJXFh@okve_ zfV0`XF@!07{9}dHs48Cu=NlH@ud_sbi+57C33}%NF$?a}{`YIDxS2mlQ*?Hi`4IKd z>Wd~0q!&lbqq3=JVBwSx(2#g)^76M!QJE@qMS`a9vE&GH1L%iHV^Lf;d3SdIhja`- z5NGJo>XLpE?UIWWBU8g7_FlJ_7Muz-wG8$O9+Fx4Jf(QLDWONS#G&_A34t&$Abk94QMw8Ybr^mf`K z2m3rn`NPXOzYQ)k?DLf?H0&WVC(iyR`l1)L49rV&wg^W?N!> zV)vlU4eiU(lJT^!C*13)afiOA&8idl@Q1dGii$W}hxd92?0Z$J(K?30UCWYXzTE?M zwS@4(t#IJYN;UqQO!sB5mC4QV{)y_sDhDQxnyn#Hdq?59e$Dk3z&)uy=CKY(Haqig z+;w`p)!VOCe+rVu3FpbO4pWXDv%y1#%aw;5D#voi!&wBmF}-CY?VBhCYM7O4^fy%3 z5$m|D=H^xzY*Nm`JoOPn)R;x9AorxyOoz_M4O4C~CUuM~aH3JrrISDAON#i!naW%K ztlryCZKZ;hJnX-c&G4>-N?jBSd?uhx?e4xRINHJWL*Gj)7mkkOICUE*P>vNH?-aiF z@RwTFRA4s)wHvFy6n*G>U+i~ArLdn547lyo+nH^zI9X+ZWw^yL3G{>?D?e=JHS8ff z-TQPa)f^@_@mw>TCpFlu6N22DZp*~%?9Dt5LpDfp@^{bh^Y|HJ&zqdrHwaRn@2!z) z---6~p5>nL%o=Oj6InP^JS~STwqRcNG+PHfY6?w!bF>1|{_#)GMyZ5$?@y5`F>HA6 zD_8u4a&D8c`8E08T}dA$7b%C6gcX^=wo;qYmGRr|a!rpgCf2eY-*^%!y!khEM)$R8 zfGtjxMcWMr1;IEDY8=ZC!-gZnSxx>2Y57E_x|sRn*o)Xoj+CCtAX#IY9=u)OTEqRh zZa?iy-KhL42G=LXTeAzf*2A@STa|eDrdgNSF0)^+D?I5q%1#~MCUPc+phC}ZW>es0 zcfo)UI*C*@@dK^LAQiK0n(N+T)(ejR(o9TU7($;cC4Y~)XH5Unbcw3HX5YyF+jHWj zTN7jzgmXE!VUvWj4q2;Q7!097!k}2n~xS1J<{fxuY&kks$R9=XvOWg2gy11 z?eAp-J+k4=PY+Xkv=5rvz^H=ll}|m=bJ2s zH5C;-wtz(RhEutZT#$%gv(1Pi~ z=ar>-?LI-@!ex~EXvT?77PWl3%J3)>rJ{jyQlbGsM?t@){k)b6c#-(x96jsO(KHc z&1EARdpJ~-jrJ)Y67Xl|1roQb+eU03zAhy*1pfz(RL*!zRRpJAhc=9HZP9QeSQ2@= zRGyV8_X5QIKY|F$o}TZRLPi3`i+e`@4wPUmTN)wyESre?SANVJZsOD4e#68dy!nh& zxHcMx+yg?AX4I+qVsS>>8V)!yu*4Dma{G%m^0cmdHpq3zY*k`4Ov?a&3l=E z_tw_ONZfulpi_`7Z(ICUxY%3B-`>Gqcb^e~X41aQ>M7N2(Or6BIHYSQp;k&T>!&;{ zIYVzcCH+uPY)rK8_2NDfI11N|EW5|17W4w|p67m4yCT4DUz9Ww^}zXD)Nae~gE1bm zC+vd)$JXksXrKTgL#bxA%2F@7%dVU93Lv^EDHrb77w+MZ$iR0}0_r|}8Fqd+=ADuS0lHZVfEMICP;z+&5O& zvAA}jV&at7$7s*a5U7xLG0ngn2SBrB3Wo8k`Ud2~<;Hc*AwUkfZ>e0a887 zl~5F>xp;AK;3op^Y6+z2X&gHfMx0mZf4}uXlgjGbgWNVWpvt{aIm=WWdGk$l=@(F1 zeP*{q)+nM@_b69olz62X!qPNfaTb`;fY}rQyB7&I)AaR4WgckLBLhSc_<*RxTzQT{ z;$iVgf-yaIilc(9s=TqqZ8tU&{FaKD1URtgeo4*qB#tWbb%)`*x_<*%YFo4cD zNGLJT*`HP<^Y^Ppp^s)P_bd4_foyM{Yp|vxZjCjmjLItK_Q@?5?$`x5%4uo_L8$mQ zI(YE^@DIAD0gI&iG9X|@{3|&azO=M9d-qI-%mH4$EX8cx&7;lNyszWvPJlX|v(3&A zVd~Be6sP_+Wskee6B6cpI1nC zFYZ5$G-Z+(ITWB){n#nL)cYcbiIh>iN@K`yR44x|Z?+L+nay8)Cx#wQ-R9(vb3OY}| z0kqN$>hx#{*PY$Yc#5>cz@BNl>Q}(`kQ4o*cWy~_FHh@Gl_~ojVIX?mrg&*BrVmk; zAi~g(v8EV%KB>8w+zo@EPd|yVOuj^xFG$||^Q1ekOo=WXZ_1sX-W}xQ`KvTf8^^aH z7?F}{2;KDjfLD(Do%%10nj97N-u)*je`NgR(68YmTfyHN&1{ph+z08CO-~EHyMTiT zVEM%2M4l`S8zU)|!AnDqGW@+BzdL`ej%UVk^iJuPhG&(E;i|0} zFiYXbw_x)kqAn|5BUTo?epyX({JeHw#dz0r8jay7iZN!^*RB?yfo&YT zT}sj9sQ16j4G4Mgj7_yW)c@D;PnAh0Lrm3Em;hPZs#qRdvZ?@WDl_C4KmKT*kVr3g zFqG=teRtah5P7KstJ4^C^OEHY;Yr#t&I=igzFJw`52Ep_<&;VGA4Ba+*HIoiQoRj2 zgMUEA(&qn%s<)17@_pZjhbW*3h|-Oqlz<>5DM};F=#-8zVt}-Qf*_qbx?z-bw@68i z-WVyd(OrVi&HMZL{qgYkUc469eVyldoJW)`C#F*#51Ea6aoM$+ti3R0S;#4mJ&ae1 z#ve)g{mktkzC?789D9BZtq!8o38ZF~{IRQJcT8Op6lr-~T6{xLH#fkliI(y@*W$hk zGtNi6{InHXAhlNaiug^KTX))vRqm?8g@U%P<0xilO*E{hoZjXRxPY!a=dm~b;2%qt zhi)0At^g}a4al`P4q$>A`)w~R(9Z>Nmrf?+pG!WVpt zx9F_^x*7+F0z}Gn4I6iIEJ~^{b%g=a4f8vc6@~f5#TR*Twe1B;3_B9L9$z>z=tshD zCKTV&mQ(CluKkh1Oi?XC2DEIerGv-Yp;wQ!IBLe@dvjkV`J8k^0xBQMoMV0DJypGp zZv_w1(GwGIvcE6(rA>v}p+tu-?FXm*nhBB5Nb16pq|-uaySz4Lir z0N!to?ORE1r4cAiM>)*Qr;iEUI%c(7%xe}kWO{{aBzBxZpVHL(kZ#)xBr z&{>l3DEPWZ8D#}@%V$1xAF`MBdXp!{;Ry*Yxt?{W2>N z)D`)OA7m8GP_3(|cDLEA*s4K)Vh4|{X)3Hr&}S)%#VXkwnA`oPP!+j(4O(h%Ow~xh z&$a}H?*AsUj$*r0?yxAk!x{5J*sW|vQQ0Z1vhk0Ta|+8DjRrOmDO`awoxcyoaEx~p zFW0Y02>{mJbCASoI{jUpiLU--x25El*&To7^&Z67`>9V#1fhkc2VhA^RkPTlQcuZv zojp$zfncm{Tz9Is(ejilVb2JYR+%H@d0kKr>{rN-H`d50xL?3C2;Q)jqM-n@Ioo;b zyv`Y=^>h=nic^Wiwh^LV*`v^vwLsyWQj8yyq%AWiE8%wx%h4U_-zOz7q^>7Y5BZ8M zIm3_+|DutGiEhi4-Hw)K_{GOGF4HIIaY*`g{e{OFBITk0vDTKwvRP6XT%PQxQe-If zNMLM`9-Z8pX93vv5)!eHV#K+fcwf9PX|y-G>q(mFm(H%)v5jl8J)H9(qZR0*`jatA zG48=%qBG{mTk5>O6--}VF|KAuFy42LT{-l0>DKu6X{WVB^v4kbEnfjsD{|nAt54vu ze=OtQG0hw$k}kk{A$3%mGc6t*qvFH^mV$2^EHUz$3WaqRCRBbdml$g}fKuO57h|wa zc4!wa2uJ!N>Fhnh!J+$%JZT&BV5U<&(+^5J!-PLe_(d=D9aNWJ=qJ?B$AL+Jr_QX|i+&C?xoY?YCH zZ^PyG0j$_MnPTO~INNa+>(h+PRW%Z_#nh4ncPb3j|3H;NT+uWz48Z&LeOltsdO63rx znm0_A3i1M#NR;s+Q*xieZQ~l8cr%QzoGR+&aPVdr`!~nO_Jf0T8ei5vsMB|RP!QBL zG#boO9|ep}CPKd!6+Im*GFoJF+qXhk5r5mqw9py&9n3Grxo2R=# zLXg2En|BQ|5Ya_)k?kj4YsfzZadRk$PMY>s)^Lp$A*ekRA`~%WHd!mtJ5E8SXBMw z+!ooGKb6*B?M=;O!=N-CYW%rZ^@$Q5-JUnC{1qHpSMVN|=&4QTsL)a)lKixB$A>Xq zi9XmTYVqYA`u#`qgHCm`yt-2*@+4As?!36|s?$kh#b&<+;_jNQAz`+dHqxtB!>Le# zM<+!Y0w&ZiW@!RzflbPRHOrydtmkAp^9ja~l2O6Qc`~}NIEG!`lt8vStksVg$O2_K zy!Re<$OOkaVF>cZ^)RwdvHkMy`OyeM@{op;u=~;7y!i9)Cy2a7ZUYj?6n(fZJZxQNzu3L};MJl#>5F(9C%Rdt!e7M= zW+#f~)(z_CS5_4`2a}cfKBkVf>fem*F|7Epa)SfP+%duz(0`z`y8Nr1m@7SCd3@$8 zW&01ruJsQ@Xt(^?>0aJ#I*!5s^AH%UsXOgG7{V^?uflxY_3R*wk(}K+fUU+O?~h|1 zG_R9|`Q<%@s=cFQJ#wB&j)DcGk#se4zW#)KW_?uQ)n^`qa|iWcq*OZFR+&A!baGkw z0crO7-iJ8%y`ztMw<+{-xo_T8lsRC8j*u#3UYp8)zerARc)rE$#5c)T41TpO`u=nO zlmgkzfxKb*VG*T7tc0q=aVc0&;oevFj_15}7k3%eTq_C#pB5*&`a8QW{}Niwi)Ih$ zWmt7oFdPfY)eCQQUYjjB#|J+3;T1n(?;EeMQOmZV4K}ljPQ3*y2NCC5D$2PfDk=0vZ!d86io$E+he- z;5RLKD)0W11G`J;Cpo)gd2AEr>n!e7f9O9DmH)?4bs16$fc5EeELxKJbhuWkCao%C zYZfjM8C%1Q>jEVI+W#-Ag2cPl{Gg0umvBGgnTd$>+cD&9P$^KGsUCYPY0mK2D;_n&U_zLR!oH`1U=CF z2P&!57tsR}W=vq;k!C|8%*CZ+JyYPS*hwTv(xr(RAww58+Z6zHN7$O*)l0=<+=A6y5(mA$CUw*DkjP|4YmIH)GjF@=ujNA zvSvNRyfH_JrhL3g|Ds^~x{fi`xaLWUpqXdX0FOVp(9&?^%lxwgY8sS(40j%6I}Pi| zOPTGA(q0I;Qxz8r{TN-jXtOJ=FV@&QphY99dYO1q9!=L(kiO&ery$~6+^$WASeg{C z4^j01??w7!{JO!)grl*-HGv=*jZF2MO;WIhm`+*bwyQoAz?| zBsXQgFD#_dbP~+9`PXgo+UF3M9Qm=5z;<>aA+)q5DDx&yL3E505BPU0CkgFkzNJ&+ zaz3f`BZoiQ{(+c#&J2Lim917m@F&pmo1O6~NX~*2Kk#VQ&o0l|dHnI4Tfx$YjOIfr zIybNkBKK`k7{4&U_c?8&(s9jgT&2!?vdsIU5rj9g@UUIgq|HKg&QBsQy z>CLVes1kqdbC*HMNh9IO%t|!dlLTk=v6{A6)B*p!v1Z;H?4WhpV?>1DadNbRlQ7F0cY|Z+4(-8u8jh6hMS2>psa-zNn`&Sz@*KtM0Hk<Wp?0?)5>u$ijHe?K7CiGi z69t|#kb^wlev0dRXytGH~Ob}>fMG7kOkM5+L+3|xcS zn=#}r1wZfJK$8*R(BwOMAiYoJBhMFhoT`;ON!=)7>`-Y^GDLsJm@kIc>D|Iob6E9e zWroy%LKRY@r|7~kW*kQF(Hk|{+J3&O=l9G{sTP)wV*1kPK;M=y3KOEHs;rh4Zxo*j zZLOd$EOjO1W&BJ!96(-or?d`S>S7e8W8!=uZwT>ZS#O@#c8{x)d>AJhfg}v2c{8RMM7QG6>dn_Re9XZAOgM?6W`}M5 zJA7G6q5&9vMRV?$jc**=;7pTI&iXtbv+WT!W20dT1Tu_s&~<-N=9_NC?GfDnK*jE* zSsbtafes_;g76U6MaA^}8>mvr!{b-wkHFizon{AC*)`)m^nL{U{$cCBNiD{zmi5u` zN2%Q7l@5$ga-3k7_Prkl!7oyIz9;m|q_=pa?cFQ1eLp0RY>AYxyC7l?Sc>U5^6X28 zS3A>_qt|9Un_Wf;Q!a#!i_J$}>SjLvDh@VrPwU8Ycf<*;rx@A1 zN(xKL>gCyNlG7S~Eo060n@sRJNb$cgB&m#D7ZWi}!R=2j4uXn(Q@U1GeU2rISHdj8 z3D4gjE;uqBu9CkVJG?D;5I0Z-XqE~M@be%mj5UehuWb-|`+%>#{CKZ&ZfQ+yq&!I* z(Tqfhl|A!Eqpq!x{(-@$VQigG`9xG`4pzTNO^&x{iGIyf;qc8_3`IlaJ_E%m>_lxw zm{2tt^klSICSh=ijPS}*Pl7wONL*jJ!(J`3E8r+8p8W7_m~EmIl~-#~-DhwK6fCYc z$qN~qrVH%>bCGzg3W_O=_PX9qyS1wVH!DX$1JhC*wgVU|1jbt`CyyzPqFvXUtVvyu zLdn;j=w=vwofwP8*D7Cq()NJ%)l{S#$ig)Pgr(j94p&T>KfZdEWWeo z_jikDKl`>Wan4;WncH5xSq^CmGBtzcPn9KhT~R!ZLW&WH=RDq0Oz0nW4r5%+^5_DJ zX}{hBi2@RTv@!ZBQ_kL&zE!O$O{;bEY%F~4086^pH)rK7n%?(dXO%9!U|h!5*CM;OR=WPfsrs*wB$QGli?jS4LIsQQFiTU*ZIEr8d{sg!!$S zmfOK(Tfw)GX^87OS;-g95b0@O$Zn?R<3Di6Dwc!8e9tO+MWrY^<=gK>q#Ja1VgiJm zlX{V68u%A_GvVtWPUHaR7hL3#oasdK8JLY$&C8+g}n2j?di*BwMmrT zeiK$VHLL=rF8L{%UAVA6ehKpv$UNk=M`C$al9m;Pl+`XK>1n^PS z$aH?MTT%w9ZYv&ZB8JVhg>M{?7V_`#l!!}j8hk@8qfO!$y`P6A>HnkBqV45 zt;Sd3U~TEy>JG)Q>B5PyoO$GKH;3XD=g~ndejEzd#2Bz;IK;WOMZUgU(U%ab! z!1VmTep$mJ$oO6TKwukO)E{zhTDZ_2zM=}?^6LG8limhJoG5R@OgiPvnP1P{JX%7k z!#i$gjn!bD)IM!!kj7MQCt;w?sImyMF>$Y@)< zz#SS@Wz4O)h^??x-TkDlEIflIET4=bK<-!t&wZh8yn38K^REi~Q z>Wd2*2)4_gxIsUO+VHk5eDwyPLM?3+WV)<|&X4%1(p-*~y%WxSOZ?x^(3W#EG!*`CXqc1Y z^$W`f+O!d!tXE#s-hzQ}p})VRclW=%z~1Cz#RqbCgbb^vpY%blSa)9Z(Abqz2u*7A zKHeTK%{+1hisX0GM~>XwzTzAG+}`y)#JTjn(JR(|h8q|>J!tZn+yi4z;p_ea$V1FA z$yD^TEOm1RLW>@63zT7fg7@=;B?jJGz!aKOyhp_B0-O6ZFRU;`8~J)SZji|P6|;!7Vh zBlHMMec4aW)a;gj<~uR-#*L~)K^1x4z@M8N>Y1)ed4w(E>9!e>9^HlQV&fjMI?mCdDEnj~3sDVCyo2|XHYtxK zx3TB9-C)5P3irjGOkXUlig^U#zfNk=@v{KjpF@GjLF{1AMKh)CxexFmxtD~y^8yiq zEy?5kcO)&YoD6SU;g2U^fnxe8X;gGLiQZk({POL_alI76>3gkuPM8A9aXmsTgQX-<4xb)a zpRiTO0Ff8gs@thEIN0!r&{|qq#!DPTugQ@sKSmaJqy6&?fX;0b8(AAVB8sh zEEVj-sCeCY@2g}@Z*eZMDY$~;Voh+qbIq+tX6w_}csuTaC%$<{W9=&Txb6#U@FcnD z?=zIf@*Mzhv5_v!mtdU%OcmFq4ssNIe!AB02>}RwBse9rt?2Xf5Es}(fV5!nqm%V8 zybyZH3QVJ)$GQ}if0#a4XNa>YfMz|%JEOFrlG5f$L~awSq8QdaDW*~;DqBAy2i6+? zYSu4n*M1FvF+L!T@`e4B^bod8*=~8NapDcOJ$IRqFElb{ZMEN=%*YXVCOq+ITqT>%U{)ILnWzl_K{(H2e^qcl)h z(A7AOs{02zzRx_N%VpF%FpGm;*NG>bZ30vmp^W=2`P`*B%n0zc?3j5MUD8Uv zq`YmXqFCTbkTyDn69HEhNyE!!IsM+i#Zp?V$fUl%Hl(ePV~lbPh||P9#TkDtFHo(< zrc=NKrIw{jRnwQ(M8g*ts{3DKax~P4YfjDL;E5`Kd*v+hKKV^mQ9YF2Xt)4QepsGS zpcv~9^m0D0&{lp_B~>KJ=qQ2Iy&q+=OaYoN@kMUa1+DT^3^9AK{{2!tNOCOPu46QE zX2ZX%l(*ODqxzqKem=g8Y=)}-w%s*h+F!K+q9mL<-u9rs7lA@XB0dmqTc|A>?}z9J z8M;oV5Sj>hyh~Q-MCVxSV3#Pm@GV3mFEj*ugS4E@k_a6c19+dO9Q?~OU9AD7m6jPA zvSCU~>MI>Gk1WYkfM|0sA4-MUkhz8!K~GU5$Hg}XuUZ#dC(vjW<;su;$uLV)ZFnf`$ngDtPxv9WA4dh63vSOxJqoFS^kek<2vvFM(%a zv^B1}WL7;kW`1TPtOuXcGU_NFbmTYn{Y-cva>5`oqhN*3^BNHwLt9tWA^nDPWbvMS z|H~ws;wFm@ZeLL+nh{ow`7=zRNJ>jQ zP6WLj8yWDr6JH~3M4}z<-i-r86vbMqh0#+%qM;00vFq*Tg(N+C57g(+Klx-mJFyr8BO? zvUjsmw}OV&V$Ob*>~{f?l*<4uHb z@$9HUIcr;@T_jqBVhfvtx{d)60 zZsD}Jg3&uyMt#SWfVM!yYa%AQhVw@b$fPDC;CxQf1xEY>S(ZmMp^a(c@2(6pymXh8 zz5PITnTTZ{oalY502E3;z!gSI{<=&PsDgYWI_V8FQJDElt&!`pw}1zqD)(T&AIb0` z40U{G8P&%P1$&?298$quFS(gD8Ah+!didES74PrgG*4oS6H!gF9W&92w_?aW1@h!FqpIbuc!46s0>{kJ`p}KE^6!lJFFYxwtD)lr+CMlaWz;(oGS?zzB zf`9kcwvNOb6365TXFg0S)kf#Oh3z{N%iUm>vx{yW7YB3AyWwE?jD3_jvQ3s+5n{W7 zenr3E*Lkk>?)gO;b9r>`^^<>~ktjfqGzXabkPwfL{Kf1rcVmM}0oVy2=M-2_o4Ge& z{xj~T7MO4keAU#_nR6B;4lp*r`63K06J_R-Uw$r>e)}+FC?gb>L>a(d^R4hns}Al- z9OgGfvhnQPR~J|>)L&_*ej0AEAJjX4(5nH~G@db8SD3rN*Z8Gfz%3n-BGoqL+@M$; zAe>jO$7U)ZXkyKqIJCTrA8t6?9DOgv*oEepS@pi zVXZdKnD0w%FC<>E3un}bH`x8AKHTF#QmgN_p|y*2M5;iWbFS^Nk%y-Ks2+I2&yLz6jkgo- zT@G&tejWXc$a=HbBV*Rup6V<9+#Nda(zH%q|8nPHZF=3gLnH4!Th8r;I9UZt7)_G2B+eE04wR z+i{6ztWuu)8W{fk%OQS#ewR~wTM~Oln|H!Cfou?zN8)c!dDwq%>KCExc~aZRQZk7dXge1)R1w} z_uMk!q_Xg;FOI9^pgvUR2f9-`62|t2aKprKwwgDl*}l(BxrS7&D{8QSqx5VVtug4U zzg$vY$2~an5Li(SFr{ zv6Jr%*Wd@QSkenylzvN$rFjR3g{2xhj=4KeJ5HBzP?}T=VkAseHU0IQL@TQllxg-u zOz_xh7&x(fE8|g#7+l5WbKvJinu1-ck-Ecf!-`$gVt=g>YacKYuNc|*u8qVsa7Ms{ ze)qg;k6=jX2g7H0!bLK7_hZ?$b#>>!aQc&%XHriC)q8Hw#+ww+^hh&aQ6Q|(VHXl8!{xX<@;Yu+WfN5g;RIGpga5H;DlNNay}nu z`h<-w&$41g3wS5U`U=|~GKj5-eNEeqDg}B)e<@;ga(d}xD$As}?;H|`8gwozv=Cc} zC0P?i8WHB}J>bc1tH~av_b3Rs2m<9a=nOg+$3w|~G!8q#%`@FaSM1pj`Z;QEQ0&B8 zME{iy@F$UDSxQh*jH_R5} zp15ADhxJnhu04$bCME66Y>2$PqCy!bE_m61JJ%}Br?OT%^a4b4#65J-3i%3YBDP64 zp^IJ;nx-{uXKV@&HVU5aeV}xo@CShB{&Lk!fVkP9rBNcGBnm?!s&^QR7xL$7@2I9S zd^qqhA{K3rHD7YC(R_Xbz&_sr_gYx)6!buzdCx15Q||}j zm29@JulAXuqVKs|CP77h%23KqP~BI_Y~XQ^xr1K&k|H+W(#ecz_P)x$v6#y#f%9JE z?!=(#)rDdZ^fSED>N#((ALQ>%NgKV%dLmj4% z%*H2khlv-=g5&X59@)8#XauDGo;{)nmje@ipn_RbrT<9k1bF4JKM2WHpM}tQjog9v zxD?c(i%*;2j_`lQHk5!>pXS{-QoWM*L_|0V=`=pfYABYL)4SxQI zy{P|8Z?8;$@DCJFXis)C<(IZTc=d{fJXr97Pk7Nv>N^Z4M}VYDG%@9ouH3I^zC6E> z?ttg*-hg&B@SV2(-FIkamDKVEs~)}N(Y<@bs=YL82rutE#xUC0KVC!;rI+kU5Me0@ z!;z<(h@;O6O#9bT?1`8~$RCy*$${|6OMEPUZ<)Z1OM~=BIkv;O^yd+`cfyj6eiH!)TZC3cpQ4lJNFb0 z_KueH1qjnkMeH)QVc!weXd2wWH;df*Hx&M=c^+><2vdAbd?o;(O7g_6;CpVJpCxiT zRt1tsuG1#lzw4xM*vi*`gy^F8&3mljTqdNd0p5Ixky_pG$BAMtdN{zP49U*T9`t#*l69_vwd|^@cwl zcK|%VVT@$yiUH;kX7em$IYagw08b#+iryQY^vAv;}ry3kcR=__MQ~%7K3CK#30)w7c(t zhA;70G(9R0XX`zS3gr5J1jyTpZ?Nw6eE)QFpn2T604+o-kPUn#H=g(tC^F&~v*0kR z(W9kt1b|u6V9T-#O|cibJGFdbOtpQ|g13m`aGo;WE}{yTS5jg(jQ`BOJShL&_L`Ez znzj*Ps$9Sk#<@-xtiT{hJWHQ8hGn^9@T&Z?R};hzDV!pu^bbTHdE1%dI=zuyY2@ z*JdFX^QM$_b=b{>bPf3;!m`6&j<1c{$hYj#SKAx=|3E*rMN>X~o_*6=E3SqM$WuOc zB8|7KGQbSQq{bNY_>tW@%)lDXl}Pu~eVM@U!&cP`HqMKSIloWoB7Y97iPEyaKI!}G z@34~wa->9-y+gNBoOp^1)yc>@HONn5Hs_soc-g)_c@I+XFSRlnUnSiI^J47a zS661ACLa0?+Nid1ro}M@9z6`)RT@+cxMDO88g00izq#ziOGtE(3+iCUz?i0-(D2k_ zp*_JSkrnnYOtVaciIo-jfK7LHyDY{=F|Te__0BK*#k@A{Hk5VTj1#*D{H*`5^<(Cs zws1;V?u}&mS6%sag-uhHhM#q*cMtyPEA`+C43^Or+MZtmy&z=1IX`4dl$Q7bT9B7I z^0mYw1^54f@SBX~@D_sxUmv!R9azUOWvl|y*|1mJHi|_e92$j@V;3uh1@RdM^(`Kc z=B=aOdNZzz4tJG^cq_33vFW}L+#>_Ohtcw7vz*(NM#z6umWm05bqt}4tv zo4lZgT!aFy(j#xY1Jne1Z}rNQh0iB9=ButEy<^nt0ua2Yae0)dJVH-d)vds~LwFW2 zFNo~EENJGH)&zS1U8KYHce=nrEtt=QoA!%9U#ea+`k1oMOGy8>3(}tqS1FnZHd6x= zP=BVrmTnd1Pf&ElbD3=k*OIuxUS(ozhM4q)m8P^d980;N)O7Sx1?8I_#nH(T(bO7R zLSZCPQM4X0-)=MMrlR>TT~8E#(agF}v@y{5)F|t;$E5$yt_a|oX^{0uEKj()JhUoIR?2#W$|$gq=yqgS`)hGW3d0dr{M*B<<0RH-DOS-QJTz$vR(m5a z1%b%v9!=~w8Ro}zmI9xTkNp62f0Z!F+i8+_7wYL78r3sVdy#z%v{n!Mxxb=Z{XcQ- zV7HDP^o7ih6*Hp}uxD4t$K_{PsaWkZCuZ(UounZNik52W=Mx?eB}3t<8$b?cURP-? z*;^8G;6RfU-QN8Ny4&(<6a36#v2|RicK*ZAsjmR)t7L6^@o{x{sjo`AIfg5f#B_^@ zlWsqli_YDA&2N9hN@-EoqykoOQ=0FUX6?)isSkSAO<-ZteY|gG)8$puT@g9Oxb2!K zC@nEMm>B-@%c<*oH}8ljRVz0wm|Ii7eZ;sw+GVt)2p|7RL1;q{Jvx%gvgexLmh|;g zw5Sc5Z;W2JzAZ)B@Nr(eRyc0ncObkaI(ENzM**}&^g>7hj?FGupGarsFUzxx&p~bM z@Y>T3zVn`x<{TW!1{O1BAL*(XrRtU(O41ZH0&@cB1zqP`^OTwV3q7})^a1IX6dBO{ z!u_DxB`6tHN8o1{uTPrKMLsoCFHKBsfmsV`uI-o;fKyR z$J3eak(yGlE0Cpyem0OT|KtTXwM6nvOUdn$73by`H49G?z8}tOO2>gY3Hx0i~z zsq1Qb4>l*CHlZ_>^Pc@K{X9*RUsM$Ty?k(%9{#KLr`Ii6e91k(M1T)ieF5z7Q`1Y% zY|M}Ifz`<@`P%()yZmw7i+`Z{{C}X+zr{NXd#%#{-Kd1|Xp58z)Kq0=reR=tP_M*5 z%3$7JDpR3zRA9HuGr}kEVAmzgF%j9Sg8M-{cNGgu9j;kU|BBzMQr(SYAi`0Z^hIc2 zSN9CCm5~ zTFNl0Dc*3+nl_fNu7Wqby$!j-es;(_E`4zX>`{Bhlf*spm~tN}Hj@l1%sF79$*gnP zFPNAX{uBclWxg=)DP7-9E0piCh7dG8F*3i*$~1vd4np#tt(qNr|3r*w(qL}}=rbiJ zu?<((33Sj71sO_k9a7($YU}}T-a7p)(Ytgki?~k2Y0JcJnxd~i&sKFi#|+W ztGUY3u8&j?NOVA(CC>H)_t-{=VY!Olb$^plbF=4*Jxviyc{C5U9B~vi_Dr!e3SRLn z4ULZH@$Wns*b<_CUYk3h%mNaNe|7gZ$;P8=*9r5UN%Joh!1QgX_n>f+ClKoURK`!u zAW&5Ph|8#_<$_WsC|4w&;~QnvSqX<+n{kw`Pv>~qC58=3a+;VJ^$+xV{9N~DFG(Ih-a9x;g_GBG=SKh#v>lEq_c3qloP$_4?WTsqg8jtX0n9@_J)v4{Fgv z(wZfytU#2duerlTy5iWTuJ%}UU`{fXzK~U_Wn7iac*8V68T>k`V}d>kok@3TRv++{ zxZ?j%r{7Fsec3r?eXiu;4>Yq?G4hm_8nE)*TC}5!{=F~QBJ4ZZ_z-Kim6d|Yvfl?H z$^2IHoC#yc(upyF-w~@tnMS{wQ;nayzZvE{@4bA%bHwp`v zHFgKU`RN`jVV$qmZ15WY6?nvBV440{Xzrr^ol#Y{O81kuQ>Uur1j0fl_ zCreb0*N`+8y_Q*0n)XKCY#ohY@WFeIvGofxoQ(Gij%#U=5(WR3UDsC&U!Q1wir6~& zC0Y$DGz)Zh+v_E(t(ux9p$7qhaIFa9uOoYX)ikXxB5 zrGgZ9w`j6(8>i)ZC`*{Bl5*3#P)u+9y}J6m zVdrhY8P-Fr_y-IR!AQVX!70#F;#H#Ta~0{snJR9HGrv(*v5Wz}b({M;WVtq!j`Tp08x{#a(5*bM^9|?a7fr^Eonc zR6Y(PI`U_T>B`fp`9LARSHg@t_8rBeT@7@gV6OM)V3 zOY4N_6@%hIj?L=hNjbb@`Mh~_Kz`eydWXy|CE?9s?lL~I3^E+Ml$U6lqz`-+(^o=t zjEi?@ytv{jS+<1H$D<3q!~|wH+0G96=ZcMb;(gQUs^~EIeq-b6B&JpMT}wc6tXvs> z*n2Xo>XVgLV5M6GPD(X3wW{1mUBwyFKjMUpPXG{vD4Rz+ppm{H1vH0R_2R_YR-Xwn ztx9mr(e!7$;oo=pB<5{j0yxz}tHP6v;+8FT69>Z<=V>vgryc#cG-mSN0=-9n?$GuQ zs{5v2tS#70PM1--rT=I;>08V47{)L7>gOwPStvZq>=13u?!>+U{+w!pQ+0_!Qmd(X zf3MUsF2+cHN`pQS6Y_5CCBd(W1#p0vTGEs}(#YZjdgKCjZp*s~_);19!w}q!KgwF$ zJuEMPWA<0VOj_I2JhHfnQX6X3(BItxip#+% z&?>tz4}_&|GG1;BVxq9w^S`YI3{EAk%K&+%Hoy;*T*M9);+$Jq`D&|PP@G1*=W*y`Aj17r zKid7Zf(2G|dvGZl;h}cZEyo^XH3>#zSyje6UC++Oh92Q7vo&@Q#;~<~)`Qv(%gF)2 zEEH_KG^WQ$)Bo)<3jDr7`uY3b`_6uNQt06zvKn__QY;Qo)3?*uRPY8PnWN$Z?gC&9 zvh)klbG|sp{ET!1^WW$qfV0l|n7_F9Vt+yAB2eS_rZi>Xe*9mWa?*CRh*0CMTZcV^ zGRF^=!?omb4yB9~YC4n{MkLL~%DOnyb>|)pzQKY(iYw^l>Yo!z`hBKPLIfW`AX3mB zgE!2&jpv9_t;;DB#(j8DHV|LXI%;!?p)chRM6?dR6o%K zFWA*#tgI5n5GXNVK|6yq``FiNQ~AfDuoA5S`XA9*`9%T}?-hAW4%Qyci-sy%F8!wDd0&_@&~9|a z^;cE#>J6o31gtzre{8|9xh=$dB`)_M=cmoFsCiVb-*a0 ziK!yG@tswSJ@2*KYTFIZ%9lBRTg#wksJx#*yd;1@sI-@NW`;)EqJ%i&7KtUY_R3r_ z06-`1`@0JT>Ka6t6-u0Xp}nDPHu4YjvWWT7m;Z7&)}p;m;;JRu zg7L4T5YxhwczCykkKZz{*b`lT{s|~S0Cj(rFP@BF?h)^4ic0b|*I&S{A`dVyf@G^j zr%)SK?+AatL}kf5{*Mbbo@DUA$FHKm607fD1gENid~dWx61;Cnl{K z%zQLBLmD%N;%(ZLN48DOI9i3)eNtKfxz?xj@P&UolJR4cn8g9j3XgW3XffuA-wB%= zM9ZhZ=EN4cYZu~Mq#EL%+A|;jNAMu;Sdlp@#vu0;6)ftndw9k5)*lg|UT9}|D!c1R zv2wkuu1)KsEN|!|Uqf%xZD(xXG)B|ySX!ST1d1kgvVJJH`y#c;zemFx=$aJ9d?U~$ zu>5LmBM#>YQ2L@6cSlMPvFZzB@CcHzg@{d9MkimDF~U?$9|o6jdID`C zNqG87B0LJ{uX09sMR6`zv(7gaA1lw^P%#KxvLb}^8n_&N>!F@Hgni3hejOg}5-*}}m}KenOjiy<-uonE0F%k`fs__T zN=L0mN}{-1rjutoH0C|2b~js^$GUS_FDeND7WidJJfIWC^o7VZudj6(eoOF&{&ufV z8~6JNy(10R?Gk~+6D4`AY+p|RZ~JO-N-Q+~qI}%8t#`G5Q#CCD3##F;of-?a_h4ka zr2n<(AZj5hYFK?6G%A6!q)pP&F{?jKa4OJC7&4yaj zTPN!|ws4U-Ua$)y^s(#u_+VtLgtr-En)^J|_YD_@3v3NEBkQLct+!$G6IqiJnmd|~ zob`Wr8R)?@Bnd+;m|h=cZ+E~?(;f$@13NN>Q+XKywED`4Dp57hx89Q^iUe=}fh4{e zDY^leayj-9FhI;-a@eC<*uE8grsGuG)RG!-8UeJvsJp}Uz zsJ)M-yRgIS9C~&?s4yVry!i%y7H;C*W%Bva~`+LArc5EH{h6*;G4McO2pT3t(}ksNj8ns&RuS?946#k*W}Hfpi5IqsxQ9! zWn73)H;3u=(;2q;M|o|=#N{htZC55Z=lj{5<60}MK6sdn$IAYZ1rHtn6ndxxa%0ar zn9kcN&YCjznxx(|DT9ZqB+K58dg&Y$`c%G6GWr=G)9ZX#22;}3Ec#M>T!Y!vK3`_T zs04ofA%qIGeNe6DT&;^EhDAlxEjSbx75Kp!=y|N%ELrxXMZ_qmqNCwetL0w&g`V=u zwi>Qw5#~g3k@rdcp88wwMB~pr2AIwdddHEPsgH{nA?RCH zv@&f^n4wWgYD7uh8`pya*=uzM*t5sLL(x+2Gp>QMh z($o4PJLVW};K|OAcvwcw7;Qf=7diMYhp*SFDb(8E2OMe^@|!f-HxylbA?x@xKPNv) z_q9Rs%J(o{p9m_212X%0ryq*9#Qwup{cQOkI-^zlUW$(>?M72^uT3+GGB=N9>WVJ3 z0UhmH)sfP=aVKtO&hUV4_ z;6xd0fc5O1ah+-ngRPiyR1_*ZPM)zKOKxi50N)gxRvqoGfZw-lGU^>yTxXRdF6x+S zo0MB?Qa4-X01D4>lmI&|7k)XZ5?of_SnadRAY@moQy=i+$r6FSC@IyepTOje7{V$N zDiB^iOFuz#`@VM@u)CmwXD@5)YXu8%FiKJ zT#+dC%VcpOoMx(Rk<3<^mwsetg)*_{O~76WYq5E6Cz4R|Z*8grF$Zd=5=`<2KIhd& zp%9OJ`SNOTd)HEnDMm}u!_6tz%H-s=Vk^eVFnZ^nU%j7Vftr)i=v0kxmIdfJ5EkKi zEX!AigM1O3ma-O@)|<=r6n^O)!)dG9$JourkwOj_ASR3AAlKQocKd1Olm7)Nw(6PL zA5GnWyy=F$A^s$}e_Xjt1@?}D)MZM?r)H&&*%enT^cs77ZyJyCZjs!L^OEg}ZI6QJ zFW?_S))_epzh5!_QBVZP%{~>?m))?Fmhsb5zf=ekUN&#P>NK)w7_~rV3SV3c6ADHO z68+Ij8)Kg2tO$pDD4<2JON33|F10sW(aik=<^AObY~6ocq@s)*_?uFVRH;~kzbE%G z1vc(_SjUn*w+`}(?H8W3ekHs1`8Jyk=Kmw^y`!4kw!Tr2sx%Qn2mwJr1PMwnA#T}p zktV%FP&%RaB5sNTA~iG(5UHVt8UlnOhy;*MsDaQsgkBW3``mcW+3$GIeZPCh_s4g~ zo&T(njFjhj)|zY1HOue!K(M6DB?&QA*5w=g5}~6A{!vCvaV8Yo9+ZggBLx$g@m995CYo2fzJy!^dXvJP71v${+T%VsgA+WI5TVT#Na}M?Vr1fQ zPVav6ugjkfr;}aHU($bU@W%KjY!!rQ;0C zzg%@WzNSh)W@L3yRKXhoQ?6fET`)1$(xY#zfn5`~yv_G5aXjO$Jjc5iO0J4zi4?Yr zhWi%d>6>l&*?ICHdrTjjxp(>du00;^AlrMaphsqn0iSwJL9@;aGK{^!t1Azr{V6j`@Q29j1;GO3bAD1SKwvh>GQ>5r?zXmHkqfoN1A%*>SDI!Z<-;c%DTjTe**Cg zQsSjNWvD{m)vPM)U$e2ZCQ0dj+ocLWSTBcd7jG`r+>gl}Cy-@a<$UHEGGGf}J6cG( zueOd~e=LK}*W_E>E}}e(j~nicvM-?adaEwg$1->JJ`{&LZudISr^ez-OI|ZYGr)*e zjC^@5A3HR%v}_u{ zX>W%^Vi1AFiCc<`l$X6a_G;I{09#{{_@b|wW^K>40pu(FHNWj5L`^rL0eZG-61DP9 z7OVb}4rxkcB}F0L?@D~}_12B9VfvU&Wug`M?R#UWNcp?5`pInj^2bywtO5~iDFrG= z#Jfl$S2+>%4=QtG7Z!8oAl{sbl!nQ7^}Kw7e$-vsz1$1~C4p-QgIoj|K3lneGf=JQ zG#s&_La%kP=IZ}YYS7bWz9uJVrOoV?UbFiop+S$%80Bejli+o=6h@;mF?&HyS3V^FJS@j_{a+lz~+>blR-(2lAPb|wO zz@o&k2ClpjK;IcL`xVAG7=kc|2h3sAH6BJ+ZYNNTkHwB-EmIIf1TQv$QO@Zx*9=0dX^QJHTE7G*i190 zXZQdy-@77Vh+s_0Qflv#0n46A%FGb)Y`-D5-!pwwJ`CvTa*%y$;)_Glf2y+c>B^m3 zxZU3+Z04RCKAfP5jMT3hFD5b-MuFetHb&p7vCLTKAx@ENWsN5 zdE$7A%P1NjN&DK6xFICdAA|=|0~Hc}LFpt7DO>HdaXuaVty=c78lN8U(&`-_1^3ze z>l;jLYX5t+mOioilFgZ$P%*hG%zXX~vZqP`(33bhJ`663xy3&fQzOeJmRgQ#M-yt9 zQry?!5PUutX_y-$rAMJmX$!JC8+YU+p-R+DB5#pWajv4->X+S<+xz z_Z#%`FxG*vI)=JBLn?H6x&O(b^Uk}u#OPj|ebv>n(xEfC8m^fDFg6xb(OB2!Wq7Dy zEiee-y;QDwJnt96U`HRJU?r8VOUZZT2liocswDxQ@VZU3k8SWn(^D z(V3!}{qmpPr_RefZW0a5r?+3C0@M&F-yrgJ`mlu4?u{8ag2L?T;!LFihAJRK;L^_Ol+=(|K7(b|}aQZ26 zx*mseLQaK-pYPN1S!5PyJ)3&S%AJy#@@I$@-~1D=ZU3LVcitDv*H4CxgJq{r@hcXG zIO4kv|CBE)!~;Bi%#WvuCQ}o*z}rqlx%NS*4>A1We&W#z*ueuNPY0n@ZI^gTMcoDu ziW>^{QS6iM#GYcWy(kWdc}Jm?a`tH*)HQZb(w5i{cyu{!|KJ8qccJhqO}fQ9Fn#e9 zSeA&+wlv$_Fq;@N;<1*MvRa4D_uYBr?4P+J6sD+hm~>5hqVDVFjMFp-@z*H``AG-H z#Ajl%SL#>IHB@ki1~Ep{6(@NZ%eokr@xpi3bCA-(I+9`Kv>WV{Xc&N?)8eAM0Zp58FEba1-N0Zh`z?E6yB3@N=q+ZWqv=oLMe*D90* zIGeclK*zNp-4nG28m?jQg9;Ph7FUzjCZbcqp4`GccL5pcRASoX^YZhWM^p`;)7}ES zE(qjm!tBe40<~CGG}$w??!l?MfBGlbE4ZUozZj%Q?Q zB!Xa=aI|eeVvF+y4gi?Ki_ORt*c}3Wq#r_KQm)PoNr#l#`}W<)c7_Pr}?BHi+;F$F@_i>UCC6~V;H&SB%rw;)?`s3fYlT9$Ice9-8=$EJcw8A0LLgGv>|zm zFN0wXo-JN_?7oTVlcdbK3eP$_X#{eq9r)^P?XBC*>RZmU56WlpZIc*4w#BpV{FApr zBq52~1XDAVoIFZw87)wvLxqBZmGjpc;12t{uFY8!8ueB1S;x_naiUv6 z6!_A0wi&3PtOGRxC@F+ju`2!?@!3@~YQ;d(+`!?e_?3p3FuSUtrS}3_bP?2`!3Wy80^Q>aSvPo&u~>U>a>Q^ zRSE<%V@)Nw;uSVKnr>QFAWaPwyZb`SM$uMU-A9)Mf}vaR-P=d>NeYTT;?i#OF#1o* zR5q+n2cA-V!Wn#gH39IlCLo~kec5)dtmL{(0)6UUHveTDnJUFCFp*HhlC(um-6}Dh z&0U(Zs#IR`g+H7c(7KE9AyLSrSI^;3xX5***R@di?f{XyBliQ&awu)ryXVju7@e$> z)|fsOtP!EO2d18#ixdWW57f50P1N&e@;)9t19(UU)ERA4YvMbfUPOH_w;FjkshF_8 zXvcO-MG>AY3FB#iayA+dL2Y`l{}gVX$Y^E2qg< zcP2lN;IP>+KvK9uesxq-=B3Ft*BBAy|MXp2O9czbQ$g)16mlmy0>o{gWfuKX>)@;iX9`qCPBU|dAB@y5p#DHK3z+} z#%8#o(?NA3nAXxi*~~R?VYKAgw`2FxlKfI{8T|J@?<`pG_U<=E1hPG}TAJ;OLITLv zS-K}*$E_mjX5D5uH757(M+-S}cJ9G)!gSSzBezc8=(!?i0#(bfX=P$^C{l58`m=;t z{|1hCMMVtnWWb`8J{`TZ(UEYicyX`Ig%k}=74}Zrr}6iQ+<2*cH0*H)73*WxuUe+x zls|e*NEtny7XQRF%UtDoVBZU_62j0#zu|vAhi=iI<{I6CZ5P6a!xA7Tr#udaCiqw8 z*Ml3#O3Q5Q$S)ZqoueI?T z5r2%W$@}9MHxI`eXWAKly0=|_nJAtJ?dk@HHz%*+Kg{^`%~ zefIv(YOC!#VH7WCF(iu9kmO9m3PL!oxic#hO)KucnHL6DKPK1B4KD*Zd?nX}uqS?B?xTW~0E#b|Uy{ zTz!$8XHDa<{j~mv)@|#7nfFtoqsrn>9%{8nzE<&E{5eYW>m8q(2-xhZxff_ZwGGv> zWvvA153ErENg7-Y{Jj`O>jli3%3yS_c04h$JnHLyh(q z($X4F@9`a#>GB#6gTlSB!WQhTv5x8E^Ha_O4iP>ZEzqNfi&jg6MHC!2bvhM==4ZN; zl)-HKWTOYpSYu|FU8(Sk*M!lN?*gtDo5YpamgaVaESk8=ZA~@;jl+$t%ex=plmf(w z(4-YpW4T|RtC5l6;&hiUfH5&zSS~t(rjh4KUESV0UiHcmBL6~OfPTc}NyCGtCgTb0 z5C!Ln^l^o5FObQ5+1FcBaqY%W>tR>0CC0_NAH<39GbNQf6mx>)vyICwRQ(VD8%FAx z7mHzx`|2Tk=t?+5q8yHkmoY*ec7pcIhneF35`ds80DQhoN_*EcSTA} z@XO5U_$&?`nM`>3G>3x83~szUwKfuP_b@}!W`+2l4|4^sUYBaxJ2Z1tfREBJeJI|dfDRGCP<#u zz!*nr_*5p54U$+mjUZJB=|B7zZ?EmJ`4~0NyDIxCwvu|~AHMdIP3{&iM&>kKd8kq<(D>v@qIpAN$)!-u z?xm%cM@e3M5*r0mYz7F}Xl;s#Vn`IK?aBIDoVZd-YGIvCM}VEMAklJpdkptBI(_-$ z#LdZQVSN`-|L@&ZK&dV|GdDx49ib*`SJ-lr#Y)-RG&y)<0GZWAKrxVC<#!PnAJp+A$2jjdrj5-Uy@(nyrj_KVlAlp7KS@egfA7WpD%TDUt^pnWDd4>Zbybt=#D z@lHm;Kd5{URs<5U6=CJNK?;6t(aXQw9EN80jd_yC1!dx_#sPRzo}9aXz_CoJ1NL3x zS08*Y(S}BwHil;4_!)i;em4+*)}s?zObC6pQY4pAb#$S7i*c z&v7f5jt#~MgL%%U!zVjjiFu^#)CYVnwR81c)PFIBjlI(h04|a2K9zgkknM8eG-Di4 zfR2*#jYmL!xUME9+P&Ufwy>Byq*}ymP`$lxG4b9$SNN>fsorQaG#p4WHr2!vo_VP~ zEVI|7;r_YcPqlcJQu6bA?|cv_2L|#et~k}7DPOKAE6zg}%ocm(#f$5xdxHEw2oK*| zr4}hnlF2Z3X&9~9CL_qtqRnjr!z*??YSm=rSc)*;wiKR!q4qqWT3lRA?Go3Xn9y&M zFLusy8iUop7(X1k#9mvgjS^+9bf>sGEt1KHZSY;5+oNo1q7 z3yJHeUZz>w5#)ytb>8`IN^uOIX8&eigVye`qbxwd+yxRu2W3$w*`!RbzVb}c zVUB*+Nqeh_pN|48l9H`Ebv8(+s{#2o5#AKv)0|p2@pwB+7IP&iVpXv~fK8i{{l%cG zo}Y%7I1|5s!!6&X4!oD-(J=J`TPXeE?Jo z;e^a)x^8j}Vw+v3Zsj|p2msuuiP*rN0?fET^f5DGbi43+?&H5ZNn%)6k%RkyDjxRkiT!Crxf`X z$66w!HH3m0?5JD6s4k^=OR2~a8=;M;G*2mMM6~0Scz@vmkDh_|0^6hC??_&b>t}}4 zD-X7k8LX^N`6-#e-(9wqo)!#sXgIpEfYB*UUKCbYrMX^il2UJ(|HA*UtL)cr6$NSh z)I;qz1d*xTk*6i){9CQ88QBvzm6Yb@HiQ@`v?@Txr8L>O{_Td{jiSsMSyPZaqBPI( zNBWBIJ;`)9uB;M>0FD8DW?K1@puKJi$XJYrvDZl@nwSlFzv-k6oaLkV#hIJyIZ2qN zthh+N6-b1)cjfnk_m|KSs{)qV?ZB->j!=(w#39&4gR{z*!`|VIj9)+#o(g}H!cHtI z-;bTrML&==1GKSJp8OmuP*B3JxJ#g5h%Xz|k|Ev#j)f|U;{C7!Mn-{i14xFOrQ89L z1x_&X#+pCt=7g2mOFu%o;1?gb@UTcQQ_s~gDlSpju*&3B$DCoZnV~E~2Kh7P+pc#U zL9z)kPUBpS-7aZCg45hQT_Fx|UsH*9x%FEOj{2$jrIRO_MDPjPZ`+l;=a>IpQlzr~ zU4L|tTAZ*0(EE#YET4q3!UFo@@7VIhf5n!2|1-8+I^I4|@)9ZuIx%zcKbt74x;dqM z_f&HOcvrs#_^5*W5b>v<0B{j`wQl9aIW)Sct?FD4Qf-e5JVpo5bhwM8-_X)!eck?S zSCN_&!PX9(&cJKzrEv>)BwuLaU0Or$U?n@IWK3b99Wwz8-=m z%6Y6fU$k4hvmnGXJDorDH4A&XfLN)3ikRcoYj87khLS`Jw3a06xMHedH{pLWnN^!+ zY+{x3?ITkhO+~WOACDA|Dp2gYD0);Y`Sn`K%dt=GiKQJugzQvSe ze3*9GOwyp^*u`h(i#;(*TM=~*g2mb^&qT5pP0n>yhI(#6llEs9nNH)+x()Gd=#0ok zl@}fCNTHen@b&9z^PgHI#?33b>utAoY|gm_3T~P+ZWTU&3rscdreJ(PUA@A-Bp%8} z&Woa})la=N9Lu~0;V>wiEt^pvDoA=%@WPZ=t2tqhrWK$_-I5cS@9-oZTI{9=$|Ii- zmTtL~R%MB2#ZhQFlAbggYv7pF=cT%StVSoPAx#~ba2jfrf!PiH?UnVLEVg{uz%EW1 z=lTI*<|KJc7JU@G4KUbGG=YmQ1T@lvcZh2Lb{Xi_Y=iZ(U4e-@=v2*yHGc_1-FM+GiF)98~ za|MKL9+=XMV=UNRiqnS z41p^)tcYf68+Sn~{AZLsG~|TtRLxANH{O_|ADyG7M5So>tyGZG9?F)`WMls*;?JQ} zjMb~%VV!`407sKGJTACCOa9JTtV5DMv&+xX)$%|c2UUh1zR4`$0ncKTuzx-=ox=Cx zK-ALO)C+*yDF)|1^`B-3kU zA0hhh=ky8rfO@^XuJG>(H3Gp!HVww&?`?_OXYS=JEe}!Gj}gh zv%w72jwo-%Sf^Ept(DY%JKMv_OAQ8ktJ15S9qU~CkXhclCyBh?QKFsyTuHuG%D zAEaeqrNCQj8k(2H?)3jn7PAE>aw|77BB=-AH z4q}F4$BDOXj7VYzk*D)@I*Y5y#!cjvC@NTXP7=3xu~#_CWmf<5=q-p?sFN$KfOLa8 zOHE+8kM|PQM6=ns_~Z`NFiIXh`pMPDO%XjdtVNT1J64VNlNMB8d%#O*&Y7k=kWqj= z=SoS;xw!t8XIA#zW-A`!5ailRH1j}u-Pj|awz(-hqfk@s!o6$t1PlCF!1EDhHAAgJ ztTU=gK9SF2oi`~D_tnmQmjPVKvpf))GS}QgwU@A}Ke$%Q_hA}qT2Mg1zH}4u!x4!y z+`J+tB|CAz2q5K@8`5`&RJSvTjX89!z|3vgm*-c$9WhZ8=y$M>0TMRo*f)~qLgjbR z$oci=t$6XBvrn*#Z8zNATPDU-zO)Hm2~6Ranu^Y`g1=0A>*k~MZ0CAa&Y1FH-Lkt; z4?CCqjREyZG{Lo9!9R3$ASEhBa=iVjE^U8cebmYW=O+!PUj&z8x1I#&GW$09W)|Ie zuBjx|1NlxHYw~9*pu6OBFxD*{hn&qj<$N00G7Bq=XL9JQcK7p&iQ;}t%Pdw!_H^B3 z?U!%#oSJe)8*V|MFDhd`jH^5c#W41(A;thdm#_Bsurg2~yDeZtDYMU`KC8o6nCwOo zW9^43e#AEk^(qACVElP(k_Uw-jRwhB%N?rJRVnY>(4t@2>P|@__Itdo*LXH9am=G2 zoH$6A-$4`0g?ttH?8!u3iP=YDF{PWo$V)jB*;BUVie`~SBCDo1%Z0mw+DrI-|3RhY zhI_$t@f`N;XT_GaJaP=cWZjlNfv+pD$`-EVVQ)@^`M|?x>-*~wX0?VVzfYQnr;fTY zIaSU4)p!v0re@ec1eB?@r<6Y!>>aqZ%;b}BB*u)%tR&K*XJyaAcc3SRp0~aW<^{$4 zl|8Xiwvlsq?4xOT{x55?RC4E^)`SnG9Q8xoy{@MB$J5uVRKe8T%RYm;fS&q0n`s#F z!3-Bz=Eq3@lTA&(Z-Ao;W>SZrG^L5>YEcx3<_`<0xR&)y&3(ekyu2!3X4Vs9k4BXz z(~W8mNrZ*5vNG=8`$psOsW9gA47T|6Qmxawb!Pd~mwVf2vS0b;duZ#(StGtb{4&_P zkF<))&U$V6JaQ|mY!~ws3(E!Ztrt*nyDesSItPLsUbwmjWd{vp>whX#F5Kd502MqO zaj$mBka$(%(`fw$|0KA6;1g#8t>5zTx=Mzg!hD|uuCAwG5j6#fog%5pRwJ>+t#@EK z!CKs1-uMUx!5&eXdkMxxc>HEyThX23q~KC7?76aTfcAMaN0P%tML-(t2g8ZIpVqYA2LPf+F` zgnU7htUa0YbJV!c_atAhcuV{0tK`NP!|&s?cipObYRjrKs;Vc$9=AYUfBH1X@!jtV z;(zL0Te$7ROx?k}=*#UQ+%}!8?qOLb|C{M+r@|R*V+EEpOYNR+_71rDiT#hsR@v+7 zImcc8-b&9v6MBOjrDXw59}35Bnq*y54y{?9hLsJ-)CcUnV12RHT{0R~asS&DX11c= zb~vj3h@;?rmHSGBRM!QPukbzHX&+p|=>#`)xFJ0bPvPkVJ)lP-PNqvo#reSM)# zn!;&qReeNM#migE$qyAYLjel9Wp1`lHc}Tj3PbwHo%{~Y#p!*PjjvPEpEoEEkg{D6 zDJqf$&~sB$Eh2v3vzh!zv$n`tQYf;FsIcCL^(w|XqIg~sZbGg3Vok=ssg;xm^Y3Zd zzuTjsutP-cqfhzn!U>$AQ8@ULrGakqXBIjoWRO=|C2u9r;MSF}2oZM1Q0Ri!rR}(x zk}PWYv^v6StLQ~Iwq`jz5qq<1LJKU&pqamqKWwROc0}HD=+oJG`H_XZ1oPhT; zr&v%9g^8=+ByUyL`Q5c7$k%r3`l6~~XCkuqzPtPe7MuqBwiBF2rR+o#qevln^vgzm z@eLLfXLg^p^!TlCuLhkw35a(#$?UZDY$CL3D7k`*i|p|{;3`*vXyP>_C9STN-=Im7 zpHjE*IM`j#{oGyJ)WbU%t`=r(Fd3F}w4 z#Y@*f7o>(t&&q1sr`lIpb@+=qf?{@Fmzj^Qxcz?UM8NTH70QKY9&5ppkggSE&-jeJ z7y+QQpwdc93M25KLhg-!7O`K>X+VxXZtOzT+SF!8*iq`^qz)|zb{B>u|DCCKNqjJ> zyi|tO#fbM$7R~%s51)a0h6@eKQ8M+(JKSe2tTaMjg+95#a!^L*)M)Rvu1fVQPif7w7FsH;IMo$mQ6ki2cjgS8KZ$$w z9DR0)riJ(wY!Y@e0n6_afQt@`F$M|sBM^Z7Gr(<63{-?r z$4b0c@;>ajEx2d;#&9dLLh=$Cm|HNW%w&bob+#2gGMRCFk$U7w9}{u4gIQ@v=?7&I zXOM25C5Fs!B{#dG4eI%VR00%knRP=ri}yhDi3xtXwk?<3N(`8y2mWm%092Z#YiPKt znyO!3R1le=8Z2Nmu+Pi%(d2G3+Xmcowte}#N(M}KoU1xwDXIb}@(*lg--ZEQ^qKypc1^%Y^D)5F~ChZvxLyne~!I_aNL+j)p^`F#I&HW zB_qoDNfoWSeu+t#p&$j6G<}Xjy}-Tsb<7Ea)1@tDCu~+?{KD3JW_u7^;)5gR(t42a z)}P^5SGG)JdQ{ieTgQm&;WgX5B>Kd03VA!7o{4_atPI5;IEYoet`@?7Do1K|N;`JC zeBQ8QJs#+SLDkfo;c^D{p&t5CclTC63w^YQOY;?sJq2g)DJEd-7L?SWnf$p2)xbF! zayKZVt;&w0chl*GH#M0Q7TLMXs=5>f8_?#y(BD-(d3__G-m>eig7tP|Pa2=?Z_;-w z%siZqE0lHHqcwMry1W}Vr^~aAY)d8m*SS$3T7?RR_Yr;ILcDMzIM3nTjPMz(5Dj2Z zpOwu`O}gpN?&g%hJ=^d=0y3gRdSP|&__SEc0^dq8s=Ob?PrBvLD%hBVYLyyjEjoi z*W?_^%4%4=Fh9eVZnZ%RUHsc3x?8k3E=Da?TDp3=YU9rR2J_&W(wvU*{`H%e~}&|NaX9T2;_ws}GCMqH3oA)#EJf{`$5ek3R~#UuD9IW2(S5@LTOO z0g>dmmWG2~C64(qt1wmZVA!)p(-u?+t~MQ;m_fR~R|k~Oy!IER*bfxf^z)mjuAO^< z2W}@Erd8h1`f!tUU$_0c#KVKqavxV%=(1|y=8(2XGl*Z*t!yUqBz2^;0r_o2Tql{ z@0aZm!mD%|cbS{s!$?-nVu_^#?pVU^%G1x?WzBV>IGhiW_`06Ad0BaIp6^X6#dwTB z?gtt{VqH(L6ys4XXZGF0@Z;U6OsgydnNNaYs}y3`-SyAUtxM=6>7t=AdNn|}$zd{6DZE*_b#|KhDA5oGEOM}TY zLLZFK--tN1V$Hb+K6O*DQLYNo7p=Gg1aG+NVKN)H+-2+KD?_l69M2E|tMxkD9#;Y- za}_|1F@X1B_Qg?*=ZjdWF@uhVcVwA{gi&KGa?`;O`bPHwB-$qDuqTqO7~=%1>bqrmQ8eZdu9bJ@ke_ zbI0_pW0M4q8Jf*_e!s%_gFr;A_)MQx4Z7x+R-v1=0dB#0QPStFr+$i53>kT$M$YLr zg>@dog~)uzJ>-E2N+iRp=S|4DLjbdhw&%bIydY@X5ZsC-62hAu+;E4h^K@>wWLkGKTel6;%OV{)6hN zIOz0{d-b+W*I>2luAeq7|H1W;^XkC+4d{5cGdC8+{$pl%2_TT4dg~Q zBW$!2uZ(i&)ugRp|fB(?@YrHyf1|a9LFza5Wmlj~t6%r+ikb z)j&>5^eKkS=}6>?Z*sLhu^w-5KNNQ1Jmr`4i$akwyh;fokum`lMHe2XJ(}ObP4g{{E#_H~3ugAP;e9Vy z%^&H;u4DaT^39Fml~U-5oHwSOns8M3qgL? z@yiBetS&QCvHZTXQn-3#p3=sUuhA`8Kw)vrTfq6tAOyF-j;GmK=!$A&7SBuC%;ftY zo{z41|0?+%`OWz>>t`9CMgS@o+a||T`WB9f0W@pwJY-{zm{Lq7;zKCiOU6IUXaOZf zNIZG=`Iyw$)q=eC5e^Yt^KP%}qiuy>$0#Kq+AA_qR~^SVr;BFIHOZzBXEbNJ$(W*a zaXlp^F)`@rv(nft`c5DUC^G}Uc`)Th3iQmDGI>@9$jvd;^%0=2gD(U7_*Us5OY4WJ z%9ep2#~}iN4X^UkEq*w!8~61$<{H+5h;{-a3tWlqmd^Eyv!>O|BmpEj~`{$#VIVs@gl7MmaenC~X#}*xM91xR><50VdKOZIZahi4(`Mga^ zPs6EpdQ;iQCVmwkb{U0=o;gBcv!E}7`6qgWNh@V5i?VJO+Pa#bs&9LOXc%U3+G$XysPKzH(YQ|G4rBNN12Y@Oq;MF)r>WI8g47@gM*s-&NQDT*|y+aQ5_uHaWcRJ=nk4v>dtPUgGoc*;K=!o?aS!vdM?k zC(6q3iP={Vo$X1IDwE$Dqh<0V&re<4v3sT5&iI@d-(;Xz@G1wI+7*&V-6MRNW=RI{ z7RB`MnW5`QyP>z$=WQMGW8eUL9aV|JKfcRq>^)!s4@pY)?SIRZ6Sr``4?Ec>SWyrc zWSttY^Dhfgjk+L>kGrTH?vBA@K@~ud-&bZwGuY=64!3Q28f%aIVg#jdbw$hIrXl|M zdDAx_70o+g4BHcqZ$hd?fm=1a6l{i~26JoNruC$r{^U5JxrFuM5N`@=@QdkXX+oEH z5X`rcK5MIxf&_K1Jn+R%aW94nG_miJI@hH6G6eXlSUy+cF9o!Zw~xfrGxjZZ!QFxn7S6z?*d7-Y#&Xkj^PZT6P!y7$URwT~ik&l# z0!wnWNItb5S~Iy5_TC|KBC8pO4hjZNN$u@0CoJ{&M<%m()g%c%nX4O==5^L>tHXEj z(Z#n$CT@YM`i{OQyXfUgkrbXns%zHH$O^YpX4h`Vn9LA(=KGW#&CK1zt)GudWD>2! zKhi#Lnmu2+N%2IA?B{kHTcaK-E~3VkKT<_Wv#Oe=i){ssemVQ81+5PJ!z18JW&=Jf zvF_tX1dqWj9bT|NH`Se``0;#UDAbxo2c%s8HrOn3B~t=tVWN zLP;nqdNFTcoQ2;fkJdfN6_q`mM8Z73Ntm~Jl=63oEk`Zf7fAS2mEOcapR54%19t0y za&HG-4KAFl_po)FkeYJ))(kafVHDggN?mxqEX~xhIN8{3x2i+qZ@mlGr|!T+s4l9i zhZHunrNc-G9=E4pa-5x$M5~3X^`xzW2X<8Z4^W+r>^JfmyDj{(*?{OUc3}rb7Pj6udWF{$Wha4PmP9B|Y53K6{#m zG@e{&9}K9%jpc>c4257WX~}Tv@r?ViSKKrnPui7@@a{0UQJmN>{PbrcISGEOi#jRp z(b~BWT{}r73|#c9t)Sd1-{T=KQ~P#uw#n0xUDi3Xtz;S)i zlvcP}-YJXY{!?pl&rtmWH3|Ka7pW&o%l4^-aV{&dM|f$!Aqz^Jc{(JSt*K9#|yj%B-fRAHu9QP{_Ha^T!g zbd6nb9k|VlVI|>}cZ*aVSJz&N2KM=bN}K_#q@vv)uVgFlTF#B!HoD)`t`(xQyGzB| zZQE8rp{eTs%*+H{QX);`xDl`kKDYAb*p@|0ekz| z)ITR-l&xxhsdcnRNk~Z%;Rd~f$`}vra=K`ox(|W|#GLAWScR>Sycx2E6IW<`4{gBI zyVod{t6nX)pYm0ke?a>yTkDe~pS?(BbaA^a9D9z{{raPJ-Q1OMqq=b5@=5jR4boY` zA zm$7&7^eev$`QYmJ{Vay{pwJIvU`;ol&c z^ex2dA7*Li(cindBzcAZLB-h=-trsuvqqk8@svjXe@Y#!dOY_JqQYU6dOLui{Z|~2&WCTLZ zAWKUNbc`1Z3hkZ#Nyyxn1@fQ#Y6AOzlK>NA<8dl+fp|MY3V+A$?I)}wR8-UvN)*;1 z3h$7!|EM78uAC45Mamx}!GD4ccs$xouU)+|_0SvA%IO#Q_pR)dmXwsbc&M{KrS4_3 z3uG&1u%n^~>*IfaVB1knM$~_|vPgk@?UkS(qw zp+wwo&5pwvx1rpBM0auX?oq9J-8hR((ZcOrlgNH{^7~8!7JA!@h$`o>4S0K?T+&tb zK;{t=a>Ok(KXlcFA?#CPWJK9BL3Z81M(e%FALuD7fZMjxYzqjYt_N30TAsRcjZGSx zSTtL3p*Ox24sPRheK7u4qpV6Acj{;#hu?7bg3JCQ1!Qj6;1}#{MeU6EHk}3(xnT5A z>4xsp9x&vGkXS90mxq_ur?%2Qm>y$C`@fo8yIH@P?s_+{3Yx%qnQC&o!qAj!m0%*v z*Yl$(GnF`Iq(N9MGOBc{P8k>&=#LSD@4PKq zjd>``v8g)!_hkQbjEZR=bZ*iXsm6?$_C8cYmDmrni7|>V#sGrf7-|5GlJxA=9-q(x zM}GZ_f0vdH^DqKnA(W|>)s`Bu5z@OJ-TZGg`=0}YiR}1D?+?L}c!kd-r39*$;Ut&; zyxdoQR_mEf46+H=wXR&ZUaFa1ER!>wL5~iFeEVj`@TZ-lyyU&Vm)w7i$|w{Hp{XOM z@(hw=wNZ0pK}sbh@Yh=VmvrFNn-pFE7C%L7$6hGh`Ko@Z1f-v-_8=>V8XuY%|D=F7 z86=LjwMFLGi&GFK|5M)mlstV)aIr$h+O_=lZsPQKT-th|_EXtcfbaA?rFeU3AM!@l zuUE5VLQq~SAH=IL68KZh*+q&V6B^R*z5On^C1d_s7?_GCMbnakto8pO*K|ArXWUfo zS_cSi{7fCew5;F_P4oVFCEw2)$RG;GNbq${Rn;#@MzNU*LKjeCD9B=D^jKi`-(<9Z z52|>@mE^FB#L9W4z)ieCD62N*DJkdbJ>8Bp+zw6{Tojhz?IH{^xcz-0tkv|WgJi~o zVBD^K6#|Mp}NmyvFx@=_Y_k zm&Vhc93=DL$`;=E>lBL5l-OCFuz3guXmX|tmwrZ2s<;`Oi+qy7v2_Z)*3~mzHuJf@MQY}y8 z8(}R^k>Ps5oO>uNwspUY#$qx}$o~A%)>rBTg&+avI1qUTL`7xCOqI}NaMSq9chN+6 zw~+4h9t>9#zg_fzz_A|+^{#$196PN0q9{H-YD0~)JAIT&=^%TkB&48(9MFpG`PdIb=&cp8PAn#_unE%eZ0fJOsQEc^$zRLFn<4X z4dEhyiqkM)_Qoqo%g01+GE(YD{+n3t$W~=lmK`A46r4*xDeZ{lCk_q2*7c3rF<_QG zsJj+i7=M>pD!~P21&#ow_)(@-)p5$|`6ya8qyH%dAnr2!3&+jE9Yjb28IlBx@P@ph zWxrjxw!S~Q?|#mbwiD}V`M|H??Be(fhuES0hamaKG<^FulN%8tfVN8%Tw0)@d4{Z@ zxi?4lmn-D%)&M*FX=nJV!LsrUwMQhI+!W&OmIDhdk(MK(n(6bmbQ(U$JLcbJp&1|| z52lQ*TvwLQni6>8_M9}qb5`J9iER6yELf$xLnrBoWTR)9ZWRO?lza4pqG%=e=UN=G z;Qq+dQfusA6ppEX39OBh$jfm3E%>(tqnAr{28Y(Mv-Jm@_kD6o3;w+P-DC z{DWIqcL^<{gah6a7Z=3^owUMSml+PkD7bcG zvp3Pm9#t?9I3rdVER;%@w`TRF_J8wd|MO$CdZ!u~=(mj$cfi;J%|;0ZXXSQ)hubIp zKGw(Pr-raH2qRMP&?FY}(q71I+As zyU2gEgooKYWEhH%dtKs=PWCkCQtIIG|8v)69}=$g=UeSbgU6JYqel0N}tj@xR_gdU(RsVCc z|37*~AG0-BuxIu8Wl|~T@kM-#2uzYSMn3D2wi zm)p_l=T>fI;+vL2(HiOxSmt5ixhaMl;2g$PpF3+eM$OCyjY=hO&wGr*#&0RZJlbASI*J96AJ zw>tH%XpQ24KD;9RpEmNpUUdc%>PRvTQ1KnmUmUUp(Oe9<{<&V1@?SlrE(hDmTCJ8-qb7AO=dn_)W16qx{=-v|sGPu= zUZiZHwynX{b`G;|-JOcOhqprJ*Lt#qZxzw|WOXV`FC(e~tsZo|rCdE~V5=w$~WTKjoK9Y)KYr`?|N$tk)o=4b9mmLLKWb z&1#Zz$8Szuv%R{FO5xxL-jH1D0!}zuq8ju+jt}M%{fw-xx0AN_ zZ$T>u&3(`x2`0lL2^>Omz6MwED&HO$yYDVIWgCx~P6pqXpAcE^^n|?(z(OHR%(ZeY zXlI+}8wuVk@L=)W?6<#wA1NMyT$Z+8>J~TyT1Bp~SGcBQ%Y1?vCpnkcL^?FBt(Y5Gm3@ zdJT$5mrm$Kr3MJS7Zp&D79cbQ>7j)tC80M#s`OAp2k8On3c_=@&pFSz=f3y-_Rfc} z;X~Ma&&-;&)~xyeo;kaI3<9I8Mz>oQ11V3 z;i!td>l*5)Z95lTC1zx*Du_%XpEH|{kSrZ*$tx-B;M^6MZjStRuRvE%<8WW>)8yyN zF(Fi4{@xty;$_1&56tL#sU1sZ?e`?Zp(%AKGu!p4J8QY&3_wprfj3**y+=c zgzBqSKuEF_!Q`eRGRLPVpvs)+2aVN6A`AB&+oPK1sLw=~*PjeZrL(;WM^&e1RU@1< z`u$P7MK9nc1<$=Wp$vlV@)R5q*C~FLHa>7{Y}#zwEX8jqTV!yXGv>bft=rTR*BeCh zaf!P9rf)^g^!jv8?AXAV(BZi&fK>Wm_h`Ty86QVI0MFc9%v)~$`fAdTf1$a#8@~)b zEE~A3;~tafwr62Mi}U)*%pO(sw7Xi8U=p2AnBz&{OQOp8pY@C7E>pj`Pix__r5x`T zFCd!Re-zQ(9cHn*MsO?q*|tLR#od}}?NU9gW#RKnzOV@6y8*;mOr2+Hjiq&}EoePh zw3d<}rqjR~S=&d<5%LrtoOBYp!Bx&+F9klTNfsFYQ-=SaCdkxgVB#GIH(y6KbinGK zuA`3zGe<1k$qBU86^kUKG%ew?F9LEJEcOv~Z{X3P_`VBh9hrQ-LdxAj%!4kVTA}um zn5?1zqX~-$SdU83eZQP`b+JBwHG}eFhh*qT_B$7KaU8JQJu)MMzsqrwlnWb+)QGcF4`u zuY&sNp`ZUa9ZccKp;?|&gQAxObzK7ysD?0{9sP}P|JCvYYPp;r#2N8~y$Pn0E#Cgs z&M^wZ9BGbz{iOw0-*wNoRzHO=h1gSs)`LW16QqgMK;*R3#j%eJ@Tv~7_T|TZ^RSn> zD2Jw^5NFErqtCaN57_p`nbl^l3X9?C9YAJ}=_B~7yu`uBOrVT1bN?fmAz%~222m$g zAIFjvm`mIyaZeczERA)i&zj>%zW4Ns>UxgJX6rcZhzT>nVoKug@KgP(X6Aw@2M=U@wyrd4&K?qc#nTFoxc zH2YpqXCjMQo#l`RJ*qC8O+FRw%wuE;DrXIjy_}y8N$IsPg`cD%O^UN$!~Eyo@7ajZE?b4tW< z9_;}#60e_yd^B72auGMqR8)}H@0Dl0r-|&0%zdZQ=%j3p3Km_|GOoATS#ilgZut2V z$7dQ@ZvJO-{P%@mV5RPicX=4Tk(G`GwB zqVvv_5njit~!Q5{_+Df4-6yV&Of2Rol%jl3* zO*VzhNX9op%qjyh4=kXzB7>Tw;^W|W(5xTBV+GHcQj@~)tw%_SNo=|7y=OB*V=>|1 zp%tjPcd>I(hjwM8L+)}PR+|Q?jDGzqDs>F0dlkjN?<1?0Q7MRMdr7hdCJ=WdR zj9=ye4emzTfMnPQgYvH0G2sqpD&P4)|X64M~49}Ju5?2 z>rQx6|9^Wy;a2!`mP#$1$Ac*lD9Yg`ccj8Ls})Vm#EA*it!?PXSv_8n7&BiRhyIEZ z3VdX?qp?qsn^saB7N*icd`JjlcP5@yB=5d1#Th7)V`iQ!eqo``KJ)Avchq?jq)gcH zzb)IJ>;DVS>wmldfBh|7>3DIpvCVWhH7iZsz|dF$zSN)I$Q1mM`@P8OSI0BE3bwt| zBhX{zER%bW1+#Ys1x<@9Wf2qZ)i{1OI0Ka5##>a2-$KW9qKSkoOht`xarqM+`*;0O zfb8^71KCk~yE?PfuTVHwePTUkb(+Q8!$iOWuaiSBx{Mk2v_4K%_oP36n$eyA1>AQw zcNQ<;5SH%drK3sroRcuAo$dYkxb@e%%r=~_s$+fs;0-MSgr#j^0JPzQnbrC}HQ4A# zNkwL@DLy9L42uh#!`!ddxL^cM72qGy$=EL;u1hM*`P;A?y}8^M@{B@8Hb z_KoD@Kh@nkZJaF#U$I24QBn;BaEJ;Sar2eE|ISYN{l$0bf%3P>GC7qZVxwmA`;|t# zMuCAg-DCnJ*oVBqzWr!4ZrV5dWF8aU-)(%u`$>LolI@g^tOVy*41zg%sZRxncrN!-dK%?CbK@r z7Y?Y~P^s#J%*1|7GROhNYgX5FE^1doY(i<*!>PV9_D{>!`q%&2QC(f*ua z{xbsl;#Ipriq7dO6l_N%Y%yS2-;jKl3r6_S^D$q3W$(L=#M?ZM>|v@RgNX&ms+>f` zc=+5MC#xOulAPh&*6Ite_SXxqk|Wd;N_j-a{p{t`Tk!9N2m zlti;M<#YGz1-7#>N}DaJkmbNgwP~RfxzJ1>SR*fT9u#quu1%)F@vVi!)vgVxl{e0; zWU5vAyvSMgIn3M)P|O3ib0Bp8yvG7rEtid_npK&0enq3_uWr;D-kQKP@_RokrhzUB z?GXD_yL14xrt>5*cLz9V*k50p8WGIj}`BohL05~n@HHo8tdp9Imu;5 zO2Tu$DbSDrUjdSuyXF--{9x%~%`yl{#P;vWT7k;C-e?MS%7F(4e6UI7WdO9WVu2(z z39Y-L;_bj7N2+@O$hrEc$h#adY=WE9)0Chh(Um!9WQ=l-VG@-}AOET`Db-YoowOG} ztxZ~ljKxPGLICQ}-%9lV8N0l~^i6i_?~d;V`LJ{+uH99H5ZlFdc@9`m@UZ#mTyhj0 zw>FMfLveJNVN$z>OBX}&ve5V-P6ZKX0>;ia!wQ4|h>m&02|N^sA%E4UXS9FO6%ME^ zAI@)v5mBl-HK~qeh>hc0w))a5^Ld*rwe5v~AED#N1c;O8-XSoDQ^ zPL-kAmLS?C?6&;!{>KW})1x;GFAj}^-yCGUo>r(J*ibN)dnrsR9jL`6IKUH3meiA@w^o5Qpy=2Q!w-3W_-BO7fxhtvp-1aARq22 zLg_MW`)r`;EXML%@dSQGg3gX!_PMiV&iu(>osGFTOue)+kItA}ugTLvV#xjGM^O@w zh`N9tj{EJmW5Y}==9nB-3D}Q}p0ZR=a7; z_L}T_Pk)x^#OY-fD&@VI(WuKUC?lQwBCNq3E z#l77vzHbAiwqEEXBUk32+ z&+xmmg>|(q`%mV4>^AGiM?bqh?OYw^hchwQm1QhEW#?>mCqenLSW|l6pMA&Jy?hC)J&a1kh z*9s{HKJ-3Q)mPEX=7pz%UM2NV{(P#Z;u4;>?|h>sQu{_gS!AFP6FWdium^MMx^)Sfq26OOm1_1}Ik*uH$aJVS6hm zVM%n$LeA_PoTXq8B&sHm;Y<~_E1BU)FKbzZPpxP&w5$~Qsl_FzrTO+@`>2=HmjvP0R z(J667%!#k1e9NayK=eMXe~5ibQ%@cO{8#CwT07;I^>MV3o=)Myj4LL(Skg2P#RcED z>OTJtmN_qTNqX!45PpA{obza2ka!-%l-O{t;L!gC9T!H{7diER!JXoMltxSGh21DO!<9! z{weovNyR05c?WiQOqS_# zFD9CQUW*>AGlO;q_BUuY2UwB)Ae|%Q6dWQ@jxw&fc8Dp*fH%4kY0@GG>o%M=XF|kDh8Bg0g8%Y%|DG&N1Fq)a(X^0H zJ2&2*t8@y^Oh)&;tng{&(4BcJEa;!)7vwKZ{3&k$d4E%#6;K0@6WE`|ne1O6I}b~k z2Rg^l7F{GHH~%8gKQ0+HJl~tiKW-tl&n+!&P*Rjo16%~-K1dx|wz$QS-*d@sb70VK825d7s~_Or{Huu<&dI86 z#(kJ`auJHCJ}J&|*4*U9O;oe5M@p5YbP@}){mkuozZAn&UY;*ZuDf|5c!@1coRSNs ziy*q(D=mwwoEswZXo+3&d}^snOKW4UK4s?YkZyM#12ImQrSH8Dbg z4+`vLeu!sGbEv&{|6SJ=&mU+ae`HDToXgA8t4n2`pCu(%$pAVN`aj?P-(3KFFd4go zIlWcB2}wxa?KBR=>Pi$G-@$Ls-1JhyO=>KMrX~dIu6DUABPOwEN7bUKrUp_TedORgQEvrWf4s zblwH!|B+PQT{W|Jnqe+WnwSFa_)kXxH5sVw`$%MZMWG^ywtI^+U~MuK@ro_{=}e$5 zlu8R7B=l~Kz8_cScRh)+j+aL7Hi1oMbGP)}M`=@JfqLGHj-hNsz)Jh5Z!BNg!Z-2d zXyB7Y(^o!2->L4P*M7?1yvE98(Y|Ey+d;Y$5W{UOA$Y%C0f#ykMQ2$RI&`o1JP@m2 zk-n#>xV{%R4WD_A<7$mN_dHNH*Ytu1xY5}BW^Ae^XMB70eJ*NA^H1oOh2Mj2$^K`c z{rwz*jfI!cai%~FK#wkiv0$PVFnN9wLzJ!_eK|>8Z~``L(1R_y=d-TZ_0d`TKFcK$ z-2p>ai15v{RGGN;_e6f$XQE5N?}1<_@jtyA@5;gkh-RZKo$8|pQjWX0>{?UhX{Uk^ zzgSjkLB6)XZrb9cXI>Ti*3O*7LmI=|sm2mh9%Pj7$hPba?o$5xag&jqM(iA_GTr#h zX}$LOU46MR=zZ=DE{!dKQQoMWX_Z{7y6*_U%wa|i75~*A|LU3lV?Z8W7+ryA{D>BZ z=wjPflx!m&pMC;?Zgzh7LcIn&B8vptu-32|VubC~(qS0*{&6|haUa-!6}V%rI08Yx zB3CUxp3u^My#2DV{cP>jHPVhuCEp)CXRHKEVa07shkT# z5w(2`zU~$yo`fCUK?#OAY<1Scr~G%cQhx@_hLhKCglYg^#ay^KwbZj>KcX)}* zl-m+yboeKnN09-8htqUY5N&Xdl*$d{Mmx4FA^okX(Za9w#BAKUS7^OW_fPqULL6GmU8NZn zZW#8t%l+2Zwa}&YnZO#18K@gTL@ZE1l4I)hn+CbaKaE$=w0^#00X1y&!dntktt}}Hacu7 z)fgAKk`j5yKFrg(?LM}Tx7M9pJuYR=8^#R-i`)yfN%fUdN^9qDJCZtOjQeGf{7d2y zMeR3n!)iP@IxK8@VoY7r=I6+B=&7%6~&kDt#}8n1b^rB6>pc6LO&X)>QOzT zVYE$@2Ui>c1+RF;DTp2^mwbwZ!B-NIxQ#xJPP5Sk^(7+8mx2W@>t<~v@zzjd?5i$Z zGwCAzm98x|Mf}8jw-}kl_ufjhkKNzPLjJ8g&z}-UN2{#3h0T4d5d4?q%d1Cx0*6zq zg&7_$Q$qXcZ-ce6w*UZDSg9}qoCvH2UMAhK4MWlde#tD7=d*Hg%>05U-Y4E;4xWyj zG&Y~rq}`YN!@v{(8adJ_o<+EXy+<&(`!9kO0^UEET6qAoODO)7h|8Xaqggr!n3i8d zCevj*4VI<`O<$mgJGXt(7;^nsEr6+PAutuAwfzA*vzIKz08pS1xz)9-yR`{nXtEn) zR81Gxr#Sv1NHDq=efN$@Bx{kgSDjqwS>vmmzX*y#|38&Air?qNU)>xlNoE)}uON{= zntGw*`xn8xZFXSI5Rl4r&UZmm7d3C=NHO-GWM!LTMWh2dKV83$<2vsNi5i;`Hrn|F zJJZfb*|rA^s4IE^=`BT;OI>?6ms?`{ZsI-rT=!Cdd}UEd^_(N#;_Bip@k;FF-}se5 zqo?$8r`2Qh*Un@1P*rAy?O;pT7aq%=-ZP@G#(}_^g{?v5biAVHyCO0TjfiI>e@sEe z<3ByCqj{qUmBqvECe{06GG1NL1+yI|=7suU?wVI?gmv&k6_vwPH=3w8bDDr0_s=tl zI3cfaGct8<0=Am*?G`~jvu&mjP5ac6BI?kTQQ5~qF-p~8_W}zZp|lu(QZ4-< zkGbtPRA4+o7S7jx*>0u{c%s6HDA3ypVsa11J^iez4m!9;3Vuu~SS}RNNv`(^pZH%& z{{DHjPN8!FrEEr?m%Zn$Fus1njsvv^sl^)N&-Aex)6??byGZEyEOQ;NH)fL-OflI9 z95qd-`i2e<`w{~-97^rzrS?Zo9T<6l&b*Ir{ttj#>-*cGe2ONLHE`w5ncGjRJXCx5 zx6DW}uL7TFv6IHQ)s-OZnd@a*A)+NwWs5WDpFxNyy`d~rK8E&LAk-`=tC?7nDu%am zt0&DgvLxS4CLy_Vw`o4T=NX@yao`PGk|lLx{a!Pj%r25UMl3c+w<8JxGgOaH@&;vI zy|P%n*HX`&yIp_QdwKx5I$#r8vrtKYVXM7%-VYQjYB&CMb+ZCS|%|003<_o6Jw%Cd)8j>xv z%<(#!f3us@_hB8_NOJd5>t$P`4c{iBPVYyVNmHKqJRI*@a7$T^V?~55I$>vBcl4G{ zTNI&{8Js@e6N$aM@L(o&Mc>DYv|#;i`|;exd9dS89L)$oY3AJ@M6h z40g)>QWk~M-Dei~^?U2*Rhtmu)WxUHakpzsT`p`UnbjNT?w6OhiZVGp5EWe{DYSVk zz?sE`OH7Il%I2ejhZAklky5FAk!bd#4=1QLY_@f{B`Lbud$=F5+8=XM6T3QoGQs>5 z%akL6&&fysyq(=EYieuL8C>t8&D|upuP=e{;rqhojmHT>I3w-MtO`xGxoj*0({Cx& zS&8<)fGa$_KeSJpkM2-G!uFzZZ22>;VG%&t#(YVI2gW)1d#iZB3LA76pr*_x%}1x= z>-9)(PEC+C8{&L#Q&Gvqn0q%XYAMLsICG}m^SONo;G$oJp1a<7&|X{-=k`(u;HS#6 zn5)dL>&jM;P4sqhu!&Mv4Kk2+H1{%sf{W=+YJJa*A%6ra4E{`z&{(%mSrj}1vl&_o zh2D}OiqHm)IYhrk?|1he1u8Dm86fXZR=*`@0h_;fQm$lSX6b|gg~yMJ+`CY#VhGW~ z)b7k19+Le)cM~2ms=OuuR;m6{cIv27$K}#6gi}37N%64WjWxow}MCb{U5*3*>NY&yB6XOQJMNM_tTb!uzjgE zahB#`*rLw_ll{0puWMuUsGXB-F1SnX=N~`;NuPQD{(hY-8U98QU2BK^i{foQ$C90UG?S8SoS8HG zHhz(r_3K%9oofrR&F9njo3q?n{iShJqN-Z{WeqYFptsb1`io)~?5y@BdlNs7>5TMn zFdtE8p=3Gn5#P=8^{rppIgN5ME{X+(5BFAAXg17Zb{A%=FI~pYomPu0C5W;X-HN=A zdIKVAJ&9|x9{VDQIJA%Lsw_@e`u8!H=Grz*+plkpYhNi4!=UFG=JRcDyk-d=S?IZq zw*0C2VfDb%qby?q>}&I=%F9Az6Q-&3d3%V2lG2)us_$;R<6cjqj_-#5u@fUlI=$BI z*`Es|>oP_6+Yd-`>U_Bt z2-wB*5qKKPMLJJNkU*y1{%4r+@^5|B`V(;7mB~}HrGW}^O53{kvW3q*xqhR&Xxs?; z_HLXKv`%C9MGB;a^;x-h{CvfHOQl7x8&VmGr}srb*Qt+zHE(C|yvNSj z(!Uv3o;wGeLi$J_jO${nbq+kg0Uwm$JUyRv>J5RS&XKn;Dp!cT5%)0SV>)|4<9&y} z<-4GH+lc%t2uFZ_;Nw!DN|r|G)JA!kg~#PieXnapR966_A?P*TKYo|=xA~t|!@*;; z0U0AB4oFPGJJe-2e0o<$gY^_vR?~fA>RbS#d*WBZK|L|=_wWzd~%pQDIjrF0Q^{+aus(qzw zG4&Qmi%m^X*q?Uf_%*kTXE!Img513)@CZ9mFgHFsR(G#(VoW)^);998HYP2(5t3|q zqMDJJytQ#=&7>gBb$+Lnsi(gVyU8&94mVH?2;v(Ts@Z+N?>*0gi87^~MVkn(9 z7<1d+Kb<3Z4d@)!&VP5#eA8{!HOOGVAKRznQJISwldV`a*HYCU_7OP5{PDYhXUK32 zBtjK+K+!`V(t}q~a6EB#)-E}awwRI_q=r&M8A(`4$*~Nsb32)^>DJnEn*mPvSJR1l z(2MoEWZAKAX>r(fXYJX2Ar7uaUzdPKUwE-VMpNPMs8G?aZ5z*9v^cSd2B(hwcJRft z@@UKbI3uAmGXI`>Mwm6=UpKcxEO(qD@Ue|qUC|x5QAaFO{y=;KG}l@N zb9v`*2*yrm>_5N@AcKGE%i1k(g;l&@WZ;o++-y>Dl6|^4>nUo}5cMd-IrFMNvAG$n z3?u_2zAP)c*}Bym8|aIgGT(8{GWrbOlcr*nSC=PH)PED6$2TkEY?l{ZK|b+hveCqx zO*mFgu3&H-$c_Xo(({uVYu+#yDSI8BGlT4elU?Ab#1lDoxF}(O-Oe?C=Uv zkR-JVt634uJ9QU zMl#yMdFBNwU0fUoKCQkX58x3g@r|k3M9DL0`4!AO+I4Mu%yQsnN2a7~tZDwNAI0~< z>3M=3;>(XyX}>V(JAbXIeGur9RPc~Ihn~Ye!3*b`||hW@|Qe260RwEPkYO&tk1W~fgQClBYJ2OS1bjQ}Bo?jH~AU+w>LQYrQQ7U}4Q){egf zSs7aPyLuUS;m!*LQ<0C?0O&=T%?D3{`*E)3@GEcuQ1<>A#RoPA{fj%Ah4yQk}_{5VAC?q6vDC+OS^(#-vp(=T)Q3cn>I zZlv5+U!7>9Or~M;T|VkHj7i>0z1sw1Ss$=;s8_MeuP8#K=Z1bQ7;P!2U<9cs%0DT~ zDS8%?2GvUKDO7o1+^j!oX_pyaAQ7KZVMF3CI2=oDMJBzWpv-U3mK?ST$VWT~%dc^Y z=`2N^Btc_PT&X49()TzX{+#V--wQKO`t&IaB%(iYhD@Cm3}PF9I0VJHw^~SLxaA3T zYHzM`Mt-pIl=0wPvWX(nLPvB<+IZnC5gAZsSmT_qu2Gu8gpEr@Q9+o%l4cVlIiNpe zBiP~L>wm*%Io)|L#+(~#q+U`ksaWJH_o1jfFLA@8GxgZjcc8tU~nsPUDuyTa#sv?9+Y2Y{MGA_*IlmGjpFje;P1hFB(jEty;+921`CaCFVtyNy6 zjuq=E!%jf~?6HmFLBwh(BS%CKogLx1@d(~pb$(4KnMN zXm9dfI{-yoE0KdWh{vn8Ahs?9e9yLSge<`3v`oF;8|sKPS!lNOJ!&8z(V9%#GW|>? zQQ!?T8a?%$jRRXly*P^t3o=)vs)i_q9YEcu`^4=_Z~PsiV}#M_f+-5EMYd-8W~jcR z%G6GkEhh($#Qo&)&uR5pLR@n|ZKZu)k9s+{u7xF!3pa$4o)4oWY|?x z2#p!`C_&r_3)b_VOkxe?CCK&D1IR?Bgoti8J-12 z-g5_*xIzBvi3xu4O@M89*e%8YYu8Ik;W{rppGKIP(ZaTcUFH$a;& zTyY!U~=$Hu3l0uth$X^N)w{x=gyVmWEemcMyiTdtVcgnyA(l}xH0 zP$(A>y`KJIp2b4oOk}8szM0w|%Hi(-2hqJO3vw96nPI2YvU4RyPFIxFg5CmrEV!xF>x%*$)1`J!(X4*zcDP0UEObB)e+6Y z2Z7BYZ~eCP^y-)fxTu}J|(A2ZX^V{8bU{1u2qibxiwB=#va z&v3c~%QmRVTSE!Mi-AGRW%8RD*%`kGc{dO~l)IiDj$MNK7pV3#by8OlXPSZ0sOv!=K) zqmx)PZp~I4D|6nllAtYpYh(djv959zL*KXwDSA*hC=@+$mrr)NTiP`v>GA&DzDT*3 zY8v$sop=jmW;?)apT1ZEPc>GUf9EcRqcZP@Mjm?y^U2iMRnF8kxc~K!VpmBS8k4iy z2gqZq(7b$~9mpV;yhI9>@Q;^MDsvHlK6P@RS2Y22Dd-vl+Tm%CeSS#@&I-nCXzk`D z?t^|NQq{0Wh!3D*c|$AT3(J*NbRpN{BY(c+MV_8A2IZN-$JJRgwG6CIq%!4($c#1Z&F&SMb<*@&OEY1^;ct(A{a?!tUmz=oyo%oc2 zi3^Q$W1TJ2A+u$7;b)T!Q$YMsOP%ZUPh7Q3xx$LdfxO74=f6lZ0$+}SM%EJmB^+PW zmj}ny_4w^NB_|FrqUYr(tv?zJG2r7vy$~g}|Tj&pO#)=^ft^cJ7j{vAt@ zFegc$#Z7Pkx(3N8+?jntZl8{1RT(tC)C9PAIW)i8dwxRTToWXw69mz zcl}=)11T)v?s)?@6f^{EC>&uFrYPXf77MqyF8XF(2xD0&Y2!C;G*4)iVXbyqJ&RE+$VDMOSqMYE zf2-4TbB&~rXHw025!X8;jd;w0q}M`QbxXp0aPQKokg)0U}*F3aJRCQcmnL+y2 z-skWha)u5zBF*ZD^8OA?`*{m}K6D5tbIbS8orrbbo#KK3k$TUCxS@If{ocM^wgV*} zW?wq=ymeJbv3kwCvpHBLJEDGMQb}&$_qCb%+fQ_8hqT$;1vx`M(a{eMb{$~P(pdni zlkr9JyJVwnQ@$d1#{02QkDh>bNV5F&oZqYDAhi~&(@;x8@szmH#;i^qv5$n_@8->~ zxk`PWlx|qqL_B=FL}k^-=svB`vr~RWEHv!m(bH(&M#Aze9Nc0<;TsGTS~v>6RGQTwmWCIStTY`$HHF-3X>p1}P8kjqx>P^Zo6i0Ct!Rf6AnDC_E14}a zE^K`rTn&BebgC9p*nxTEQOCrH39*d^e;GMMlh7V_a=w*|{^Ic%~G5fwPs9t>&d zE37a&k9q68m)TM20O9xJa_qD+I}N+WdVHi@=kYKxk&rBUYg%lye}AnEdDT!{GhiN= zp1l_0@tZyVz+PX-O5fOtKGP;}Y&}M4`@Q!B_S+QG3@@{;>}TpDVhaiqg!B;uBrW@r zj~A0)AQ5b4Z0UTCS7lLV=Fg)nPW(*Yumh6>)=VkxyTS}m2$Q@ujqnB z7Q>#ye5nC9zIf5iH!Nby#0j$;udnionu==1WmtRjy%FFt8$vH22qainhYa4tOkk)W z=uB0~e&2hPCx-jq{N%d0ed6uimu6%{S-)Jltu2suOFU?60fYQ4oFKX`2mMkY0hZS0WMcM)aP&D05^K;yfgv z%)5Uw;37Nh)&z-nkdvsNfW|$13NLSbI{c%AcV@4EJ2VcNiY_O)Wg!)Ri?G~zz;otY z+{GzuX31;o!CXPmT^k2j1>ORb#c=dfJvFbORxXo(sWD@RDV9V$yEzNh*s5Sw#Z8Fo$HUB3MoxO^ zSfcfM+MsS~GQ;wrE&fp&Tbx|0Bb7)k)YPLA`|#N>YtD&7*G|1V6~tXoVqz*b(Av!` zry6~;OXvJnlhWNfdRYzrcjC!tO6M5O{KSF^0ysyg{1bM<B?`Eogb>l=XuK zD-JJYU2Ac#c?*Xrg*}0SSYt<+PQ!JhqLmaD77U~PjE{hE6snZ}L<>R?wyY;`F)HSd z-nWIdclxC-aC7dRI$SR(|MH$~(%i8g_7U;bb;drsS`(B&uH{`1sb$ErSg!AdOTS_A zgR92Hx+@1Pz6dup0vK0Je7&Y+$hMy;!jyA#^RJr}cwJ?O6gF6u!8knf^Q)AtPp3;e zIEJI^?ysDDOm-2H0Y&5Ix8NbBK5&f~A9Q@9aj%luM)gCxt<*!tyl%+^6EKlJe7zTeR%z7Ey6IF-!teXp-}E0V9@_7Q{Ua(;-^Bsh{tr%7=-07sp_*Smx; zNy@ll`~{6tPiAv>zbeCg3@g(ee47)NnABHSBJy1Gi_|ldj9mEkVY93Qu61&jje%K( zYO5cI#64F7!u=7}%%7JdH{N$}`xDYzo|f>AIy)=inB`8sG$eKg*QxPV=ygBrkz=$i zX9?}B0VeiizEmh=%nf>1Fm?BfmbydTxUsRiF$3rqKs~>%!t|IVEP%JL(Avm�Hjzo515FCsK|qG)v|M z3sHXi8uJ}#Up82Um>ay*SESUw$KK{ec0y7Mx5(?X#H#rymQZnLa+iiG8k#QJ^8=ob zgW>1hwl{l|!b97EBgO5z=DbtP&>90LaP4+R9BFHLULaV^kv)sStOu;L5NSQ(%pJT=Bb}Gc7i`F_uj}VaU@EG_*X|u?eq`G?fBD zvoG`n&i>-NCrfgRfDXG=;543PFU)ZgpWiP zCU55H?D=NNT8IRH;mvDnR9t1kY!Q(lsugOnWLl*{h!xIR;Iuz3e`E$`ba(0=VQyXj zjGsNFU+md|hg?DD2T%a7S&w#WEJh(=0w+5%-6BpYampUtqH zbcCh8Un-lBq8Ql9O^V^oTan!&*yy62{Lx4L+2a=M{cgr{nko8zm|vY-=752fkS;Jj z#|>L~idX$&N0b2E>O()~#>utV+h3_J86z;8b=883PKfldFFU06d-uz7J}!M;jWAg; zTVCwsZuV00p%X~ofVMCJBvxc;skJA1OpOw=W$RH`@^0>F!p3p6sw1968bn(Zf#!Sd zsAb?V*{Cv)5)k`{KcfijjbiZ9c3+qFl>uCNzp&C9vqV(Rn4pO16>p=^t_&^)xcq8=)m<4qxYc%zNfm z`{37u8iTmPk1L;T)R9|F_k1u2KQch|*rtuv)&&Z3I3n97fBGyi@t9g0ghn|~ve-lr zFbEAvlc;{2y{&65UZl1iq8gBLV2+=fDa!ozBB)Mjv6tGR>hCQcZXfN?**dk&mrd3} zgCl_=KM_+-!S;bs)BaH#&%IO*7})N*lfOCNFtQsrfW_xop+=cpi}Xy~5}eHV9>|&% zXJ|mTIbuD8o&7$s67)&4{a7;`H{iO+eSkxQ0v943WK+Kbph*ws{JH^y2gk`t5(OQ( zJyAAq1n1?WTpx-hKg;t(^-FjcZ_yd#2^A@BN;4ayY$%J;o>QcvzoSaaq+)pkXd(FXIWdmqi|o+aJ2?i6%D~WkAwoa0*z|al~dv z0V9&%M`f_sq1sx|L$*wR{M%WNA>%6T$i}UnH`iSE2<1h3*s9AjDNgqTu*P~daSoPT zA*P|jwNuZ$1VZ1Wb#gQ`?}aU`_E5QV{?M&a_bg>6q9`A$L{eS#m42*YNlzHqSp-R> z;L5%75f-jW^k)S740b)K?hh5&uvsS`H-};ySyHD&FpukPl*>`xie3pLbp1HEBvY5Q+`)6m3Y1~v*<{St30jK-*8t=_5^*TN-xj2okBVZ{RXo<*-{$8fVUl2} zr?|sry2o9fo4v9tyOP$F))chnGANgaij|UYalBuYs!=9- zGl6uw{sIJNBqKXFe3&g|51GEBjYZ2}`ZLUf_Dw*OyT43lbbJscML_z&+3Yr<0(+7} zrM|crGTD2d-t59jh&PK`P>TAA_LEb&0vhiq&?{bd)9Ry9!j0FNZ5`*~W+yS}L*atN zrVSYCfmuTxCrpYr!7JaU94Cd4+Jh69lm<-?4~`wQ#~U!k!ltKn;&pY;zcJqcP}wp5 zPPHcv_=sT$^MPhX`=AE!X?1>n)ANslZkYR(L}R`WyO6#<#d?YfWPTBIJU#7R7U)u3 ze_xsnXeP-KILSb(zpPBR@68HDd=bJgHNqN&P_mVHDs<%AlYEhK>qdQxb(x0Pj zEDRJL0BN(lwRkc+Th9Xju|V&p8JF(WO$#gewoSJLrY-3RoAk+c^Vmb$?Vg8pjUUOK zCQZbm11F6dhzWifht_8oZ(f3n0h^zKGN!Q~S?|NG+VZvVkfMz*XtOVm=0wJKD}(*` zE9lrjLYf}ho-3Pr*#dgC zY~jVy3B^2<@|LY2qvrYK-j$X|v<`g9GCS51itl{MV1hN@Lrr&28{HJxs%kCYgipYn z&Bng_o>=fu-%y0B4MRGQlHe3IxaecGIqA&&Sta_|$wqCx$E9^dwZ0;+d2r56HMCEu zlIjx^OC{hmf(TlREuTXMc+IcJxmeQXYq*)|_igKG(404afQ?2PcQB?seZt!)%m{$< za;?aT3m0as?mEnRwWy+FCEDU8Q6SE6*zLBQT5_}i#b;~WZy)>>YyVRxvpXkBWS@w=wedxr} z&BvPi6KSC40!i<|E@x!t=gF3%WHvhK73%4_<6|@Pm7*#7UQ)CB4!29=5AKNt-ahcz zH@;tX3>aKvmNo%}$sp^ahDLqWHVN(ZLrzsq?) zw@M{11!}U6@>wsO?jZALHwL{?g>Cu8@T{7IN^HmTzW{nJ*m$do@{{LB@$4nes8m#( zp(`{&2ku36GLh21o36Vc?X8eC(f4{PmB->4x-3dQHbh{ZWqj~kUp$sGp3Xw$>T?V4 zILo8)hRk*t9Pia+Y8}SWH4Irx7^hg=yxZzW!Ij-%ouGeGA1ZqMx(;_i51)}QTyPHn zXRcIu)QjGo@UGjd^?~>}H0`^5;Hjp?l!dCg3AdnU1N18z@IGD6c}{8`^mFpw*V6=@ zllQ8S@!oR7E^dmNyHDL%j1H8TtlQ+Y z*nZN{Hxj^<-KC7Gf~bkpM&DDdy5U?yq8^D}o<<1Dm~=hs{;qyA>CN3a^;69=HIsC` zn~lP6c5GnMInO1Qhq7~ZS=dHm@$}Wb3>kT-}N)ylHNHQ;ttm=;U9{cvg0(Z)@^Y&j~YA zr@S?kEq9y(Ro}E^-VL`C!6@WjQ_xzAlY(IwJ)ssTcgj|)2Q6J5l}X-FX?2FX6~$)yRV4@ltuU7xo1NAF9OE zIWK^R31`I(6+=#N_)S3pPamTgC$I&(j{FAIsuuYNrP5~_Tl1BiHTdZ`Yp_m_jm|?i zp$8fH`DS`jl~PB*itBwMkgR3Es6?Ur$PX-dj=Q(JFAVF*~oj z`tqaxw2cemJ}BLkgDH8F1}1ru_gUcx!YJD-;l|(QBF~b4I)Y5`Kuq61VeWgbgPmFs zp_5qEfCt;X5-!uZl4+(qLO+P3~j=M!~cp zyLQvEyntUzSf!|*PB~!?7_R1-Y!Sv*AMh?C4)O~nlNF2-3%;`_ydis=slIkAgRmO+ z+`6tPfIYQM&8c;;H`emEz`TOJLg%NZJ?bGp*|T-i=Q>42wH}sy(+C@fx;c!BN~p(t zHM*Y=T+8JA>%~2v?r-YY31WV_gfgu0GIu*W(P+2P=_`wk>I1mdUO_2e(zpf>rkVAb z;}_QPAHHm#&-99pnru<`Z1svQQNnq~ri&D!;wJMLR-@L#uJj5>bXFbV{`e$XL10e0 z@u&XyS|cc>aZa-R*aHHHZ)3N-MKXE;OQp7u{d>peweMLhGDZMqzy-;1zfAh7e&ZaAo1vFw(Df`XEz0V zM)Hu4i=Is@OOuCJLt`!sBvLC(7K>A88{%w0w4o&fsw^7Lzn-oA8M%2oGp@+AFKW6@ z(a@?8My28o*=SVOr}`93b#4tM{ko|1zMxjH5cNa{h;?mYoRJ_JsM%zoC5M6n>n?FZ zPZ734b|dfD{N4K?MqGfHl%Agu)L~q zQ2*M2_mQS0`3+f7ls5_;@q1Dq%^;gZ}k1gFlysP&mE?GVA ze5_LpZV7tg%IkAzDZ96p8iS7t3G8kVdetYK+=^@A`QkTK+p9^#8A&Ii;U?R^FSp60 z`t2#Yn@;gAy6YZy?1L!vUKuLzlTIR}olHZDxc_*EVTvK&k;SQYTKsMMy_fNdZ}+lh zijH1ddGhJf+jgPpx^{!YCbUwEZI+d~IdH=oIu+*=>IRUu8JX*x|fxSp}4?Y4XB zxiz9qr%?!bbF1f@0Un~%hyR}zQ`=(JGd^-zM_^{tXi&;sLU@7hO51z>r^U4YzgkR% zG=5yVRt<+hn&s^iwHPbt?Gvd0-D~->^F0&dyPbhstN*LT6nzP|c&w7p@WShCA8cdc zld(Si1m{U-+!1QZ*acaEBr;HqS>OCmi@9B#oat(Mspmft;4iOyNfmYSVAJr0u%wH} z6Iq5}7#V9L&p;Mp@P>a)BOao@fIQ81tBb{}sRg_}s{T57ZqHXqGVHHPh4+396bi;w z6BM`g!plw>TxKf=?L1L6DJG%6OLrvtT|?(S*#6AxRNWEe>dv7TsyySwYT_0JDcGpWb^&t{8sjdVg$+nLA_NSjjF8Oe12ui-^32Yc8$)pW`{zlNS? zjr%RUac#JUe^pJ4_1t-WNNnXpO|JQs&mPrSg@qd=s|(kj{Yi%&eJ4=-1!OsupR>I< zQR7}a4j`5m<|F>j1Ew4?XFHSZH~lR5ni%!3#mFk6177-4ClXO!(gh-XeZs<<@NbH-P?U|E(Aq?{r0oJ5)Zxk?@}CIOyJ|Sg zSzcT-hPD<=uyHgwtjYHSNc1z4=5&&LUpvA-3xSNIL394fvmTa}=eSJo#&ezZJGJ3^ z4>C;ak!4l-R;YCdxp|)(joIOL)6cOReeZ5AUMDGF=*_UzAaw{ z7Eymy-fHV|SX=?Yvh3}1;i1)Qi_6g ziZwtMEeU6YYNG+kfB}_GUF%j-eJHYQcjeb&5ETI}R#XLLW`58=#7D(?&2rby zPH;HG*~+{LPaic*DeYZ?3<9T&Kpc}-%%;?I0gQorDzEf|uZhDZH8QPUor3Z8Q0K9Y zl1!ue@mqbyQ2}<0<_=UCfSuUaP}#LI8~%5tk=n;Y2j=taE!7fYT`0_)-IG3&E0L-| z8Cp_@G`yR~?B#WlvC1DPcRieqnIg0$%P|mZg_@4P;dKfb=*D| zAJeP7i#N*)r;Z1M6pzvLEncZ}(t=2cd-c!b^2)n?bW~KT{2zx=N8ip4`2mm9wvLG6 zrS6OT;Y@ECHlctV$GKRHdqeE&BSTx_JJAjWPRp>*9v#y_3nHTQ?1iL5#}JW!@;V z_9e=4M%Xgrjn4{Rjc3l$|ZI$*SXV2}Oyoh6>^QeUs^b3T>D3RXLRfmKhM zX7d&8$tV9d50ATgePsc}4SQ~WH(`rPc_Z*nYIeFjUZ8deLb{FHvL>4n z_U-0Q)}K)%XN7)b4!#$mXHmT4t={&bVP@y`S9ibBSt{#GFDPO7a$ntd?HNW*xWfG8 zwHgLtIPD6>dsj5lGvTZZv1(#&-#_Y(N3}KzAAY4~oe(oQnB2>3;hLepEbur&mm`0O z)im%-f792Ms7vb~6=9{OaqYr`qRih!V9Kfj+hpvJ9kx3>1&z99KPpoq zEnzt046#-bvKVey{;qjMap1-yyBvd5we8Zg#>K>$;lu@`OgVdAfM)}0c~DzEZG#!% zwm_M|hVlsp{)A|*1yeJ*In9qXZx+>AEE(IFau?>8h{E%O4v5aJ<~`q|Yg&R|qo*>T z&Dijs<|#*wHHK!3=9iiO782qba)AR>gBDfD`*?5kQZVvEWo3cL5U+9ub(?rg{I@hc z-uaZGw>6W~Q#!mg>@z+-RQzXLrI|>E3A2K7=@5@s6Vk?3zKt55K~`p3Y&t(ue)O|> zNYHRl5tg+$9XCmDJ!+r&e5{1KYk?Hv84Fzv)C#-%$*Zc97|#AbGbQGmWYApd;6z4? z!l*fsvb=G5=0n7uuxN3E5sG-ymyq=VlkAH4f;F;7!j z9A!fpONEz~wCgqS^iNyvEGNAM26`@O>w1(MK47db#@oDWwRzabXR(jfCCcZ0%ZGdQ zaj@}+9%Hr6gwUD5X5CF`EfKnK6O&=m$VNZPBPa>uH=g0Pjtd}*Wt*fc#CW*O(*B@U zpK0oiy?wllKgpYKT}$0C13IC?gOuYrvtqM|XFuyPACjV|diT)RZphLc20*K4Ii+R1 zrW=NH#?YSBcs8_=_uzIj7PHWmG@szLV=2beGCTS(zKi6>C!9f}woUTSmE8Ki>t1C| zy*4^zSr!HycV{%o#gn2MqcoM?iRU!RRXI?>8@FJ9Tp2zX@tow`mCP^*5 zUc@nlX4it(j#V-R|Hq~A46t%sCg&u53EI%@%-sFVm(Gc7pW43fcJ=rA?hYPh!(pmP z<9e`C@v+lfxOxhrGQ4+2htogpx1(=S`P+qONiN5Ycjp%M$=G)Pn^U}Ur6SIQnUygJ z56Lg3LaRGGi;NHo-v7}~-HzUyyLzS5wSX%oGBRR^9qO$7^?*Xd#AUNtVUQzNZU@!l zBA5f?;!5_)0KFSssN{S@He?1kc_DyO^=xgJJDb!I`Z?xC_!*grt?$MVEg=U+GHGoS z=`I-xMXU->YCvFNuz^wpbMe3nRyy(Z!^RKJTk$TufUxcA*$3lfJ%;wh%yeLKEUB_N~`gty5a@`xt95!@Y}&K*0p62E7h< zPm4NKc(O;Ry`Hg>_nXN@Rn;t;EUhUB#sT0f0Z}My1YFbM_niJQ(Z+Q8!YiNFoyBpk z@4)lT?Y8~;F9p1F2dLFayVSRc}xydj)fjOkTN6gMmkob;B5Pi+F+sz}?)VC_Q8nu*U8u0?TV4%&shq1LQ zSDI`|N#i$H3J=(A^6e+rBrL@Y+=0M`wk_||PIxE# z5xUbMhEiRTbttc;tB&=TQ~UK<&vN`T39C9-PdN|GFYj1Z|LiV+!1mR~y3H zE|=Io_uzhgGBB?Vssmvyqy{uOvib~ZF_K@ab}si%2Jn6aY-n>cxnEZAC^g`tsM2>Q z_Jt$$ha~gi>;HafUp_sWUtX{1R6x32Uyum%Ahn#tcv%IhQzdkPrRoWO`8y`3u=e)K z6}i$>Och@hfHr)Ke+7Z+4z}_RsDmgwgntApy%qk$pEEO@kdq^d6N%Rvx|vc ztetfF^sU|0qDmA`~4+RULptR zh}$baYVvrbb*rOJ-W|_Yx)bi$)HI;M1GA8|XBnH+*kfHu>SI;u$H-j^b`R3khh3OA zczUZ!ACl=6qKukUA^GG=x=sBM$oJ~*7-iodbQZOGDKVTq4cR`#W0pKeuGD4wNpSM> z;lb_p{D&5(RY#?&E-IGXNUV$Eoshl>NBnKP_G^#XhnQCf<}scRHbJcXdwOAYzx^{i2!EcH22!dZHF?@kD9Um?7p^vKI=+Rmh*hs!DLs5xM>hY2S- z)aV8^B!u*akLmV$$?B>Uigg1M`lO#ICKzMN7nOkEjMHdf*Dw!fxC;e_ zmk0@V_voG?ES#3ktoA+>%^t0#T8~{!@p}Qi5?_a3e{x>vO_ZML54KcFaF5#9JyLx- zr$IJ_@R~AgCT6-h{=C59hT`RR(a}PXkWI}R!EC{EG5}VXU4OqfpT6HdwS7a~n-sMI zr)GW1Gjf$33WF|bQYN%b$f7OWa`WFeFW6Vz7$nWfO>H!v7IMJ^Mn0*%?hx6;EuSCj>LFDo#+j_u? zz@^~H4E2?r1Qbf%@4=k`c1Mp#37tSZHDP332+}z|-Ba8{ro2Bifr z5=e^!sLSjvMxp>)o*v9~PUnHe9tt~lPGJZyOAVAo9qkpK(&0VFq4aic6R#@h*- z5Lj{2@UL@K^7V(cLwbY^yU_hgwmE^V=q24k>raNJwl-TWt!eNS>5Dep8!dX|QpJw) z*NkL#EPOiIAn*S=q=DW#asoVCI~Cbh1dDvI)x}Ec+niUHaf$_1Wi9qquga#Fa{};< z-A@Mr*geP8eUHy<>qr-N{NW<;NqkKWU8Xp_h(q`sOb8G5{a?V-^ltOtW`yj(bAeOI zfF^0_b2Xd2=VzyB5)UJ-w)luPej?8WRguqtFjnug@VDtM_qJfuGvPbOMoUY^{{`@t zS@sP{ohYp>{d_b$iVH$SU9M>y)ptTZlYi=tF~)SPgvOTN ze(d$QqO$of05=p(sEd7c^zN#pap%|LLq3g@BwjFo-mR~b;o=1z*(|_Fn|@XOea*6% z#7^Q{OfN%?;}gm-bHY>{xXfb#2Hv%bQdn}bdl`&7N=Eb70$||Jt(spDyZRdZy`o{* zFX)ennZ*Z9t%{og<272Jmn3zV0eeK^5C+elBG?(pJT}MPUEuCLMX$N(u-_=>70~9G zIh&!H?sc%dxEz7Eajc!O*%CQPLkY$uw7l*_6uz%a%L#9(TJU8eKE!wU2C(9^sy2a5 zC~q=!a9r*AXn?^?z$cke7Ky_{&aq3*)8DliNDZ4oaorSqZhJ=n-SdhRAgO^}^(G46GPbP3=bUMIsdG$TVqG&l1bRkW_+<}iy%=??p)I2r;y(U0!U zar3ek97dlFcN=ngj1uo z=SxHvnDr-nQ}aFaUx1a3;U5E{rD05k{mtV|QjSBA!No20qfpLrDmJu(3RLQ6y;Hy= zg)=2(z22<1Sb6Dq-BEF88`wl|{t#mPszkZ&z9r&!o?!8JvxjN{EY`sR<333RgBy3k z#swH2W(n4OXpt&lam2kY1^&TSp;1c1g$+q@&Ip1H} zhTW-LzcGV1myX=WQvZ#r`Ghk= zH^ILEYvI%@>aF!V?Mj;s6hD`lPots5@E##zgfF-#e-nukiPK@>LSgDs>=U4k*4xp> zz^+REv=?t6iy(-KeqyF=n}?2>b=HMO)cDjMdI5jb)XnMd6^Nte+-oZuW#l2}W%c2f zx2WqH$2@9KeI?#!0LO5sCpNm`>FJ!^pUW=L6BHs78mm5(6u9oDf)e;+E^&E)%bJe6P!(C3z8f4u~y9Ohf`tF>a>t5;wN5|*Y3Y3{S ze@Lg(;K!&c0)Eom{0*rh=bJ({K z-*fHMRwM6xA=OaXt+B`Mny=&vL7D6IhU|9MUjEYhX;TcDS*!4fNLzVCvC+g{<-?sJ z_%1-JlWh5R*&c3pK2vr6>%3QM{_HT_U%*fOC}d6S_8~lKw306J5{Lw`vB)+>|pzVc`nnM+buz zY^-M%FB|IdyB^V@D!7D1?;`pTb?SFewK1q{hr14}zEys18|BJb=u?>Hxzf6+MX<7o zx6k^$*s(=1O{@v1!{>PTDN|5kp#fT#v2VXIg3W*^QX^9xOh#pbGj6 zK&So%Z102kQ>0Gh{{mjH0C?p(_^54ebP_uqA&*ogdaXNCD6{Wr5msV0NC!1cd@s_86?c>upv6h@Bh}&= zCejeiO?(hKsG>DM64T1U;Y(5yKin*yP_nPKrGxOm7n;6hp12X&&;a^$jtcNPGTB z)NtQv-wE0lxr4qpAA=S73mDdH4$%Qx7~8nId8MJso&1F}k}Day6up>e9Of*S!A^I{HvhQ~{6bkPym>k+D_94aFYSd>L{bm3v``686Cduxe zm7M+V(D?(_yPAkotmZHVpWG{d9iMkq#{Yh3$i;tX5`t?_42{y(Vq;V5)bMtQc5n)& z4fBmo)GkxZfBiH(cgr(td;W6C(k9#UAcNl6sL5zZ`qXjpHO|wQeZ6%u!AV$07NzGQ zZvd&x=kW9{_g?wHH03^$IuD+eZupt7W8ija#umP)B~V!SwhlzK2yw9wir?y1XKD}r z7{?#TvF$l&Qfs+AXxdd|k$CwB#Fq5g_p`Z@-IhGkpeH;6qJb!dR7JmrKn)P3 zBiPYx$d)vkoVt71)U?f^O3E1)_u9lA3Mx!W>oYW(?k9H0LD^f^Z&bD&r_btz1xQ05 zc5Dy0d>EI{K)a@CD9YYZ=e^y(8dvyu%h^_5$Bn8xa@ypNEv57;r+-iv*YeC^9nYcp zpdt*N=Rj{hY`xS1^-V&NmOnTNOXS^$@l*6k=6H1)Pc7xHOV=1wjNSBbvVe*oX6St^bZQFUzmd2p`j32ciq7@|P?q z`HOQ*#cO&G)7skUdI|$0WdGwEYJ#E%7-xC>y+F->Ca?hnpX%@zAiy{UDa8qY9cS{$*dPaX zlTn5n*C^c;bk9xH_?@FMaZf{e8s}u!f&M-tbw}4AMg032RUd09F^52on6N>f9;8r< zXA>0kPLE317IxjvC?4p)VY;u7V@L8oM^esJ2|D{Kl-7V2d*?|@`D<-y_o&9RZwr$9 zLxwK}2w7>&goMJS6Cv}{`7NY+(*7FTqZ;vH?{umU-_L^Ew$*F&r_4j%Hwq2wj}f#m z-;dhH^+M@Ub~arfYg8zG7pN&)_XMGh3K}Iz)z!qHa#hPQ(kG07Ai?f!ip1?Cw^Apx z{0p<{1drpX#D>9T*|r+7{vYs-&pC;Wf~M60p_!Hu#b9Y9nzj{n%OV$9LbmDO&psfI zAy_H54yVMEO6j=QQ zFatrwlYbo5lvG1!Xm}lZmES}f?dT^f2)CJwoKoHox&-mr+@IW!opnvZ(l}&5roDn& zgW+p7CbnA=w(^=k8}&&_$`_9k$zQL3OR8v9;s(9bIMIG>Y$NMMkWjIrQRpPvnw5RE!bd?&orNunv7&VO|WqlNi8PTYk<+x+AJVmhime| zkwLAMiVI>a-Mh^TR6|BNZ-(3QGHdI!IaP6Bk`fVjRK&dM-Qon|};fB3^lmLM*&(yV+m8FF?7t__Y~G>)8hSF%u@^DNj6s{WQho*@?oVuM2@y zVI5PXj~eFf@5(J`CcC_`fnQFyzJ6H7JfKLd+Z!C(FKM)FtRnvc_UT`n_7Ihr=#tp4 zQLoDAOUvk(t<+V8zUVt7uN!p+Ywn)-hMA}Dr66C<+gwNf$lJm?m4crHgoA8U59gkZ zBqrvIeF$qzF8wBbQk*w6&pIV7U_PS^_ODTCl^`33)kvOsy3;6!@^0TsP?(_6)+2*? z1k}H39O?97A9!m=-a#!Kl%1!EOOGx=G`B9|kVQF#p--&AWz1Wgtr7}Ig)iL!d;K3b zJ1QJ7e{%n|OBXd59ro(kk({a9!VlI}?jMm1)X>AK+oPjto>oYiE|E6WPEcy^`h6Km z9&+y4H1vWq0=#E3zNW*v$lEk^{J za%lOB{fkw(08t_XzrQ~WPb+>fd^@wVZMGfB6s`1$hhE?4Du<}pM- zNM@#Av&<3>H-81sx>Ec1PXHoW z0*NYXA=vJYhO3EPeEV1hByjx{0CH&Bh^oCHbt#Il0JHb`Jz&h?kzB&oXWfT=2@dry z&%8c|{1)v3<(neJ_IVdJj?xLM*&VpDFeW4M7>_Cd)g}YIBb=Xt%iu{Y4+M965Vzoz z7CQ?vYyXwbpb#kG2YrS37Ywi!Q9+?Ng)1-4Lx*$jJAa9XQI>Nziz6AklA1nYld6b~ zZ1A~0bsQ?9z<8Hj6N6a92`W;cHP2X^d&yC3t5B`&qpU;XUm4x8?<>+!o5qh4N#o8m<6V9*B3=lP#r#SyNo_Usk7=5`f$c68a92D} zEFUEhSF+CaMqnmSBkkt6Z`8?z4(N#k0{gqT{y14w{Jy*1USL;!oL2>AW}FjtKI*(7 zHa$%%zV*L1#-~JzusE{BHS@t(9q3hR$M;PmP;F1r=cNdho@B98xst^67&)?ccSJ${ zujWmE0Ij?-jFPbsPpS8lK{`witbJJ>+?L$>u8CQFkN;SlxzKLKptWuL#j;ezEdo|K z!S2h~yY3qGvAXp`kojnjeUM)py7oQ}Qadj_T=yzFue53S^)$oaEVyzewvj>aVZz%M z&}PtG|)tl zX9^29+E6-!aVLPUr;?svw(0xEM`8e`@CN=bvoxMo;K5JzAAxtxsyLZ{d4oXdJL`j4 zu~6$|)I;P!3tz!)o`7>X3?mhPjL7PZs|08Rd(_M==~4gLqOk=oK*u!V?8Xnpq@k|L zBk~)U)q-x$FH93=O(z0+dx7PxOj9Yl5e0rYXT+i-#BOC6O4A(7njN3`uwRtQqOnBY z^h~A9f2#5M+~Ny0zakjoTF9PKUgzDP>OLCwpkW(hGCDE&Tb~^=_~Yf0rQ}LRZrxH) ziyd$gmCjT`Exy&pl$1njLmJjK7C*;Z8>DBw&?{j~Hb_KFT)z zW`Q|!_t2>0;Rd-<6aniS1tzvdGA!#lBfplOUn#shjoM_J@9C?*)f@U0PhcYtE*ZB} z{yD6MEVu5}(3IH1W&QEGNgCX|*WXP-PR{#A{aIX8=6I%Gc|*fGF=%Eee9m+~bV<#j zC@ncFr$WSM@e|u`@+P>WXbbBc)vKbWrQ@iwqN4mMf_vUqYo20XvB}?tSE@(EEF#Yipk>`=%kst?t<0I>{`%pNe&t?n5#$bT}Dj_B` zhaCPPc!+arg^}ZHk!FkXy1V(cRdus%ucnd*`_#9=difTt2kI2x-+rM$skTQe;Bi8Q zGB?R9OUZ|qCpI_!!_7&9hAG>OrdP3fFP7+h&f__>iA_Ly?n(PCk%YNW*8(svGNUs8 zrE>G)T^^Fh0}dK_w7UgRpCeJfHE!FYiQ7=&c`S05sx>S z+^@*ZE)9uCmhq{7d6^;EA*j3 zyr`9JWj*?b1JvM$_CHjg3g|sqgN|b3miN)z)>2>uxp9xBy|-=uhXK1+5-f1p5!n>R zwCec>Lv`_^5tm5h{gc~gK57DR)8CZb)IP`WUOdE4 zru!sd*JiDf&zd48RD{_@X_plY9rw0Rq$qz?Md>e}G+~FXXbUBDi!4I2(W;4B+18JP zw64l-rJ^}#bQxvLSr){~Gq$eboPd+Zq7uuxt%neo;C?Te+CpqE3A`bfwU zjDjVOQnhPh;bm;3jnTHL2M0D^`!0fd6kWaz6=snajStiQ(4vtenP7TAr(9%Vh8`M$zaV~$5Gd8RYcF0~1y zLAg_eH}hTrjjECs%aVh)xgXA<+gMnYrvC!S9yJu+4u2rcewb9b%;BkG^7yuPF+$;Z zc`j{4Iz#i)#1O7q;R_;hC2}j&Qx;PH z`bu0H91`840hi=%UFcZd1Ej6{mX&_N6xL&&|1RJl2o@bJZN-CKL)p8lgr^BqDy&DU z-c3EeZ`2;F+|y`ffwQW!`rUE6%CXEZ?ye>Q7o;8zg;l{|PtlQ+Q7Dc0-#X0bMOLCJ z$FL2aw_wkjHVdQry(3We7Jp4zY3X;4M3Uc8x?l~i$;jCHq2NOyF2~6!ae1bK;33<- zYpm!s&X17;s4D8&k*Q5j))64e{q$7*z_*nU5_1mQA1R5&Z76Z!SW0#RMmp>H@`vw# znwlEdFx0#6(wowIs>`S_)F_@PSfL#m&K!vI{ki_FJsE0N*T#bLawOZOb_0yfBQv*`;i0P=G$fR5sxmAmplg_Z=c-7j4 z#4FcZ@AUA$?eQ;4s)6UWye_A4;|b!IJ<69LN>axYe*tpYHm8$0+dcv|;s?j=(tEwr zX8<}#IFZV^K|ixk$D)Q4^$XC2g#pbr=H0pzZ*&ekdqmp8>G+%2`!~-iDY;U)f}a3x z1LUro-+A`fBvJ3_1$*lB-D+e8^B3V-1ym z$;~f|sL5h*VFTOFyj@T(L~rsDiODB8Awn1U^=imp0FhVBKe>Jx>iyzUL546aPpks` z|6-HG^{U$|m6CRtgjafz4T5M2Z>6ie^S<?4V4(_cbYu`} zv*KWt0T&b&ft%%Je@-(bDnv#ffpl9N=`lc7f`J2}{JBxv_>_^A(?Jl-BemO4CX{s} z=PA$VRScm++cmsewJac^XHrV)Sh7Lx9j$KY%$qT>-cNfv=PR0v#%^T{T5ZufdjXRU zc;uAlA8{V}3JuSeu%9CZvmyxevHYN5#`X^AnaS6Nh?4D3UiVo196E=HOb38Ta>4!+ z!Pw8ze*yQnJfZ~SY;=v&j;OkACI1v(=ds{#XuDK>K|IO|zDD>}zq__Yi`n})sj)b} zow(>gOtc!-b#n0XTIwrbWWu56c{%=h712ypC$7>o!%p_ zpy>`s1>+ICBJsbQ1S{yB+liWEAq#z7pA2*Ki+nM=L&k`3>_*plzfpZ+I)`z4_Y2Qi zwvj{AzP{^o8=DjL3t7aZCtJn6MUH;6pF@MXJlxl)EGB0DES#htNWZrHZVrPNcSFj7 zkr$-`eSJLb@44492W#H2m+F_6p**9A-Z-1(Ky8Xc`rrU`@P1HH_VX*EZf{IlkkFjg z7U>#mDkUX9WFSY{ZhDhuRs! ztaQ$ch>nuO+KoL|HpNjWxR_%rqnvV;MjGY!It!kAxte%s`R^m* zaz#+;Niz4|rkTk6w8_s4p8(k>bN*5&4hQ7o_z)SrQ8huvBMX81=w9nrJ0ZmF5cb&J zQ?t=r|KkbPb{!kZ>`iegMEA&5h9xXqb%OSiWerk>x3OveQnJI`8*zwBnjoHUh@*da z9FFVjJTb$`;_}OhGN~$+^bRs0Ooox=huS}`@CzEP@aU+0s6r%1r(o@2fTnwHw3g0Z z&Xkq!WDuU;YUe$o-P|$4o)WthWXSkB_JCElDFR@zi^+&WMXfb zRy!)O1U73pY`ynsTX6D7mDi{&@bC^|vR-A=T@sf7<_ste7G=-&sUlg-N*ZkOdeFsB z&$s6y1FODTm7!i>unSXC38W6+ z2kGy$c~r40Wb!kgY)Wt~quk|V8tbTIM_s=A!8pqQn3{O<*2UEKfbYNJsj%opmFhMuA+ zt26#mD7~d65!3BRws*+2()s&o3&i=+II}Qp(fK19ue3T(@i;b<_=<$#5h{FC#Sy94 zPkAK{G(YZ`5#wNbPT*h0SyXcoXcR1J7V0F<=E1i-ti4H1MxTA2^<;yBmvby*D9`Id z6|GLu3ESd;`0CGX=DAXhk2J&?8cS>j7*XIne@aprsHa1>xJuAT%|42mfAMtlC4abU zQYGLk{F{V=WEL6P2>%Fm%k$a^GVq0!_avR)jOowq9tFW7U;pGM8~b9ia1qYv+we}h zm%|`*iDYA_%nOb7(n5~2D31PjM`+vPf;Vm8z`%@9$wPVXBF*Lph>H9dT6=NzmN|wC z0VB~>xy7Z3VYP2d=2vBjpP2lU1_p{2`U7wH1vRYz8;ULcJ!rgI?90&)W~6^0PP&B? zrC#FI%zt)gbtTLUptja!`(Wtrc3GRe77R#mzVv)!GfsGJFe2I|L;mKw{r|(%d&aZ* zzH!5p(yCEKYb0nx)gCoMq^dTJ9h+9o*lJU1)M|-U6t#DZ8i^6KRci0OV%CVg6>a~| z<#&JX&vSd>4VSobUOCU>_#WSpXQNtHmf038M1aZ;NYy_ba9h6i@HieOJ3K*iyV@nE!ZuBm#7T zWAsq$^XUEb^bhdLd-?qrVBUH#k8j08C}*P>@0_ofQ2vN+gqndXJO6kYIeGt*(Au=3mn?htJ9;X3$;n1}UEe&ZI2nShZQNZ{G65^>#9> zvuYAQ`Vl3vkOIY4I3>(c?gfv}9VgF=Nm#W1G0%Yx?HdY;}BZh8tJQL%AOM~JPM3}^3?xFa`}_zqS@if(n47NU+%WtPwf9l#wASJUL5~$b5-7X zskP&)(y4Pt;BY9bC=2d0Nm*Z#_XqXyL!tv;FWXF6dw}rxYj#A<1jl>IoKP?+xM_rn zbg#k-vWEHtIG_4IETes_0vdk8Vl)j2(6E@KjwJgY3XAvq09f&}-5_#9N=!Lz5;tZr zqS>RR94iuOJM*zW-<|F8F4wQ|+*5@Y>7puv4IE~I~z{%4a^%J7YE1R^ zy%l-+=Y2rEEL;j1`3Ww#VVy&~S8f>(6GPT`C(Uq0$Faw;0OuRSpta1~XAXiXsDL?t zLoH2*9sNVqBj+(VQG$!Nni! zVN^50Rs?v~xod!h6#H|eC_`K7%?IAn9FL&?X&FZ^1y9l6)U+L>3()Aq%J+Ofhy^rG zP61>M4U5!v>6Olb*x1nRFDO0#qt{qT*3A^ki&e*r(l_5@B0t+C-Vt4qE?B|cHHe%b z+_bZQGb3ywrsW6x4?Zg?vi}~WTNL;gWxv?waj>l1+L0=Ast{}E>O<-PkM9zfE5`-7 zo3A4-PS@$AdTvMD=aGpi*o-;xP3_mNxzPzS!y zL!8$+ruZP91xXHG@tOd$$=fF?3z?;;2_Iw9-|MLxy7lj$A1inRjuSK>l^tW1pRyqa zt|=3WezEGOYNK~}fl(05o+Msbp1lE>IMzCQHg3#p@s>?C!E=Rh2PvzL;f>-gMMlB@ zBT3p3WMBVu;44v(Y&c9=5E{teXlgQ5+1`s5M3|AwDkROmIJo2WA}`S&Sh-5YGm%P|Q5KLiJd z@(0Bj1=n=*Y}AK*))gj+;r(Xx({6f*Tz@jZ(YZ+=;=`C`-4+dW{gu&LaYc+BL89LS zd~mmRHxw8-hn78{<3CMu2`VA7mFyUld_ETfvRAVx>Z3ghFdp*9Ny%{FGf=G9p~PSn zn_K>p#vUBZxArSI6n>E-OfyC5`mJe{E^Yk~pc~SkNWRDfm!%Qhg8#T@=U%ZH#EC}= z+%Ht{rBlF~zAnuCy(=VoaNNbDwweQM>DZG_d&5ic>9ot2Km@LKRIDZ~@c{i4+|*1< z%aH{R>jJo8c2h!8m$akbhU5P^G}-7-B#u-CB@{VT2Nse8%PH?2@hCUCT7eA`+e~IO zL~=|{?^tXx?P?rkWtwIW*cMwr@iy6ScvYM7n~=z_MmEP#!OXwCko<;{`mFx z-a`xbBT5Hhd6F#TuNerzW(9}DfKJS2V-)8%jFKT^hQcVLU_z0qvv6`Bsu!&%aGckH!YX^l{`SXO?6) zTPKf18|NP-Ln((F{hKj^x4a+Q6#MqoINbO=$muM5E(c}5dYk}mPzKjNs^vwAb@&g~ z9*n=Lg$gBe`k5TZ0PcRG8DCd$Sij(HlYeO+(c3aJ&z|V7UUjyGm@3Z0Gn>a`BS~7l zQ-6&)2KD}({MYiT13%c4|K?GMNLT=d-#?zn3|(neh;=yyUO!shaxCwUi`V?Pu`OiD zk!-+j;ADacovj1&OKjc%KkIFQ@lES7dyu=tOI-H*P?M-h@9N6Dpws?;_kemSYnjI? zKRjqZR&@kSyF>+16#blt2#p8{|0u3MRv|k}jd&?{TV6XjI8@*`ccV?G0tYsz8%B=l zr}9O(P7Wg*IvMxu$;z$1->>9!Cx4kG4bpco7l5;$&eq-77DE+p&lj63S-%bbkbK?B zw6Q^infUb0>v)p3bQS75ny*pT*6Hi&&V#N3q1~l|;%w5xJIOVJWSDSsq`a%Z?rjk1 zGOG`TvgYYE9{UBD=n&q=&O|xmIT52r1L6X#E$0*cXr&4Qn#|l}gRcy!qPmCtU|8s; z=fL!rod6I|-NL#X?V{$dUtz@W(m*sQQ5J5Dozx=;>Zi)6?2RJ7cQ5$_un( zKZ3l)aL9@}iAC^ISf^i-y*i|4Y|oCOC+d{Hsanvp=!FSh^y;YHyp0f)V7y}$;z1r4 z?@zY;dxV7#@9ms*UhG&}=TpePUXPFvDZwMZ?@UXvt6B@VEzbp;EsMCBJdSxMnqi#@ z!b@)S1|?!QE1aF2|3{)@#%W_6Q~6Mp_u@NVY2=*O$6-9`BW9*q9J04v{SiuN*{|nrO{^^n(-f(nH2SlqH zRNh_2T3jc0pn;BTj>&EimidzN($I;+H> zu>rZ@)Fh1ksz4u`jH_<<9ps-grM9N^ZS{s}%mgr&#f|gS3Fe_B{c2%C$wjfTDJhwi zWdUzj9YBxyk7iRD(2FG7$Q1CX;=7DigA^U z|9kT&`zXH8>*}*K>>m9&KStO#$myO@Pv4d=_O~BF7!Q9zN|G#Zgp0S+PSh1W*o(3T zuKehDBIBx~<7|6mn{H4$$*%wq3(sCFK~(Jzckv2q*8!{H?JFjgjM9XX@yI{X z<`xb1eOXx*7mmzAjn&4bO_OrYY>d21x?mBitTuhOsHhJ$6>uvrZP$(6Ono5+Na<;k zA+yM9JbqhLFS?+QHFH2&jQIW@*a|rcG+g7WP5l_GsO_M(R5V)8m!9zHK|%5%-CV?- zAnUNcf%gV#do7&Ua9I(&^2nrQoh~JX+|M3Q?5cwU0pFUqWT|I?MWz*Sb{s_b@iLr)3#Zh$j9R5o7WaD|sx4c< zC3e_{XGP7v!@Hc|;L1RPR-xnOp$gHnwbMOcHiWx9Xx*bxzrtfPX2Yc>@h4UW`o=!4 zB6&4`OY_C8xKAgsJZA_hWJfJ~Bup>21W4v}O*TqWQi3?BJrOOW@l4=|k`a;n?EpX_ z7U2_A-Qvl6sQQKjzlnNYM>8!+y~w7kS8x%2a{#ZRx^zq^?Y9GBRr z>RWKlGnbu_hJdZ>Pya`PAO$*_8h?s1Y97~bhNax3)mG^A~i-)3c*yH)yjE{@z`#mKcCLV{C1U9 zTD~DS^eZkITdv3p{U;P`m zVe8Xx67;b3xYY1&{|4XAE?UxZ&jHhU;lt4b1gEY=9W9LC@IIY?$$r|cDL112mJfhC ztt8i*_pm$7|05yfBh&ln*g9cZhF z1SO{?Xs`VB(}ky9w#&n}sBQYl8V7{sdasQ6YMWD{s^*SI{DpOvA+TDQgXzhJD z)~bBdtiQ9Vc^NTxCQkd4-?v~v2_uuv9_KGaRk2$=G0`IxLHi5sF@07^Rck7E+nomG z5k*3s=toXp|7_hQ<88@gQkYQWuoyn^M_Y$X&;0dqvSvD_wtr=3s$U^q&UOY$x!%q} z<2BVaY|d=oq5?Yo!z3_{nrR z=i3RO_P04kBpWLSelWyej#@dSIv6XI5KCB|?)SN*K}1v%16m{GiI3`kJb!S5Qy3#` zHhtP_muJ=1eD^2&Z_2sG(dX_56xjemtGk{bn0YGr&c4?(xK7I?FB8b7AgY+C|cK02V=55=gAMtt(0R4+W;K0e2xVGMxL_s zgMe_O-(@^EQhVL`qI5Qs-=<;>--eF=6IVB=cBOrnz1CkCG*kQcwYA1-!CzgxnyL4& z#Jp(qzJWq-u!lMQ?=GLdWOt|C;Cm&NFbZd^`lNrhwS1tQif35})Fau}jZc3E68y!pW+v&-JmFVN;$UF=7rGFY zeOzE0=My+a7X#&$t$zboM83OD@wJpNJolm6#GzC1+kmNTo;?1=W_lsYyBT zkg5&#b-{wHlUbAWPzp7>aRH)3p7Ec=|4PiSO^|Z`SY^)K^@gV4rk&n+>^_D6!ldjt z6Kg^4p4Ma4?H$#zfy|C3A|(3_z9hM_IG)nn3(c>Wj&B!Bfm11_j85GDRm!(Q3e4_S zDe1WY)eFHvI*sI)z>tvbug*QvswQ7}{e_!cTBdUKVcrS!U`H+x{Fw_sZpZYNq z`O)G;B|A2WxN*5xA;);!ox4_V|S7xIV?T>deRsghze)FGr zgc=&?f(7cnDG3z-)+&PDQO}d+B;ZN{)UM!ju(pxtx(|nX)@~BkKavY88DJEMP-Oh* zIgBe(E1t@?LjvPoEWX-yBiK7rB_do9E zW;d;>ms`-NE?K`wS}5<*7tu{8F-aq1ep;i`Nbz&3N>}j1;zVZ3@lQwOcL$Troj^@Hz-~U`jM)8c0(Di!Uu9Uz z1Ilw%0w~6DYSCn^!TPpeXehOFXTELD^!Nqp+T)K( zu-`R>IEtmt&!f7R1_RSY^OBt<;(^?6v0l!*YF2%QR1U*x*EON86kTm0K)P+%bhw@l z!n``Rz`4v=#{q%WQhQlFWUY(3^dwkk6#T-CTr(NjmhxLnbPr~0160dNk{`Ti@+LJL z>vVsrDXB477Kc7us;f*V^JJXyZq)A7S^svT7i+rBar5aV~#( zjq_&cY+znqd2z$=m|iE?j3zk(F<;#bx@!>=Q!)q`UNmEKAnhz-)H&{oSF`{I|Kn> zv@NDr?HHIDOSY(7o^V`@sREKx|MVBDf?k*XbW54Q$RuoPnt2VL+wazvt}GAksR@I< z-k1!U-T_vz30OtFnTpZhZ?wns>$3c>O}dhFerpeq|8SFd+V&@5exS)MOXfa4C%;Ntpqi$Exm#Kjf@5%BK+}-K*g3(hx>h}mamyC)e z&(96giz(P9nt5NY&o3$Vzt1;w^=Hj0*x__%Dm<%owMU*!p%!B-|64}(r}Rv!K+fk2 z4IheQj|s(pqc4H_lU3j_&Z4Lep5Ul3yZG^2+=GPIz=`kII$BAPxTm_+|GdJ@CXkz3 zQSnglcAY@n!&g4-fIGmFIG%q#@0(}f@VE{PuGEOt0_P4f-2C(WJPOc{)#|XG6%_1` zZqu1|Lwjk`z3J*ad`!>UALOP!g>jt;w*2(47V?zL@KQWfLsJX8>JP8O)|cUc!Kyzy zK%S+O@egQVkH@_XbjE+=Xyh|E(E7^|k}vS`^$9+kqaSDTV>hfH{h5xI$Y08~_W)Qx zqqtQ-W*nKDPWspO-RK^Nxl@tcMtX&1fc)B-X53Ny*S8b}|8n008$&1OwR%vT! zidtVdsbc{2HPQ!u>zwDv*^CEqiuMhJ7WRbEZTL>z54mZ1_ng`p!M%kXoc0JT#q$5m z1^){J{_opl01|K-9|_uj%bfSK%{qIzp03_*kYlm zT5QeGWOeF@R2fdRxivoghJW31@ z{QCe4ow?h&H{%Tr+lpalkZ+4BiR*X?o}ChSqQYoAy^e0%*qf=<*WIprk1?t+L9aZ& zEI_PT6$=Ms{vx3K4pZtIRS6d@8bzV34)&#`D^A+&-@B%UgC|0QNp?vMrC#0mFuHDS z$o9Q>#x|=U5u>i|j_@uH4KE<&xsA+$AlJ=Tff5TY_(2C~MnmSb0h|yy>rw zHoKrY75Vo4ELzBF2KuQtnlo6HYoGIXsX=>3{f@Am&#kwWjOpu$ZbVbF^~u0(RynU! zo3B>kMwW*E;x8y@w46uq2DukM&fQDVS&y6*pWJo5EtM_RKp^AV-Frz31?hO1hR~C@ z=xlCq&)9y>u?`s-ouN(?=kWN(U!5%+{hP7kRXpLA&_^TzEdEoL$xTg1eI}|ny5`#N zu9ADI~l(tmPcCv^6gn8kUo`<_}glmhYYfxka6Xrs3``VbGgANl(1KjB?@j z*`oLEN)~-!Vl+Mbg^$Cf;1??ie|6)$^pn683SC`sS5?;TG)MvD6Z^vrcwrm3LEy0I zSbQ4SW@pNC?VPN1?_PQwZD~jwZAeCLb;llo1TYyFhE(73F__PmsM0-tgDFmVI?XSn zKdd-+;7%(n_xR>BKh!rpmm21ijj z3Gm9%oS}Ro*+s#=xN+3dyxqiQz0UK#6w{YI^5vD_Duyq64LA1B;6A1qWszVC8cSua z7-JnsXDu~j?J$rR6mjPvq3jx(Td#fOP*?MS+rMDE>ajZNmV3O{;iMMKI15%DTfwv9 zdsRkmjjdHgn4{-Q6oUt~f)Z68%PMe?!-_{t_M(9rH3Rt(5F*(TMrFh@p6u2X{=PI2 zd5Z-q3jT%CPGjnf`(KA{n%G7BIX7p2V_UudjMaTk1AM>;=%+m6DYQt+gn3R7Gs%}O z_ywzvG6^$@4s~79cYW1@g1F(cr~Y3%CANWbVhylBq2xrL7`+5@@xRQO5~@$nlV{_w zDSdax53hVz+}~^w{;2vUo?=p7WrQ`9x4@Cc{Q7hHUn_pI8NYvj`tO+TDF@g?GhHZu ziA|%zc+nGGU4`2`1lW&P?quhJ?#GX6d!YWAOjWIQu%DnWG=T`TW(fmeI-AEuCnOel zMG)&Lmt7==*T5nMPa};3bMphR{hPVtjJ4GTHCcv<>)%&S3P34m^{Kbr`F$5`Pd9o; z!ZZzuctK&TX@;QTd+02=6knqM`wr5G)NfntBrHOUe(O9WsbDS|NCXwTeJH-Y{+k+ z9x8OfQ&5y!Sr(y16{h`!_}qs1P6rXcLC6}CCyNBUpn-0Ep6BjoB7gN(T~@@FP8q7= zwTuX{WOM33Tyw{TO!E{r8;`U@RsiIkN1Evx%PuZ=|bUzpSZ;?w!d4tIfoY^S z;B0~7Wi{uwpVofL0;^W7tsZHq3e;xb6VKcKv1S$PMe*_Ih7& z2E4*&G1AsfTh)Z}qR|&xJ4v=CVLIBVE%q-tjb>ZD;j)aadqMmI*DgO1giTv?ZWkt&-${i6Er?k z&X=+Rg&WgJ$0?n2R>UEr?^tKs}c6W=x}xBiWvxV#@R z%q~M^UVGSh`?X@FM{9W8HZ+KY{oo7Lk5jF7>#L;t)wimqF%ki9CnUxO?)guN@U^Ih#M2gl z>e!HKZ5^t0jgH)u;o&T{C3DVsc}b795gE zZmblrm@It9(A{Y5%mJmUrG0PGF9Pn5WuH4A zc1;=Q62GHL;?9-FnMDwEn%z_HaioZG!{pTKDk!~fd^Y!!4U({%g4osUG;V+&1(QWG zv8L)s6M2^k3L;W6L*m=mtYY)GOejcxhn6>K-&V=ir>bLh4)qmJr06#EE=EhPe~6;< zJ5L8n`MMMFvimkJ_@ab`R&r2o(P7#w8H+)^rp6QNk%mhFmkalpu7-P<&mh~6m0L>Y&tInaQe;q$$WlT@D06T8*-eoH@kDrZg1ay|ANQ z%#$;=S0|Eu!!S{Z^zQxQr&LqC-v7F6;zh^3(?7i;zbwAixw32(mkU7Oih#PDI#4H* znnmZ;3>YNK#a?Haf*wx&v9htns+EwdJ|SVXk>Yx3JSp=m@qZ*IjuibR=3FexT$zXL zIk29giIr~3j|IZko5%!Gz}h6`$gF6(Ud`b{MNhg~Y@D8&zya2BM6@>c>wJ>T=;ePiA|lc06P>-sTq8R-8Cl5_d9J4G66RDCwY6` zn0J%iY(Mc~0h`IXA>T=$5n-|GugQ9za!(9T<{EUkGO;Glnoo??w(4u}iCcVckDenzLZRH#W26ZpJyAmL7jHJs-PQr=kZuEk>ZHxs%I#i+PPd-Vq$Kl2-5zsZ zx%DVCXif6Yng2Biy5lrK1$)Wubunz$pgr@TOnfYvDOh4WAm<*uoTW`3O34G2jk-@R zb|POs$tqaa=2L>!Q+QqXbFn62*;W>}P1y{B#u3mb{J!;*D)R{$Ql-=3iIb&X*Wu^` zhurt*Jie;6I?d9MP-Q6f?ZqMYzB|g&493;|%{%Hx*o{r>T6-E~d4(yc91}h~JS4UC z?*4ZfRCN~#NtZ18sX}F>gy*q2*YUe?-I_;ze}rz`vH72Hfk9v2{9AyvJ)} zU>!!RyCh#gvyO~QV^}bQxXtWhpc`cXmaM%ll_TF};X>1?G9^V4wUud6(xe~X1GA|^ z>j@mf!c0@eDSpMn{zN90VxqtT+pIH5$XT4l5Kl4stYj%MXZ9tmum0JOiB8&6H&ya= z(Bq^;HC^0$lVc{l&cv}-%}}cj!=~T~llCB+#jQ`~uwN{o4wHSP?YXNW&|{dMs5s*! z*u+LBRnyI{b5C_jQuz3HW#U)n#QOZ^7y-g&@0|^eIs#n*R?y(X_?faXhQ;C{-6Zsz43ydG z&e>y}4$N0R`!Zse3u~J1qRZ=jp<$s=_vNU=S{olI=WJF=GlIuZlc1)i10l3|W!;&) z6UYM4V5T=W0XfE_W8?s{3KyB5i?{v^WzFJSU>;%+FF2^Tw6avy4X zRxy6}!kBB+rzdi(Q``ymv9@`2zX45i5G}YG?*{MIt&cr*6+(k~J;x_ChlzxIvsu(v z-Hs`xj{H9W%aC-ycZuy_x4vq`H>~qoVY(~6B7gfdCCXsTu|kwd^h^xDMX}Y~84#Dt z@(R!4B4cR2!!o0wG&*TvSrl?KX>Q74s6l4hnsd*0P{^IcjVz5kSjTh5KJ?lRyUlky z_jG3W3<%jXTNrz1FUciCiwA63Of8U^iF+P`q>-F%usIL(9bAkx+byDC^a^XwAE?QavOKAEncH0;k=%?6_8Sdj|h+kC^#ikNCi$GTpHtqQmuMcxc2? zm3NbyQxu0C)x#!De?5($i={D`LDAZKsB*@H!gOwX6i;+-?#!gl$_yd|>Mqg0e6%}$ z=?zRo)F_}4z9e=Fv_T@exY$#tC-2zovGbnJcL#9Sf5hahIDc${x6FTCS|0#?P{nO|r^dOrO;_HQDN1oYB-7_L~~gvAT=4Nqsm7 z0XYx6=t^C*4*4{;L*SEy=j=2|PVdyKnX=nD^WQ2iace71>lF3_r||@DlK@Ynyi1mW zV{%ggP2fPK^qV_GH7yAcnw{72fs>2<6BUs}IZxORV2WpF1?H-=^PJwnz=1j7wvWGz z>SB3OnPWz3b#CFd8?%RbOfapo+q3d5t@KV*DxqY`rOp}sQ@|iap5Mj4rskfK)-5u% zH=g}&w28W6kAvCb0~A7J{glvQC!WWdkZpE){s#;SNQPTzQumNwbkZG^sel98{&AYY z?a6V0ig(`>OlLVCV-5OFf#I2d@W`8Auw{S*<3y)7Uq_Ys4uJp#_p14oSjP_D-4m0d zlczm@|Ik90SO4~H#c%pnN@}J>#3c%7byPjr;^JlRp8ui({>DJKe->PA z__UKgtp;gAow6CR{y_@#-0Hku85l_qLf9anPONk#xpaXw{an<$zZ~8bu2YqxID_sJ zr`_UFcOWE8!Q@Yat}GBhMaxqbVA7VbtHtm=5n|xt{MhNt)O_u|%$8CQdPxJKkR~DC zpNytVphaS2 zy7WzS!zHW5#ET|9{m808Z%**!`9ee0HJJYGxc<%8}znjt-_lbI*o$V!|b8`0&=S5aL5Fy;xBS>!z^ zyQUuvbd5~K@0ySyO14ah>2VuEiyNU>9>M(S1y`ImYez_;nr!e5NKof;hO?=2gLBX- z!$8XDpjVT6D@65(@rwm1(0O?;Z7 z{Kx`vJ1*TF+yDH&=Dj&rVX9Mr=O`O%HC}C}F8U8lyZ>hI{a-hDs{3P7;t04`+v2W?_+a>R1~1uRzJV=dN0AV5P? zw&9WNcOU}YuBxI^GqGPRQjj7V*M-a?Egk92o;Z=I0-sih8*aa ze)45m4fx*W;!ARahb;O)b#k1{`%4kVGicb=#HD6+E7_bz`PYdrq#_uqJH)b7094Wi=|TWhM1 zk~0m57$aKfbIS@V^MSX!2#8cj=U^OahR30PnJj&edxVULCkEgG4C03Ffw^5V&IV;) zM_FYYnBVwWp>-OFAWC7z_~HHm2#A!k#@Tv9r&_%~dzw!oqPQsVNglp!Tt$Pkt%O(u z#xG5s#gC}Gqyf=BySu|h&y1eNmU-3noIFgOqf5buDvySBJs+5xu5qL+AG~T8mNViVtB#A^$uyLfr;Ti;e} zZN0+DRpLpmRXPPYnmo&}aGJj?*z}>SWJFtQxh;X(I-&vHfG_Hp^GMjv^P=k{pF!9vX~TBD~Jex~=K-7Zl|O7aM>1Ps2#JTws( zb=_>dON2H7SEcR5W~QaX85>ul|Kp}Cfy-7h4nRi=@7{NP$~T4bf2u@XLm^W+sYm@Z z+jEZ|0PljhA;xfeWW-k@x0Fs5!sX8j;1U%$dh0FU4dWr!I#!E#{R0hth?jXy5px?_ ziV*RQtT%#T<4S0+1PJX>K^b0Ex}HvB)x8jti{cT58$5)j{|EGwy2wmb=MyZqAo6YI z7JDJne$YeO{5vJ>2Q~&Dhibw?05EGGdO%gxS(j;kz25dBWl4_{%^HBvk8_89r-$Yo zHRUFEBuv(a3QaC}L>&yK}27U#S%6h!~q;B`jjWyHk*Sm^-udmyg*vJ%X z8++p3V=haC^iQ|E_@4#eXh*a-Db!@IJ)lQrf<1{6BebiP{EzrHj>RQtP+7{m zCspla#$~P%pog_2R_OjN&r$3YsE}vG7&>U$;o6x-J&})#bKQ5yc5r| zjK-r_vhG)kP-LrF{R7y|bv{pJruh8j+O$9+Bf4gruaX;=M>H&+*o6ZOW=54vFx>Ga zhIq@EQH&CwNI+2MaJ=3b`SV7LgB8FA9}cSUb@89lLYus!r=Vu$Iv-xUbY_sJN+M|3p2@9>cp*5~|$ISPr=Py#|el-8i%~ zlmbG+qOA!Jo&!Npl-NDm?Vbra zMcnk=5%Gah@k02S)Rk#`~%>P**nl3(mNIC)wMgL?y zU@%CzfkNdK6-6f~+#+}HXpN}Oc}W5bMy9@^xi`{eM7U1##d=2K^5Topx7KF8j+B^R z8vNBjifcsRM*NYzQfy(ZIfvtr3HxNB!1hl;^84YxEJvCT-k=W~+mqH69S71sBE1M~ zI2bS4=U4lv0)S&1n@pejMxo=My1-%0@%7Lwp}3DD&lUmlwElVZ)E`{_p2?VSO3!T2 z*PQ9PeiwXRjk4E)qE&8qXUvHZx$<|I?*Y7@79Qp2h<=B^)}-z$kxtu&A^1C9xh&0X@QdJ`b z^+}}#DC!67F>N5XA6>7kjM-ROJFqXsX-Tdd0fEHpdl&}WMx7l@`hgCpD0IasN>5!S zx`oBV;(I`cLe$?W-TDvyp1#C;wb7^M)>sE~c`d7E6Z=5Sir{D18LjS@Er2fQXf zn=Ysg+K|Ivf0FA`K1s~0WC6gxj@(0F7|y-(Bw6>|m0S^gqGmTgF{7UGWO?@S!RZL; zzaGFvLaL?Q$Idk*9y3PV`;MC(>yj_$x>*9!5BRs0C zCkvTSorvG4o&GxVbbFq_lX!=Cy^aNkKvWC5BOm1?s-skkn@li1c^>tkfZsLBnTt0m z)5zU*nj|wMX+H+s!)sHe;S^K46#x{{SV<({O`4SR{U1%S+3Z2XpeLOdk*GFy)t{*ybx4W$ro=4ljkwEdJAvJb9l z`@I;RuVbabZ(uNKWRQCpZ|U}Zwn3WiL+jEjd8DzSRPxa{LDGEW=Gm=6fsu(R*R?$R zf&+7ysnDs%WgRH&GDrW+^N3;Q1JJecIXO4MOh!hrwSHrVZJZ^RosFUqiCT8l=w+l8 zvd~}8p~V@Ch&4N*shgF|oIVlwxEt3t-DK<^P-JDa#PR2|AkQ0ypHrwyr12_Z6NMbD z%Qx4?8&E~FDeyzMZ2Dc_QQnpf?;rfkOPwTP00bXT)FVy(RX2HyQPkzm68f|dwmuQj z#$#zT`;~S3b7!UzL+kn-X@q;lxPFTNC<6k?WM$FW_E6Rq&Fnk)V8qv|J`{K}gA&FJ z0*#AN613Un`?EGLJxbT<8#9(F1$k&mj!o>XU8e)kcQi=tQfcF-dp4F=f7Fn zZgGE*^WxWcj(s%2z$y%gt_SC?3E&^RppGuGajaUo?nX#n#>*)d1Z(t%h?|8MLR+Wz#R1VScTQ<+1PAFI3QJ=Z4dhrvCcSP>l^V^a41NUBbp~nnAf80 z5pFYHtEm<&g~%QiHvN5RWX-X|`$i%zxoK>wJmkXA@an?%_?w^m4hU~t?B&>~6odtr zMx^X$X3)L-$8%a}{tqC)@~|c#W$ZDOvH^NeBT7LAOR!A%gnk@*|kB@K>jHr9QMyg-mO#s}8q^=|ik?&)D}kyfp_*29`%gB{IF zI5Ibt0&j$Jh!TsckFv@{lQibQKyD!DM`gv}F#Y4A>6i@NX&WU>u!u#8HB-vSQ81D9 zhG^0h`-loV3$QZ?;N{`rI}a|a!9^OzNS9KPgZySwZVEth7!b$H>>G2gLZY6Q`z2i{r+T}Ksqm8wz2lS;zosj^V=&V6#0&~~N z8^Z`wgsIxlw_d^To17yRb$0k|eav}~_ruz9X^YePIolqqzHxzMkp*|HDXTa@2Ej?2 zj%%%_D`3Rw0+MXQI*@55j@dIFMsQgVYm`*Z(j>To0DH=S&O#F{ov9P^_kcXc#dDHB zP(dL-oidWvm;lKzgPFL=FFq?5ZNcuqG@Y7M^)0?2-F;2--Ewm0FDlG(+#FTlb1Oo> zNRO_)cr-iIW>sHSR1q}g)gmy&z`yD2*4IC&-~Uhpb4%+X%}Ud}=KdnZtJ!Tr=3_oK zt>G_*(gQRL=yb_*4a_TMBv0~DepWSZ%RCM>8~YU_ZC9Kdky!VzsUyO7iuJU?g9R}0 zYQ0WJ6AqbX19PDrnTIq!uLP6qJc@!~VIVl?g;}p!;S8VW-f74eHMb z5Trx_!ku~2i(`UBM-x)lchuBn2K4nRDl+RRKeL8NP=eGi06Zg76niv5V3!RgG{WTmS)ry?fI+Sn2h+9Zw^ z?%iKV+|Rxr90XrMZ%za60_?C0SaaGz*U1~iFQ-LbjOK4b^6EZw(3kUMOo?_*%+6P>8W#b?BExlU- zyt{?z6iCUh(aQfqUeSNo?bHz^=3g>`N^uLa55A}qd)pv3Y4cnjl04$-W=|Tv(Y2x9 z7`iPM%_h}oO#2%->8e8^Qf#pmv9Y;T-A+mLBv2{(NLo;X8!{8=cwykARvb}O=950D zb8Zw-CNRY2G#%8`P&ZwKbLLhG`1?~}xLb>V;BiEqa{b%LmLAqo*#@0aGr^PpA4_RU znp#u{IlQf^=ogNwxQVG_!x>#f^Ff>i^&GbApAO!&#kKZJuQtz<_U|3ue!fo>TDIGM zQ7}Jvg3HSS%X<}!O6?ELy!W4$Y2fmP;-$@(cayp+@3*D0+g97e#sWr2*I>1zu*5>9;)Sbq!mmsxBJ-zdDBidUmb4Jyq{H z;UAWZk-EMwjHkzcYyJxo0^ExK2ph2~q=QCo$jXB;Rm0{m{+ERt>pr2zWG{>j)vmhY zrN`EsZ@JM=-WjhJ1tR>XAY&Ij^F)#?e;L%Lz5_w4c~BtODo6q_+i|EF2FpI&#LEy^ zvPa8M#{WLT{(c0mf+OB{S&gUv2pOqDz-eU5EoIG^&qALby2ixS|TPUF@|>)r_C!X*_({Nzv~w_S0^iB{t( zLN%;EMUl2P#6aCv+klh4?8Qj!E5!dt+k3~e{qKF_l$N$)w6$lAY7wKh&`Q;++N)Nz zHW53aLaVeW604|{)+UHrL5xzH+B*@uwO17_-}d}I{eI8+UH3WHeXe_4kNfpU5XmQ> zyw__#pQ`fmHcgYn_`VK#D;EGRt-p4nGj%|*)Ll$`zU_6jwuovKk1NO%?e(Mk_v(C{ z3siKb-OGgQlk+C4^7GD)5+W*EIYlbfsv3767&~wUNRY4qBXk2%(freip7UH{Wsr?y zKsYDIR^5|w+MNX3|ETHkXeZdcv9CRQHoUj&x}+i`B8%j9BVtAJ>dRGOMbN_7PV~-~ zQn2Azoil52x2`En4`i1FP7GI{byq`Xg`<46$sQLO& z_s7ns_h-3%2)#l}PTS}$Mt>gbEjlXSgrH@*N|sg8`@ucpMBR-aB`cR?s!cxvjybQ~ zeV=d2`N3E4Z@vd}R-R0IK}1L8Yj&A1FfjLX{-!#iK}M+gK#IVDVd1Brfx4k4vWb`7 zh4_VEyv_Q}Epqw5fi+=PK|W7xAwey^(l{=n_ahq}lafIE9lYD}pQV-g3EL1ulUv1O zV}y)dS_#P@NB@Rfbkfw6Kp&9mb3u#BGL2kO9rDxYn(8~7CD)t*MCQrU2oC#&%#Jjz zqvuTzY;|eRK!qLoK8sDiG2^~B^BM7B>VlnrVSWK+?q={RJ&2#!-()ZIu}r#gUI$J) zVC6Y#ZSq7ubZ6O=ho#fw>fT)*b*YfK)c}U%#^yNRZaF)J69J$Z>reUbfg~|f4}g7W zS;Cn-K#ozVd&w`NLE6Lcuf+BauwL_^A=A2FwV!g=9%+NBqYahQ! z#*xhX?XA)uN~ZjL>X2$dq*s}Wx?Sq#2HvK5)haBwT|Gie%jM`6%Bi4VR_audG-T{l zp3?bs$o-8*i{Z@&K;L#3~Drvw)V5tKE)NX^?3T@}hN{>r$j^VL?{OEzAx3`a=J*$V#E$(m*qnV4d_eP6b& zu-Sg;`92%D>AOzW7l~|#I=$NrxfGuLdib!4{ev$W#Ob?aKzB2`0$PMbkCZxdkq9;~ z^)pavAwyEBg=5#ldVnvbk=LuLOX=O!OzmRP9IkWmHRBZXKEdTm`%V8Lcy4b;STlL; zW5z?=ELncWC46RF(kp4KrbbqWG9#9Czq$t!7cVmX^$cC2g;fTCcPxVkXwyn9?MtO< zk*6tV`v`&KW<#2`N9iKI{cnjszeFTssh9*MH**@PD~h5`$VW4^T)_gA5tb%8Hq4iL zImcmU($DJc7jC@#p+|RbZ0?>!piomb6kS{~W0&G{0XfLAx@%t~Ss{olC-w3N1&FmX zGSYt((lZONo8dKfuc&({t{2){+&B*54~ZpyAB;KWjIrp~cc?ejnKO*pG~!W%ta%Zh zMvWe!Sqc{4llV=@p)x4a1}^H}e$&#b^NwI{F7Itfrz|?<%*PL6$)bj?Jzn;7aPE*EPaA#tB_#x^U=eaw& ze$LW4@kCL{hD*zII`r4z*53LgyQ^_5R(mLKxOi%z?vCAb=(W4-V-YurGwq8#8Y<7=J>IumY9)%Twe~!@Li+Pr$0fHOVz_r zkD3wE`u#{O<{Xs$!Pix<%A7pmeNmbWA!brnpPb7$H{7ctuLK9L>2oKu>Mc?AHa2IE zbi4h5c?OtFCwQr$&6DRhv$dY_vLjw^Z8~IdtIwxD8S|kCWG4{MRl(w_ zIykmmJA8#IS)7}{!DkRVEjYrq?vt|6`@2}JUgTT<&_UtFoM{^2J^CP{UoZ7z!l$&0 z#2ruu8tDPWJ!-$U*%5C&yIn}Gu0~Vsg`KT88$Jc(;t0BXR?TS2SKpm@DM2B+^0oG= z;2#%v?VC^=PXM>vFGr-I%U)*Fp0`gsJud65WIP#KnD`Qa9(5j@FN^}%%GqNcNXSMzqr4(r#hQ4I|(8lCQQFYKm}@oRshs)h?a%V~B$ z;V$6SywdC`!LB>cc0|9_trRhEx!=9H9Q9}Fmg9F~KEch-a75h6vazg=-W`ARwDxo- zoMJKg@%(CJGls$k4TDIt1X_LR1#;#`_B=bIgrb}HoSbBf@gC>wZGM}k(4HY4IVuC$ zo~zAe#EQJh0fhbzaW^!-(ZbNqXyerzuWADLt6$&)9x6Wd=-OW|;W2WxBkQ;x>{!B) zotPifvqnvdCvS%5vBB0+I6lfCX8){huGLv{$JMK?j?bS6Gavr;CjGy~WR4sLM_A}4P(1eilKl}oU z?QOQ10oN&FTgo}u)D01kqLN@cyP-q50xzgYI+t3%vU`r@?L7vOW>y7Z?ubIMtk8X; znd|;YpcPx#H1hc{F(%_j(T$zghjO1#LKwZ*qa8FE)*;$T7)_RHX7}>k0N0sYHRY*` z@>mo&08lBpW7030uukuzw6pemybOaS2+~Bpmt@(Ll9Q6OcN}+Ho z&OCiFLxC)hsvuM6CD4@A{4csIyn~4=jlA`Psxi4gN^7>?TDbR7AjQ`^;Z?QIQioWR3?25+|&=L?g;VP-HxlcicxF=`RtjM*?Ft6xMINxP?v3>v8Kb zy@|xcujbG}CREJ9|IsIc%-4(W_G&g;g}z(|~7J{{$7t zv8GL;MVt$3N0WF(EzXDFyA-jgei5Lf_t9cxasbKP z)}$nwE8{C_DVwqXqrQu^;fgdMB(?kGCos^pBa3N+1BWRtmY~<`_qMZ#*OV!ULu}+j z0&o8d^jnnFExC8QENP9;)hIo2UIF=WK%)T188sqO zA6_?iJ!>lJIcU!3JWrKkeGah~nOHf%TEk8DBBes|t1q~WA$)9|BL!P+g8)d_5XVlI zn5QrGqj$VcIdDTQhoeQeF|ovc1$ZTey_!6m2A5|Y$Oi=e&ha-W}R!7-K_xN@jvAA1GdUl4$} z@;cbYkX*Lc2Yqd#KFLYH@=%+dCAlLhx`4#^eB|WUBpHc+KT5e8mwY+@Y}H-Eo82{0 zio;qy5!$vy_N~6${C;iJ#FhJ!z0qcOj-Jn6%pK~whelW!=A1})M(Iu5#Ovuh|H@UQ zlbH&BF3zR>H!2Vs#`{NMiYcNoC+7N9C+V)9B>))8k&DKfPJn8Kg)81Tz;7lpw{dcI z*UU0_rqm-Jml97L6uP9=*^S6)m2=9X?q&C&9hedZc|Yx{uidpE@$VvUX6a`SUbEAwdNo z0}RqZ1&67A^@>;#VS8dt^4W+I9s@@yZ9_ z>!{D+Npo#TL=8Ei(SCbE?pVLI+hSOMLQhD&m8l1eq!ZNgZCBDv(~}$umfkATdbqwT z_l@;9nB@BE#(Y5WC4wTxfB|Mbsx6b?6NI^X5$;u^MN^B8U*j#h(~k3OJ4{qWik-M3 z%q4iq%M?b@P9LG3*k*bC;K6kQfA-O!Sa@K97OL3vmOm2Ay zQ0<=X5LU+YvDX&dkF!Qbv?to9`kbELG-T%!ed{3@0kGhTRKUTt8=I`)$@CY*TQ$tz zUvY@UyE8sMV2;qT3+C|bDl8Zsd5BQE$g_2*U-ELxZHIegH^ixU%G@bfG`FxPV8T?a zsCLTZ{2ProUK3}uXimvoT}n@QE|kE%F9ba7luYqIcm5cANI*`i8;P-i<+>P-~US`RC&H&sX^3t~Zu7I&+_! z=^F6DH?E)B9@u^gwSkGdZ05)Dp|WVK4F%Qdc$6=dG?yNgR5qWlA*XCDZ(hruug8ahK)6gtvJ936dnX51yx#B^=?bi96BXHAitNDXd>mx+pyGB>y0-qyQ7 zdeVD5RnH)=a$-iRhS`#go0%9gl=Yj!JPoI(W$9q1hvsak@NUIeFB|pB^RT$yV&X+H zIQFJ#+5H|pFa2ycJ8<>STV%H6T21dfMyaRg1Cp8!{O9~u`IP~_dBzL5r#`uP^}_>D zpMr3F5|ZOfxLf;jVo|2;SZlg@z^+ z&3nihDRXn9Z;xv9^;!7}Nm?x*hP$41xDeS)n*!MuvYte1z}s>HEK-IilRZX}DiHk} zSBE@7`}qQo*qc5NDQ)|Tusr+S)l#MaVD@Hjt1R>v=G2)%17Nf+#7HlkWsM&ruz?}x zX)#vav{nJ{*BE0Pua6w#P#tFM7d!1_I}*4H)Ke1c{gBJnlS#_x1)rb;dK;^2!vv8W z#OD*(U|!6o>cQQfw>*|N9HMLUXgb`fS>m3)1i$iHo}PG!`srUhw4A$B4cIZU+MZvx z)%x{suJTlmeTSqQ`=lbzdCSjoeN|U>TZ$eUb|ZWGpk%6(+7KuJ~wDTuxY)(lC0FDtMI>up<5%9YhCZwcRq7ZWJg*Eij84;(YFLB9w1 zjlba;W;eLi2$NGCv3tU(>hQ6D{hMMjlEcu`t@0;)kJOEWamj`ON;CRIK)HAvf>z|d z509HyDP{jL#$vuAeHe`8V@M~6z6#!wy#3(`w zB`b`SogyYQoVjm}5c+>U{T8Qqni=Sr2Me8jpBl877Zqo4zI7IPN4`AJ-qY^F(K8U? z+}z={{IUuVZ^-LW4F-e2od=HoVF&dkdAQQ~;cjP14tBWp(Dm|&uOFk#wY^dx)ZBs! zr=1z=#(wW@ugPu8Lvw?lXy`@QT2lpq83n@BdTISc04MO>nh?&5EBUdE>8wl0s1@up zp;Ks3_f;82i{aObE>RUtKafo(5mHl$7!MVan}>VRW6T4WM<`);4lpoU^jl)Nw>Ax; zQPM58{Pu1c+eIR%*f=v&`MoniEAk7e`&*1u$g}K-d5w{$Qz8-p*75GazmB1tLt(xC zvqe5T;5MZL<`Tl(ur;@?o1QVjU7S?}m)^mtQke8ZXW=5SCEkj^y6dDP6PmyEH!5BD zrQS`g^6GYbn)3lSc?b`9o)8r=VAXTJt;^BZ<#{V|e)SaZcb!p#x#T=d74wc5&tFPo(j zfnvS%Z6U`VQA#I)BZ2k~YmHSGT$RTaGRs*4Weo$1y?*=0pK}T^n3xMnfy8cBR2dqkA~^ESHoVMcd;q3gu4Z6|jr z3a+KA%;XA2PnK~==c}(y8SZ4Pevstj9Z9Owq&&+elD}BL3EVV~@QLuszqpYCuMJ=i z4riD+I*H&(Vy4>9Som@|OlfDeFIF<+C_cw4EWE5|+Yu)Mb9QS#d*qBPNvX4#RCXE}RXa_b#&|fGKs?9gcE9q*+*%>;$~n zl`W&aC5rl@`uJ1eYnFY1F*!BXa<+R7_W24a_-~)(@RA`{5Q`DeCLq_-;i=^Pq4&cJ!X$ z*9hzFF~=kQl3}BMHMnN(DeOtoOh6%L2xE_ue~@<_n2wW{r4^$rfiEdT!OLnc%4^k* zzP5UV(d!f`G=1>ptE8t_a;f9cGnVc!9v1e2^AO8cTzj~J3aC27e1K1}0b11tsdly}y(a7@zXz0vy)E(w3CdJcc4lzf5F1Hexg zPRY$l;Yz*U{Wq%8s)lTWiktZ>e@+X-ySiD>6#iPBTMmX;N8JPdC;RGI@JTBwEs~tyb=j}|1*0{Y?1;- zrcFK6zKm$-^ALO0r5F((Glt=G^8h793kXbd-=21f9O2e%*lZN{I=AYxdBAfZKioFi zq(-sP0MHv5lEZW~$*#Hd@-Ooq2eVBPIFAbSc!Qb;B&rV$QVP?ndOl7y$p$Jz25)U< zzS5kp{{2$6!nO5kux?NVajry))gPeCGneH>ywMUy#bP!!-j5{t&53H3|y0Eo? zA$C^)wxpSWVn({AARvAR&~EVp=5cVW1z;ZQ|0nafjm3A;8aY!M(EK#BsarVpW}^+oF&I5Ch$ zr@76lk1x!owJGTwmy+Pk7qnat8}rzDcP^z%nz3h$KD7TUXtdz%qdE8bD-hbsj69cF z=9*Hc65sbt(WVFYzaA8`gV&mkCp~a63mF8{A@bc1Wb(a6)Y;@P*ZEd@B z4;xD8+@W@0DYm8HP_~BR!m``Y*$rZ(V!%@QX_6*?#n@c(X&p0%e~r!7{v6C*_SS{_ z(y)zUOaGJ6*D2p7F12n160Fxn;%YndzvGn#t(9^}9R781d ztKw7?|Jw8^`B%93oZyuw?jE=Oz|w1 zn-`BtCl55kdv?`nV}xz1!cw`z>G2q`uG*^as)I52<=fhsyjeQ)l0fF7n&s#rnT)D#-?D@~DeSh< zD!;*rmhWBQ14nxU^(Og&XS#$F{-vX?j6m z?m>6jxGSXJv=$cArP$ShB5_v~#`cF~Ep76A+gf8OCKFg~Am!k9jaJva#{GvU0J>f) zL{@i8Hy!9p8uMbpO(r=7ax_{dc&)RFd*Ead)i49YiA%DYOqfBYIIV#~0ZCtKJO`&} zxa7uZ^>(zI+WF$E&Fe%|f!bY`76omQJ}U>1Puo7vlCq$J$(aj~&lmB?m{OGZCU~bf zx=XBtk5kU-29RVMm=oxhRZNcwe&)mZ<aD!#FObP{w@@4i0G(WTf!x413#ckj$)^PjvkJNWcuOr7V>2k1!E zCTl9O*!@s_D8xAvQf4Lw?yC3Qajdj}vW zP1u}&=sY8zw9=O5T*eW3_`u1m_L}>Aap| zccTfDZ6M#cexAel^zzxct~Fms%hoE-_dr2eGa#3j2jk^efY)TUS6DWN+VM_ogHo&J zm11<&sX%)g8B0`MI)l=(t%Cgpi~~fut?E1T0?i{fn_g)bT)oEz{Il)}20CVR)t2{s zIZqqW@hAsgif@|M8aiyrEpOSlE;%7D-WhBV&ZW-7rKW1k@nfx^Qg9X| zZ^6{Ut`hf4MRHSV2HW?oaB!p4LyqjFk8tGXDaTbLA;U&>C`_U}Bb?cARm5xmQGF~f zh{C<+gq=Fc2$-mA&Sp;zq}+6kRx)=u@Bepp=F8}Qekk7<&ebA z8|aS8wt@X9zDI)cu_|I)57nkL9@lFM1-;?~bm;Gd+iWTA zo_i1RONvp13nyJ~UeO5&D#!*sIWKVZSp(6s{w^{Ds}k(y2=oVW^7z)sm$`9JQMXb- zSheM7uhgLsXXmC&VMG%RE1-)k7kfT~r;EOrN;2Tjh6rN-!; z4G-^Ccaf`+zKP`{Y6u-$ODkptB|ra^E0bNi^+9J_B{DMBVsw1GO+&ok<@<3J3FUS= zk*4ngZ6!buGB}<5Ej6=T?oGE9D+$@i9{>zC*V8FI$4Vos;`@cEkysVC;F*i_^<9zZ zRX*Vbf7KBV{MeEHJ7gkvXsY{nF`T2zig{vvr!mJC^|n9)1f!kES|qw=Rc$#Q)mdEY zOd!cwnTKh3*D8-C0 zIeQmiHG*xIcsjbGbf3NOfYEwafGF@#**JMB>adICoz^WzT3WkWsWtJLq8GcTf)m+> zTTfXG-x4>T0pt$2=}d*SgQ{jaOWx2r!|$P8qEVez{?A_MazF0@)1H%y=und57b}66 zo1DNJ(BJs@sAaqv!ah#W%Segn8nkr$5DC73P~Q_NtqZV;(c@*4Jn7X}e4#gi(mB zMbl7GDN)fm6mO|R$Lw`=?KS0D5pwco)$hCIWTn-T18b1>lG@~Ffb`xpOF0fdWe#AevyX0kOsNd{Qr z+jfr0d%dOn;?ko!t-cFExw0#?Y!uVb+I6(DeX*3eenFj)`uc{55Tu;uy}$5R0CFUZ zS)=h2%eShjOLcng+{mmdQvTz5k9)<{_R<28U0ffzmeg;F$G)e6w1-K7gFMBazC4w1 zvBNjMh>B0d?O!Au`k}H z?iQr?NEg2Um9Y{N*tL{rXYMl^%0kd|!ol@D*<(*LJ8mvpsJurVJHTYW2*1#uJggy? zA7uuxk^+W%)zCG~nF>(>T={G*jE1fASnXuHKxr z?6)K07yTpRSQT${bY0%f80Ko-S#=b859r>>kt5k$0w`2hA(yjR~k;$s&tS!g8ZWm`7-RtoQpWG?>4f0)9c?`mQAYTFgE53IfS$Wx! zx|WTLN2dc`yA6A>9Xs9gf;%nRK!91gN2K8W?2Q6%(N07$BVYD6MH@p6_t=N%u`5L6 zCl55}#*_Gut^uP#yHd)idaUHF7n*Eia*|lmwTvT3$pRMjBs)1(Q#MazU{DF8v}6Q( zqawcLlHIoVz>DSHoJrND(G-&o;B`K-S(oeTQ}7noH`fG54lvYS(ldt?CYDS3QeYrlaK=*iIIyX9!mou1InOBFnZW4sztnHE9aay)kEvO zX}O;lkF2}o^nxdnxN>AQjdx^(xeZGfel^n2+RWZNPp zN#EPhJ1+ZF3Bb~|{iwv(iZU)iev5D>~?&fQDKgi_Y!y4!LQVQR%_s4BmOT>HvEJ@dkD(!WX{ zy#`KuwK6(cq(JzcUZ2o$&K@{!?2gb1N*JbY9TJEj-Bzi!icU$0$;U#0|O2?{z2l;izD$~e{3NlRS3?``w%D3yw;cwUxN!D;d zi3~$j7}M@QaEK&orS{uH;wEmoVx5pWwEI`<`R;1@0kvrnOr*jAIpmncz6}CiX0AZT zZfeN=$zR>z=7aryB~Chl1t%YRdFQ;`b3JY_vN^>2n1i(SUCrEw?rdOkX|CDogBs<&RI{ z{3F0_Vp;oJ$V^Mp2ctPpxjGN)7|!5ntIhnuSXAG~CHkdTpKFIb^u0%>oJsu_QyXZg z2fn1iQW>8;fKNn=lreC?{;GuVid*|x9eNcggjhfMT~Bf4@AVYT;YyW*0ta{DjvbHQ zjgp~&r)%eEBZAsyRZ!`*wU?ND_2TNv(VN*REv5Y)x9e5Y9pIlA3C?G=tt>+)Pc^YWoUGyoFu>>;r`7s!Im9>+6aLopq9)e?FC-(x>D;NVZU~@1ME*s{Vw3Fdj0) zngN9E6!+Ufx8sZ*7OM>RZKBB4d#vKVS;e_${*sH=h(C3we&#*n5Y}5Pmy6#>oj={P zcCI)64c7B-<=o}EuBi_W))R!*12fMQ=<~2$mI(-oV>x?vxi9=$aOMQt5uC|%?4Ei> z>Ug*5$^p6x^PWjJ?gU^n$`-2T<(Q z>-H=FE8w*gXDwLdddgNg?FEvkZ^o3CKjx4~HEntjQhv7lmPLxm@t-_k|Mo8b`UkD| zx|H?Lf^CT2*0ljy%Eb-NfblA=XF7$C`XA`5=!i_K;bWWGLQQUF(7Tu978U_Lhk)XC zJjeAHZYIn0U&WLE>&I{f_{KZ9s~4A}!_icFxkdWRWz&YDP6jvbgd|9yUA$`faRKl- zx@Z^&M^|KR9$=}R5dvtX|F4C?6$Y+&+Ar@2hITd0h@X{q2_z2YoYr@H`MzMT9$zo6 z>m-PG$kQrR!GzI;!Ut#EVo9p?R6jBR?B2Ix?*(G8#e)TP?eDg@)GD0PRQjXw8(kOE z89Y&n(O(p^1!z7XD189M2}$je9Qfh$=@cB<4?R3vI=6|oHSl6Ed<~jpnbzQHg>IiU zt3v>O{yz&>UVds97-c&;fUby%G8zuwgg^17COIVY-1quU3c?KQNv82(YOPP~GEGO| zf)ilYuVmRZ;<_+wz{z((!7)4tD{8*o&}hiuK_ii*|} z1iukUNA~1CeEu0D1Lx2+xxkfjED%Bc@5Z-BV65gX~!nDj#b|R6j!aHbwScQ)0WM_yK8Pz(FNK(iNote;{(~hRCVL zya}s3#tqG`*OQL73%q$;dnXZY)%~1@N*>pFt0)?JEPVXDYrRTCeC5MkLbp5#hS4Re zk`GPL7I&Go3n%mlFGnwR<^(j|A%501=IX=kD%%GS96VlTwBX)DLBK zh|pWxRLCrRlEiICE9d!yLyG0SV$cr**>&?2%75Ck=U%L@k&XkN;N>1ubm~nqnq0q? z|Kj}WeF)qd>!Fg^b>3=_wjPUjRQHojQO@NFB1eboKx*$n3A@ydd!>T(B4fcNWc79G zN5jO2SMB`si<~caI4WT+)7X+AT$EA6$cN*lkRz_-26%tc@W~tRu`?dRt22Jb7}h? z@Z9wQse+o2L=%eSc#X-#tShghl|;E?G&-FsYzZoL%UPlM#)DEp0OmO!_HcAcPC5Tk z_)U5!BO!65)OxM_8DGnEsF_o{k;hd6(V`nHb89_L3X-G+6+(3I@C40{!=6rLt#7w% zUyIBT(}%x@JHgVI^o-qdQ+4tKQPwukzsv__n~kp9)q<-%+y)q5PB-_B$f1R%Kzg$7 z%MrKjCV1HSWo|h{eCY|ktuj%@IC7L3a%5TVl#FNU{tlMi4|_n*J?M5U3IZ)ghEv~} zJo)YF{)c#gao=KQx(4Mz2G|z;fZ|3|c}!{sCa%6lEoXZ_%X%zf;Yn^U%xaowCu;$h zHCVTk$>%@II=FgPqBf8#9v7(wv~HrasHyfuxPzC4_= zKC!-_^SvcFJ@X3uprL~*9J}iGtkNU16LXD{zb9%o+)axXEZ$+);@Vn>@@X4XI)G9I z6l@lti5_S*m;A|nuJpMdoW>rKFuvnUOEWHU(If*yI_mDeBIIF=Nr2V#VYjOVIW=cu zqNRS5doyCQ@FwSdiC#7P2SE)TSq-zVs2FxuCgENk(0|!2XKC3RC5}rZ671GQh?*=J z_pX^q5B9WCHNEFun5}0>j7#|Y!uj)kRC}D)mx)Y7sEx>Au_=prl87UkO%5N|BXhy04w+yKBXxFA0%c(rplxZ8H+ojTLP8BnEl_C7F7IMR}+a#D!kTDyVs(y|O)|N9Zn%&gsPIC|{N_N1^V5A!oHLy_%SgmI)|kk68{zk%9WcJuzc zI-THwitTHkAIIuL-D*c|_$|7L?*<@qBIpQF>UWP|vdo&E?V#apBEw>?fM=B1y)ALIf3`?Li<$HHgM?R$gfKrllAowK0)GXnp{ zZVFG`^sBQjrdS136uc{RC1w=5banlhT{?3iwE+)+c=_w}2<%;@8wZX{j&tOriozq~ zf}hCd<_XpmPUo{Nf-0mEsui_OEiKz128>gf-nE&Bi47AEYijYkHn8HF@yStb)f&?T zry~ChfWU$zyP~$hM<1K}Z&t?t-qRP)9@w~%S^eF-g9+`PIN$b1rS+W`drvKuuCTAo z^$G#VwH1zG{H=9U-h+8^I7pbFrVCHps;D0S02D26Q@&(@fa>@#uqyr1dC5#DP=x%i0@XzlZQxfh zWyD$c>o+n7J<>BT(|yfShgtyh6dt~csv>QaxJz0FUl5DwwPBSoXJtSiG%xhwmM zMxMFw?N9Z^wr%KCyJ2_R?s2mT0Z*~N_^$ZntYU_C&=QlIP_)1m<}FV>Pcp-lsRuf_ z1*{K4+4kO;vlb3f9V( z(|jL2AyP@X$Hq4Dr{;?V0^I_O%tA{}MK9=#*wc-|YOZ{gPi1J(P z0VO<8-~NtAD{)va;Recr&m9T@=+p$dJpGD03O8BhcgZvTb+_gc#Sp>qHFDSvH-V1q{ttN`78?;i%BnT)0f&hkQH zZ5Iq4KJ0z4qfEnh_dyt!8RZ%o9g}fjZ)$JDm{VAk>ha1>Xx7GP5-TZubYo|#dZGY; zQ(`u<_eR1%%;hb1#qie!i{T!`$c~T8Jt_Hi?(v^YPxsBA|Gv;UNDbQk@yxII@(He(qLSPK z?{jtMbg`kIJbCfHE2=9CXN)v|%9Ja79=&;JwRP`{99v9LS_u}<#O1jR$%RI>+-LUr z*cGN_D3LK9HyvQ*RQYOCp|QfXfzkXHXV~o|zulI*WV>xC!+^+XbMZsXShp##Wzkii z%ikX(G~T%caSFcvfXL4L6!;dwUaPZ%A&wr`fD=jb$ai^p`Q><7=hx-_j$kKzoD$t7 zt-$kNUfG=geV9PQ;AwXOoDKjnt55;$H=>o*bK+paEd?D$zE!rppv9yDFEyDNm`ZcH`-7j`8R!pJ zB+LhZy8C~XD7$Nf$29{o)#R>P92uG0G&*`q?bID}56RXm?s(E08{{2dzQR&cD7xWW z^8scZ>3T`0vi?#?^>3DVKSKb?oSE6pt~8)zX7E*mq1(H?a(%z&ok>+;HBjy-1)^!| z+giqMW*=jx+KOToZ<4(-yxlcreBU+VT?4_=@sp$XqA6_5=F|ydJHl;}lLQC*`QzR_ z3e^W`s1T#6x4|pgE(f}N<|YHO<4|g9TA+EhHinE)Q|SHXS*2TC@iK8TBQVtDdOoD= zg=6xH=aexJ3> zdERV|McVoeHb?2XZ>%1DxVLDdKF=ojN0c7*7Io`x^<09F^sJC+)99l$inhlD$(mB) zi8zxx?-Qnf@dpndT&S{jg=HE_-?#N&Y~!#98ZuwZgvumYQ@2nd%6G*3<&bQ@HZZgA zn5EA%J@%4*!Z*%`42Y`s&=;@eE=(E^u39enQpXW14ig4S1cmP>U#&pJhR!iv?!C9p zm*nZ5{jf*QDX42Z{N)E$fS$_suydW{tvN4$@rIqnrX4Z3jmChXP-*t(yul9ho$OcN zu%wr(o&=Z+V2CwXdt1`4&1>-T_{KaIZ`a84*ZLb(jLt0?q`LBQhkl*!R(9WS0yY7G zG2WY7-xVZE%)AXC%uRcB$ch7lldr@e9nD_@8#T6WL?O_GV9&M0Ht1o-vrc+2I^ z9?ihUZFHJ8xlkz(9LGs_-*C75ckpaLJdYAjxbjz%I=K`z+VsYe!O`7kRu<0yNM%i{ z7MqE`Yi($;ip{pzkE)+37YDN=h5X9#n8+KST~2S*y*W--G(6+WN2Pibs@!$niEQ)j zIvH6<;>&Gv4|Rq}dKKpGZ3G{URf)=8l8;n8M>Uqcr%e@N>Ax6FaKAC}8;}3L6lghe zpnAX#FH)f5@1cn1ydtBV)Twbk(00j>$99HeL4C0`w>t}B6@CgQo!w|JmYSIAE7cDe zf68tyJGV~5XVauOt1~DYhxM>no)n`$!EpsOujqSsu=)oAb5^|x*K->=F86j7`&6S5&HbxMTdv^)*fS1A2kCLe}a6=x=s9b13OC%b(z)X76$9$>may{<bPxL3CH{+iKXw*0X;xDzwDkKjv9h+u}!%GCEX~^s< zGu6Sn&rnM}dyTUQ(0zHcS{A|smsg8hi5N~;hV~hNQkePobp4ky3JD^i=fL{VD!X)D zhLbOQK*zQ3Ifxkm#+UNPAECpx=NRdDE?J*<)Y)i>RB5q6=#w%Zjy|lYO4A4OpF{EZ zgsiuv?Dc7UsX zqRn=yp|4*}=TYjHr?!QIuZe4k<+YN-3OW>R+@?cmMd-(%h~<}+)ZBsU9Bwq&pdSFR zHhcwoj`1*t^MJ=NT_IKX@(+u<|1`<8SJ+XMjKK{H z3VvLUu{8a?>4l8QE|uKYr0Fb<&M3~#i0R5fj&bR#Baa`yAa9yV5n@q)y zJE#Bim4AQCB*b;5>;05`z*qMH++2XOsu9A^boisK2y!3tc_0x(N6X+^$)>tQ;$g2x zMj_tMS0L&#`r&;r6b|PSf_Z{5`MB7mOO?9HY22{5X^nR{0}>~MCT-JM&28e5yj64G zK3`n&Hgzv}zKt#@qry}sz0Y1fV*u?!89PHMVP+GvCwJV487Czh8~mt3|IgSv$MsPW z9azz%#Ky%92jF^t3W%RDkhFaf7`3!mwwa353v_pR&tg;Q2nwlpsl6ZcS{oc>*!nRl zHu}WY+*n&Sw)9(P&GUfaTyVvqbE3Db@}*GG%SncpdvzxE4mmBjTnmoIyn%x4*X(NY zSMGfF!Nad0Zg%mJ9z8ft+rgflyGEs|l-$jsnT&`CxJI_9A<6e07a`(CW(#r);kK;X z&l8o-?2U1^Q@MYkSE7rk#`X~0MgP-z4b=|KFR7@q93HXk^(rYYOuFu|?B-uG_a$M5 zO7*yI7JJ7O8vQU(Mf`8Y1f%Y9PQ z*V%WO{Cc_(qwt4*=DLpaXQ>oGK|s~}DH(d3TM~^%En7Xo$HRo2LS%P>V!vz?chWgu z%ysdep0<^6m4MUg;oFay@Xovt(E_4rlg@M)lJS6kQ1-Cbk{=wp;U;@?bM;tZ_SWt5 zzf(WyF@Nc8V2QkIc(^r5B8hRMNs$;F(Eyjkxxv*vetWJm|8sW_^S>;J?M) z_Af3zlT`6znu085>M(h-Rs8AGE5C`0-~A>oj_Ci1pY^s*%SS9xf`}Hgv?{s5TrOt! zSEC(RHPMdLN-%Y*M>lrnqYtSqX!#trGE@U9syzs>xA7P>c$ zH1Pm5`_|K=U%Tmp0PpS5!|dOXe}LzGAvl**g|BmCgY)#tXuxw=tSezI3Rcr8%=f7E2J+5_wz|HDaIAc*V zb~H@}BR)htQ>l5Nhb66h-MBlwJ}-3kZaO2_Q)Ckc1WpRq0Kt!j10S|L1x4ywBe6>@WNJ zkeSS6&P=Yka;|l*b*$s}udUXGMWnlB@$rT7Ztcf6rJgn79{>6H|NbJQrPq61Q69{k zmT%I%A0IOIot%a>5=d@ADV2*P5077KKI1Ukj7stzb{mi2o)VT8i!aAbvB%J_zmU{y z4+1cj!&w;v!t+;x)po9Q`%#n*py4MfXg_xX3wRXWKCWgvXS!P6+$TjjGn;?2=n>=9 zwInjD{?71Km~CByHndAfP%pY-mV($V~DIqe_a+>S!& zo9mB80^iN4ZG+t^8x4PLJuU|?^kT1i9IbZmowm5#R|$Rhk(3wKgQ!L2%u%ls$V0;i~EFB?^9yEVI86Bu5&CwfqsZ*!lrU#88;V`tu5L6Ch2g$onv|My9Vv4v(% zNS~iM%UwvVE>uSsOrjVl`I~M_fBAUfO$GsGT0>J_BkafdB<)Up9E?A98T8I@MvUE> z{iyWYIr73EW?Sl7^`DjgUG4vL#f*v-4AX701^Kcrmcjh~fXWU9ZTh}Ncr_K+52LD; zcXJcpl)S8w6lkh*{&@OcriN7e@9WMvhb5rxLW}BDy)zyRedopAW73x`hm2Egz z`hPJgy^v>8c=+Fk7AkfuJVEYUar+6mHbc9T_KulXs}i&LmqI(Ygfx}Scsz1WM$19} z{l(GO!%Ca6c-bOP{4Qn+J-W>&qZ!vI|7=tL2-VssFV;miC(cB!GJ#7C#G|1B6ZOs< z1fQI}AK`x~h-B0yYT{Poq=+Mn0sSL+%#Eq_;f>c>!dA`VYQ1~MUikGzBda(2l8pUi z2l@H`Rr+b#Y6G}T2C?Tcl%h@Nkxd3yfuXTLU;k_5%GFOQ$Cz%O#+^mCa{+g=KxvF@ zCp9w5kfC6CKU>EypH_J<-~*dHTgO13Wc<*7&S(EK4*x&jaoa&ZMb&Py)$n+9r0=|z z^Il&Uau8iz-V*xv4Dx`siUTEB-6Vr`JKbCmMD9RbdyuN-hCfeaZ(n3{?Voqf!@+EO zSy-kC6p_{y&Gm#zEgf&tG^y2e!pMPZ`AZ>^A50dO)im<4pZQ=-Q9DJ?hF;e?dsdeR zn|hZnl4R~UH-Aauv<+_w;N{Qon4Xw+%Ryp1iAlA)_8>84^r(%x2G2twg!Dz~!ZR9f zjxrKJL4aW)Av`D!VMHf=pk-uq*SCv9oi{0o9?VWdLE%dgEHp&+o4LxUQZudAY@cg( z?_Rn}Y5!16fgVSz+YLnvjHVoIYHA~2a6cIZ-yL?Nnoig|SC`(e!A=XopQxf6FVOyR zmA~<`Pq)?~aZ&Rb_bo)R?B~KRbou7=;9rU>1nCAcn!D$YCZ5lS_bYw)n{1emK#Ax7 z9XI|f67U=qAq=)o%$tWsva7ajWNMQ#Yhh)tMkT)48F1tShnJXERt%+j$h+op1G~f3 zS(VhXUd4oacSA0$SXCd^kjF{>KQHE8(}0s4eUc9~GC0!Mz!bBm<@atzmFXJScvx+t z2{fh@K|Hr+b%51~P1wFN8S4Eh%sT8V@xZUgi zu8!2TF2KgAJg(6`Ah8QT%#)_AcHaiGYerm0;R+2Nz`kEf>CN6hCEUJ$`ob0xG#6Nv z(YtQG*(nBZz^K?`%E4!f(pzW2eflbj6d;$*@?4% zVlZ1nP3cpPC2zl^g-AQ$bwea&57yRiDdqpBnk_Hh&?)gO(hHtrfR)EJ7Z^z=mpMDr zc}e$Nj0V`8l*zdFS8A`oCYycERPy^FB=ys%;WW$Pu!{x32QPO}V!^h=0%c_}T-O zXIu_8B|+1Evy%(nwb|PunJGzqJ;`XMT^yh}GF%DP_(glcZVgZRpUeK|E4b};t7x#W zsq(0@s|E%FjKbxsM_I~qh1{k8hUS=|y%dSqbc9vJau&hyEXnuL7+cQsZ~ z-p|q3)W{}|qsR86yGP?2+jPt=RowRhxn~1>Fn5lzP%$2tr8`j>$sRS8|F0^(8b^e& ztjruex+O8&^V-crAwb3{zeqLZaVu=>j2&hOq(iQOme-BT{ zUsow*(h>LsK*XojWOQ1v3nRe67zI*FTMbNgGgnne(xbL}|6dqf0mDy_C{9xN7!vkjXS5-Nu_0Q{2Q zu*he01?v335|w5DPyZwuEV1slMaEgouO4PG4l;fIUP}a4^@>R|+hF{EZwx#Q;5tIV z8=~CL=;!V1chzi+z_mKvur~G< z{=I4lXIt@65O9H)diEN|cq>6%4?Ur{=`*D$F*-u#w8dt%ORTZ>8QdP&Sy}r%zB8St zviYXM%d#qudkTf0KM&=)oAIKPK#3LmCj}2VJ5trqz}1=IWPivOPZ0StwA#4npl+oe zNBuhO(~;o^t81L8I~`4H1Vx=4V8ab$fSwcKQ~`E7eg@R#?6;0>V|7aU?!V|nW~W7$ z4hVrWqeS;pLQ^rX*e?!(7^EKS{_1m)m;n5n1p5iZ9&# zOK}tLN-hCA*%%Yc-_0U<`6rwED+RLN9hhk1`JZ>m4_Ph9kI}D2{m=+)3YeVAZEG_F z*Be-F>k~hc68Vwa=NYC`*{k8fZ-Qf`5>HPn_ZF}qaR_PzqVNi*g3~{n53cs=C149L%oXjz>W*i;FG<7LFl^3 z=HvG*z`6jB%XHADOl%24zBcy;NXQYU)GYUM=186m7CT;Ol>_U3pN;JN$!vGmd4V4yI8AW@_*AErH~jbluMB?9Lk}d=7v<|JlE0 z6%y6Wbfw2_L@qCx-N^r;#P(>8^r=v=j#?wV$rV7_P>6e!1hz5tb?BXB+V?L-@`8`u zHm`(DzqfTbAxz~NB=_hU0XU3qgCBqsvE41{>rAXP0HX(e*R0EniQ@Wp!M^Ro(&nP{ z*%KT;X&np&Dzb_%5IG^p{_}D9;6hJGWxT@iqvxT ziU9XxuGUGXw~#uRXqm?1Y?(B?9AZ=B=9`4N3(J0bG|<2tt%nU}mx}6cjuuJq3QEpu z-g0(OshtQjIQ*=TDSd2zYh$b}ys$6w)u=yL?!Gl7118&3Cq1#tjdvkf#DBW^vL;#u znc*A<=1ZjSb56d`9lCTYfv=LW-mV5@SG_rHdwjefUqvU2j(&B$GCv?OsspvO+!fVF zRxns2xIXVbOK=;1fvMKtvf0V{rp^Jm`_hSfZ7-~kg?@gYE?|_=|KXEe+Vbq;PYuQ( z`UgfHS+M#O7D2j0>EFCpN?@USt%KxS;N$@uoJ;=jd0xzj$zsw5v{vcs;Q>vKgZEKJ zt{72UJ99V@vzSLpOJo$CO%`2{Udf3-kGCT!0l~`739);@u?mOE{k+WMVIWVoIez98 zoY_?96_E&yL3JghigpJWsFjHwE+>90S4pg{uA4XoZpUC z3~~n&>rw)RKqE(gvGyu1XYgjYS9AM`&m_j;`v%Y@ecGqY?dUIs|0w#FL)Y2U!r@GS zMBAt1!OF7ia5n;Krwu9=pkZFiHOs!-(V%U=9Fw2;p3a}N`=9Mmpxk?~fqh7`HZ>!X zLxaZX+(pszInZ+?qBgx1XEu@hk?jeh(!;CXN1CfIQk#LTlcJF4r+H2;mX3AP)rE2= z-k~>)9F-d~vEa=+(BgI@Sdc2hb@FV`6zgD0*8RLN!DcUc+1mfJE&wP_4C&*saPin4 z(@{xdH{9lE(rC)Os-A6POO}YIP!>wEA1aj$LXgkXHfC{5Lrt{}W7f|_&a(@7g*U@S zHmX<|Zm#&PcEtii5)b%X;zx45zmti3)F;VCu2Hg-~iY^H$gh)Qy5?cCe}NG4I-+F@X$O{Ugkk}}-d z6|9)K??^z0S17eIpcRa|amHD@SEz!CTDl4LX;n3d6!$R98|s1s_V|8kex+paharbm zS6DLbwFXG?alj@$Qnn7==~7*SChq7L7rvoJIK6t?43)-cai-tIQfj3!kMNsFCg*8x znuBqH_g-i{0R&%C1O(=^w*JOa# z$<^#a$+PrniT|u8_uuP1lRSD)&JMyfNn`D0Fx3s9>O(Rjh2H`fwC*|^l!OloQ@k!i zQ;BRg{UuXXupk9=W_|Vc>Qm)NI&5RCcGD->ads@sNQeFLI~>;FtD((N>iXty>+7_s z;vesSe8*zCH54R@XZFOlDHnmzTZ$f!f>ync4FYU#D`92^RK&w`L&6taWNl5EBnW?-F@?CE>{zz1QiIm6m6CR{JPXiEr(|L#)JibMV*^(Id~Wq00o5*^-}# zyFtJD5gu#njn&Rw;r#)TYrY9YER@ASSxP1iIn5sQLkH?cSpar+jrJi?oHY$!nAokG zy6eeKLO zSonhPR8)7m5l?# znDeS?XrJzHL3&$&&cuW{9k!#ixw%Stgh_>I|1vW64X<`&Lq##_&7 zYFTa!+C)%me8ZFqdFpx;NFV7gO=yg3*q3|7^DVzXRW_+VkZcbz$T z_)8~?aXm&BT2w|9-Qp6c+9jMO{Im3nkFcjgZ}xP+k%6!NABHP@+y}mNA~@};AuA}- z`!9u7gq!LH+bsEl<8ZP|+t=IOi>JnthiPxgjgng-x6EBvPbcOi;-(SzTp18;YK@w_wa(-wUQ)71rOq0z z!O_!u{swj~@Z!&NH-EC2KNk?;io$8%w0%`lHvDgYB4Ack_p)+oTTdo_pStkm-XP|N zl44$ECL15!kR2PPiX2!MA||+0{eU9+TK{9EvDwR~vk1K^PfvGmQ=7o&=x+g01QqwE zM)Lr&JNPSQ3G*oGYAe+jjr!AHb$YzBe?1)G5TpK9FxJ0xiQ`IiPrp`z+Dqr~nJxGO z5UZbHH@Oj4dPj|q#$8KFQWLl=_+5>P^ERpbF(JbYEvIY1?RkJmASzSaun2YtZ6V|9G1J{;K3P<^DuQ&&hB*SYh0S zbknBIJ5`H)I@bjq>qmby$?UeJd1r;OG%9F4^wXT(nFsAt;xYH9j28`6Kx-%EpdFtN zX%GCiec4IVF6)iaNnjHBU;d~rN6&PiwsQCG8E*aLCvj*5VAC2bVXrf~C)HPI?ivee z^j0)-V~Cx7F|ZFzuDGJ-UeZObWw=G zHdrVOMm;}s?Dthc`Fp6C%Qkaq1#2&4o#cj_nr+(Ub*UNi-x&@J2F9M$Y|~;~45%nE zAuRdP{uImUj{t6@n?cnzrzP$L|E=E@Tl8pP$mUvX{_}O8xSMD7D@FeEjts6$BT{zg z-DYjChR2oOkHGNLiZ{`~$DcPB3+ctqk_2Ln?(|VCRq2q?TlaOj+@H^(ER}^Dw?H!v zMo-D5OpA_){+x(p5BWZk+r;sZ2eWl2$uo*icXWU2apNGTcE+w%K|6tj`V)iHWPW5? zl85upnNz>cK8DAbEPh$@y5l_@Dng|kZ_XGYo&03zZdnj8R8y`jWXHGvN2(eX(+$bN z@mqnDM%1FxO)^qibhkba@TJR>N2b}t_zox-6x28?(TlaRNF*5A-i@^QC5pPgiizLr zQ%D5y(Q2{ocaj(ed`H!NwZ+=2Nq8-2c4^c}HnMJ}cJfNz0=2nQY@uYtMmTVFQ(nDc z?6Yz+gyt_rQ&>R`rQ?iipP_% zZ4W%h+M7*^+IYzY;2z~upL5b?-Ab;*7O$vA@-PxnK`Zs|s%7jr0s$Jf<)~n_7Wxlq2cQXEopA+t-FyQ%y&eekM`nMRT6 z;HnyElGwWrt%;70&mEq1FLaNUl)bL0BM^B*v%&5B3>J%T;vWq`ix%(6-Q?sSh7e}g zD+AShuCB!}SanizgSj)yhObX*S%o{QSghpFXQRjIwvQ^^~WgyMJI@W0Ynvq%1ILP{9aOumV7&+r0f7(8xlUt z#RXvFXfYHAO5`4oG>JoK)3uTGpwR$OF0{j52&{I+u!D-|Zn4gvqG*{j9?OsVrQQMI zO&Fc#Oi{aFLyN_o?CLCPE>R~K*`Je+A#FJ+w0FCpgSN@6QTxYMPBYU6%Ncq_MV#i` z4Eb_C;@X>$GW|clt^YI&Nxf>{J+p$;X|Qjfrr;Ibj^G=c&+%-SX$!3sJST7(#hm>5 zF&~AFS<*eYqV2Ap*%lzEpb^9+%s;pc0BsVFq=5FTQRyzM+*!=4u&P;?3!@5n?Q7fy zs)r9deDHXu?$d%816eWd!siZXAsto?=7CS85SMaV)&#f zNQf=4Nx32S&uPnKm$#UN#6A`(-ID&wVE*TNzOQ-K&nr|;(*_z-e_AyH_ejc;LLcKTIP-wD!NZ(c9o*Dz$Y zh5DxS0^r3IxfP%vc46+?X3y&GMPJ@zdVOudmyZdj$u1X?fBMdt1s#W%Jkk6OA(F|4 z(^j;bIhCCDQ5bl0RJ|SS@+xC`*1;fgw%((n&wZmIsd?{XZu?n9h1a>W{fw$gtpDw_%8Jzm);MMbqcGiyV4D5zVXoTv}q`C)*}_1Q&2JV}IX_y}|V{cKjqqXCz6T>%!E+N+!FIk-o5$U80j&n?k3hfBu_JM-b=y z5;xyf`$d^7pucZ#<2ev37D(m!(WQ3^JgTV6LSkltOt<Z~?AT&vu1(xnjsE!)xkCGmg)`|;y+{p$+a+h1DSjJ!DVsi( zy=7y*RVTt#D2BVpTJhJuI}`5lP@#mx zE!SpnE}Z$zJ1R*<>wITmxcO)X9>0h)0uo=gS%Ntj#^%gA`Iw1dfahA$Th}&FX2CS~ z`1L+tC5oMHbXE;UXU97&XM0z(UFe9E8TKnHl(?5CW#CzalM!0qwJ1+JE<+2 z<%!siD6l$l$-EkMrfaN#U^d?|wC6$aUcXPg{OZ1^kO+bpw zJ+0idY0Psu&myK6Z3~-=PkK7W6MF|Z9bHEQ$fmWQgR)!G#v-XoW^<1rn>SsEqnEi2 ziPk65Pd?e{d~Lg@PAk{F+83({3`zd>l<%fAsXx&M6#fhcP^>@SuNM3H;@i%LmuIGi z%O~}p{rrA>=OTBHysJG59>{#Rzu#z3_+mzcsablm`8T_eJ7|S_<}A{KHz$56^!;7? zVOkSN0&HQhJigI`-GbzY+K+87Hf^pB3S~gkde`?ghJ@V^gKHwgt3K7rVr{C~o^LUe z#OR7TNdi{R10KBLluBQg1ox(zxIYW6k&E?5l6@~o@Z%PEb>YSpjP7qgg&EzvO^7dP0palK~abz zK=QWL`BblMcRyKjnp z0DkH*0H%F-RHW0vHyt6PSu?k;Q&H*g=5<;X{?sw}>@r1%&{Tv;e-RSuFEvxTC1sdW zAnHm`j7`zoWsXly_Z;A$7saK)(>`(fP7QuD+|%j(B~Qyn;S%MCciUa}CY-Y`jR?TJ z@SYkg8r#j-()6@btw9pLnpc#^5_|i5uaLcx zYMc`^<@Z{#&8!2IjiMWKIH94YP=okY%{f^_vXnp!?Y_EM=g0(kM*qL7=^c#*C3PpG z8RHgCL6glGu$^$6mz#dh;F1)kSDHoXH^t)=Sw+3=aM|(Go}ft!8gt1-lYZxvZ_ae# zn3mjcJ6C;V??WCIz-Yl1&lP>i#!@w-q}M-y1k73r(!=kuHFzypxosWYN8gXrM1`?;pIzYj3*gsEz_vZ_n*}-aUbHA z=ij@ve%Zb7A~&^O%mj5hlD+2z029+MK0n_qqoP$|p?mUcj9CF0d^>&q9gEFDmZGrf zY+!ay2>}yU-xNgLI9pDo;|>w^-SOp#23!+rz+YHz@@tiNPXk=Sl_qmo=3q~TEPhel z_2%8q6Hm(i9ZW7UI&n~L@>ZXgp^19*=9p>s&+NdsBC4kY59XbCFqYh1$p)UHxz59E169muJQAPI7>$h($)2d3ja)> zc8p#bm)sMj=Nwg|0KK^6z&)!fXiA5~cd1#ua#lA&tV95G))wklUqubct3{gcA|Mx% zM1F+!u9T6r_}yvGY;_&qvW2($oTs0^q;QMVFX`z~wj@7|jxA5`{LdUk_2~fGlRnS3 zwAlzIV}2M4(s+?Q_x!$LZ;k@CE)^To`phq;BZe5Cl#4AltZTFEgiK)kV|xeSUJ(&C zNoIX~43zZFueucs>U908hAeh7Aa^-rzckFrrc7E6Eb0n{%>~|ykYcx8TgI{Y2FDvp zgxp?;PiD_6SE*|!ZHk5g49BfX3ro`2w(>m@3cj2)?7c_d)myh9VW#gaj2A(6f`Zay z8&||^VO_<6P61_=@X}rAsBh4QXhz?V&UatQghx{hNp=qcUr);RSc9>h;3g~3?wv{5 zTpA`duQZDF!PSh&)gfpolW1 zMU*7>RC247aJYy^H&O~z3nbWe6m%7G#(fu-1@VxjIqU$q?98!j<~T7&YtrugQp>N& z%(zEgd!a$wPMRMHMPxenF{}iCP@t%2c<^463l2n^qv8UUSEA9FPp7{@&!Kr(vY_Fb z$`eX%!CmbIQ;-8J%noE=S|f7qISupqa~q0`PnR3qh_P}B@&4JBawWfr$2`fx39XF9 zdF`DTyR);HFI4fwHDF4!GjHfCU}v`dL!!odmSPMxRI-3w4!arpo7I8ob1sdRwrqEI z_y}go`TmMsvB`Exw1eeSs}-2z%uRD+cp$%K`t0|+GJ#OroO)itlzwN zx8~`Isi*+KDqh{KKgrN$#jQ-q#U3R~(1M<8Toxa9MP#c~O*aB2rExI?omVP!@&U>= zYGS=w6w70|GLNS1QjXK0bDVA4yD&488?g&6rD&VogFO}h8K;nV*>s)NM|$~&Qr(Bo z8?iQ9$aZK}T{L*NTHRu%1~Qa;YUTO~>A0FR#H+2O&_a_UnNWFRdn$-$SXMqP977R> z9%#Kd=nO1N>~$1K%lgFA+}g~_^-k8-X3qP<3+1)K4mNLyH_)mUqo;|U(8+0y8PwW~ zRu7M43wEbVGchQ$XxO}hdpU#+X$6HscU!QLMMeXhoT1X~w)wy1qKpGMw90&RJpxBg z^R%};*==0cD)x-0$m#GFY$p-*y?(thjzLMD^Qs8W@Lz>rH21M9(LQc=A(zN?VZPu5 zmkG-aFw!04E-j-};d72Vvl{3kyZOXdV4;hRS|%KxvnLT|Y%Aw^2|Ph6lQki~3B=>Z zq@3f1+0oh-buhNi624s?wBwBou+v`&WoQX60>o%#nKg7rgJb^XJo54+Yy4-H8|cbLP zd=>g9jvZgW&82>sG=q>@Kzuk5cfW2|G*3AxcjgoPQU+iEAHgJNlY9`(;~j%xK#x4S z+Y(Oo^~E$Oh9!z?Lv2@R7@IC(COa$BIyT1TC-f(iJ^{S(csuTb&Ml;Wy(VK< zn@gL{?cr?^Y|1oz>GLIs@y$KiY5hv)i6gIUt~$_{YL5qj?c2|R#EXE%b|Ryyg|y)Yiq!G)kMqgW)=8*V#>Wea4zu5PCw}IcC?n;9Ta`>an=khbK1aV zo8dG5P)YN=Mer>IBoJfk45sr|e%my%noPFrh5Ho5?m8Pnz$Ff`4|#bpQCiON z3?GHl!0KIKFeHcs@r74s&*=mP29&%*N-^&%j8HJqgd|TY&rL)4cM4>JylDx?Q#F2< z1nJek6!PU{c?RDu8M{59=l4p|BtAY!|7FgV2_I=d;LLJbK3O`A@~+yXR^GN!Roi*_ zZN%<1=waAzdmC@KhkU^NlK*K;M=Fp(bJLIK;pPMsZzsZ~58ez)D$6sIT=kBRD!p@& z-TzB3C73gGe5Xq`99KxL)J^$J0LY|zP<5;^)#QPum7`xLjn$!=6BXAfr(^ULS|PFa zI0sY9yRyH9bGelCKMX3Swc3wMt(;}dR6p*i!`Sz|jOtx%Y|F9F+zH+iR1jDb^xo794HR)Jn2^n8>g}GsE;*5IdnO-CA=Q0A8P5!Y2af66 zmD>8G>%c*fDS*xW6IOVnnf__aUy8@;z5{z6tUoeF44QDc90G(uOpMEUxVgik0kwHx ztq>9MInYloG_RWsrsE8)>N05b2I4&x*BZ5Vp5c8U^o+muO0hDdaY>_;Wr@K{d+%Ma zDe>diHKtnYf<-xS7U{GWHnLqWzYu8LJF04Kb>3DvRz?Q230xDw-k5tmAwQGuFIIGwa zLIQ3~m}7d&3+6INZtsSR<49fn@b%HP;H0I5x@s$M0phrM;y~rBLYkyZ20wkGll|q% z^C7rx;>(Y+!F7s+im`J!Xc?SHeOjcmeKSy|{I}`K1i@7PmyGGpf?@gezIpNt&)2AXI#A$^68-rkFCo&kYUdt zcoQS#pyAWNAUHmBL=;>TU~V9#{5y!wkvoK9wY36MxTC5K?I5})9|)ejLobGwJD&-? z3{;IKG;&^}Zhx$zC2@WSjLYMYn+j4c_SoVwMIfLk8HkE-?@pQ$r=nbPA7vL7#dJ;R zbARef8zZ7h%4}PvU7+iNqO9t}YwU9C6}~%3F>yNs-=(_WvcGP0I8K;;!hTt>bGnES zAm2-A=-6Yp4SgC98V;;ACq$!!x(y_}VbQz=U1bkY630-zCcs!DRf2SH} znvy@Il^ai}H10jAWUC2UxisbCt(XmLZ>V^>zW?#;2W@aTrTl(}DGBMR3^X4m55ufk zbbMsPHFS)Hze#sgk|2C4(}HY*V2f#zUf#F$NcpY(lo?Ol(@ zL5_-xo}`Deyiiz++>qv#dMP7IASniL$wxnjx7SB6en@Aok&?^75@7>54moB(RIyfG+ z{IK%st$ZvhpZtUd3w@ISkLF~avf6qCIakiu2J@yLPCUo$OZ@wI@{T7wnryp`o~uDO zA!Ya!-(_!w-B6T=mzTpLQJO1<%J{f|28Hjd?OB51c>$Swojw~98(m`*OptjR zB3k&K;nVj6(3@6}68Vlf%0F&^d{Cp+Rd#wlS1rzN^i&OSbE!Gk)YOFB_{(fd@d$b{ zg!@n5ugQB>_M%={P0t85=bC3~y_Nj17M4=w)v}__2L`eqs5I^DEO*6=!F7^yw%e3Z z5f2P1k0 zo|blW`DyHhGu=6~bC%6UWZ0Vm1?%AZ+ht8()@YhT_8eO?3g+EYWUQU?Y_YrT_~1az zG1OiL)|wa27*dz3X?7A5(#pt%B=znALW^+#u}zj{QN)55fv7(IWH**M zBdT=|sOUkwb)xbhOnBrS+cm^j&xD>!!=V>T97Xo|};O)(Z$HoJwD^Vo&GcnN$YR*>wW+xgxkf5 zTxrNghiB2R;B^Ag=318O);HY|g;Lr5eRNG-qc5L`@UeHo^oOu z_R?T%>Mw=aUkdid^WvI=PocWqE>G21!W_s}0_GfY1b`~qo}PGOHPxYUM{YT4II9+L z=<73eJ2r>&=n8w<{V;w=uz^?n?}(Ny;lQcSwt}Uxx79ekMM-`E&CLso0wR?xf+)o7 zv~C1j?a4^B_N??8%++l>q9e>H#JYL zlhNx&)t7ntAcHaopR;SCr(5dJej`53fHj5WgVT*DXqmJrRHn%5WQ$bZXQO2tN<%K{~9aA>i z57e#fuacdP1)Da{A0-bpEff)Dli`!>{=ow}3L>xkDfpw+_R2!2mb>1klJz5GsqW+F zpolWa`K0Gpg2yhUbKSIJ`@>Tm4Id{7yaIw@+l68kdcfmO8zuS};~8OGtLWUR?cMhr zH;()4^U>q+azzjzL2-cZSFCaP<5N{U)5`XDW(WdU`LI0QuwuTV4C);<+v}Q`ep3tN zeU0m#LC*bBR}EhNxb*JRb~%(nEvVmD>4S2K1+dR6&v$le)S29jucHZXHvgkv>TdHw zE-$TBUgi_kea^&~v`jn5`j{5U6*PM~?UnoO%)r`Q-CHWBM|%om$MEQ)v%KD*YUGWL#|uNtSb=V8d5cjn=huC)KjS4b^)! zbk1v~2ogMLz5p=K#>$Hg?I_}T{2^}qA#T?Wop;(qU{YCi@PSLkt^dsTbPwfn5@?2M zE30VmT1VVzv#>}4Aw+Yry0*uYYqw>ndke;O0h(I04C|E9j7}8AhZp+xK3L8<@pt(C zpLU2ne^YZ!98ie0FI$K0awt-jRXNItq0o7fBhXIy+oF+!4o`Yv`J<6LeF9H9ZoPhZ zF91A3+u$iG)pY5E0)gl3Y%1h9C>4{swC>ZNx`*uhFn?Zu|K)r9to8@Btz?i57ul?x7a=9EBS5skPatDTR1HK+f) zp>ZFtojfiUG>>-d||1lX6{GWD~m4|V8+}L)p0xE zO`-qs@3c$q&XER)L|rb3I?ZkF)6t=P8W5vp4fxrs!*w#I4Er5RbF~K0w3gWbh6vh~ zH&Js2n#rVP%PSOP8msn075 zg=6f0l4q|W0{B>Fy@_h$wh^i>Q4V5w%Ddw7)zWtf^0`+?WgcIxYth z2mpswZQOKDP5kJ}>6{u0Tw)v{#*9GXz<~0>piUo58_u*Lw`PLmD8{35b$1rHJcmtM zo?nZGLEBa*Db&a!IwiFmUt0S%-y06vrvtyq&tbTfm~Q`wP%=~n#Ao5}Gio1uMOdUZ zYV1Ge@#*0(uLV~zN?`2p4LPu&`gqwrGR5uzw`C_s%IFFl+Si2}5x;L<4)OD!FMId( z&ef)o63m;e_&MgD64dzc%fQ2>L0~k)^(Z7Xnc}zY6y?Hot|~DVixku3*l6V}hdpCi zDF@}v@zJG4R?U8A5s-43cqq4jn*U*@P{UCI!mz0H^X?yvF01pq9H6{6)02EmAIp=y zKBs^(F%=UdPqNVWQEi_z`eW_v>y%at&`r8vwjF{wleXvtZJfS{Ur?|=L&#ZGmkZBf zcAsZ;`!4S0y?d{we(wPzC*mt?fxq51GAnc>FRhRpe`7|{3@Labhdv&(E8`s>A74-$ zg5)^FvWln8&mR$WYvgzDXj=zPrPkr)wzRhdg;qqVN2tfYa*HG?CxccPzpJhFX#%(M z1hgYKPZcI~y@z3`q5Q*!_wV$ZC^|42PX^q&^>WT+T+s)_ZU~X9+~krGp683V8r?x1 zGMH%YaLT(RkCWAJ47bz^z~fk(7nA*$0u`bx@hbdDRbu7&!E{c;DiOO>I!W zIrEZHD2BVC1gUgiOUZP7kdoW(=uu9Uh-_P6Q$)V~Kg{%Mm0sqkKE~3j^rut5x#&KD zxP!_!D@~hAvx&1!NKs|w+0Uk1U^i+nW9g<0&4}S)s(i|UuFq$*)K-mpe<^f$kwQvZb zXhXSbt4XtCgBO{0NU-*VquDrja-KxhrL4Fl`5c!Ap4)eVrvUytYo7y52JYblbRyP zqM}hX9|mReVQ=TScM=ZmsrqaIJpNG_4KI$8k)iWzr5yH=DX#h^e_o8$s`(7k3yMJz zRIcwQy_(#2{=82OBHjL7xU=5>O@XP*s@HT}Ro{44mR=(?nSwaCt3N3td3%+)K}&-p zVE?Jx0oT6r7W{Cr;=?7rTFqoDDVg9YUotXnC~ww%+T06e@bwxNz_PwMRDv_xS;U{H z%3RtNf$nVR=Dt^)eHC}u$x-l4v4UvVy3pC$+roW06)ea;_~;M1;ev0Xxec(aa&sGr zDNU%GU);jX%#ZBOC$5Ie_m3)6ee0_?xT4XhoNoh7;vA_AlnB`Jd>$TK>Yi?UDCsvt zF+h$U4;!zq#E0-jhs=tYNZ0R#tATShukjpF-~Q1%4e|3@g~_a>_vD7uoMoGhH+?-c zSn#SxMbtj!c2%A$SS7%%z+zddYez`cgp^eoD)$qzip>&J{i{}W`x$wlFpE4X$n6Rp zs0_5!QMNyG@g6c_rTv1MkUJE#dvcJ~j+lI!=jfAidUHho4Tp2^g?7(j+KsY-qy~Hl z_w-4Dn8bsxmJ*@w)H_TtM%ORLlt!{B%4*HXw_o8ApcF3g~ zH9WIFt)RjGrKf~s-RmI6NQqgnK3|vPd222AqOY_ttDI=R_;_Vf*%enPJK|q^k3n2U z%w6nr5%lK#{QAfKT@#sbE%*~tQw?3BcIApIz@}v;w}X{qo>nCEp3@z4LPLvafz+|` zoWW*X<<5zBd^<)L=pLdJ_@v!Zp*srmP2E|3xsTk7Xea8qsL|#W@Kf$8^T~KkxYorV zcmlN~40k^LCbZiWa+jc@uW+XP>vyKPXm&>v{kuUCVoGH*85V}D4Tu~#2>syPM>^5! zzhYeTs@}*n*i=?eta1YPl`*;$kV!9)XTMOZADX~>0gJUaA+B2Mc{da0h2324qUsev z@X#(RvX+1KI|Wm<_!IOTGh(V23&|pkxu*XP%Z*NW1DI%d#846J90>n%-;RTT93^Gg zl*G2Mk2y{Cdp=rhu^K~WDJbb#(VFe+yOt@#Yt8dyY%Hx7J&xNmFk67A9?^zmU}eb9 z2T5Wbhxv}7x)0@{bQAtV-t7?YGuA--i%C5$;SWC;t?Y#R=7!S9Ptgy}x`_v}X_dtj z7@FTzo~(S3hFD;1uc2aJ6C$u^Fo+h;re+umHQA+wb)9g-!}nw|Q;kB>bwc)y+IwaC zhBvQJ_=~cBhxv$2YyfMd_w}*VqGx5JWzd8Fi?p*0Yx4cW{tyY3R6!b)l2#a9BEsm= zoswgWkS-+@lo$=tNRO@&LqJ4Iq?<9iyHoVJ{r#VJ&&y}8IXK{k`?|hyo}W`hdG{9* zle*&eX~$>I^^cr?zyMI5NL^(ZBTLdPwiuso-pQ+|kC>=y4z-O?YzR84*U3gR{#2~d zfaTc?wbIftbl0K30aN3Wj^3MSEWltXG2EGXyKs%@!sHLvmuGDeDosLIyWJ?8R;**Z z?#7K=_$e2i3DsQlr`lx|4O6Q`y!h73Yye>xRSP^`ah-Fo?G|60M&7Ni7tJ}L3eTGh zpA^M#ZGZ)v~ z0CY#>*!GyGuB2A;X2N5zw<;{7D(jYmDQ<*lre%3)Pg^+Nx8z%>&Pgk(QTxPg;=akf zbRkr3^lA}NNx)&fh2o;C%u6l%5&9{dj;hANJzFd5;5}Ai zsiuv-J2w<*{G24>DGtZ$&d?QY(UfqMN>xZ!aaVD9=?r6nQoT0c*|krZhvhYD)jycC zjl|jw_jT`-$EUyoa`)~%ul5r)>WQw$foWOZ)Fed8toSQ3Z_XvTYmLS|`Gf;WPK0A2 zTIyQ#xoKR4#%E$y{j7BqO0RtV^AOJsF&ZWwC%Uc^?U2%RmjmB4Hk;~*isHJ^SUG2( zY>BMhYw71`7(xhEN|jtL?vR5b<$Iu`1$l7b8@(3fT1p~NAbQ!d4PBaiE2R07KkVv$ zq=Ub1e7|p+yG?$c=-n9+CF7q16^g=fU&#=2K5j?gBY;eh6*sI6bj}J81$9zkFfU02 zjUi1J_zkJU0%-4U)liE>omuX6wPaX9a)gjiwFDQ+(Rhd%@b(ER_3k=v_f^jg15knF zq*GC69fdkGsJ+vBc^wCYYU-5P!+tn4M{Pfv)rjMCVj9t`9br=58s7?9IHXeJOA79Y z>jV&M#|^y0mVo4pXnsAga~7YRjN~tgPowiW&Yb#8Co~@v!su7XaQ5ym zXtwP)chXmr@Gs<-b+DL*vcDjcR9fI%{8y!P^3b!nz~D2Bu?s#FkT=Cg+i<@(ZPxyN zB?S%PkZrv#$q%T#0Y>VBcqZw_bIzY5MPchcC!@;d8>jp!=q-Bx1{A+;oSuC5NB9f_ z-ci)TrJj|`j8{qFFuhExBT(!2A?VlO46bYmG||~Vec^#m!Q?M+1ibq6$>ZqT&S|H` z_OUwZPY>VIU&ccp$G-?9p;^l_*Z^v47M76~QPhtcIy6tu?RIvC(B3~(58mNNL`v0( zqUwKbXBu&~)W4cXTAZ_)CPeFN@{H35N6p+sd@08pF*KZHx|v?^1BZ@INAjdyMj-ZzS_z((So#|VVEQVUNGVqVF^2j zQkjp~KwGMa)WpO`cMU5jM-^uUA4xS;!Xeh)pO=Upw*-F!>b1Gv{VK<+$gEBeTTk6E zqtzPiR3_i1?;Ih}#6^8N_oA+m?UTY!Im2fvMWY6eWL4wp^i^xxwRrtRpXc3!2Hj01 zb>Xz=?VO5FUq;iZ^2em*r9H+30@Ytl9byVwetk;a`^Mkx{}bin_2-o%W24i=YMEC` zEuSi)u+YQr&5k3_ihqasW3uSoZg|zkrI*cl?ruXIlgaLOWrIiTcs$maUWe&Rvct2X zx5c*eL`1=dfcty!&S5QI#Kx|05l!DJ5?d@x09R{>Ea=Ka3y$kb+3B>fusv(c0K0Ze zWh5AS?ySEycCo+KYlR1jKg-L<4EuL~AwkEKi>)XQxf%|Rx+E53Iim<2U<$vAs8u_8KN=mqXJbH%LzF~i z5Y=l1k*6*qkI_nV=1d8WJl+*oZMf)H)$G4GH>ypUmy-?!u?mq`&mLw%@j)oc(xooF5pL z{o*8aOdlsBMRr$Ws$}Cwz-?(8r_Y4vgeeQYi4_T7{rsIX#!WU$l-kocdXYOpdhWi* zqj!(>@0IbRa?zN1b}4>w^58NXq{GppRB5*2*@H~XBV$;gi*3Yi!M?6HH;jg1 z@nKNw6Gd+udlAW=7u;3XbGUHpmRJ-Z!Mfy5H^W`+5~ z&5~7{Fh?Uj_KGkG`(Itj^$@USBYq$IZPLxk^6k?K>=qaY9t^~Eur!Q(Cy%ff+qQ@a zuvqf_ELEa^xGQo(1To~hGEu>TS4$pKQDKr255ZnxQ8wrCZb999r>h-(3kZxXc7$(i^ zH8x3-W@5{hB#76)Sk4CaRsP1LT}muGT!>t5FpoQ>t29&EPNeS1bPc%AxM93-@Hn_! z{0D-cpLBOtd_cq6yKdxdNk<_jKDjl*k^5hYyuB6D!S;VC@~%?Etkp!xSnH~pldgG} zWO_c?P?O@l#l(aCN1h1wB98~%_|hf*4N}rj0GdHSb!Dyoy0X~WoeCU7a|BKd?RO4; zxQp84%3FT>jH5Uq#vfMTdigzWRDfJP$=%Q^(kB7xbgebN*lmJ9>yFn-HROF71f;HO zgdKaLeQzgr9+Ar0KkCCenmQD(_}(&_?IslOov&$UY9oa8?f_{)HL{vycqOg9cfAB=p%N4k}<9_DibXX(O1FuoC*lFdcS4(t0}lj7x!(d7K!7{Z8NCymlii(=Sd zl8A8YWH{DJaL$uJ(pi-I68Za7AU1_`J&O(W0)N0aUj21FGN%?RaAw>rycR*X9cW|6 zwUF8bpLuus?U?8zP+t^mBBM8%of}4>JPO(Rf}fSl!l@y;H15a)VwpEZ&E6g31ctuz zqj_c%Tje#-LYCA$^yUJW)rX?aK=~lSHl}Mfp-U$10vFo7EDVu`<|gAK`%#gN_qr2X ziZ6yFm6(KLeEEAh>*7oAVT0UNO##|*=uBu|AcFPGWJGaW$2z7x)oM&2E1sGGk2uA* z`UYi1D!qVOYFLvNYnpMI?6DM;G$Z&a;&X7JF3C>XvxZx6Yu9IT_UOyY&)H-y;d%BI{-oL6+QehLdIxLm zeFKqu_)Hz5K0d721saw@l0@wtv4}7J@V@o_W71aO)bg05MXO_9{f(_z4Ukzo((F4& zDcK`<-?y<&N$5H^A1;vV%l%XO=`Bdk`mokx^%z;1%4?z5eRXH(5yE$ZjR_p zq!jub)lj^ZAF8)0p3h(SzQaOeB(NhhSvf|A_2Mh)5nJv|A_;0bxuh`e%dg~q!*2W; z5&;5zbGV1==()5BI?_3@Vb-pp!^@`b{LUA#cfnyPzq+!%uRUwHG?codEn&O35$Yvc zGqL&38Zng24BEo9f}I49x&WK9;-9~uz2lZuJwP6x`FYeST|o~J4-TkiXwPz#Bb8rM zHoBn8;beDu@q%1j2VE5!93+Pg%&{IZN|1SUKU8Zwk{ec1%DGDLs*+4l>g?89a>Ddi z<;D0seXpGpXRL+1du{{oG*Q#HUYJJa-Av+=pOQoRQiHNX3QDy|Oz{PRCZI(pqJUv`%dsu@!bku?6k@YaTc zHPO;R^eTh+_vzBsa^zRS>t0>DOybFIlD~0lttSrCtVNe zkHV$#o;sACtx5@>c${k8M>#;#*q0oaGn#3j=AquipC?|^H(?}Cp}{WQvr&6mEz!f1P_m%zhc^k{O2#v! zT#fKz;|d*MH=N^afCRem57kRsjg4!-Dv}=%IPdQqHdgO-+nw#5NoG*lox%2X{Rky( z>HPBRT)G3{_|2g?iE-z7OWGHv0ad_Qvs=z+FLqA2e4ZLRYw(T60)fBK#k0q`2f(mbM|Z>LwkVIDL!iM}O@TSLikxiF}UsyNq|Pv_v)A3e3N;O-r3j_A#2C zUfE%+@2M?#*2OQx(f2GYykL{WkGuVb!*HzGFEff1GE(Xox6^EwFgE;a_+8V!_Dt%`*PkYT|n`rv`G)SI1@teeFwCF9tq02q#36yx!t#}6{k z)D@PBLb18+OUu(|fBK>_C-Xo)k0YdZBQtS2zo6jLB)t5gUW3HQY@Zfy^n6E#PjZ95 z2brnRuZ#(}^my9a(GrhUuk6<0ZX=h9kDXvBU}OEb=PJf>eESw9ljhJ&DVNuKoTR#* zv@oQCzdrS~8~mI5FaFiJJGZ?;US{p3?>3bBNva!xkr{cTSAHSf^nq+vaozN8S?6Lm z?lFSU`+Dw{EnFubiu8A6b?!y8vZK)0^~Rxoj6{#^hYx?acIHU=q!)4rpN4O}om5tB zXd`s0fb;MPQ?}$Bc->C`L0X^$G>GMB^L#ob(uAK z)SxG}s9SU6*F6Ly3^KyBzfUUlxb=AmN-?~Q>G zE+0VCz1)*8C-j`dPDe)|tmlx&U**K~!qWrkHgk$MrHi-`fOLnps-gUzma-9a7TKOgTU` zu06~~g%-grO>J%ATBrPe`4^(g6PKlWcG!X4qCJ}Qz08dB0Zd;dG_w~xf0)S~lT^f5TbVX}S8+A$elJ})}Bw<&$2&4(6U?PglBU;aQ) zOTbW;vC!Dn40Xcj@cc=^)v_|YvQbw-OIcVgL_`DMTg`uE*@uBb(iiv)-o(fa?-rK9asu+QY;BSJ%Sey_qBY>ps)r5dS-O zfmF=RQxTr^1f{KO>wJ#8epkLz1MAB4Y0I0GqDufpo4x)MYU9K_?CVy^Vhce{+$llO zLeGMfJ~>Zj7?3h}$Bzr^Oz*gP$D$lPR)MJ>eH1Ppe=&R~hFo{ans+M*t3c)oF$}4FJ5&1p%ovzuY5ICr@Fwqyj|eWlu6t?OFtjB{ z3RdXEMm>lU<^1#wC<(l7vI+}k5A6!7a>et_yYLcXPFit z3}O2K)4Fz)FKeS*G^Y+H9ja#XBsc#Us4<^`P0kz4*-5~X(2B_0>C7wl^|mH^+yiO%KfIoG+WcTa)8{KowRElliGgdWP=foc=eabj=6_3b0$vjg)Wo<{B zfpz9=12W_b$>4@NUW6FMSR%fOGXhp$uNe6xt744R6wC$3gnpJq*vHpOJvl0deBLU0 z%TzYjThy2{19>IC|ahvrh{uJG_gpbKoO=GnFDxq6AUZ3$J~_UuwcjOQOXIdgE`*(V+N z3rg_-DOjXVV{z!JiSZ1c=qT!$gEtiG9bIOQ858#b03-mHp43&>&QBJwh#%Jdj%8vSQxui zN1gzgfY06&kv5{LN()MeM{0Xo{+4Z%A z#-CJ;DCeDY6;Xio+Fd>I3mAUAQQX9b`Vc;WctQP=$^t4|i<0w7FgwWA*Cnw%ypvC6 z0y6eGdE`6Z?w83V3LbsC(PS(!P4^466EU8Kp;&{_kK7+bstx$`J$7R@rVpp=*%xi% zico;rU)eM_hhDGp$%FI`VXWle5$emf3sh13Fc)-uIcx9NBa z$r5S}i5u_pGs=5S1?}vuFx>v?K6220?dGi)*1ZeowuLG$Nqb3qH$gF$_0fmbR z&D%XQQQo5!;E~8=jl&C5Ye%sTi%Ctm09WA(+Qn}{rF`O}>A$g+^WV8-Cs=_!PIgY$ zAR_J9$jp9>{nX2!)v`onGNWBbbLs5ICT(wfj`Fwboi}W>z`MY!W}{Uv_IcuY(ElA< z-mQw9D>jd;)7x1~FzJRcct-|0>5k}D=SZmd;)iWtAMB0@^>MbSOo%o!oeJ~oU{Xw` z=N~^)yps5wI>oTaV;=Z8>LQ+&<4GC1qDMqsAxGE_JyzJ#aQ6o48DIOZcd@rJK7Q=H`}+$CiF_{CNjzz%=oFi?&&F5Z`#ZkCnEvy zg5rz5kHB)_5b#rwJ{eUGRr1)bYEonw0Oy)+D?f5PPMP?4Pih;RRkSo@GTHha#7)R_ipLikM)W_AA4p! z>B4Y)ZQ64V9IN0Lb6COmuI^MUvcXo(Y&dzT(DT($5|9!|d5j&#lmXB}hl?P+thLm$W-0R{_$CGUSf}|ENfg-a-i^;aSyc=trHMy=COAzL^2I68H+ct$2?yH`LKL(%5F#;<(=XXf!nRT?}v>8j45Zvn(d zqmpf&J3dTNRr!KP$y+rnM|t_eLR?#Jy$FZz>(~O&DctzhM^+ zX0FwViAZDlPm|WnNzZqO8NK{lv)nxzGD>cD&Y15McTz8=b{?sx3P)KIMJ)*T2U!0! zUV`{KFc#Nr<#EcJm1EEJPne-Pv4N#lS*-8KGHRmg(z#&?hL{Y`AiHzxBas3>o&Lu3EuK6ns&Us zEG6o_#Jb<08*TIXhFyvN*2Lun)4NW+_peSRWX-P|{(>~1f2!4hF7D1%DXGgy@M0#j zCrXx}M@H}#ar)MqKP{qP{(=rx=C{E=6^{zc$?>x z-Ffg%e;j_Vh8VRK*P7vUt*W?x7;a|17MSyKKVY@Qg4B97-Y?rL1$#!awT|wXlx$H@ zRo;cmKUv(2?y+6{;FlxG*8&7yAjsO~r2QQ>1MaRqB;gNm3vW8?!-yrX?vnxB5MP@Q zⓈBRt@Ex@;RFxgf-1NMx}fe{tk{MbF3jgrb`E-j}ML4QYe=#DVw7*zF52Min?5b zhrRAb^qdOU09+TDdoK0kBDu=>-4T=2_i08u_`Ss5^nMct58vFc=PBOv`(swMOBj4Y z7N~}NtX(;;1K}xxOh42t@_9-gr>&5BIY@zx?jcLe7ETdTDu3s;7 z`4K=p0*8LNRT)&=3w%A;{069PQ}r=`RzD?cY|N`Vvo% zVAPX*Y!i=xkZ$C;e{ye(SN(K?+8aAK<r)4SdzIZW|c)XLTYz)B?I9x zS3|(yaTVai6Qu=;zyj#=D~egHYDMDpuVAl<)(L3WDBR`2-RK5*DulI|C+PUj9MJ+G#Ug)s#Wo@nnU@v)VTYGLFJMY~MCCkm zlk8`i1z+JumXAy*vsPt3I*zSjAlaRVYc8Nhgj4jY0Z>q9d)z{8U&$&^yDv-{fBrg+ zdw1 z|Ni&i!<7c;}8Z;u3nFgD5u{bSi*tigH~tSjq6;PLr-ST=W?SP{cCYxW9QcTCIRHqcubC=6elDeU>Zf*+ra_Uw0X zm+f|~4)*5}?n;DFLp82K$A6CYSHOI4``)FuIAb54ggBLIH*3xCr<7bL zY+9(Po5r2WRq(Nep@Y^t8G2vh8n{`1?S1?bvngBP9mID~5-$UNeizC&Pp+nCg_3wJ zW9NaGAk4V`Cl}nvBVFd+4*>+^J&wimhFWnobp;JDPrVPxi_TWkpYjXUg~iFHbo?* zj&PEK=gIvsd+XDN1^GyFbdFX> z>h2pKD!>%L*si{B;N^Ln}G z-b-4Iy+5DF(KFpz4!Dnog?y!L6CyQBYlqLZt1`rp!%IDXL04bqN}wh3h6r5|Nk-D- zX;4U5SZ3nbAyVC%j&Atywt^!tq?a633m#54u%8=wSMj32G@y#uP1Cga4D>J^%pQn0Z?Q(c6TE#QC+G$&c`J!B+ zVJ)o_;MeB85)^B*q+`ntdCg4my)0L@gon2R>scYXqS!A>xG+d2G?;LBZ~`3UJQ5re zofgAb#r_9r@=v44a62Avq{By(OZtyyltONi3)O$4`IF*p_w`ms2`d><93xz?sM&p| z<+d;B@$=w)OoR2h+-gN9;{NEuars|ha@BTCggL-bnzI2o0-&}0edAiZozjUq1f_+ zR3JE+vr0G*J-`N%R3`pd{TiD!b2g6RDNARsnW?*J&F)HGHk6qB_T6>lT#OoszNDKF zI}q!+oo76m{O!xed9lm$di7jHy0LlIVk*pmJDN|#UvWQ*_$X-pCCAWu0a<*_1_C`- zH;@%(h#0FLl@RF@%J&rr5p7J7{KP)MIa1)lOb+E!Cqa*Z-%vaY+|UQsi^>BrXEzl< z6Vfo*4I4{z{hXJ1xUZnY^k!Om(70)2Btehf4S^n*ZQ8C|p*`FYv#W?y^(lhDnTNKbY zw0!+_hz6VkJB2BX?q;p}hi#?RdgB6_&<~2mZd&1V@NuaFSu&71NHjjk4z3uZ;xIA} zaF}&uOd)>?$fBHmG>9c6w+%s*9$_>1FIJ>DOasi`lp(Zn!P{>{?KbZLD)m{7v+S5M zc{t~W_%M3XsKPJ7XbanKy1&hlbo_&vCr0pG9O=e6nDnTmW-h%}9Xed8RiEvftIWmf z3+tkBw7x`wPD&E`6#devo(UPi?~3A0_Q^qc$oGs`LtDMkfRhKnW=pkf;tQCKSnIZ7 zey;`gb-a55$i>JtlPq7zjhcZ<0AY7GX_}}aG{cH0HIV98Ju?1EgD$uUY(UGE&p7bB zmzJ6KznmY9B&(2<_ef-hctz$UJ&~sd;Lr;~DPYsbw``H@6_>jS9ST2d>R{!*Fa*Vb-1)tVL`VQod zyJ?YRv4<3udc8{k_CUw~a*0A8Vj0OR{Mja`4+OU&8Ep{P*7%3Vi??Yv2z0rwUUc5^ zlHwlMp*ULh1gxN3^t~GqWyDfrQ&gNa<|)+P3ym^2TISIGK%41{sfXvzHz@`G^0k1f z%!;XQ!wow*@rRdNzuIXoq#y1lW~2&vq^FnSdvzZ3?G`GaA)a;6LYFbhc`la^^vDR- z_qFJ))&)qrAp+qf7iHIZB56%yIXXsjDM@8ldmEB+tskA(!nOZhD0rv($i5L%(o#f9EDS^H!#sv@B-BJD=YGR*{x&vbEiBx;LK&#0r zd_a~ia$H-VIQ2GV2Tcd70~``dLSW=uJ_`T6=4p`@bE83(wiy#%peg!>TC^!Apijf$ za4WRcZio6Y1v|1u=TkuRY~r71j*&5mt{dJt&VFb6#V~})i#CT#6ibNqwrPb`F~J~{ z$ToJ*$2uDW7%%d_nt&$VuCwCkE^g{ZBoBU;N_v?4fpMnVlx*iXJ&*y+Z}RdDUp2c#8T^3)skZz} zESNBtGZwA)PIu)M@dn96R%~MDxBGla3Qap=%n96zM}ALBZxJVq(C6AJ=8vH4<1Id*?!%a2g(4y_RdGDoydL?3V2*PJ0;LTCP!qpDri zh<-oRE^b8A6or+N>>zUhRsvHCZ;1B^^dG&y4Sbj^;4ftrJ^)OX3XZ=ZbMF6&4?vQ& zx_h~J!^^Y6kXey0dw%qvF653rjs9HNS;y(rU(kiu*S{d#T%^>O7}Vm`)#N)0-FIfU z;>xmufku3gEPF2)$HFiLL1NXPrR>%m$(*2p3$4HA9{9@N)>yk+j}}=NHmFLnBZXys z?cj4=R?@-sLhb`%Be?3uJG*-3FX+@e_XqE(G*aYPYqduAozZ>Zd%p+XvtN5LKs9Rh zdJfbuIsI|)-8k{(*uNL1kh|)K$js&P)IfcFy0p8;jhmhLdi#7YwbY*t69XzvWp(b& z26ykN?`hfB6OUy(Av{0wv4{TrtU%4-ft1bxQkVl3BIPS zckNOpAgB0@8aP^Y>Du&pTh!ze3m(}L5lG#5l-Kp+$Q$!7+{>%eTkgVnuf0>qJvT2Ow(TJQTmO3ZIXqvhh6M9yUGL?>+s_!dx$h0D+pilcvDCTI-r6I zsLy5nHJ5rQ!jwSQ6t!ZZ@)x9vdhB-j^PlZd8GPJOM!jw?Uhr}K63=*@st0JHh{5aX z+{AEH$} zBmtBg!bTJn9;Q58h%qXv({aktkyK1}^`) z|1mR`HRsc8jQgq^=q&orTJhw^?CR>cuBl~f!>*tSbRGz=2UIFh4E$VDE1OG@jff`e zny?hv{trApEw_i&;b25u6b&44ve@ceUNZ5>gXwkeL)konp*>{L^riE@-F^j4_mBU^ zaGUznjCtRGMrS#y_)7n%Pb-xCW#uZjzAoo&o&O=qp0==*>0PljAiI6ghp0?Vr=1uq zy!{I&Yi@+}J@8)Cx9-o1(Z3t5RZmYElA<}eIlav+MC1?k?QG#$QkwXY}xdNAL_ub)$1r8Oj}xalY`Oh*NED zefW@HE3O2!?|uEDYyNROVLzLCxKCX}q`aW-^$H)lO^eCl#Mt>q#$U$feu>nUSMC(@ zKNqQR<1}cA-tE6xm|d{PuX%|{E48>6h{=cr!DIPC1m$~`quMXxFtMEVAep+ zK=QAIY|q^|4*aS(xl8VpHgR=M(yOYV4};athz2;tJS9DOf*`@DZJLOD!oK}7N=s~gJ*aUrT2tWD6X}LG^s&GmE(HK)A_;?mI9b3HQ7`*&~SZ|>pD6)&+Sos?_#ibdqZ&?3ex!hI2$H3exbAgM_! z0~cxBB2p|@UQLdZanC zah!?#8!36E=&q5Ho%&r{pAk<|bgv|wFUH+A!AmJPD!Hl1W8cMnZ78lRzKcI*W=p_* zgw-OuJ`3`eR?prgg$(Hzu`4ItdftHWw}5DNFr4fadmHdTMVbm$DEuSnEkwA6`xJL- zb^O`ua4w$b0z`o_jw>-Gq;9nTW*>_)D%878!xRGJL_;z)2(n01E%|21+sINB9|OG} z1wLo9Z+a0h*e`IQ-${_ZFFaY>@^N~rgkzguzv~KXmXPx32M8YH>tT!J{F-D`s~5T} zlYww4kjWmh^qlcl_|D%D*B`Gd=~2V!#l)!D?Vi6UKg~8w$vXbjqeIPM0?d>%F_x0m zztH9UyYnX?$e3&)KeP3nOw&I$a+nD#9N|E=RQIaGQ+I6AheMdWZCsdczgf8@&x32V zo+4|Gvh)Csx3^pN*&W;{G=L(_J=G}6Lq_T&VoWW#SQFKzxQphaD?vdElPRDb@eZ+p zJNxp8xT>32SZ16F|3is473;eE_XSlx@f29ks>*hs+JA`yDwR!T9bViMbmBO| zy^r4{y+UfL3ti5H7F``{}~&)`l$UOW;dZjbQv4 z2-wDSu`(#RUl9^}p=N!QJIE)nT$MS4$+6#o<3 z8G+HOa)l9hqiw{y9oE;z&dI2wmf=p<3YdEqedeb88+v*|p_Fyjst51k7W&rkDdZTM z?MV^LA2Ies*{4sgXyw4rWMvKn1`guGTm<74Y^P6cXXdcba&&ExH|gZK*FeimcXKth z-yOu3g`c`|E2&I-IhR%5Pi$jB*0JZU_zHJzK)p=f4b-$PMD^ms6RCp@4%}W`z570l zd+_QJ`Okl&cnHwQ{XZYMinG!`diggCf1WEuhV{yJIx{;De$y@QdXxJRs3rb=c+<8| zIW5kje_O^0gw>76mYBTTZ-*r>Dni7B3kF!gB=NqtDQb1#eFDnmH8b^|>QH6aD1|ax z;j*xlbEE#pb~hWStF)$<7+yCmr_3tdM037vsg(&!Jx#R8V3~`DAx@aWb3GikEtIXo zfxR1_mKC2S;i&YaC`4qh`=J^soX8bFh!{CWH=o}XQ9OyIZri+~@!O8kok^o6b57$V z3X9?gMWY)awW-|wFMo?#5tH|52=gZ6A)?9>i$Z!aC9Fze`SEqFJPc#iGVYOMJB zeL&ae@eufb;E_GRv~6bqY26zikIrcSf^N!ab+T_T^Ih6- zFpGJfy{XNwocm8!@ko9go*6!iDz6(rH5sqk{!He$F8X}LG(6|mpd38&g1BZY*F_HD z3FHv=VD-A}I^~Kj5AL5!lG-fnzl3J&3k|Yp3n%(23$6i$S{dbg=kqEd6Zt|Gg%&0>#Y$OOeIs17ay253Zr%RP8MvhawKO`OIO;G`uM zr&4tfhVCUPWzldtZ)5LR`{hECr8{ul;RHPS2dDC?$`hOEx_R3hU%b1%mAmT#(V7Ua zlIBd0TyA4AW~n14U`lDayaCDytH;UPY#KDs@TS}gWKUO{M$MbhtEruKt^lc6`JCks)5m=cCM{@#9Pto+Z9<7HE0D>rJ<+3OmdB#pO~|?F9g9Nq?y3IkHxQISpia;8DpSX@pSqD*DZSL-Mb~mvfNpFS%W%B?i9YZwOc`d;;;NrMV(&N zg+9l0T}je7X+R_gq!L7>+l~QY1GworJyCLkT-7P6(7RO`~rCBO4##naIN)Ig*WZvx3{AmZu-7) zo)12ef0`UoGjYQy%+8TArC453lJV*)-J=e?EF)ByStt^Q91(5!+Rs@{&FYQXto3WE zL^rE7X^SW74$C0N&Z9izo8Q-n_Drm%uBgt61NQgI+NY<={8VlZEu8S^$^+x{_oF`- zd|bL|NQj162fuK|B+G62LY?0J*oJK~GKY2hq>h*0c3J%u;~F*2mkyzr3GV|77#|8y(=Z`VL#39;@Y2Jzx4gCQDNSCohFLT0g!x zvpl|n29C1kr0)`3>qQ=icXu>0t$d1yjYCQKc+q--HBTQ~#Va$pP5{>~)b(!7k+X_P z*sxcn7SyiD1DzIf$eLp(PFuj=y9Z)On8M@st;k{>NATGfjAHC2EprD$untT4;Zl99 zmX?Dlcm~3~c!aT=%>@>yGklM%tOtC0$qsvNL1KHge6g2+;j}FtaCj8~4lfK&w&Wx~ zW?5a2>N|D9FQrlX!?mr{a}|ZYpJv=Y`TTM*iWR##ynZ#vM?ZNzwH5R*(m#a4qK{X| zqoe;A1Ny@+T|dzu?1E<)Qw)Y`%ad`MOdFrNO=t;fgrw7dxrg}+=IJ|2Lx<9uq1%B% zs>OBV-?_K$Ca;JWbw%UK{C&|KbyP*dC$WUeAYV;jbi%!mlT%z#5(|Njn zmZgwef24@D)gP76)iQUqmdsrj$tl~N#l`-V5jUd`1g=YeNPYw`*JU~OE|keC9%f|a z7v*_-D&))`ajeX$c+bY|a8{}X&J_4qWlnne-HAsT3ag0S!`e2D$j~F=kvwK;M2D2W zHja716J5Su7Bc><_4iT%L((&OJ<#UAuH;6CIJa3-sg;&mTPA>WV zzTeNRKb!b8IXXOtwPRub>e{iWrtavp%;+X<)uPrHH?2z{2T(5CW4LNvnafQbOUqic z1y49a?!PzK7Of;Oop5qEcD9Rh3tuCPy*&;_QFSYwv^`rbHL|WnTrOPEGtZ4dj%70z z@m!t^<+(%Fz#T!WYZE0^R?Be&PIh7UFh^lybH24AHNI_H14{H@jbe0O*8#W+=Ts+% z{D??5r2o~Sk|Vz__{N#&qv~E)k%Mv)-z<%>kp};KgSv36Ff%6;c%Oyk@_Kv%%AP^z zq{P%$Tzz08No?JanRh>uXtV&k41_8HI>2hbPXov0Rb2JQ;j#F!i1gVFk9egLldMek z!LPjBF_+ZGr~lSA&WO!WTMCOsO;|C+u7Y(VJrVYzL8<#MTQ3;!QLjV*xnC2;7w2bU zo2};ki9hT?n=99P)Me)Xvu_T+Q|Ab=7o>Q)2yeOSkZN3PdFV4=8(byf4OpbtXnR&x zwPxcIT%j4na0qKtj5fmGs-NRqqOu8V&i&)~KPyj%&FOmjIpvV-VK=E<9$lAt?lf@z zmTVy@tJP;TeEmIs(;L(H^#8g3)t4xSrO1gnu}Zv?Sfa8^XsFCjUZ!555;r*--h$@> zuet+y-7ZQ!KaSGi2^R)mO>5EQQvX&DU~LNkZfnq99`ln!ICh-wj}3BVNds&0x5cx- z$SnHU=+28ESv#(~Fs6(#^@7VUEWy+hc`Um z2?`Qpq*pgjRkrSgk2ihh{VtHl83{D`<^3j`Za#{s_Ikvj`v?!{U`}lln<50S%Fwtf!(k`y}ZAS?^hOoX>d}JGTV!fc8+DYZ$?!%jtoB@+* zKHzqG18Bw5U=ZjW$Mr2lTG}m~^^W}na)^HEI4bNEmQ8ZY>{advMktKt7=^2G-Id{& z8qBL^;kRIm93DTjwcQS>U}ElS?~zzWl&@5-*vP78+*T0Za-B^?!V3D z$Eo3=2*rOK1+wixLhQ5}mMJaAQ{Kt3LzIn>bp;NA9pDpkfI4LvkMHWXhJlu(w`860(a>b^kdW|S9{;_T*Z>K>u ze8j?!dd=vc%lwPPjPhYW|LP=K&ppTk(pT3wr>f~HO;4XkJg{lcB#knz0$$Xm zsHi%Y>;1gH44IHDFg*YvL9@rRMOq`b^NX_~1yyh24eIVHDNa}z3l4&K_yw3sEY=b~ zq)RLTMm>`-mj-{3&iGr^k{*j0!5X)%r!ovizAtfiUJZ5s<4zwWh*bS}TeDv--$_a_wVKvhrz_s3{ly!hbi zdQFMufNbY#o?~PJ-rH_`s~GL7pn!!VN)qceB|60928Vfs+<9au%iO=_mR5y~0IsVh zY+*lCY4`3w0JzWHVhmxRy5hs_{Wlw`=pa~<@0NHOd))c*bo%S|_vi9Kx{$Yeg_Mjc z`J>Q5_JXiv_r$Tzqhj?4p0WssSbyOjz)9<^dgBC`EsKf?8 zCx^?t{J&qrV*5nB2W--E^$rKdIh>RN>}%8IuEy+pJ5xl3`y=1(8vTg$MBQWxyDxyLpH)4NtnTEa^<#WqJ(jf;mrdA^O9YsPe+5sI@WvYIg6bX8u zNa0HG-Hgs7p7mV&yvAMIHw@(+7L>D#G5hNeo|ctX$LQ<^58N8aiBV_Mge9sPwYx%& zV*(vb(_+dZWfWLW3Dy$fHr>$%!T0{^=b87nlYAfTaJk zZXlR>nuZ?HYvJ=Gmq&V%o1}5aALt#ix4dVouiFM>z{YBx z>_VZKmU%m((z(Q=Jew}i91wkoxNuJW%y~Afd;iaTED%Oy?d{gMF#YmP_`fv0Xu9QU zH`~IW1!d|OGKXH2kzdNej)KX`Bd~@3e@Bxy5I}X{T~(4&i&qQAOq6JeXLbVcg>-9wjs(;%Zru9|$HLhwq4$RN)LU zIh9w2m#lCAMycD-P|`JH>|*#pth)A1PQNgV)3Hivy!vYnXVOWS*yz9w-=m7ie#NEp&1I!}Axl@zLo@5){w-1Gi`bw%*-W3x6^Jk|+PCEzO{0Xz0jKR##NU z!;f6#f7sv@0}5(LlUeI4?|lWmO9T?WKC^2IY)G+lI%Cw&5DsjU-J4J?Fv=NZ;>7w^ z1qMF}Vbwae^(<5o>MfL1C=(6DYxcu(q{9 zpZrVnT7~+E{Yo^>Y;V)HYDqT?gP)Ve$Pz7yeKVy6|4T$qVpW!GtB*FB;*Ryk88uq@ zNn(4=>4JGRVW={5Buw!-!FZS16cG_$uDF?;ADoZTm5I(x}}dTmIEFIzAkZ$LAyY4MzBa6 z+hdn>K=ot5l6AsYGmpggRMs|Js7Oh=obGl>q99U@w*KBA(*@-~dcWfWv;Sh%@fw{I)BucY+umwoiEJs0#^=ndJSa!CJ~j=c^1*`)u-dl}e4=D13g*jRgK$s>Pf z00W{fu$tRGH4Xa+YzdoGO!}4tV)4awr3G24bkOe%uA2ZVZY2m&R)x7jS15yiv1UzIl7u)T9ykVz$Z;=0paM-meVgC-`PJ&G9kB%@n5@ zYPYUiSYetwizhvDyZp726jRc^3cD#6QOWQB5@9WntvS=`|twx)fE!C-1J5B@TZ; zo#*%K2fOPYukATLALK{&(R>Xdw`%b8PcPaUhm9$wAmw*n;W4WD)>BuEE?o-HHvRzQ z@3?a-w+*(Bn$d`|r*3-(a9{T$azLZ}%1~EM^+IzjrydKx9n4Z4*l8OHd9JCf!o@`= z#5tnqbo(~+jI{pBLdg>=S!6?0Xns=R-a2?wQENS%QSC&nJUQ43lkQ#2fDIcFKq+G` zdhoPB4BPF6g7)5Zo(nwGqNSx}ESysn=)?mR-I1mS3x`aP^8WKP zCHSA82gDQb(Pu6Xx|9p*u98^qi4^`zL+T^~05>`3AK(Y-e~K4oyIaQukIk^a+O>1o znB8vb&A0r~he9vc4P)eH&sw*5{-uGw{i`cn^@Klj9&&gB)`c|GUpIF&7gaCiy*7wO z|I>$9+eZ(^OdrooOWuwK{)0ECcCwtrzyewNJ0jkJVCU*2b6LvYS46BvaHV*tOi8_` zEwl5}Uiv`2?TGOX*5}71^pa~`rIZ*KVJY{Ip*GBj>_k0Hj|=+u*{&u;W?klbXpzvy z`0o6s)a`PL5|B9W!N%xZnfzY)>At=&_kv1D+(F(Q_-;});23;a^D+g|;bZ&|Rhnq% z>R!BOi%C$fE({-hsMnbxFsuP^cAe7#wSO>ILvy-Tn(Kaoe9PNLC6Uh!7H@gaF~4wB zPfKtB%{%GK(P~TV6kS1GqY=rXSurbJW-7V4OMaqitu_33mJ6Pf*`lKRx}@^{pqZo9B$oQjvLfk&ZvqG$ zmH%y1Mn(o8@10DSXVH}Gb%dk^MA3QXje|m^ZT<6AYWq!~Hc%j^ohzh(uOp}jxRY+u z^>CWjg|VWWF)k9ewI2x>J3ofWu9EZ#6aG!OJkwAd!*059aGz&&W>9D0MK&#tbE~Uw zoYhnacGJE63bsW2cK~tJXJ__3*ad<{Zi(+2UsN@vGEQqa(MpSH8{65Mq&vy zp}H4EZKe4_7Uj2VpL)PDKIsh@I7KpIKCXOStb~^E*C@?q$~8c)6WY!?d3TT}M{fZo zkrC@EP-6g;YR9HDmhUL8v!0CszUy2eJ15p^^p}U33iXfnTe$65+voqK@#KsIvsypa z6lg4?-kx3B`1PSef_q3W95sAPLt%c{)!a1@ z;r4=qOw8T9+X#Mo z#*EhajkUY_u2!_!%y-D3Bpe(zR$q{J==p_H)UW)sCmSQc*O`{Bks);rtzy!80QQ$x%|+4!Q_*TL|t80^7iD@JF=MWKnQ#GTE<*dA-VrGSB3Hz%LD+L?;iukfks`~G4)YlwV_IiBHId8t0+ zjAk_E$50)~_kqINhXmV=y2bMHkL3=odgl*gzlMzm;+%cf z6H)y^viA7>Nbg%~ZevXFn{NBdS4#NqMI7BUUO;k}^ytSl*=xH5)F&G=jjIVJOh+fL zYAs(9-23m|#7k0`gFkXua5o7!xot5za1{jx91KKwGCpU$7bQ1Vl70I4#ozZ~|G4c| z8vblw+PqdTA83}pa~RawvM_;XJ>32uYiDl#^f$5K%cB@=v)xqv7)jkBX+Y7Shn*?; zh;Q%7arW^@y~%Hy&oiF8%E~Ni_r!l2;5fJQ{g1bZcz6{9dDGPpS}ENZujHA7MxTeo zOsbJ?{D9Ugk)d*?E>CM9Jxv30>wUET<@|c>v3~%1 zvfN&)xSD(@^8>MMzlp_@Lg|E)&4rtI74F`t3rRVV78>={_}R87Cju5fyw9d77|(he zU{wkF_J$6FT{(y=iG#xBk*S)CQ!RyND(ob-$Xx2{%N_N1Yif)4fZfd~ z`?&!O-g2egTi?{(T5syTtKK)D)F{zdN;vW$pz~YBetJnY?{O=TB3ZM3R4mp-OTqLX&Mwrg6U|Kc=@Xs;u42T2T3t-O-^T3ZzQ@e-A@Dsqv3p?n%P$ zeoh%4k$-78T4UND(OR`|eM<#6hyOh&aN|UAEJB`bhw>T{h^+4P_hDdI$8ec}dku+6JBqkPxfY<;^nQ0+bi6*bjJ$=7M?^|)+*{{F-*^oaKNu0uUx-_36oUT@azGJYP@gQcM*FW*HD{3(Hufp_2 zKRZIW-}`DcGn?bnypK2JiMw7Qeh5hmp{nd7ORU56JZ)zP@8a4@cF>*SX@rX$(iBW# z#|-;pdGeU6y;NV8!ijBpB{xBq?7R+4-aOUlh}Zjfxah+&kWF*>zNT>BULS%DY)fn| z)YE@3DysTbcgG1+k-QsI$-cq-Oz31hYzth6br$s0{7#lnzu;`Pm2xLV-B9JRi}E(B4m55Cf=DxtP)up1tT>AmkJc7`5p^8#?ol64lR$eqfKnOBtE2C0fcid%YO zZ))7zibMSBJOIf=&7Gg`;+u9_YpVcjDrN>5FumUSkolt{G*1+5mGdnP*u1g{fl4%( ze+u;e9A0$v7on$To2vM%+i4j))x!L=)Ws0QH)(BYucf}sCH#K&$(qVExL{>4h5lM3 z%-Ylhy**R%?bPbqCP?Azi8GY==Cz`IVY#Fq&n^D7+h3Mhl$ly-H@;LhbsW7X+oBxm z&mOh-*1bVpx%CmY@&fsmsH!=KKS}%*yvP!5DE>`~bSgrHlfx=Itexe%>nm$KP0T`} zua7cn?brpK~I1pO2>J^cx#M&IBlKu1joUe$o`yKV> zEaelp<1N@=m=OM^M@tkL4zC>#!C^W3Etzd~8Z(xvrPXiYFAc3m8%d)o=7;^lvaS6Q zK*c%bRC4Xx#Ygq~UpMBz2g@voBz%yR`_88GFw5myb^DV|%){>p3E#@vtYJ%^nsB@B z{pT)M|0vyot$bqSWxG%B=h3>o0y_MNhu(JxmHD<#G>yBoTpQ{fY>H#J|EIutFf5|a z<2VQ5a?h#U7;@r2@puIBrq1j1=?-AVudJ;7h4_Yzp5o-gFNlGDvTXD76neI6;Lj8Z zOrL!H1Q-+44!$3BD(JlHc>$vWGin?ydtPbg+})^0h8Wk26M(|6Ak%VOdqM@n8& z!Pv=}RyxE`Sy^zMk@wPFoIX_m^)OGB0b!&eY#Q`2(K}GxYL1ejHpY6ZX+L27o1V?i zzh(?BO#rXycwJoZdU67kTJsl7Dypc8s+qLtd9vxn{o|w2yr&=@rg_pY0?Z&&e zw9vy?C_STax`K`x<{Xj3Uy*zlJ|m50;<*TmLuT-9>6C z?KyX`Hl4;ws5Q->>M!AsJi!y>hZN&VYRLS~gDp-xLB7k;HCkjq*Jd8YxW?Loi}4-Z!QF8(t=#onIeu^P{M->Nc20*&iz ziK5!;me!MWj|aPXm>~lQyYEx*--E#&%KS#CR6CiJXiwC9%{{0B&e_hwX3&=5$Uo_t zY|qG@&6vfo+N#sCC;s>raNbR)WNeZLe!@n&`uhVXKhNknnO}=ee@zGW4lg=*e-&h| zD}#~58z)Y1zR*>Uw?tD!%2-2iUq(=bI@kP#0x-h&ewa51gGkFTiPk|;q9paYnXZu} zJ)=L!=xKrfFnJ(`H8i!jqiheM6FgSLV81zy8gU^+;+wbe@hBzP2Bwg?Y^m_p;)Cv% z=7J34DvolXjkkFGH=Y083Ha|;oo}b_{7y7a8vK#@{Es8TXc|MB6}>Q&r?GLCP?jPJgCgW%pX|{DjiG&{e|2$?U1()Bs!Rq_!@kyjj)H2-+3mM*;pGH?Yz|S++mb{1-J-A${@8^ zwef?1!h4ezo5MWlP+eo87p&EY`nM>9c?PXHH!4j!|5Hp(SNDhV9cDl?w!`LV?kSg3kYU?3x8HJ;6 zL33_*Rp{f*Wq7SkjcX<+i<6=6WQ*dnmQP3)+EkKyz$gjCkfC6{m_?l))#ngYh3krW}V?NB=4(X=}ts{2@Bjq&~6h851NA8LjR7 zMencntdc(O3fHQ!OqRPhNR%}2F{fd@IZEn{Cr-tMDcs5L18r*M$JuF5Xh6`?Ft1uf z4Y7IdlincCQBiPUa#L`8D8aTl>GZ{&kl@sQX)J3{+K!`>1JD8vcmwM~y5H}~c{r39BQM&`BFmSj4iUUe-I zxUZ0cbk0=GHV0OU$QugZ+;Cymxwm@!L429jM>tuKtxnv&9w!62rwP7<(HoK}X_Lzd zz-4ZJPegqxuvZB;%OFW+N)sm6kC-~iZv9{6qhMv@r>zDpZnDm-&`_@p!(Xu~N8H`LPEjcE;<`aF!I*--|p5rqMrTw!?)VLbq%QD%HY z@su)s8e-|N_BphvsY4q$vTd5YoKkpDzSzN~=Xi)*l2NKdZCqjl;ck_oCp{})MN{mNZrOjAZYgzSOq zJcW0k-*l0m$gC*1k~)+oz*968CR@R_CciFmn=EO!eOm4?L0J-OYa!LhoQJ$hB|oT0 zs$0T6-%(kA>zP$5*pIFLcvnq-Jg)#`(d}xgJfCXkUSIvzJIwC-Q18Pm1NF<7g!mT9 z8^~DK`o+&ac7<)_@48@10eKm3ncP|5tgCAYq66jQweCpzb`Jl1yLq|;FSPvBZaC@7 zNb-@Sfg$%aNe?^Qmihk(?3num$SJ$++p6g;Y;=y3(mY{dWuGSqa|$L+??}I2-5NeJX@G8}Le~*`^BYOH*`Ac`82+isV1bws6)TN4I%;&=FAroJA znE@osdw=bNvbf;i=~Dr}G|0EAmFASE9Zn_G4eG(DFygfUk|pfcFSQ}Y{0kB9tJYlY zS_x-jl&h6Hu&@t=DAc&EU~gs1#I1z5?R)Os!lTwUv&gAt=0r$~-2&C#rD3x@_bxOv zcw)#8i5s#O)muqO20^I{)&1_}87;F}64D27Owz zwDchqU_H=B55FvK-8g$;n-6}0>Xi>D&JNW4#mjQ=l`-`D&!XQyIb9TE_0O4rN={?W zcW^N|oVe=dKAy$TW3OUaWwH22bOBra5qp`c=XMSi!+aB*Z(`YR9gDHey)Gc-z9pFT zOmA2DRS^cZ{1SaqHe6*m?(Q8LEkARS8MbB4tCX?^Z&;qxXuM$0OWSdokqOL5mmdG7 z9U`wq|AN9ZUNDSC{0Wu$P!Aib^%#7zjxO-)V7l;288b~c5D)?rED=Oe$`7l)kIaZ@UoInf%{=|N(N)gz zRq}bL%Nn7g{#263g!ak;SIjy5$nN~K(55-G=l9+V`_}l& z>qB-RU53{bzH!tb=1Q9aM*$LUYPR<3?x-)6!;OihsXRG|hIw!LzSdIwaMc_9nG^+R zjT|Z)&v<|6WzvQYJv^}b78w}&fW7YoPS<0$)dspf=R?V?(<}#w_^8Jj)H!(UuYjiR z1L;ledA_x~2XCyKL;RIIu$}qjy4hi5=>AD)v`E{Wl*{`&AzIzMUw!6-dt}rja(n3@ zuw=n07vV$G1E0d%I11k*TU}E}r{88rpxNnR_dFCk9MgBrL5SqK6 z+=T>3M~UYWQEA`rkI@<4fvT*_1enu+vWJzsFKjk*k9?%=9MIJq?({uFO?0+$OhwO{ zr(U0T_W>7gJbbOD7RL9fyyD2z>j#E7hs$@KYTJ#m@ZFR!PUItApuNK{bIicA9LMln z+F!cTmdXH6P2WBxJZqi6>0il)*1Rxrm+fu|Nm0?!K~_Qi$S=ng`iC7{C804Iq0#SL zZz$wmn!YvAg!GYZ{RP&4Fed3+3zR;ft}u5}z%PsN`DC*+L=&hy73TCUs;xs5y-iyh zr|BEyLzgwmVblRJa%m&l&mmQBk5ybOiJ-S39uc2oKems@odhVw3H47OTzHhq2^_ZEklRC&*Wxd;bG zGp8ZXF9T(Fv*(l9gH48MFLPY|2xdn~=%TpsQyJgT|7v-xZ2f8wTctHU95p ziOfRjsRuKLmLAZ+)Vr;X{c9o3xD0P=H#u;7XjT07ogj9Q7c}eLFC{aVL6!NX)hmD< zMh43Y!bC`)%&7pyk$=h8OE(cN?R+L8`3$=>;m*8f54v}GR|@XpeEEvELn`g^#0b?5 zR=#J^^M>;seVbmnBVQErfu6Yl8_+YGY3OmsI7qS}mHZ+MP29z zch@~knbFI6`3^&diq0o|akb9OGgj?XY-e zjiA1nX(6$<1!NkNlV2a!!~_#3_eM2UHYrES@v)CZ7Xb#n83io3(g&@V(Clmcl8KXK z_xK5e>fk~2Sl*~i@ByM%2(VIVaVd^eMCn4z_4%ZN&>LV~`dpN6@x>RT*=I@80S1Ch zi~HM`P?W@N`=@FVGh+3HmJST*jX7o66S-Q}AX)c!>k4z}zAP6LGCy15LLthkVCbS?blx97LuuDFd*?QH==AXP+=^1kvk&d>jcg-nwu~uq!?Z0PkIOr zOKh8|shr*VM=sdntBX)bQX6wH&*&h_VhU)%Vuo4}Kji4qG2RafM5g?h&=TBxLiir3 z{yG?FVtI_LJye-E-m1^%D|8WTvkZKHyS%QjrZ#R}2$}UebFfRaI{%@cZ*4yDIiCHH z*wj62BOhX?&DQJkyyjyO`sL~Rt{Q&1G2|F@Rd@SyfK#;vX}8dsBt@wa_j9zm3$IS@ z>xZ#`J)l|{bb`TqqiR46L> zN<4co$VGoGNYBhzCfhH;Ek+pY5({t9oJdVyi7J~4&PdNI{dG-OHsDw-&G`oS`5%9f zCZ#sU!zN?|{7G+z1zGFKro4}NwZory(Yo2sU;kO=xKn(&li!H7Yn?)dGs9&mzb7UZ zvVGU4dr{G{Ir=O#^4BgaehXV^2HO$kFWSM|jC?EZ`5%Tty!NV!OA|kHaov*f<>F#d zhh4dj;sL3uLX&?)6%(Cg?68kbo(MqN^{=`L?2u06v&r$S9Ne?Dbj^H8o5pX^Q`EN2 zRHRGLt8-835~KLjE8bxm-xp^DRtGlDr&kG#kh3oDKkQ<@wPGK3k6?6WTAKCjs-~wy)9CQ z$3ko86zdl)MD|oNaH1mp|5lAyilFq|UJ-R+o8+svWxow3qS1-RYQx=&WjkQgS1bhV zf+3wC?(k(zN%Ji^OF!tnHZ0y0&^!`!1jYg5YuWU4S*HPUB~#_RKP%>ydxI6^TZ z!L(z6DQlxN%AyT|ZV`c><{k4!8mofznjVd(YGd zK$kKTKDCka0dAR)*qYCf5T|_2*1I{NR8SB|RtAzCCb;EtT}g}3yh+Y?bxs4TT^WOF z3r7Je2O6vUmi1uOjbOA;qoRTqpH0sRm|vP0_kpV?F4QVk;@t{qt<9#{wr!kStzuBW z-E30WbB%1vQEg*ANJLdq#U!hkc2E||>0#;~uX^d-FXo%5J@zxp1*v1Ts}&eVxRAcS zG^qvHlAk=H0M}jG5g14d3vdgM6c4lU>y&D7X}eU9!^J0gJKg^(f~ZWa#n^^MSFlZS z7O`h%v1~A=uykvq15Mv=xTrLDN|;xn`?;#ilk+=)^J`4##L8f|A-H>=26!&quJ(xv zEogtdAm5QEQwf<&bTVrz7n3{A;)BgzFA6J7Y!}@qMoT>*LhShr6|gyDzKt*>QU1uq z9T8QXq|k(>S?bVSrp_{z+=(yn`#GaR^sK;{ZC{zg;KUo?o9`e|WiVl0j(fhF2(It? zGRlkBf|hdRB5pWByRqT5QAXQ%A}9RwcK_*UV)7-Q&DyQ$8G82wt?YL42;HrDpCGD6 zFRI#l1KC1dj#7JxtEiayn~`XFcjCs;?I;9_m3jM`oSIULrh2$@P~u^Bfws95wCa5+ z0WN8WC)WtE_1xN~dw&Ng;>jf$il-qiT-9qXw6vxa455qpm^~>UyRI_(Cn`S)Pdq+I zVqe}BP`-4#YxY>FWu(akf@#?}v_+{w0jcj5znK=jKNm+un)-5aeH)V{^}}0X;+8h_CYEgE)lUZyha- zkB2s-s&bNI<>&Dsx7324;fVUUVW&mvkXQ&g>sC#NiC0`UXo?Wz{m* z5+>un6DHz%=lYyvwbz%KhA$XlOddlA>A1C)XutI$-j7?kNS9BldvWm+m*5^P(v6<3 z|2lv|r1QzBsy}Rr*dmvKV=37|b|4OQW=*HrTD`PP6K9+lgZk(fWHHlt?>&)#{+{vo!s{ za^xagvFVBnx zUgb^0d%~t3M?3RVMI<8{qbid{LJ(@u7}VIujru9hF?~Lpyj<=CqkmdNn9%B<_7;P4 z(zvy~UAVDZ&2vw+5r@>UoTD$9u|dYR!qbb#@U{j9*(~i$zXH(P+D9l{C)zZugs+l> z&d}&Y_w{O&IGVr!iVIwD!rtEA@mx*Q79JbqsRKVvrtnX1@?9^yUOdz&xcEUVC|CoWEe}@<^&81A`uzY>n7XJL3YPQLpKWt|~Ix{4tLJkcz5N~cw!>x7LKd(qY zlp#7ws2X{L^D6Vj93q|XhL6OIx%sWrN!e1`pNl~AdK-Y|LVy=-UWWC=Pw6#Hy2uR|pZo)14a`(Bcc zFD4W15bs@tD{l=Z|E1xVM72{tAHk;{ovQ`?OJkRVxCy=EJxtPN~0HEhKpt=A1739zIZ=*RLc3 z}MD|{1qc6B%i3sD3zO;G+ zPnIP6}I7>bwxzrgFtQ46DBi?YU^`Q=BmB!%ife0AU(dqb&eM{RtB~?BSuW<;v zt^I8%=E(Z;fP>ufhSq zDP=e-TRB2)?X%6Ly1O#4Fs5wY(%=EZ-X!+i?tR^SQ&H5`J;S-A5$Te-3ikC@4oRxQ}!3U~cG}G!c@Dw8YyxjN`~&GsN=8*fNd5xd3~`iHH0rvKd?~ zJHx!}YWL1APb;K(bAaQ8xxg#Uey1GZRbQNT7F%+8G z?C7#^Y;*x(DPv($Dr5+iVNz23k2;2=O*qa#7 zFEThAyL@H2HTYnJ(~t63&1ny+ORIcem=99G_#*W9IAFw^7SJvVFsj!gGfS!Ki8 zyqd6$ew?OdF)5vveMJwnM#0UTvhmWkk;W8R61a8--uoz*Klvrr46qqa+Vuy>{M=a}gbFRLi<{U&lnfHKKhGrc5)Ql}OHDuf^GHcP(LJ-lg%Cptz%pIlxl2 zI-|E$iY7JQz=V~DJ(QK#7@vxAx+nx{|IIA;?2VgjwBNdk#~YCJ@%Zr`<-D7 zFDz&RX>$x!lm~BNsdsiW+w?t=Ib+P~Ct`#SyspLm*995MEK3l5VlLqMko?A`HE!%j zO7dZwKkEN7rlAqjZR1jviWz;|H1@r)JcwyUkS0hu?4taXy~jpXqNHC0g|gyr(bxTT zdOU9ORUFL@t)24^Kt}mY&A5&v3e>XAP^)@_i^qcMZaO9PO)AkrTSDHCTIe7vpx)%L zAEBLN4o^1GuQ{d|F?f9rkDhd9cZW%IsK=s0Y4HCL#S@gOO9y2$My)DTx=zo=f%;2d zUjd@vJWySmQHTtq(5OrUZ?Qzw4lG784Vy0QRAm0(a9HfpO1Q9@hOw#7ZVprv4lN=v zEFHdO7e6#1t2HM64Ty4fX10H```f>5EBxf-v(X@KxvF5Zt{-mgvxmLkZk2=W>EpQh!NQCrWX!<1>UBGOMOsqbrq8cNwFWrxY@;7PY3`?rOL z0K=YJ!W!kT?&9>KANEC=_#=)K^j^Om;Yq#+p9xOxRa6P=l?~YAx8wDW&j1M5OuvLG zSeZXGG!%CvPAUDwpQ2U=*1SEm>BKNLZef7kA^%^ zWmI!9(qo{?q|QrCn)2XzZFLJcqik+l@zU6Ded|zvB1&llR z+~dn&XT5OQVGO7I=%BBv!FH~Bv#HI7+RLUU!u7>3SHIsMp%KZMY+Dy?6G?=xdcWgk zqdHbT8CN_Ae>G7M{d5~`(^+wajM=}VeR)?FtuV^}EXi9s#b44?sc!Q)6MeNWD%aVr z6VF8=EFQk;WvrvWV5V*nL=#BE=!5BCzr|`G9m_I;wGN*kZ~vMcTs%Hj+uC%^8s#eu zj^rB=Z^mhyejwjNq!6QRx-_+F+$qQlTKUS?j~suWtOW5d2n@ZyDYgC12z5|b5sW0Q z8*?L-s=2+hY;?U|&GtrpJn}Az0Xut&oXF=%g`myn*sG{GZ3EKbNZG@NRIbvBEV4-zR$){XEPSHLJY=)7vj@o zvi8Tu7b>14Of=Mt=P2H3eU}l6qw<gLFnHp0+$3iEva*G zaRWGNKX{1fMd5Z{#~#$9KSJdv&X)jT5%F9wN**HcgbM$c2I1e>)C*~Np`rhp*aqtr zggt;`l6W2dqp1VW-#&s^JTzkd_=9o>Px!$}uqBJ-BMZXdi7DJWH0&LQG{J*3b&qmw zsm(fvDWrkCBvWT<6#uv;3I2a*d+(^Gwsn0N1ObIml-@)EX@Y=+4vO?Hy#x@Y1_(tu z5v3?t2uKSUdat1-p(BWNX`vH>H0c593S0NL+~?eL?z#8eaergn@y&mjD}!VuYrgNC zZ+)JL{>9^Qw!XDkswjOO;{NL%g~)DJ8&*(^m#0q)Z?m0eCDTSlvV>%v;w#Y#*WOpU zo{@CkGz-2YZlGYSNb7Be$pjRofQ9i~~JHs-~f zq=W+jJ=-r;w^ZphvG?ulHih^0yD1Xj>AaVYF!{UY(KD_et8j!&#c|JuCai14t3SyiwJl7~(#2Pl zx$(bz7U_K{;PU$x8MdAt;jBRgpOW_^#`1M*^h zuf}Eis!^eN=mK55U&wLAOLR& zM*HH*xIw57yDPsCx3ofg5Z)!}+`4%`yOAIa06OTQh_^52B>_2sYzcvH{flIRRp=7q29By=uAr9~ zD1&WLgtoE0Z$)Z7cG#7h)bp*+PyUcn;~_qr`DCo_}i;iQ;)`M20=!a)ok{t5GPPWe_((@6C6k6vN21$WQ&a3iw->p`N%i+*$cp;B7 zBNZus>;_zu`bAy7y0N{~)0ersm?RqFO153cGO%M?J%%t4hWmhqpMwq}n=d$^7!?+V znr+}FE-q@ZFY-g1Dn@D3rd9w^C59A9MIuJ zBIm6P!>VLc>k9rl54VV$i6n`VijIzLvgK(<^7i>}+-i$zF5{Y;fJt64YhhmFK4oym ze^XyXY;(ORCEJ_v^DgD-?uC-Td31tL-BI`CO2-~&)NH{8G&VGI zMBaRdsKhXiHPzGgOGQ7s2AM42cosvwrm>AVA$tI3LEEZ&s zt!&)$B2m&`pST!I-YA!Crdho{j?pqYQM(NybK)uoGA7Pb`Nbvq1yS)ytm?*;us6ap zk^p8J83P}=rG4pN)YG9+QT(LAyg%gNMVg1MsT0U)fSMCrUei<)do_7d`GPe=D?dd| zWQQSGdYpMI?0K-tTk(;1VJe!8EPAl#UBYz>B>{<{BUsu!_W_Vd$x14Q+0fUs$TuKK zVOYX{;U0&dK(>0LBc-OqBrd%8B(1P`JPh?7Z`MR~zN1B&g?=TAw=AF194QgzF@kMgY88Vs=PR@B|PBm(37;^5#l z7ud@ZCpT?wv~g}d+ADu0G-SAAJvxpP*)vQy`FJgO29e>`B8elE^5?g7+wf&OR9AXF zN{xqqiE=n_SP(iOdo4yW6Vs=t;S~jmYlfZiR&l*c_z3m%aE0r-o@_^Y+N$l(E370i z`ZB>%MKLcLejE{*n~Rg)Bps|>qm7Bb|J`~g=gG>aILCc0D|1R#m0ai>5H!DP&T?(N zE@|ChgZKM>>*oXC5xOXHUS~%8pX?|51z_WtjamL|9S2R70YZR_*eOE@9JQ3#(eP?b z{&yX8yQ$ElFbbHtmDZMhspr;QQ<+mpeqE;}4`qTsZE!j5Joh{B3zHsv5N#R7vx7nCIo^RDeSKKuIV z+It|4cMKzCc|kmFE9D5i_C%q&-h}U$k&DJJe+WGd;cCC9t3vAK9Px1*PKA(9piWx! z@f)0Cg6-pOc}bb-0&VL20HGil4PA=J)(!ZuL#QyAcXd@NFrCOc6RG)ltV8(5GBcc+fVkojOXsbV{ z1?i%v-x((VZ62dj>kQuqAgY^95Ct$!60{cIsH*1yPj;y&CGy2^aAeAyBrW@OaX%5Y zhYKq5{Wt2x{}c0KzH#|&v;>kMkv)bydo8l*9S*YyeIzc8%|JUl$HN9Qb@n^~R2D9` ze5&^in?sSC4S2Kr0~uM8)fMj}d<=eE@()h%-qwe#egyE;xA>xmhDtX}tL&w>k9M=; z60J&?I$k!;`ww1|TIvILubw&ry`1N_btVA-%m00-U1~EyKm$&6okz`&uc*UdG>sFr zFCvu_5_cSfL)_yMzXrbp00~~JjQvSwKsd_o4QMNmLeacM*BF~_bevTlXie)Jz@IFK zoH{-sx3rlf2TE(NQ)h(H8umiQ^|(}X9?1l7euS=UWyI874vWx_rlZhS!(0cetfQIx1H z5L5@c4ws9IBctT=UPo3Uavj0BzGU>>)k1Yw#R)MbON6{T}oCudX2CSx{3$_d=f{Vs9Xk}S4`G5G5Aa(p(r<4}k zvHObZEUE>#SY5BuV6s0FIN5T-cIZ`JPz>@R?WKlaDLrWXf(9$eO;w_jtv8F0Z^svU z51JUw%gC>1%yw4oU99TwzyB!`z+hl};33vsZ){!R6O3xyARRqu_IO>W%-$21qp(Zy zTKNJ^PM%ELX<_`d4Hg8sf2Km=k<#myoAqG@=JXoWdjr46sqIJkJ(`ba+(Ak3I~g5$ zMBFO?XZC*?%HQS?bJd3p zMsRL&61}I+LByNa*(DcIRj@)2m3tg~g@u?9{+tBn{#%v)+TFBo5-XF@zmd5AF_=DR z=D^~S!3gWU3g{5Ur3Q$xtgba_@ie|GddiRYgn$0+P7+Pjzm=f>=|y@LNp&-0aj=E~ zio@DQz{lO+0WYaWoz7oNDcNdsn}-F5A2RWXDXw=toz(z)IZAvBO431mX^Bf(ySkgv zI=>!L;9w>?ZLb}G8@EFr{|3X*0KhQhegnpf`>K3mG)cYxKi&Jkz7EpGSG$h`bdIiO z(j!xM0T;ntTNrn;j=;&RGDUMK8Vc5YxbXsh7q{k2F&Q6=!h!O^zZjM%C`To36E! z$2Ku<;%7h_UMUB+{pFRYw>kCWCH+3L=~HX+yd+}UmaCx33J>Z}=EEV}{JPX9lQw?w5Nwcshs?PrbS%ulTBV3LX`T++=neR0`+f4iP| zmw5jJ>MJ~}CS?IjV|Rhxu(C1S5CeMG*XFitV}`b&ipkbu*~X!s-WWCg{R|?lEn!H%=v7PCX6nXO;dP6|Ihv#_2 zkF06Fkxb#rk~iU)@t&Ht%GC75h3qkKPm&VCzz2ER%3$nPrK?=#)Vcs&+`FjSf1@#! zOq0GWS|6^^<=7Sh}8~6I~GEC~EfC z=&gXg>{E5;wpSTTL1(is1nZm4!-)1oG(a*j6&OyXEh0cLK*wVj{NrtYnEXdW;Z<_ z-2CPoh8a)zp*MikV0h=ll)Or#B-4F124Lkj5P+aP8Vi$%%8Q6;rDjc%CSSWuoAg^9 zXz$jBEA2GQ`czIhdh9hxX*O;1lYI!+AVqYqNzBqO8mpuUr&>peU7Pcs$h0!k$aaPij7inYO9@cCcu zCpn#NTZYBRNw<|yzY>gacIweghDl*0(m<1z{6#1B#kUa?a*q}h4b7*hKdygodR^Pp zJ+jh~>A1fVCxYEPD`eCDnWI*3m}Yx4N(UyiGx?>qhRvl#IQY*|Q$^2@mOB6dQ~$ep z`S<@&^ZD@b7Va{e)kE(i)@I8?R9)V?nlQV2YQ_b}D$!Q6FV_w2mYN_$v1OQs!n}XF z@1iu7FFcg571&?$CRpJPx%Cz{)#j2`gsl~+5#u|-=_dd?>_-O4kQY3-jBrr#tf3dq zR9#zBpX+fHjWuWA3>C#a?x@Qt|5bGVdCi=frWDBH!o%YdF0NwePvjAh9++wm1{ZZ# zQhxm;bH#6l@po4DpJPctvj5hTerBJf8wTF~YPSR&7f*cEhW;UIR4tog{sq__E?a#o zWxq?6$IN4U@}TvBk3E>+Bs(Uz6tNASfCAi6M3IY&hVSLUKuu-MUC_nvo*gT5>X#EM zTUFSA>@TuWJ~*m^q4Yn_^Z(bs!aJuBm$kSlTM3!8%a8b%rN<3sIof+!o0^~i&>4-I z^?!3|BBJBQw3TnixX%ih%3yckPo^n4fX2wEXhZADGmk-Iml_BZJ+z`P$l0hfsg2WKZ_uZf%pl@7H>x%GHYezY#LqE%I(EzR zxOvRD7vMR>zWk*X^<-t0EQLkU^@qm=J((RRvk zAW?O3ZR|R?k3hEtz5G5Jg^jQHFosIX=dkrC^xY6Ib1RZ5eveOaxL91tO3+~6&(JlR zIc=@tbLky;V&M`B?1w-w+GeL2D4URJCTO*L*n1YoKGYPK5=Vxhg0mR;U;8ev{RqxD z?yIW^6C>s4c%11Tok~>YnA^@w&0nVoFj%-BM87hpik(+rU9~A*`!}YoUuqmuPFsxg zM47dzii4gy{W?|MMAkK&T&ZZ5h3{z46u`n3;7%0e6Z*i|RG?~iW48>(!*wF!nVQs@ zCvp>Rob0);#Z#GnxNwSBX-F zxfM#(0Th}c?k6H;qT(mBUtdp$)|9IMaJ%}dHUAb@Cp6GJ~wV)&hy1Br{Xw9+H~u6inzEawUt4#6o|}7An~BWa8vP|$ns|C zS!t1{LC_hMkFkOTs7pIpLG_*qlNGd09N5SD3b}4(=ua5opT@Ac_cy;H$~Ks4~}#B=;4RP?rpV zP=&$n`1biKck<*hRR&(u9zs0a%CUHuOBx&a<%&2kr90jIxE6QD6l{L-ES`%QtJe=b z6679vH1gd-1xHsg1-y1b1W!gNoqE0k7O*5l312W+{f^uAlKw}8m# zl8nfJ2;1eqJW4txXoln{K_?0&?(`^r6)M-tYlPD&d<*C3N?-K#mFMMVdMbhotmDb_ zI?J03Gt)OUu~aB3F57)N9uXSxgEn&%evj`uF5sUo+(d@!+;GL{X%0l@SKqO0mCu7& zLl^ERAxgSJ-3!h>3hXO`>6(dL%bQM^EURiSOGqG3wb7V`y-3-b^Mm7Yg{oAvzy509 z@+EFghE&69W9My)#Q$^-Q-;s2>wsMHD|ScmUREZP1T?;{*M41ETW3usaVlyiQ;tDW zKlZ}gn=`B(VLF~ai%D~XC7z2ILS-slSpa4tWwmMPozB{x%4%jTRSsLAX1(q+05SJp z23@fGoCRuJcVct%wiR5=gZrZgDUip2MD&%X?_BhYQo7G@SJ7@KKiQ?ZY7E4(yBYju zUFSy@xO3=f9_bm)0-3X8L#^Hd_*V1f`rrb@`-NZSm4A{I`~Crd88x8(X>I?jDHW{& zi}r5r(je}pShmG&LE2b82%ZMZYMHW9?Qu|KT#eaSNzz$0aVD61`4?7=$tE;}gGnVo1y2h=WoHNe8^oi%a8ES*Up(3KQrSAuR>w8a70lM;BdGwUW3ZBe7;rBgJ zCgR7cG6xrs=m;`QGyC^6vK5bg$ zBpkyIV;_lCoW5qMTzH(`TLh8~8Vst=JxMiK-&9()080Uwdm^@vOJ6-1Oy3o7j%<}y zF1-_=Moz_n4KLXsrq4ZU+#%CIg2&q zxmkiCYzspnHsWGV<>Ft07NHCKx&S&r41Dz4FcY)fd3RN(YkBKJMQ&~bUduT<-_5%g zagdWv@0>}=nWF>C{)zF}DyZk7JVzi=>R0!IQHN?qr*XarbiDS5$Pqqmy2#8Mn`t&D z5ge8IV<_Ad@$S>|7b9xFn1za}J$-rk(gKS{p!~P|Id>TEU1!P!)OiGJFI7jBKTq9y z*50foKL&Z^duO8YLI?xevB&PPgZ?l=uTxPl>v_3&ns~8i#n;ZA_Rs6KFctroV6bX9 z!D;nQoZMYo;;!J2`wh*17n*3Zg=PgW@5Auwc6*uUFXkm!q%F(`wo}c5zb1B%1Z}&3 zI0Q1uU$O;i{d#*&7py{0joP%nd-#s%dVXiN9WmR+;=+o+WO%V8;cNi5@r+OaSEX;A zsjJBZng0(n8r(w+YH*!}z2OilL2f>+7DNsj-sSM%RWg#c?eI&E9w7q?`SwX)3Jo|< zKK|6#hm?@mXyX_;p_Mmi9D4i6Js*nE_7jI`f=mKsvNrnuRmy)~MbpeZn>=D2%5}oJ z{NmJm&DF-j4U?YGQThbyr-1vDL*?{{f;>tUZIL7z0wii63`@^3bwC>Lr?S&Io^`HC%ep68&NP zfx?QE+5XdmpOvt|R|hK;m>29l1GvvYZ=Y^e5>zKsPS|SFeFA;8S(N%l9tAUXMMC{n zK2cguX+W^xlab;|3#-B7kF?>q#EioUgB@@|T48bo*)mXJqE>$7FoV50ww_(!daeq# zWOtSdJAB&so$ii2Hxm~JceU@qN~}9|l*Ie+=!d-$wTidR2r3C%)SXMriHe1W#t+$q z*af@v2aPZEf~&Z{X)|ki0ZF1RPn4TWSm1GkuBJWSdfpxOu92gJ&!2yrpQl=x+SQ2s zR>tG-tJkL+&|n*kO8B$JiIGx)fT?ZIuf8RP#X{FVC%juYTL^KaR+YNn5XH9^D}(J| zO^l*he4uXcy8T5ntG4dkIVLPC!$WtlTzp4WP&vn;CkRa9y`$hG*R8sK1N`;2%+Cel z^V%^75(}`+Zs&O&9o|WvS$g+0+xwBFMc+TfXqi1;&vRO8jg;R62$0m65=`J5+S)D0(2Qk8gec9wGJ@2F} z{Z=9|A@7ddnZc&n-bJSmyZ(Qp)zkkAp8h`vZEXUFv%Smlsb}HSkgOtXoF~Yo*}FXd zmb}uZAo@FTyxgy8_=F5p62^9#8;mW+Jh+B794_i0^-~Z@T8a|Yypj|O+e+{h^ops_ z#F6W6=a&86UMl^cWZE=;yc%{el`{X&H~aTxp7?D)v`ehj=&dSX~)Q>F!_7{lhb;wN4VB^R_Hsri!}TFa%$tS zxyj$p=8MVp&kDDHjeUr_BKU0zrG2dL^Ygp7^t|wZ!qLWDYEbNG3d*(15?XZ@UFn=G z`TZLn^XO~Iw%zjLD7<0+(*@d_TWPuRgCtq;%<=85Id_lSX>IGBVk;LXFeLwU&X1vN zj*W?*S>wBDgH3JB9SNa$9L&BBq3+X4SgvFoH8#_;Q+9WA_PzyYkW}Nz>{06z;OkVp zG$x%^keVNKCt%8A^7G-|tM_B;%Z|J+AYa>lbB6$Qts!B#%%oVK-Nb^p6BLwZ{UYfP z5CD*4=#XGAKVunl?T?taKm26Mhun0c{>4TBE8E;RU6dCP!wmVsHm9xBIw4=3w9dg*SI4XHt(^pnXv7# z>1VCA>%UxBvGT1=y3h28adfF z4q-mkwzjFG9S&Qe_V4jS(bz==WC^sgM8bGyTukba%WbNaZux zjgiFWXN?K+k*iM^Z{)7uL;3{73snRrSSVElJO2-OK9iq3#kV z$zo10hi_5ttHcFL%oRK>IVHvC=ovK^{D*v8Pr2;fA_D~h>#hDLspk6tdx{&)b=<4XyH!DN8^pyOv3QdiFR&GBorkNWvCO_> z8g<`NSHxMzd~gcE(&J{BG~dDWeN)+-!s9nDqd&d18ULjG5gO6oru!2fPa zjci7y)&%4oZtFhwNw<9W7eKd&CA-l)hEmCJHfvl**Vf&+d_L)N1aXPG(%1iq zlC4hX0q>C|a-(G||FqsP^k(&>Tno%XgHad6qSA&}XbK_ThG$Rx^uFg#o$cR6CElWY zY@`0c9G6v`e1Gz%zjIaG4>iVX{fA|?-8pADmBbnP(+@2ZIVhN1dizdOysnfB=z-g?u1_hsjW{{$Y;$I+tN05ev*)JPagn8OgH{603a!R1q__Q zTQgULv*By9BId~Ww&$D99h+?VNgMms6r2`YQ2v{W}>{W7=&FK@$FKBDszr%w~NB6vir;b;d6i#@EKlM zIPZASKt*5@S5_e2=0@cB0EAf(K^@xR_q>^#+$W3GuvC$gL~ThDQ~Ls@N2A{qyE^0; z8_nc;8N7~S&uXO5W~BX*WX$VsQ+%Ltf5f~ty?Mj!w9{5qNc{*{oTf7dx!?lJOw}{n zu0P4bQl4p={_y?{#`AB-#R7;Ku3BqhlUI5cJ;{`Fr@;4*G5|B2j^hLVp$-Fa^4goE z$AtldUE_jwp8!}&^+KbvX4rTkxY{M`Ss`vv%~!_DpWgNdB!{MyA0veh@kuO92r&PH zGpl$!)_BhSmaHhPU={gA&_yMYvXyJLJu={e<;!)`D#Ez@AglUIyA$@1Jqvt@U~K}& zh5MJJndaC>js28z4}r{s*eKjJ;4DdzRK4x~GpuQ1suAK`>6e1txocjku(rI%Qh1*A zQCsruv)5s3*dcLWdMG%o>L(W!hzj8zHw7=A zew{xy-i{e<^fT%7G3P-J6e5lBn0d^oZ^7YWPPVG4bjb_BYY>-k{c-_V!_2;l*|Ngk zVtB=jN1R1KB0C>S&&9=g$^Z2(88fd}K-vUnf_pG0ti+B#Db3ix7g59f+0v zqW_SEJF;+h#P)z9^VdmlTf%h)m6@Dqv#s}M{DyN!&ysM^44Dg@T!BiCugJ)QsM(a- zh86r&3X>|trSQARu_qH;BK7m=<;H2C+MUR|?-|EHp0qS{eTY9izK{Q6ZhrSKSo{{s zcjFe^d)hp}SYFDap9M1aC9I!!bZzB>Kt7nhbT&SxofMVq0&pv4t<}WX1@;s)PQ2eD z8sT|(_>v=Be-M?>6d4SR_%~@X=9nXMUlWr~Zsv)7obY2rqbK_qkks!WBWIfX@7_Q} z)L=DOkUn87E!^bEf(&lJYC;9Q_H(SWU|=Oexrowu!#<=5rsR!ka1X1mKsVt>Yg4Mk z_k}+t@JaK9_klc7O1}0<`md!b2z8IAOz~6d6O-fWCai}Ko5UzGTF2k{!qtEZ9g8%N z|9rUoZB8fTjoMPl^uiri7Sp&KYi+!DYWbcgMF+UXkIvTBIwmpc<1zKokR5rHjyF0Kn!H#;e_q6xl4SWf27h ztk8;b?zu?aKdg%Kf62wP%9JPgwJ_FV1H^=95%!%Fk{#7X(L0 zH{5y`IYWzDd1>P+%>PhVH4)4ib|4F{XNLq$*7u35Wy_zf;dNFbxw!fd-D+0l5-C?N z^p(v#*E$mm)R}6rOy5G=TWa7nt#{imTV=~D^rfz}elOV8CR-NQDF#=%{{_uYMg_En zmhz?PsXPpt`}GCZB2Y7_fP5pCEKI+q?_4ev1kF~`a0)GG30#F2-K8plVhDJgm}~lY z(9gTB#W3*2cB)QF7&mGxF8d%9XdxG^8~Z7`acerfa3^LkAott2eQ4(JUNkG33_^v5h;*E1LSHH{N8^EJn#{GQ;Sc*d+l& zmyB$cOv4}GTp_Kibz#C&7Xn&PBbSj9%`X9n)#Nfa1jmS@P`9c!vpMYe?g_#|Gq7<7 z^;00uSK54T_BI7GLZ~{LI?c0VNBntM;*;#n^nYyBf0rIQwn9PqvKh-J#Qe*cI^)Kd z!+*T0y%a{F{Q-aF{g+yTXx1V54|9a`kqK~|T;uk|`(@JWTzAdcG^_&unmsCt>etjR z*|7+I6XNzl##s5=douV#{unAq&XZB?P&1fa;8hb#OZ%t8_4mK5oK6iS?tfa19&w0< zEo=&wjI>1ofh1z#wbb8q)k&fqf7hlco&eOQTE)>6rqvyG&8HCC@10hLT$j8$aA3=W zltlFSp8-71sb#XrxhJ;e2o+d1_Wan?RO3fhg!Dm&ov(u5KxM@!Bcn%qvXV`Pvmz(z zhrX)|z8qI$($RlYs+a36_s>(uD@)5y*hfM%lfCrwvd06F6XIu8dlep=U!7Ur^=i{G zlj7yco!+A6Lq5TC0(1}ZT$3&`F@>8JyBTjZDV1;a_VoRFDQ5k{b)n=iIEaj)9k3MM zM*|Em1NZ-nxA6~u=K8d5RSM?^gKhnun6Z;HeLLh2O6mEv3!x7B>h)YS^FDX0=#NBf zlcAo)#pR{r$bmQOv6K4RSJ!>rxkheX?4^iUNwu;24;Kt_3|@;h+8j*%wR$ih7I-Vw ztdZ_rk4)oYP$nhgUjDO!CK$Z%>$aUo=L7k7~XOWuuMPL13N=H91{{MY@3)}gxfj?t!4Pi_*mx%8~Mic`L4gF%%1 z{J|*v67eHVQLRJb+@XicbuZSdAW(*p@sb28hUQZO9AeB*_#hUeOYa%p=YAl9tDG=k zu`#pvAgFm(RQb~(ieDbGQba9IB`3V6RGwYeZ41O8TA_%$YWkXwYs{yRL%Lj)_#t+u z*9?hW{W*+s_zd7Hf7UV&CcsqI`X9Pid|^JGz?j&E;QR(=%W-UW2(wzJMB^pak{(nny-WxFwOm*_K zyu`~8rTA&;lV8_UV_ASa>|%~Ia5{SCs}^EC#3MJ6gp$|e5Ga?L6|K%fjP)N6*@Jw@ zxRtshf%6h)!tD~T@c5}|ZJpNdcKzRZDt-*#29~fPZZ0)yy8$hQ-WajEC}S8e>zw2} z6+xvdH2fftSap)2!4p2Wsp<1J`=^EaW1pU7M#rG6Caxg++%&KtP;Mkt^T*S-}vk8NLb^})DMg(h_+;p)M{U0 zkXMx-*KagjC8y(myGfbdui3trrWu{|>Tqw8-g}qmp3q)1o^wsVk)F(D%0K{QxxUusWqdo{AFjh?sN*&f66$`J-dxF~8tFHH0S#UV!0gwAv!6 zX?nc;ldK45byXniJQ2h8Ve~Rc-wHqOny7Jxf*4gdnn)3f>$0a56Tc2Fj32tN8DzM% z-3T&9S3GVY9JA*(>iO}A5AYkUXLoQvy>IMDFVq)P2}@C_B#$Da11B5i^ev?N z+-#R0UgwE(9L#=-xJZ>>x*1&CSD_eV=}??-5(LTQ*q4ue+SiOOsz(&Mqw_}ltqN}+ zOufYR%{h~MTWzLG`?kw>D?_WCs?p@{pb?}g|%Hfi0{msN<-nr~W&>}sHq+24F! zclXj(7+TBbTrT2{|Jl&qd(BB$Rt8K?9mblZdlZvf+}M2meQsAl_VtC01&W9fx)ti0 za_J*AO2=bO%wFtH^I+*pLKwtwupC~y`#39IXm^(JsB}uzDn0^Lr~j*)$E7Tzvb4ss zJvBEoJ8z{jVcmaD89|dapk5wD$K?*UpIsQKIy%XER66TfSr+~A24bRKw~cq-`^37J zyt~jb^PA@QwVzj%uFNl-z;zQAQ#rmjW58C#Y*MTn*S&T_XFO+On%;MjEDHg{!fcfp z)EcHGbjLHat$<^M1$3v|oxdQlI={?&JF=5QY9(EBGI*}}zE{vTJg**tEo1>7A4}oK zH3k$D%Juo9t>=$JI0WdDsKYqX`L8~mATWrl^>eI~fb8qTuF!Q~8eB^wIk`*l5602s z89mC|kp$Vor$%LUp2ASUpQ3g85D4ubpZb&cZ){>@p%@Yfu4MJ*|z@j=M`MuPGX$c-g56H%)2@f~2YXu!_d?FHM4)7e$a% z*+2h4EPZwTra9>iw+I9e&+0!Z2n`3@-O6TTMW#ssVVllnd8UqhDN-JZR?F+x{2a;t zc_B^;&~UAThqpcedo;Xt(J?4@;y6nj2h(#xdP>y7m$-#h ze#ECFV>0S6&|SaH>-B$<+1<vnERs>0LLi0cug-n9k;}D z@fVMNvFNp-G*7bv@xvIlcX#GuGTs_KtZYV(fL4r&A`(GA4uL!A@%B0{#>J0@Fnwm$ zEby${mNl-J-K(@H_(?IU_AG*5g^yolsyzAo8?A#dz6v@g3mC0B)Y>`u!4?7B*dy(P zLT5cXprUA90cu8=l|<%ZlI8+chD&rNCML!q9$b`lgGL+CgBh)~>WwSI zmfI>gc(`Z+jfM-IXjgbk65fZD)mw~wl(lzc#I!6NM>IwJn3sNul+)MoS4XK)Iy23^;*0!M zdhUlcRQz?$evSFyr>Nz=o>2k|CTJnv_I~@41xQd(B}wFFwp)y}EY)h$ure9XR?VmC zaB*2V?@F0byQ(zFY47(?VVJ5$)A;ry&(&IoF0 z_C>jfJ@0$!20xe#1Kk7b(1j6nx2f-Xm@>$madpg|=|UL~C~O2ZUL<#TkLxWRM*NN= z;5R*mm$~qh9i0oCWEMjU^jg{iyiS|!r(q8v1$QA;wyL6&DuiEbMW?n~5c|6Fb^F_9 zy1KOM*@k#hk5tjHJXvxC19`V4XB}@6fiZ1t#0xbTARQ^_SK9c!0{1a1SJKg95cyU=S0b+FVe^>YhO^v2d9n{%JzykycyJdhKAI^t$X5{fNvP82YQY^nXM!8&}M~B1vMCa0U&4!(>}TiwLDQ-R^IJ6 z$lrvQPtTb~yG_{ck^_Tp;O?fSl&sH;kFiuvExN%N(VL(F0Wk>UehTf(AGrjsuh|VFUDoWmE z<-WHu#S^TCQf|n-Qg2L9GfnvXv2=_KZ^xa_*&XuPpEw_{<3G5Xf3!g#aaJ8_UTt^? zQTI5Dep=YK1{8}myC_K$c0bET+w<&eqy$lY<`Apk$`=EV84Mie0|=*HZLBT%kWg4cim|; zCZk$!ONq6-t~+!*%~rpt-7Ch}kk9{#LiD`0yYl@T8_~lK*#^YTtA46yF)4qN6;K?A zK)UbBK9LK87ZZrkqH7zd3Odm}JeLzPgBXZhLEk8@&Miwq77IO?_-SN4Z+o(;9UVo} zCvan{SzuGJR=CH$TEut`Z?5!BE2iS^=vlq-HcWv&Z=8+X7dyOOr|`)*A*8muYTsdW zmy)TU3E_#Z-x*Qgx>|Bq(yi+ifL>>Hj}CD;Bf5(Uv0Z$N``ipSUXkvpF{zjqM>~!g_4Sokupidl z1t?KfZ5r-bFBNV4NyZ$Xhyb(cy*IL>ZgV@oTy*e`$$Z@Kdc5eXLb#T`?Kd4>XKfFV zan+fISBZ|@HLvmst@S5P4LrJ@FDGx)pZ-$?#m~e~oGykGHWR?G+~nPD7{a~x8Rx-H z7~{B)yLfOR_-oC40OD8tHih35O{PZT)!!Ppb`3|)l$iTlIyvK27Si8!6EReP!OHlX z2)abHhHvUzmk={_1cKrgs`KI1w;`oBz$|2^@^aC@S_4-74OJvTGJaLq`{bvUvmbwN zHI6ERVfs;mf9)SBGDJ>oGw4r6i zoegQvYaW~1xPIzCF~B~5LZ0n>LjLK54}U6=#>H7!%B1GkGF_9&0VR!qcpsK~=e%dL z$lmGof+)=?$7JYx2)k8z>Jv5Z@PO`7yr=W!>IiP&yI%bC72hV%+waOWw&mR|61drPXT-e==*K3UHS^;Z(_4BdT*CK9;<~r^LM2L1_t2|NM zcy7EjjWUgz(^PYp{zi*#^H#-Img3~(hbA{^NBlXJ-E#QVguxfx^m*P(8j9nH6}Opd zS{TanvEe$Qx`{*l_zMzgS+sa3XT>_4B26GI3H+obNWQ8jog!f`(}}vzJ}IWc4-+e+ zP{^pI#{GsbA|gugtdK;l>wfC&Y&Ag_y5cih^bHVB(tGd`x=1@SZvMR&wn#hUA($HIjNycN;6r% zE|;gzeh}wINSSLX=^|zX+_<&0dEI|kDv?uN#~7BltK@u|_8{tOdZ&`UxG3DzT~PYu zb#XP+?*(UmHQ-E(RNRPyJS+DyMXZ@~`EzmjgizgERvrR;E&KPdyXqv~*T;%_KaFj_ z$G8^zN{z6kj;W11;kek(7TAe>gvN=yxDnip2rnY2)4o$Otz+K&;cOK<48#bka^^;K4*3q+(W~)nB$SGCHUO$9=!)Dg^I;Aur};5t!sjlufbsWliRf49 zlbL+3pM@B=pm|i?YFU$gN8Q`k@w{&Ow`Uz&FOK#CIHs3&@L@5Rn@eXu2y!C=Ea-fo z^C6V+cE6t&G&5g#5AmgL`py?K9o3^kUY~%Q9Gl?65#P$YrwUU}08ua!t?-IQvaM;W zK3`U|46E!tpB?{l`8{#`15@|uo(E0%RxortV6J<`beMQzE8dOvTh^Xc9MN^!<+H(ylobr+mA`$Q&3m0cAqX5BEYevRrU$X35IeE6%;pJdPe zBzvjfcDTM~aT~d)p#_vjiw1j{PTqf*C*NKEq-lP(i#48_d9=e?_Iu$cPvyt~X+{e^=+ zGBdbYs;`MP+;)AE9t)}Dgt$(L8Qu|b7tXK&Dc@S{k-{u8+|I%3HR7i4ovaj~YtFak z3Vx*|^p!sp-+dK9WQN7J9(`)HvUmDYk&FCl_w6v#z*#B@-Y1=7%%U>ae&cERfTBH7 zc3jbk;0|?OsP$TVH({aDYP&TXOXc<<`tJJ>%@de?1MI?E*A~S_4-X{Hqd4+nd-`En z*)t64FwWeibePCIpllA_3l@ z77+c3Liw96PhYdwgr@kwS8tpd>TPPcI5U4{>Q!0UKfL+)rt3*x{y))kx_T$D!9Um!a7{SBt^-6n3)Z;n4Ni7}0Gz&I?igc=)w|Y|3TKZQs9PU$B%SK99L{57hwkEA^~@3#1q^Fng$_numQc)vg}ZHo^z}r&)m2+3 z6lD}$R@3jUWE#y0OPGtJfyLL-nFn|D%G{83;yyIgMQRbY*45 zo94sj*X;HgGZuq5i&p0ZlI2KXi~IwA_+|k-&-HoVSw2n8dUxO*27__@YGWd1;%Y!a zTg$09Wm#2|1>+nkel>jITclW<20Zy~buChWEd8DwkVT~~6}yz9Q#sRg@8{CqoWAd2 zYooFdq|~Ou8-Fc#^_i+?9;Rc}+E87aHgGk!Kn3L6)K2Xg4+|s*){DVk-9(u4uw!%n z{HhXdGwLk|5vZU?6eh57%BuP(ia0vtXnAE()2FO`s%UUi1{h3J+I;Nv^XLclzgd+5 zaoU?^93Ai}ZZ;aEY*aib_DpFD1~FZ^TbE3)-FZoL0E&ZUyItZI$(slWv6RSWEW0rn zIwJ8%IXtpZ8^)}&WtS`Q%*68Ny$^8b;EHN4Esqx|BQ1k{3*y}gzZ8Oa#!u}tfS`g} z$>B-L_7oSvrKG8~^6=+s4evJ=f5<~;h{5o=RzYf^*8KCDP#%uW*=z9bT(G1UO{YtA zF!)pCcJ=Yg%n@l#dw=sa^!U?Buef`@{gfg9Y7Tf#=MPtbNM1v51_b!yJHwCdzPBgD z>cOo)Lf^x-L@Iqi=ik!GMosh)$z>G`RtX^ zWwI3?dq+;JeV3A0v%`RBUzeqLU0yKr;I1(8B>P9zzdzA}y<;)$*da<+)@o0 zcW_h5EKM0bx@oY_m1dYW@Hw?J_{Tqit)nlRDzII;Ivhzp|ES&HKDZ734eLPR>oT&@ zgPYbjlRn&N*QkAcX8sOQikQ*ceCNKoGFRuhlsKHx^wzN^vxdn#`-aLv*Q)x7C#4<6 z#E9A1Yxp_!MSV2zimpBnaImc6r79<2>B-WP0!CB(x-kMiy>rH(l4Q>(C7*jJ);#Z? z8~A}=FI!i8mvK;`u?=Zdjs9N`76>z}nAX(oPuzP`n_z0s+o}fa)CNtVHJIKV`7$puSgy#CWy3t?1@*ayVZ&N>x}R8PdF77{zkREjsHqLC z;CD$`43FmKjlEBpx!!QpI7R8fVM(@o=;3v*IQI<@$2$L;DX@v+&wr(5QrCZL(hz~Q zG@TqCt5fET52jsCXZJ!!GCT|=0VDJ-C7DB`fZCG z`ju>l$iA@U#T8w{_mv$DQ_EiNrL0MAK_PP#?St(8*WF2)mu$4f9*-;mda zeVmK(0xka}V?R7mA9sO>&fFWsC*3I>J&We>=nl+LHR@)3!c`sqL&gHy&%T)1m!tm)oDhVG=s?YV{s1b|whNF~GQQ7dR%DMm2x<4mUrCulPRca8h zY-&U5z3N%8PV7)kq|9;gW=tR&swE$u*)W_{_A;^+r4JH>H+Et;n<96 z>%TvDd}#-7NkIt20Q@syvr~xFC(NRX3FW8zgB9k)mw2VX8e$_=)@WsGh4 zj*PMymP<9{iPCfLc!vbmS?Fu-L?f|3TK$)1bT;1`?m5ar+ZI3H-Kscxq%EAXb)H~B z)>qs1_Z(!5fB23ms>*i(5Zo`3%Rbk)qiWtXauNLEs4l#J)Y77hgKpGPZDd_c^Qb(u zDJiDJm`d8XmSA|(swX<3jfz*{s_VbCA9p7`weA28x}=;Og}HEvxP_8L8cgM+q?GY; zp9cR=szrokr+i`hN{xh{>&f&+CB@N3J*U#(@KryYRs{+xN>c4BO$RHwboitAmr+FTQa_HALyt(vu78X4=XD1xFp26ZsTUh>?#AZ4lTrv`Z6L0_luOi{ZIb6m`6JPEiCP!Gh)=QQCr^Ba$a4F znxK@02|Xta>Y5f<;{o{_{7b_J0)R_uqw}U z*VkW)j`@XQrciO^l&%povAl5Y#0A-Kt&8EBEX4S06qdC|x>|ZU{Qd}*1%l30_~Co# z8Fj2g>?YlJDk?2Oi5XwD2C8b<%h9~C3g{Lx?cs~I(CO~`=EHOLl*#qdB`J%J&C3nd zK%cONR^zL0`cM>qt_A_KHU;!1JoL%;*$mnhb<)j1-LOp4Non+^`}jola@R5X-w5%- z(|_{|*al-*A?~muCVkZ#Vqdc#fKw?x!%2tAjSx^v@6dF6#&@bATuL zaP*m{Q?GVcy^23hOAeIi;`3UK$s5px&8-raMx`i$Or>z&`;z#)O_v6wL;9Gek^Mqk zS5jGCQRV07(=5e(zKPqrfwE-zk zl{t%47}P)EQ501v|4%hnbgVd^2_5$S;}P~}2hptFm&6?wgZnos1xm12|CC5BWPWgI z;($6oMjUi%zWX=wEFW$ckk+o)yVfLqZ0uB-(p66kh$>?eh?ePs(;PP6shC}e6lZ$M z%TAtAJu$C*zXb3{VSNuekFGz?GrN{n#LqV*>{`-fuAS;TkpE$~9N4$2e>sU8ee5KE_q(xk^W0iZi>ZQN2$G6O z7E{0#|HqNio46A-bjh8770^yhai4h|u<_`?rjp;s)0n~|%8)k2o!S}trduhKs)u)7 zbOgOtp=&ak-@&+(_-BmlTz3&-$QJ5(r~`MU{hJNHJu_DE zI!jiX8EyISeMf!V5h%0C+R*Orhnj?Sbj<(X^S~W4=~&l#dS_ZG^Jza2_K%dHQgc%I z$GqtG!XGj9x6yr%zj$$b4RxAT_xKgW{{J>-gfQF30?$qo|9hVDC>lHZxB~L(dzTw} zQNzZ&IDlv{fmOSP>tOe1EZ)P+{W1XF_o4aGe8S*R1pYKKr6WXmV%g}1+)-h|OgBq>5(pXtElp^k1|SsC?8rl+$&2Zje!!o&#yAL?2q7C72H{1%Vws9(CWf$$xEz1;w@<9^KPcOsAjm`r4{GtUC>Ln5EMZ$}7#9pA5|E{4 z?UfD`dH$UjHB(zU9!g*5<-F)@**NTYlzt|+dmF8Y;id(#Uda<;`oiY>D30IyIUNd`WNy1ny6_O-fOw z`IvO-o!`IGPpqEB`xlf|k^S;W&mNU%NauHKVRFK~+e_?odFeB}9Ixbs9j zV~)x0?M)P&lwUltO5bRT*6C)7zswH)U`St4Ep6yr?Qo zFRe^&y7A;cpHQ#0NoE0MO`hb~gRSF|)zNc7eM)<|G+NrLzTUSFa;Cp~RcEE7>QFzLE>dX;-=UJ1EIriId|WNvdtc%O&Bhm?QF z1otp=UNB_yY7%kVV*-V%J}9bbS1wUd@_dKvDaIbK2SVBcyAAdj+y-R@ze*nYPIXK9 z$HQLX`&zoj1mTMN4Haka8as*st(!+n#w9N=?Wo7l}; zm&?GzswlIjq>@)2kB`o6xS(hHdD{9z$YRP*bNCA+{I?^HDm?1XJ{~VJc6s;cSmEO{ zg_yqp!?9O(7pO*+i~k^X*9<+o6}Ts&I=XBh?|oNU`P5%I5th&dhn@*XZF}D0{j>L_ z^d6N15-D<4h&xbipgi`1{`i_TWc5S2)sI7LqyI19LPodMuYizjM7w>jH}3WGftN_d z#k!}j$Pccy6&+Mn%a2xc#Aw=A!aP%T&XA!8qYbiWM0tyzrA}Z}TVVJi>i%7k9(hIc zUB7;jVd<`yV}DvE&3b#?PP1;cLzwoSO^AId43eb>3h$)}RzasGB7wO)C|UtUQH*t}@=m{%?Gc!ObFVZ@@;s7aL{4!< zNCxjO2c``4D*N9aX!lCoO_lEb1eye>aOJxV9MflS7V9tCapJ6KMG{QDQi0MekEM-W z(9y@zB9D^Hwy$c0>ck6%WCuf$S$_c->b1ewLhUw1wRFcOI$r1DZf^9tA@5Z#E;Ght zuUu&C;)cp9egr#%cflhQ<7?7!M%H_Yp}u-DSxU-3Qk52hu5a}FDHa#Xr<; zB2CylD1T8>_NGB?;Bm?Rw*bHW^>T$m6?~{| z_Q3rPqo{lfe1_KUQfmC7#I)`!Cj8j(>mQj!G1>KPLMM#LrTpU%Nrk~iB^E$Yl?1wxyVGqD0A?J>Wjh;26mtcQ}IkM`;ZwJh_V$+>gvnclU1-5qK$-?^Yo)d-Cbd z2ac?7NFO+Qf%;4+eBLKnUNsmGP}Q_E2EL(Q+3HPincQy4fyy`~$okTi2Dfm1t&8On z$8!|~I28#sQTQ4C6}G(SQ-jvZ#c`cI>yZ+lS(=eZDq+)WVlDxDMttVkv)#aT$9P+c z-|nl5f+n<`-P6zTzOiC#Co-Q`!ysYO+@U?Tb(xI$|TX*Y}H);72{rs-(cz& z5p*~Jm~Mw!0DFAV5y`UqUHUiq5;y6vlb%qh^!o6ZTNz(t3-X%O@Aq4+^~kLF>|UeI z2zFi3!DUKM*j+i|Zj|tu5g7(~pJFPyx$rim34ciLo)Kw@`UKgCE$xAzcW(c_(LqQ> z6HxAgR7ag#sRPQ&={b_mja?XSc!Akh!ya*j9wqHO_O7$Vs;ln$=z{`vUEdJ@;}(HG zV*|tHplznz{+*zG{LqQD^DwXrRO>o{OUZhUStp zyk;i)$cEqSL7~TN15=T4Q?B zy9;7cQSH9D0fklJ5C{@>{3vbIEK_ivPol@_WUa*3sWi41@GD;UVCbayY}&nc$$e0iM1pZO)shfiO4gOvbd=nyWI(!JXcv%qH$-$-m$a1zn7Jtyd91}2_`!z*=B zVd8l10z9<1Dx;mBHI%8M#$RZE$i&HkUVJSjB{|e|hFt6c44C>;vJy1?r#xfc4(k2o z`k6@(RSz)f?JYnw$ciPn!Lx$_a_QE==gOrmM;V(B-APTHvBX5^<#qre}d?5d4D#9Fk(m!SQXcXnR3|Ct)1EU++5Kf$>5m9UGvw#0_ZeiJ=MtrxHGB5cJfdiub{qVlLPg^j**?? zB`zApsh~7k{by~(zM$9-?#>hqPl5Y{&Ur~v7L{R$Q^5){s-pt$OfRo@O{_I9n?B*> zknf~opjG{qS=8|`>BHxbzYZSQd_nKXXt?Jzdv+TRZxOcMf(NVWG zY{}=Bb)URc%<7slAE=c+uHWt%PW)Qa}a4<_WBc^ zA3P@&pLmbXruD1b1gT4i=lW7y<`)MdHy1|eFFPbJrphwW4Fod|iE|T^O>l`;zYTQG zS=H^!N#pn}4iSfXOH+M5VMNItv?2pbGN+ykck6>|X-3pP+G+mI?)b?d8ox6U|IVtq zcFZy>3Zid9cD@oV{+LsfA)*bAmPApGs-deN5O!0PT4ypnHO;Ca)y~vH@gAZ42X3@; zohH_5Nt|;e+$X3t=%fIGUs1d6aBe=0N0Xf}n30OjEtlew54DMPWAb;o36NCCP=w+Y zW<`Rz=b!#YyXrAF%HzcguoEz3e=cdhzv&tWkl&+qx^uv8#Q2eL+L3eX7U z%un|l0Om5#@H)a9NMuOV3^66fTva%Am%(($!_{=w^)7QRtuR+uhh@sGss6xct>nps zNCi#b2aB!J7{O?)F4H09daR(-OH(0^3X?a)~R!Og}ebAB3 zdf_EsuC`dK-eiCb6L3mVo3cO~k*NLMguwxFm!$BJ8mVnTmUV8^z8U7*BG-a0&t~oA zA!drGN|5~fiwZakat4@HvQ~NNi6~fnQmmVuzlD9FG=o@lLNs4t}gIz<(k~t@^egGzb;MW^R=hKOW`sOwP zaV48~@IS+>i)&HYUJPbl1P#4mS%&MA-=Ux<|HrT;lc8!?G_iZr@!RoM-cWF(;ewP& z^Xj3fB>QUMJ8ZI{n}bqCF{XNosv#Uo*ig%YaNu76g!#Dc|C9v_7I;yuW@4_%2BSmG z?%3)5M=3<%&mX%%C-P5!pRU#n(PsFte-gqKw;STUcaH~8(IFXON6`P-oL^MkeO6(3 zmP#dPcW*tebWg7eZS)HN3s^hV{m;q#XO~%r8RXT>o0-W;&nD>Ds68%STg+^X1UNAY zkfq%V=^`&LH8v#y_|95(*b2Gc>c|l?p1t>1F3GpEm1{tmhPxr&*?Q^;rOlZ|S&CP*%i z<%>prmX}xJ%)Q2){-;LR;V1t5P6|$~mMrZLR{|5DOp5Pk_rgV)#Dh{RsO16MezjEk zO|d)nq$n@GOz!vndCuhnQaPOBd&aLg|M&MZ#|eU&ZzY#;V$iCTn8d#DREklzabnd|;GHFu~X znC=ve*Pb{8qT@&OcT(edtyN4xJo>y-;x9x%w&2+&hG<>G7eWM8)Ei3$Df)SsSrdU% zr_9SoSN(E%TrG><0*H9+z*lJYBJwXl@E>MTAo~7dg61vH#Ke_}1ey)=XzZrY?*|@J ze~LeD>2fu!Y~1H&ef-8$Y)?WUAl^MM#9CU`W>8mBmOLXn4H1`j}#{z6r(@L6hn$Ff6pK8{j^wHRV?lp6Uo zZAY6lN#7d5`!$jV@panCAiTV8&P#scu%hz&qcTsDZBR?3a#c7ft$Qmb<_?MqHK6F6|cXN$y|vJcM40gi$*Y0t<=%R}CF2eoXHpa_ z2M3A&D{iAiCbcGB5OrMg9UQUaZ8r?#b+M?1Jn3S7Lu@ssKhe7>xukWt!W*%B5j<|~ zv=MoMS$z2~K=I@+;J?q@e*wm(6w>r&L5*t;3F#G>C~P&5vvD?QY^kruPq0+;6%u;Y z92c`~3t47^(+qTR2uj_XF)d{3+Xc!GOP{rrIlL@uCgG9A@SdaMp?yN$a$j{XJLocp zU~#KUmg-1Ip#5fij#7E`@PvsTiC{YqW?R0XMWGh%<$>Ph*u(i3$otZNxS;@t$eDFdwen)8~ghns@(q%uOmUwKT%gXHPP4N-pImME!sk2rR>`tV;Sk zF76n(v5_klg>G*_Kh2!Ptm4~WCKSNqS>gw>k3sy^6oIc7Y zL?FY4rOugVu9@K<=9s?lfHqHWOT@jWECGCJfdg=mVj%;qtZBE&o)XLS?b0+GPolwA z=KHDj=3#Zo-RIqE&E1^`-VD&*N~ZRj?HP>$1Z%g2J#7){J$;t}DaK51?^*)*Tdqsp z1tg2{2k1M_4@G~9YQ~Y8RT!n4?qw_{RvW7bGtyA_?&R~;nQCDX-zDA7i`QO5rUlAQ z0`pvV3ug2S5G#m?)^@|{IyBWH6!hz>coNsWGto_L1de32q4lEPa;ChfvOM2S`KmDp zCh~Io)yjNCH~2x1s6;wvddb;^SJ}6?zxY3nC}$HW(4kuO$Ie}+S=ZhCQSq>1Dos{X zjU8rYELGq3+ZP!@_iHcU3GpI0YzL}gyq!}$jdk+3J;IJ3-%#fpj_4Skn%hZO33JCF zni_2WP{UP{#$Ohkzkekq#j#briDPtdp0@ZVcuZ&ZWOU}iG$a2*JA!js)ZN(NL2)EN zpx(mRvd{osMeXrCCPt<6AJ!b*ZsA}RzS?(d&GN<~ySJmB7t{AiwhQoOXDMVr98UkD zdF8gA%7@>FB)x$<190V|b_k6RoZbo=U(-Ov@OI|GKfUvvNqA;R86Q(F}r2&w9 z4>J&%>FOi5@5`B?$D4;I*N8oPKK-(!I!vEc_fn&wL?7aYq)S=f*(Vwb*X!rV{MX{S zn+=tBuW+eq+dYF;7vSx<-K%ri#IH=KP1_kP$tp_Cf;4?qXhNJkD=Jm8_|I0WzspxF z24GxQ(aQr75k>U-vS4azM8E?`Ppus&L}D|i)bmq@g`Gd+Qhb4XW`QV4TB(zLcR18J z6{DL@*4klvj`4Psf#eL1_&3kGi(D7KuvOPJUZ)Tgy%+Iq`LR2zF3gSFtovwyW{qmQ z{^|74s!U$WZNLe)n>ur(uKy`ap|M}GQPWPC_v0t;n;kBCFE0LYgx!!)yd(hLR_2dG zTI^&L)O`K`^XEl;(eq1wQUMz*tY!fHY->^uSniD@ylKCC0)f=G7kq&gHxC%AD!yo# zw9e^MRgLX_>l=gXe%}+slCYpd9lmxXhV(Sr?U)*DDP%|MzOEx&X-cLEO;H-j$oA=P z3TzjwN8TqGz>GXUI3L(QfW{*SJPXh>*RmlK*R_!`;uF}Ls|tnDey_9KyrMa|&i>#x z@%jadTUU$HbJTI;F`*i3zM=UYE6H>~x|1T(Eki!w4y^y~c%*maw>GFsh$}7}dc=roTvCh|KUjx_NW-#V z_UA>5)U?_W14hZt!uqI z)mM%If{aC_5@?eFJ~S4_wIyENo`fh3Td6q=u3NJV=8M7LNgC`A^FWS|TtSYm{ZTE+ zm*f^B`%CZ}68OqQro!TBR8e)9dQGbkR#)P{&6)P@b;Ah-cG~(WTFL{q2YcB%4R0YF z)50%D{GCfCvOEh3b~*ZRG-^NvA+FZD)J#4)@HhPa=s&tU z_AmthUw~ZB!xP+xEw~U-uT4qF27djz<_9yTMSgJS8wG9xdHai$0Uldhe`IUb$wm_~;L|@Xe^EJ6cC)bR?&D zl_C_pM>8NigrrVXxP{<(0aH78-7teeDg7QGlCNA!8iR?6R%8xzMAARd=uN0isZL;AI`9E}|5}xoWKdl`bKI`~QGe6=P0tsXvPad;pGG&ht=5{Q zr9Y-no(K2J%2D%eE$S22$0qZ)jyf7zphst9SBdi(@b~}5qU|Av-U@1k)6oN7^0|4M z{8n7*9XZ6KvkcnidC@N4-~Bq}_ok>2wGS4XjI7dmV>5>yjE0YDWP(?@&D;WPdy@h- zeEE>;vVJsIMmx%*nqBGt0@yzsn?JO|e^jwpE`0Oublm*I(RZqSxh;j|gQ;hwh39q= z2YGMEvw(_MY*99}+xhWrYKvncse+(%KpPRnOe;6HnBYq{50kc=fp~QkKJq>~86cKn*rNx-+ z>QJE1l8?CWDqpHac^$X6aB{Y>sf11JU2XD!eS9klwQq zHmkY1gy?mY!jGu`!S|^aH9QmQ{PASQ)xpvhRk+hh&9%6tDjyH~-YDy6P!sr}pBOP- zWJhK1ZOUbW%0>xGw(ZnkKnvY`%0G5NQN`LQ(uvw%{`NKv9hdqsJN>e}6h5P9j$&kX zgj97iL6UAcLfhE_?mSl4dQG`=1i3UQ0{jc`BPtv`08-I2TW3}tuI~3MXhg@FaIi#QdVb!IA>|)$Qw^s=ggk35QH;yoL~JT{ zm7iHY^Qq0O#c2A%_kmdnslhA1sNp^e)h6qQ9Da3n+@!rpao?&a%5-V&^0c*26KYey3h1ZQ$U8njGhZ%M!11E5|ToB zZCf~+PW2e8fiqhlv@x=Vl35R3GmxEy<%we!rJYlo<=?lP2G`|{vFW~1 z2l?UeyF(Ks+3M6<2$#C?&Yg`5p!^-PLIDriwzU z$lq%e>(G{6cFV1=?OU0jv1(mHpB)>k=I44&8Gp|`v%wgY3~gAJ)R5U;q>m9QD8^0| zZ0?xMX{*61TtrIKtE7n~@xYer66q#$yH^9pGjiW4yviFHu^2aU4GI1r;kK+$JgjyZ zF~rsII0}*-?TrF&yeEw5S92Hda6bKF2qjrmc)&X77gL_jx_n(87*wj^ORW@o>@~wf z0-BLnsl<@(V8Es-7*l*13=Fs^>xWjtbYLo(LH;&1%{2RwsxhE zuhs475JM?7--S~Kq0J}If!F$DceeeNy93509=JatY@Yol-oC+G@iwA6rY+^Q&l+v( zr(EFSO|Fxpt=l=Yyu8|}2TT}wUR;Kd#G2JEeM2X&D|IvRv3zq;r1bz!#yF3M z@a-Jzmu%S;xE7Npn+rusgey|5?gfE3sFS-oW+80C&9q##c5`;ZT@TC{n=~K$!o!UnViG0X4#YkplD7KtUWPkGo)erMv@7=9HT_^K~Wqnq2E?a}>0uCTr z8yLal#+4WOl-lTJ0O6 zs}uRhZFp znfu3f;+8S*c9Cx%i$RbiTbKjISN7D=$-=WdAffGW^SqoAG80pk@^#(R%JoI*>`**^ zvOkscnf$ZsT%EclP?JQ)%}q9hNi^EUY?k{g7Z+ncc}b-ZF%LsWWvY_dvZaRR;VsF- zNL#;g>&fwm?bakcrHAVG@;;i+Efpnj@T1eZTu^tuWi)UtOrSt>0GsJex~Ws|xwO`u&~1hNzgqR8_2U z%CN`t)u>JPlJta%QqLk~RrX*;pKZ>`aHf|{fS}&i-I8zZ+l+zb)!ukl{hL7zlV(l6 zlQ7kr5AyOEB7zd+hSHZ&oWR!X8@`<>Vbe@Qp68MyyY(|psTFQ~{`#L5A8+E)S}9tG zhcvkWCcc&AF)~oWduCjtJ(~le5uZL5Ko1t1u=w$)jBBy&5|weF*qsu}XTzIh%?%m% zPuv#EncXM8yzWO`ZCRhM;L;z1O`vRFC0LcO{4CD=xKj@KB2G}6eda$E5MTW+jkgLr z(v~~g+kN>6y=uWRN_`QLXs7?1k-j0I2%c$m<=skN6XA zZtw6+}-_?f}XSw99b#F4iMHGfQ6ZXQ6 znyFqzshP8c@2;IPh{}QwfU`xm1?MHjEp=dhUtjsWW!p z&e1P@VuN{JgqvBJP2GOT$A74Q2fXlDn349qKm-7jf%DuZstd#aV2@(>q8c4+xZt`N|qiY{I6XMgtf^KpH?ZlfuLJ-ocw zGN&XsZBg{HZW^C6c2Hl1S@nu8aK=8Demc^@kcN~!5L_#mkshvA5F3^v)a-PNzGX2X zNzK%h=SpoI%QzOT)Erf`KOh|G?OZM)J5JwzD3v^=lgq<5p-={@6e8%=+d zYF5V03^pjwg)zwVz4DXbJU43l&lE>WD5Oxf!aQRTN%twsn;OR5#oQW7kHBe!?Xb(Y z0(7#RB-7K;KMbSvZ^1-@pD&NMN!|eL8;C_@myK0hZ-u`6X!`2L*h@uiHi3MqPmyO# z!E@^OvYR>lr@`oVd=^Knq|NUP~ue3?=1p#hbU#th-g?OBKowm zw=gd~!F6Srmxs1R>=~s3i6|bXsaJmoLOPC1;)KO< zdhC{bx2C4B6b4_~Gs`a2)Sj6M~a$57kq~i^rCtY2g=~W)cBbG@^rDqKfs+;0t z#>S@v+nD5X{nkln1`QBWYd>qv!`ykmqL=(9renL(UzjjnTXSZR()#DN@JLft#o*qC zxT9R2!z@kL+;Z<-MG83p6{EY0+AJun&212bymf06G`g7T?X~(j@aI<~L3djCm5Ou> zaqFXT*tf?R4E1-5nvO;_xiVh%7`9_TY%sBB{ligc|G`kyyGjp`SB6%TL1GL)BP6vJ`}3Fzecp51;~38sFK#ikAjeDAH^=?_Pr7 zjyC#GXZMjQ-)rb6J9yc)1S%8^JZ(O>pH=2h4X3P~+G{9`p0|^-L$49_y>d-1eiPzR zmPrZM4a5Y7b1-qWP{$@M3T9?=;@R!M2y9 z(%R1Btaqg+dx%&-a@NH|8h>+Wif?7~LoL9jE`GB|CkRCfE&D2bgq~7P9>uIbrAX$0 zu#%G$RXRdVOlZgLmhWzKnM<=jr@gdR6QFVBCQa`0gVT+>3{(=5Cm}bIYwh!-14+w( z0~lK4OWQY8&!HxgWO3zB%DF|GM|+9Rd1A>>Gf&g^+g%+8x_3O_pQNKxHDzv4mi*wH z?XCBYxum36g{V=A`=+GN!&6If5eZOD9>Btds=`-#)zQ=b;Dlz692t-3G~*dwe|@cz z1X0VUvV9$ZWnM@I16)@4e>0Gp4H@bTq{(E|v)_24qkv=|(yEvC_+F}~quS*&;sJFA zLKH8uEhQKpp(n<(l&8L&8_$4%zMh_?g~5P5-G|+@KZ0%y>(&MDRiqS$844@7){rnU z_LKCJTiP{A#r}HhFRe1i>sKO!Vw6S|1ey@RW^Yq1#=7Xt72l1E5*5X<4O%PIR8G>j z>p@f`Bc&lRi{$z;GbC4+zraTLv2n?Oy7Z2k3Mf^d{>U@%&X?Ldg~_s@3nJ&zbCX9( z=XQ{C*hF<$z$l`6{ztu6T)UHzLTg@M@>)cU4+H8HtirOkH-rG~X z`imyvd}&BT2KS?c($=E()XAfpuAwh0kJ)Csf0dUFnQIAWY-|S%9dXra*%YJQbrD`3 zd>O#+BFNlzkWU{x&K#{19tlQF&e$zx%)5u(G#9%0(N6)VuTam2N@gTGv-CQ2HlqaY zw23Z2O^_2mr@+LcxvxjnN>W^)o6q>)lq~zf;e4ae9!7!L9%jJEx||$Ue{jaM>P<<( zQaz-Lu%mYO@3}F>7l`iM`2W|9YjVeOxbQ3Ap=|O5XAPjGM}@%AnG5&m3T;%lFdW28 z+nRmt&A%n8|EAC%3&_p`yO;))bT{9w*f=T1r7WinJR}{2I!Q*FI~5RKc$Vz@jF8jp z?WN-aYl@p*ga98IO>I8+DDqJCVZK4zJ`E&-jMBmKLY~o+xZm1=csr3}^wh=!pwXnM zSj{8;^Jayw8Vv-U0rZjiD1pKCcJ(vuvc2&`i2W(i&=`b7!3*Iu{CQyDG}wsMdB%jA z$L>AW6fdk)>Sei|)_=cxtijx1L0pyB4PK{UaN!bv{jVB3etFFxuh#VA+em-K^rb0K zC|LIWnpCo+OSlM9H%aFC`iIM_tz>~}emX|}4uvpbF2!5EbsArTmKYPOXle2b!`XMt zUtimtZa_-Mj#&&?mbfnF;peh{Zaui`wSBkDJF%^+uNrRH0-|yIzW6X`-h~Ne$L%WJ z-uTO(?`&z+yDXBRBUe6cz{e=;0bbBu(A|b zVhMee(w$6GP0JNg_(96LEK0k=pFv0Xqmf(x8@;0t5sb@t2nE;=C{8#pUHCcr@r&2X zrqI1*lnc5|ZIg5YG01HsS?>g#d4zRjW+jt4J10bgW4wdc3~x{$1=5fc9)cdKkbdix zUs~KwE{>fT00!Dw($4aB*AEPcI4~&&s&GwF7hp5Sev_TLjjX(E=#MSVGIvI#3n+Xj zk>C;$3c@kBN4Alx>*vY^4h_{&59n#4Y3Z>>DFG&O2Aep$62GO(=YxA!wN>!Q14IM- z53-kid8tAt_BV&L3yh2(DJIE4-q_J82K;hABR?Pg5BJR#EXoU(Pid=3Ej2*Mj@*W+ z!deq`!zv`De5r}jc;UW4Fc)D*Mpm}#u!3mrNa4XN1x?o5?U~Q$c8p9H6jM#`5Ar?S zW?H~nz8C#7;oAKXyhz$`)sUwmD8hv(w=9$VQA>Gpg`iFBy%Z94*(b5LKUyXN^eLqk zkv?X3RZ>{V@#aUfXX}oBQhRZ`G5!l6bhb>&O0Bber4vlI@MI95SaxrWGa9ob;`eDv zZ|oRF9lwaqO0Kpk_Ub~1C~+nPrFK_>CbA4Cb<^%Y4BF+#eaeqx6MU}VSGmo57r!Wa zCH|CEs9{$`%2lkrp$HQmZ*b8x5Z$XE(tX0<1%JLs*0GG-(9kZ`BzBZq2+WIm)QQ~3Er=HbA@kpjREb4CEVqX zzkH<_8`|-M#&$|?0Bj~?K^Z8A<;M0KlzaAHP6FMgU%oCKouEd7F{T`jnd^w2#n~ma zMRfWwx^fMG{f+c zZ2z;RwPAg8DCZmCzYX46?ZLMMi=hH90_jP77Gk0|(Oe&Q$niW>c=?V)fbAqrhA-cB zQGjuI8U#T1DBdw%Mu)gO4IKpnu=C1>ws-1b<3V6vB;^7pvzEUmWh!XoQn~9yrPwBCeNUl6tS}dt9-MYiN;;uwU0lFfjI?2ZCOVlSKjAbSJK2Yex z75YEr?*2^D7Du_4Lfq(MpPOqepy03RRglU&?Dg)EPknr9 zY(wUjd>xwp-@TV`6~za0T5s=lG zgO9B!fn!eXH=irC_46ld>~DI^-a=(`k2~3tlU#rEN}J|yRos7AJJ>Q?K5Na-+Q6$o zUK}W%<-G{L$aaCn5tlf;Tk64CbFVKS&j$Ztt?{C|-BLOo%=H-BuU zi`RX9wwF4h9g4^-KHl)AeU6?u8`9G5uvRkSgOP^e#`eyV#UO5 zyOuuXOVRD0Z8qxT!XvW4W#*XB?O@ugdjYa*!m-WSXxsCW|r{0m_HZ`UOsy2$3V zzW|pI=6kp8?6EtDb;l6NzkmZy?&APqIq{;47g;pN`632~2_{9ftz3gvLjiWTHJ8#K zMb{s+o#mKcu#2;MF8fVB(qTjN$txzK{;xU}y-^U@Rj(}JVUoUX=r|&&HWp2YPvDHh zd=FXp7R`;n!v=BP%}3-@(fTsRn-tbYeeIx$>lI_xBU;_v?+8^#GDo?T&zTQbR6`n?S0v)`fD_Yb@!sM0rvL4cH)vr8eWS zPYF@yp(eWB(N)4#g)ldIqHhdq_g6g`m9hYoNHO`#VEyfiqRX&-mG8O^jtI}aVG>Tt zgta(ZB;10R)k*yrgB2(}Hh+k!J5IA}UFclu?f+nUzm*&;(0-bE*%v7MP#r-h8a11} zbKKLCm3De_I7|7|+Z(i`Mc%PM@DFqp1^}S$=UGY)FoXhY+{)<2%Bm83n4`a-&uLBL zZ^kLh{!d1BxO|-pC$Ii*SRKhNvQH({N6XnHc)pMw_x?>ktjel<7=@g*oVBT_pXWN3^86+XN%$dV z^Y!!P+Xc@b{BCbu#1d{kFus>i#F+klqdf|X6M2reMaJ=CPM>&rnt!0y;S#f;j`N&4ZH1bcuc&R;GhoaLNKi1hEA2V)yT-3b(dv_;`0|0`3@p3~$#|}Gsw|z{>y1vpvrpVuH zxab{K#n;~)?^~z$=BKAu^S^X}c{lvFne!?A6EQZZ2lgQ+`?GiSB%Tk+qv;&$+&C)| zEZc)m;~drPAg?g|byX+vqceH2bIyHdt#FV<&C39368mynW304Zoz=*Rd)t`P zVCwftSldsN;7LD5l+Kwml{}FWcCW@;Nm_SMJl@g^Y086@sB0&5D66?${xuD55dEjD>6hA{w=0v%NQSUJuq#NM;3Im@ z^yH-%5}@wYkeZj`Ma7`E0t{oClv3hE7X3jU&XNvFb_l~V?~+I!e0r-chHpQ4jF;`S ziXOd|BT@B;k>`W-i%M9-|CPyy-#*X#2l{#u8siXpmnwecP{x2V0Yy)U_W9-h%YnEj zbQ{R~=pD$OSh#fZ=G>dQdTlTL$X~@=O-ZCz!wh#gvbhc~N~2lGacTa|%oGP7{5>Dv zc)Y=w7!c5Kyev-*7^OrozOlgM*NcAvPwE*aGYeNzo0oY(M49Mur^;@5GklXLxb^*> z5j*rLd8=Xf#Eak=2y4el0<%+#nYc9ywbh?fU`|mS|_(ni$AeGeY$Dv)U4v%3{`*D zlri@Y#Pgg*exZfx#N{MG13-GxhgT58WS-2*y*^1N`~KSLShW7KG8tCI={sya9C-Kb zlMWXB>o_;*qa*oFx`61D8T*li0RS3@IJcnZX>AEA z;)gIiHb_QY|F=AOyH23+Elkl7q4DP#5e2$A+2&#q9Qe1%P7AP}-)|1c_Pz7jOSGcC zefXKKSt0b9KUjs4Az=-jI5_Bem`8wNsxOzjsT_KvJf@?Jfl3DlNN(TklB68#(g{kq z4l!!ZFCzgMKUB3k4qA>tJE$ia zyw%y)N%9^a--Dm72Jr(Mo3pwiflT3(?M)b7+h+&8PinQ(4ryo7T4shGz>jV1j=nW= z>PRND>QYrng*)#DG)nnmYO^8@?KuD#3b~MX*ao7L=w z&_56Xpd8Rph<4oczv?&&{iV+|`Lo!OGk>7^a|ldsQ%UI`h`js?0SB($*n=Us^L^#R zzy@sWO`>B*kscrm`0V}xyL{jLCkRss=1 z1UJe_ zgg7?GEU@Q`RA8fVe+FM#IBCKHT%Z*{nc<{Vg8X&&Uw*%34O;nRwe;UH1-u(E{@M^$ zD9U7=Ih4Gt$Nx~NHbIwoo|Nik-Is%_9PZj5&t^i6>fsQjcTb%E`|0 z`2mQM8o(Jm-hrE5X^ejFmfL zXo43BePmCOqnhwrO+ymkmem2IV(~_hC8suf?QYMlj7xw9(0JHa10$* z`3sj^2vG`LOYE&<5+J`QyylcO!kXR6)8#iSOy`zwiVRB>ffK!w-c4UQ!${gn94e!U zrGF>wO#_KZ5>Nptg$i zdyRH(cJ@Y)W*4~>(9rz$1rzMi$Z=Qt=!-ee>iPW&rmq)0@x&7pEk7%mp%uC6J|3$x zFPg7c7yZ47AZ^j7jnLG#08!q%733??I_Kd>Hm_QN>v$@%9kE;2#b&E^kCN?Jpx6>39%-`nZ%Y7IAaMA^&icBh8j4_`6oQ+ zUs|}stm*mpSHj0P0%#SlvZ$q$5EJJiU+s=#sY_vpI(Jk9t%g$?o?XdUer9gvjNG}& zV^qrdYSP8ado1EAe0gtRze1!SSSN7%(j{@6*PrU5cIx-su4kLkwEGH!Er!eR!QzIz z(#@xeLlV4?vyXI8LjtZ-Qa`P1nfSM8WdK^CH#|<)DS>i3%D4}&UTt`Pqbz_}VD$dq z#r!KC*k97?UWy$Mb5Qu_jXi3`Jn;g4+a>x;G0^vAt-f93H;rCB)hpbSHZZ3v14J_A zdJ}q+stcG`)6-phYAmUh#uhLP5#_e*A7NWT^^lzY6&9N3Ob?kEg=u?7z;)VvGswx=08vUOdDrUbg9vm+V)tJXrJ+)mF^6tl5(R9+}ln*Jo+RUpkNB>4Q!z#4HJL1^chCF?N*QebDc&)d$?*E9YzxS#eu06^Z<@$wsr`)$ zO%#RR0534b17Du4pKh*4F)^;Du1#kZY4AX~*TYl!2Y581->1R(as4y2SRY5t{NCM; z)__NUb=L=9K=Dw^$!;_Bh<}ghp*0@lApRKtIzwx9<==XTspV|KizARf#EVGS> zd`Dta(cuQB;3nGR3jk(Qu7=l9qdvJB*d%SW}O>@RQLWbfdr zqNaEys1ma6-i}{e&+Qk~(4| zPoAhBYV{c&CnG7EUg+~#G*MFYe6Ye9SGk)!&7M#pNFx>ur0C+M()_thdPJENWSX5C zUpl=Q2S&Cqs)yp7Ft3!Q$U>b_Y|h#qM2w6%V(8vrUFN7{ucl+W*n>jk(Qs9R8tXE| z^6t{Srv}4P8`yK7d*JFrgxX>0S8ul@dd>bCjVok3*7^r{xq_ z>y?eyL%Iq6$GyIX$X*C<{0I7`w@tfXB3Ig}c4u>`u~uuJ!RKXFHA8;Q(l&)SL&K+^ z1|P5O9yhr#)%TWVabW0fp&kaP=WnSeIo!=vM;E>Br#eQTr-L>5s45*Z`pu6<-Ubqc zPPzJ1xLiYA3BZp&cs;dWF?m7$tc4APPs$QznoW?~cmq(u$Td;##@#@pdW3zyw*M-C zGtDVz8IUiP2rq1Oufi3sYkr>!Qr7XLFbtgtVf4xUv84Ts-c<#tN$A9wrTUw;!~`0p z=LGxrwevcuVv}vT`yvJzlML)Cvx88Rtxkb)4-NZCoX+QK@7;oIKV0MrYSARuW!@s< zy_aZ(pS_En>gvteu>3l-DcJTFimc=Tm_XUdlPp)z^M@;3ncK8Qe z`ep-EanML^RECIbgIs~yP+8S@1=IqW)fe`s&oOy)%BUB=`ey@PDFVRlejRH-vRdGo z7d0d53^e-<_Qv;n=Vbb72cDkiRLgTrfAws;G~gi#7d<1{UHRJ?a9v7oRx=-1l%k+_ zm6R*?%4}A=_kI|+&a|DP8H4#96M&*j_I^YW>CeJ-U=gZ-(rX@0G<`&7{yVxq{=3kP z$_eiyHPF$>OR2gpGuiW-+)J4DJ8vnx?2+yJer8eQhN7}gEEaqNaOqiWzv94~~8jc z2U*!Zsd0t{usd}CuSy?OT{GKvi>l-nQ%fGj3;XFQ3U-XNpt95l5|Mn$-)}97+;J9` zrm|==GRfqAny(m)^*}nMzEEo~VGm*RpRT@-Ezj{u7qhVIEp|m|AO)R@}nCJ4Td@{y-P^#p_slMrJ0H>+Q_%J0crwT*hV> zDWfQ(l<}@f3oV|X-S<;oS)t!d9z{+ae`D+yRq#rla&&@N_Z(>~F&;m=G*E1FcT!&w zQ+~=u@~4ZVzUrvaDVXk9+qpJI#Yxw2D(w;o(y;1y#Fks*9q)$mWkPhmnk_4uN3`|B zj-bCq*n0vIA<31N_WaaDj~vQZh`J{!@x^wahdw)GbIEi`6!HX@+OX-%8e?WVx-sl& zYyz|}h&+2;r!mIh(B#voSKyeFJ6pD+MQ`)4XVh6{xCIyt36w(U0iWR7-8V$Y3C)~61LkWiR1J&Zs- zkUXCCQL-KPx~Ho=H5An14VmMUIL{V)LneievUQxHoj?NlpU0n&E8zNRN3oJ}DL#^rmP$qTmL>niqXZNRq5zhcEsnsHrR z5vi0YaC-5+#LRT0;1d;9FrC*|ok#6b4jidN=j)P%8X;OB#!o<$D4Qa6W7#byIrA@r z(>T9VEYKXK@Epm?S-`%3c93Ia2S&-afl)H}P6CqcLid!yA2yoXis7is`_e^zIqb~} zV4u^u*BUmzPP9**QY}R5P_Hw+hy)*IA_Fl{nozuF<+bmC-^A0z8^Oa<=ZufBaMyN) za{A}eh5daZy|VE}87ok%EWWqddx^BZ{&yMhwI0!kI#RlPzP%}ji%WJmmj{c}#}*a$ z5f9Pub;~Gb|BtlcvR}p=B+tql-qot>R_0N5tvlY71|8q~D_s{{?ZDrGa7MNqHDu#^ zOY@93a^*_BE*#(b>hZ*@yId*T+@&`H-_QA=ZPUA?>d9O#2C^;q|T$_}ERqH?6l zWpv3`RH4}#(@^?&Es#cY321N5tUAio`6wulNoBs{9b zoDkNP*Ysg>Ne=lDGsgqmm03Mub<{}ADlCRT+5`VI6MfY`}&~TJCXz%Azuu@c!ol!5$`5pM*^F%Aa}h{Fr$d!>RGkN)y5>xiES?x5*hd}lGrY~%6j)CNg>tMCu8r*{|T@aQ!j<0cCOD;kJIz!*EuM!+WE0(V7Ohm+xphs?t*QrzXBGGaONHS)?}U3um9!WwA@$LT2?!8WcG{lA&R56^HQ$Z8)U;7Srs5A9_;z1 zbC*1$=f8WhzYUO(sPEaETRM2=E*>6D9FZ`DAq8;0L-#|h05?rU$--IF7SrOle;^B5 zm~>GTtns`ZWzp^a4`c!qL>}oz)HrY{ENd|O6m?zvLu{mN5ox?mZo~hQ(B<@{2Ki3x%KWH~RUja=9ceQhtk z22uO6#qj1dyL&rYV5|?j%Q{w$7CD8FHkOBSX6FOL<5GCmk*uxq! z?R|@3pN0c5Y#O9WS#{T0 zp_+*b77n=h3mdUa0c!ceShA3zc~nzd5c-U7%w-zsLVZ=b_7F*4A22 zeQ@b?Z@;mwUAdD$Ek+sl^CdWSy0^qYOE-W1`i2J-Ms{4^@E8^6*8g+EJ4EaJ&8`b` zCDc30OC8deuE!#!!r2`0CtN({ZeA~AXYLzqpf%k*q3#PUf!Cvrx^wys?n{DiCX#Ax zPs^Gy+)N&@u;repV1y%0AY_?F`M>);xq6-X?${3h2THY<^OK9ye*dRNbI&wtwsx1A z$33UK5Wu5df9`U$T&hf67KPHVsr^9+Cv2uITnRRO#Gii{h&Mc`r z$R`gRP{}MN54aM&62H9y_PQoz6(9Z2qrP8$x^7VvD@e$TWd_nv)$OkO#!}3d+unNH zo)96nZ<3?j9N?jVj{?g*Vx0Xeqj28(&${W4hr_vwUmlv^MeRJb? zRkbvU<32o?SZVw)*Q2QToQ-zD1$W>xjh_}txJs_1xI?K9c!;dN%O5jK9&Hg~!)lxt{!+$l0Rm1K0D>{2 zU~89{R#fA{G#q?xq`7jPjj4Zqu)L!SO@~dpw1l|l%9$**ge~tE_NF-UCm1*IE?z?H z%Id-y$~K5uPo*B@WI6!Ebkgzfn*D(rm!^hy#a3#kaVGu zNheIB*S|9jEA6qFCF2ZU5z*R~hNK+pSKpn1@SRskI3vmETPlyD&dQWyrHeveFu=9! zOl4aO+F#$Kf3Wk0Yni|2Z;~G*{(DQv-{-;bB#-!ipwSVvsd2y*FnUD1FhM){ZHjCD zPdGEbdo2!k z=a=egfz#~N1<8bl@8Ma=KKGYh+VQE7ULQ6Llbv?<>UU~+0wRkerM&nr_NSLeM`cUl zt|iwsF+5nqcgIO}cOkGG*s~gz0#iPAl=aO^?F)uibT7sO65z6TjU9ypm(z`@s{Fx& zpR@P;sSrzZ3?Oe2zJ+%~)gp^P*<}-{e9&8wx@IHC@T+}!_-EYeDhu$9fbd0xzwsN8 zsoLPTt`~5^_jO7U@^#Z()5!9~_{10-DZyMiDJ3v-Tumk0g)26}o6{4#* zKOZ6$u#pP5=DcThHtxXBX$OO)HgjFd)2kwlrjhFcALEa|6Gp0qvC<1A2~YILo@Y0z zMTpFo)ifvp!ml2b^6%3^1J%j8v)fJy2aCQ$kt+W6Gm?lDhqK_-nEC}Oa{Uyl4dToB zL@(UQ@j$_W@D(tHlDV({5x7hi0Gf~WWNHoAF8t4Bg0-tpt=mdMNI-V-QunV)KHoUQ$Cz!rzPa&=4n7#HY`4D|0 zT&ONX7{``G4$f~H6|5;ulS2@-7uQBU`?=im>>1hf2R*JOk`gAl@XU(iY?uq})!&~C zkE-56(pbozJ259dm(J4I!E4P1fIuJ;f<6}F>$N+FPkq_aNyCHIWvFWbu+Nhp?W66YIX4rNaOtJlP?q1C=e97DZnhRixyp@Mz!*e?JB70|B?0X& zzzJ6><*#8>FU|E>HQV|tzpKW=;-v(+>lbkv0f z;>-R7_*L8>=G=_3voNVg)tZlW#W+sLk{d0G-^utu%84t&5T4YOxYEv=3e2WZ9KI-@ zq^>6k-qJ*7n`Rt*;nRI?Eg@6pCnZvb@@CC~~o`Um8@&d+YRw$+Z4cO+gPt7VM6d6P~FN-8^*!u+S$ z=?W4UI3rLqn}KIX*LKd~Bp9b5#{$Lu1Kl0(Hqu^TWUZM}_7}`j3R33+XXTPv03gIM z{7zQEcLw32eHeq_?jfdA{6Qj+6~^7%20VSOwo)d^Vv0dR>ht@fAI>Q8$G&clJt`yqzt>ZbbsUP3tFLCbOZ@?F;=3i;Eyo1_-eJXx?#Ct>Z%evWCzJ!+(kf6f{W2Lb^BjC-z)p_0baC3_C1I z2?=sO8@(lp-}WavO0P;wiYHo%RP>bTM1DeP2edTA;@F1*mHdCj%h~{`xGlgA9r%z7 zh*bUqT}?eysl|)5UL7}Hj{+~Dx$rI!mho~Zd@IU##zCp)ryMu2<7VJ@UsqkRg&7C% z!mm)4q&DbBfZG>PB50|;(bs-tt=qu?L@5BGm$T6=wQ28O1^>gz;(SQMg3NG9f@PCL zRQF??G16%9)OgFAK(4hP|KNMpjQ)HR0fb;E9TE#9A`ja1uOZLCM*zR#@!tX89jc03OaV0BebE5bCS&P)bu0h#_y}DlE)m(irF@Se{Q+Y}qHy3=~exy|wM|l?%-+Tb5 zRUQ*(`YV6ZdM>}lCS+T3zzrxc8h-#tn#liBIf2J%;3`>EHCL)J-twii4a-Fx%I)ez zsAZD!Z~7;m;@!h8TiUcQMjKKb<%ND;hTKoqnd$M;jlJ*o>t}}mrGcjvG4Zqbw#~Cc z#y)RGc#%L%3%8l>!?-$i)@*t!$ehIDa$ij3Z5sFCsKd_fu4a@sNdbX)KPiw(~L}PFnDC_oI3K>ZQf4M zjm^gvyaY^AR9s^6*7gA4L~QSJvtIe-=9d|Vn=T0xucNa(85F3J$q{~hfdmKPe}iE< zRlMsHCnzsNnIx3`oA$y#)`+B@dwv=0QaC?`*~_{22Be*cGsl!wq(M(JZo4dInNUPI9WiW76O% z??JA3L4$`?T(xfk`rjwf?>5urL|X321u_J72x%SyE9`~Jkz&1vtQ7I^lCGHMWRz)sLLo2 zrEthkpRPOwo&73fw44Jbuu>DJ6BCW<@p|^1yF9$9`(P!gj9zc0Wm|WT{NEJd>c^A= zmyx+)GnTYS7kfT<^E{mP!r3X=pD9uzJfPC);HSRio5nW4g!%783EvIi%# z50;p^O&C^IFC^}B`O>{je6hC$zofDl@7n0|w_?Txb3_fQ-;8e-gf6i9Iw+Km&y9q@zC)5Nk)KfyVlfO)0SrFy&iLw)$67qY%)N5P}i#;?h; zBIR6wyeF|=0A(e=b}PJQqz?MUO=ql5Rti#>)?iDJ)<7UsnzZ0XCS6R10wSWR&ahkv z9$~WX`dh^f?UhZv_nC{_ms@$iI=$;^s}pZMN+P** z(g_k*E8p#t3 z>^?XPgb2IT()jK~gTo2Q(RUDecf2*r-r=R$3YuJkFMhix&4c?J(bX z;cHK>`$e%=z3k~ZzECuCi}S&zj?#l}8uG*h)||D3^Lk*^#fP$faLzj=WPJDq-O*7p zpZ1|SMQ?n$J1P6rg*-J;_$*qXgGGl$a&wal%T)}kfO7k>x*V*e{z2I7uCNynj+SWNO#) z!mc?lPI6^BSWx6QlT->M(=Py0ku{Fs*GqGL?AJ1-(Z>aQQkrGV=tfKXQ_KI`80AGS zYaK9WEm4*gXS<`gzk7IOKxLU_#< z9D2vZ-T`iH_3T9#Te8fwBke69mlec(FlBWt;e$aAw`w)ywDeP>P6Em#%Di-IG|PK} zzIM?;aLdzxrl~G~9?;N}J|0iKXs2_O-c9G5g^}gC;n;lhzxq)dmT?INb=rUV=ojsMxSx zJdi;{TS+XvjvdsyXjI|82<9Of*VRGl2*f?&4=f@F`R4T9NNo$^g!CV-WWBTr@O(YI z))MI4Lc`(d|A_F`8Ke3({O6PN64#-vS4unfTjV_(A;7DvG4I9HQSPI<&v<9k5bpkP z_We24qG86|uk%1 zH2A44f9U0D>UGY2xdU(_ewv3_rM_vhvorsh4o7%OfBpSR9cq+9qU zjCeEnZ6WD$4kaN0cra&u04^k~n1~&CGNQQk5A-qek%9tegsUZsCUJuJKHl|QFjl%c zPd8mtU(0Dr%Yo~Umpi74Bqk^COz}DLZq%0mC2}d%*z^=%Y|;CyUL>bh^S0-^rX!JE z@dU4_p3x<_w5fy_`n_Fa2zD>XNr|&qhLuy&)Ywa%sk#+$nXnl^z2_-^Lq}; zly^j-!>3BTx_h%;=L2Kdeep=kj%WlBzT+Gcj_Ui$R{HIcbEaXuk&fnjiU7+uxm9P0%EKNfRQezr$l}Nx(f8j|qoq`fB97C>^v5uOF~+59jq_b7xW-FQk?> zaui=@`;>1>Oeyq{`})B36Sg+u6rpY>bqh)gnsu%_tm+M9byPY1q5o-*fQaPig~-s) z)w&q-yVUa5RU?}8`#;CetzRSN=Y2zHOu#+|trLjld*6#D!@h0sWf6QrZ6IY;%$zjhRJk;^U|*t%BE^naS{ z=|lpy#hYgH4!VZwja4ZV>fa~Y4Gh$Ph`h92#b1pCrU}O-RJltJKpjI^k#|L^ zW^Ed}oa(f6wX~mOrt{096?@1Q!8eWUI`VY7nUv7c3p})EE_y@pRc<#|#FN3HAkBgY z{_mirBb!2op)_5W#yWmxZ6(Q-ZKJb6VHkc_@@-lO<({O#8Q>ELPA}QKuBv0-zz92M zBC`|frz-zysQ__+A_=KG6DQ2u4_w*tMSCo-1_u6`+B;}O{KCGPVZnvh0q z%{@OE!Iw{YU!pj_O-Pb5z*wWR{4fAr6MBT73$jGgJ^hu^9egAK%-;+~cF-#O1jepS zewHSh4_^w=&J*@+VDcImuz*fk70@XI0%|$9x=n6Ygz_fE&$n4=0i5FG9&6IlgzNXD zm>dA%!-$NgjHRa6Ot23m&F9V*yX9&O?_!oeWY=xySMFPx8P@^_Fu{NXWCvt%WwOq*m*F&3QXD-tJ7Pm6H<3hka(LB9;R$-v39d&A5NA%~8K2OiEfIr! zksBE0joGK#j2HVS_3@p3BM)yH8O}R3kgB^_iB-t7;8a*&e)LZHoteSf-1(6<)bvnq z=0VXt6(tAwI7)MQa+dq9DRcz(-T#9>?G64-s)ah#Kagc>P+3j4@swHR3Aew!!#n%8 zxmCP@#NY*y&Ifyp8}7Q8cD#(L{?J+^hK&sC?jQPg;#tDyu>@d^>$%DAWnNg{JX)7w+t_QWt0A*o;u&O1@Oww9FHl=ba473AU_8rH_d)<=7#P`r zvR;yRYtFmJ3DL0f7iX>YYxO1crFrQ*9F5B5pLRD2^VK)~l>=RFanGVfT@4 zt@PmCk8HnLFT$TQi=(1WpzIDPN<&XIEsEgzl0KYaDD3u|uJgmjP{0!8-Gy7I;WuZ` z$LAQSH=+1_mS4|~Bq5^9Ui(<=KhPxCM7&krW_9gWdi0_C@yq@Obi|(G3I#Y{p0HSi zDGj54S^z9>6;j{IuT~9kjHtwmhz8Fi$}TqZ<+!1^3*cTye#CBG&L>b0ot)g!J~{gv zT{~!Tp7nJo!lZY{0miUbV^N^o?5|dDtaOzJA>FtT=ZvjN=?rp_OM2k{ma#OGvCc7a zJsKK)xjg{zIW6D=v|c}EMEfg`$lGT5_0!@leNrT2`dy;+{Je&J2q;!)x^j;?mnDGQ z>iasAuCnJyz>WsG~s<_@6`>&sFMQT6w0`DVT=AtcJ` zm1_BneVZJE^*h)e-py7khQy!I^p|2VD(=ngM^${U=)iVm&p zH~k_9!5@3wAekePw`ZSuzRV3D4N}Zue5d%$noam^x8{(~zSBe5^97b4$0B3k zqyhy_)M*Sv{l8KT)gsjBv`qY);-XxjEF2H%7n>k-CA(j;nP*m`Y)rVbUmLNq$H`c$ zzwAYE+c1Nbcepx1J|OUWR`#~hm)>;-=uOWF1Kob2jP;h|w7iT$>Be@GBk0fLcDlU# zSpG?eT0Z)H#Q=Eu4`!K;bFsR_=Mq1d7b8CZ8UL-4?W#V=RaZYndfV+G^C$y@j3o)b zub(?zr~k8{RnZak;K?*xV1s(514F*^gQRm?RkX86>Lj1k-JBV2TPJdX5v}F$=i(R| zm%tCQBAV0;Ej*5NvY%#ylL0#dchJ3w$q~}m7m!c`ru*orclpU;v7TXr?8@`HwPQns zU%evRi(nNfhG@0j3)F`^)GPIl~{NoQQ=lRQV^hqLE&{vrdN^PqK37h^jqUHFb zUcFXb(|zL8?_g?Z&Kd+gnbU*x+etg<@%2nr>mQ&yc0E*tW363LV$KnpcU=+-%Mnd_ z#F=cuXF`%>-%6kNK=|2bP`*==WiC2ZyX7+ODkP@@BV`U!Ou|6%<;L^u_IpU-TgP)T$;hq`bfCWJV@~7 zS&3`_?02uyxhDZ?9sa$IA6|?z@16=LJ?H_>4qH;YRrP)Pps0Gh1-@=q>HL%1N4Q00 zn&wzmlwfE&WS4#z55D)Yr95`5(Is6bcFGLrJqZAtMQWn-bRHfF$qUK59H@XH;u6Kd zc1r?1A~wiCRa~fDwtb{3UnbVp-cg%F5~1$xmLfmT98IF~v^Z=Qa?`-OSP83CydkVH zjW-DiuWD$8hu?PK-m>1}D9=*vT1i@OYyJg{_J8_1J#{hxo1>jYrKq>n0wZVXHtj4l zS(zv;X_>l*Fyfq#h~UF@UFT}JMq7&QL1V0>x{9WLIa?WYW>KK~ai9%b&#nf31G87- z2_aU|epyJ?RJ}o3tNX^A&o<1IqX?R257EY{m2&|BJQIbMtSK(kdTR%FF%Kfa}(cZ@qb&z z58t}Y&|6PrI{Q_PkEcS^Jph?y&=ugUfFxAi%sTF-V~zjinn-(cPt60&@4x*s+u?mw zjA#}e4c5L;cz*csDt*F0?SdQOC7|6BV6>FRNj%%a(2a9j1d~wv^s1`{6T%TDv&yDN z>WRb7C$}Vay?@Vz5XNdK**-`$wxFOetyjp3(#E!?hOYvCR`-(RG@oOdx3hb@}}5mcl93 z^RGr68TvJ%=`z)?A7wt1sIQ7|#*>XO>p9YX%9frqyu4Y#B_f+uNi}uH>4O<&O}Uo@ z0Hd!V8Q`6SkKeh0fh0ZqU2Tz#5Ytq&19PU~j;USRJG0C-epGQdTJY(m6n*K_6 zIRR64y*^H*oHPyat!Aj-xGd8Z9J3T7#(Pmw4jPiarYmT|*ms37pLW}im^goY#c}ki zUb$tnT_~Rq60D$3XRfbH^3pHU2IIurd5#-hhG4+~sg)rxnQ8_SQSTZ@#&kdX%1FkB z`mQZFo7BEL4wO3@m_@D0i=%ihKjv0k_BFpezam;qQ}=#BYSfpEMR~?VRr0689fSCX z{E4q;tRl76%vXxwiEgsw_hX9_Ls8XD0aQ~!l;-S&3AafA_md~E$5z6Jdks&D-gX)F z#NA3@2Hi9p7_j5v;wXlHu9cT|ff&sRGER|D1bw7pG~49M#5hZZ=2=g;W`0rkaV7;2 z6`THMcNup$4HlPy^-25j?Dz#k4P?-|pmw&9Vr+E0S6!3le0q9xG9mh=kpc7MC5w;o z%lh~{b<1Q$U30D+2fkE|VU`S%chk#Fe>xAg#o36Ay~56IcIvL;XO)swW3B3Ro4iGY z>v{Q0zDCmnhI58_#_>cCsUJ{UT(XvZM`o)yU>({?3p^^VCh2&xWc|t?@7NV4oAyy7 zYw;@CB->73w#G@xwvp$PC1ksiuGW-6=E=!0sk>{6t8{QhGk4Zh%7?1faeEmWess&u zUDo`PxH+ERft8-SwCngfx0}6*^n%fm7zv-|f}^$U@ktq`K%M1Djb$s8yP=kOQ$I06Y6}5 z1=H=*3%%duO=gAgTxB#1E<0xqTXI^`kE&@9cYR<5_f_y(y3PtVI-A-fS_EBum5$A=Z9zYf1VZgQ&^!Xmy;M%HSh;3DPqSb?;#`qqmoE=-{<>R?zmEOA zTg~41T9|rST9%bEp8ZH*WpX+`OJLWv(2E-%Gh3`S{nM_mWaw!v>|6;Iy(MZKp?DFY z#B82?gQb~(NEAy@2c&L{s}90A!|luMoJPkC6@M(tJ|ZdUZeMN1xiOS9Eyk-fB|l)O zc4|3sg|tLi*bi4J?zm`L(BBh_46<8!JS6M(xwLNf3iH31`VMzC>`L!tEKvVpMHP8_j+G{KrYww zd_MPc?sK2}9ONL*?2D$yPHlRN<3o>AFR1yxf48XH%RH*nh{#S0lW8vG$nO=`Iz#E?{wsBYCfNDFhY){|XQbk2mYb9sOvuAN! zT@5@>qKg9g6nNglZy+)WsEA333%S$-my}*N28Crgm`y9ofu?tp)ZCQ0dP6OTZUp(l zJ=M1=rHd;dk55=hdsgjLh5H)ESbh%N*hiTQMhDHV>??!7O4Ys7D-=hK4Npc%df`^b`IRzUc(veDc;#y&uILjkg+kuo`uM+Q9%QG}D@Cc9IESUrQ|VSk zUB;qa%5s;#Tt+J&x3$E1d1eIszTwHx6>j2sy;;@8LGk3w$UQR&V#|(S2E&8 zeG@KyuV_6Z=T~EPMzPJtKI2o%?Icb2n0FR(@{-j7Nwz$pi%fJjwBECT%|Q4Du)~`P zk&`Y)76O9mPDGn&JH+37fT3OPa2M$WmH`H{ZLL4cY(D6Gzi^s=W0z7i0#d#`v6rJ; zQt~Ghu;726ZSLT)O@(yLnvG ztI=ZAIJ>Nf?du<3k{AD9R@*@D;;kc>&f_swXUmrI7F!YCe(3teijwG#+F5}N`*D4H z>DhoKW2WpE_8Uwo=ox<;&%+`)=YYzVNw8mS%ryNo7p+5dvVR1G$>&jj$J*lx+oHLd zvnTlBh-O86*^!D0uIZ7;MTHpcwm}6@=yc{PCQo^+#@!7n*Wx*CUON=Yb?C3aNvi{M zrzv=;24oJDI-8K-LMIc>=vz)^l0&fymEwS(R+ZafS(mH^%qSVh z4Lg7T)MK=3dZv>t$^;~})6Q?tsa%CPc$oTLJmF#9PD&H(yoiYO{gFlpu+&DiOssEu zI)l9sdq2|@znpdh>lRAfKx`DyO-Yght7MAaHgvKGX&L+%GfWO`e^=i+-xF@EGGvf<{3DlBTS7`pnD#Y|fu z^VlgibUJ%f`}4ImBiv*S3ELbzH7O<@UiMq%YbKakpGP5BZD;8%k1U>S6-vA_)Ib^* zee!W~)Y@L?&EUPDG!A|@P-c`26NhD_VU^IPjKfclmGVXlrRBKp+sf^;OvQ~Gq&jGv zJ}RNxGp~ZS=+W1mDtXyK-x_cxoh!9)c;fg_Z(++rg4Vm4oeE&a&2r+X!S1eM5Nz=L zjMzNywvOA4wwCcFH`lz+&aFD`8MB(PoPHM}erQ1%tfvj-lI8?AcLY>Xqp5Z1VgPTJ zUfdmIQUlqJfs@)TX-HRBYp06jy*amk<&r|oGv#Mg%G^{Pi(a%Q^&5$er1tGsWA5^o z8YtPNEpLY+(Vp~av!|pUr|_3ema?Y*0nHlKkyRQv;m)OEvO%toMrpgW8I9~z4ET4! z62a@)o+tdzE-X(vkR`=1GC&NVEN%fvtQ5L$7)k#Eu_fTB#W|`3qNe{Yjm#kq4|)c( zOe(%M+tCk+kZl@0A5 ztI%xv&BC@^1bxV*9?qo>UO_?oqKO$7qTwh}%h~bJ`S(ZT3k>F z$k+kaHeMejMYXSyDbdU9wWbu-PaSY~{)Z=#2d|YuadH~x{;IJt zjc$W^#a}E9e&=ZGj0zOQW=h=;_kTw%xVn#$@_ILr!2CQ2h}vj*IBL0X;!e>wgq5XU zrAOZrNZdgNip^8SsZM%?AQ21rgEvQym{ zYdlt-*yCa2xa=!$gL9>SNknQXOE?Nf$@uhHMply5flBzrnX^UD&QFlFk-QwzYO2YS zF_ipL$^iIk;i%(P2XEaObIb#zhHg9<(DU)`)%CJNvobyksi!E>V2s5HYZYoUfW>CWt!Xbd_)06!mV2*u%RoA=2>|817*3H zI+A0JN{D_?z14IOK}31@U}<@CG|`$biK8u4f8Mp5~(e?wLQ{HZOma6CxPQ0eon zOkD?5bB&^VNymuw4PTsme2l*Te&#NdUQq_@$<~lSF8N+rgWu2W2}bilFIB6i-6nyXjHJlfNvh)M#WTb`-Lnp>N6#cZKo;VQB)XELER|`-^KB8$Fiy z^N@&7oT>Cjmm0@M+r#$yW{$SwD#U0Sk*k=+^(5fKv!`LQ$z{lT+UZqipLc!C{$4>* ziEFzf0kX8u!fPY1zuCexwS@}tNOh~0w(58Ex6;?3B$8}LcDTo{e)^$p3~y5(O-Dp% zZxFRUVdYt{->uARRxbX?e?OAaE3Rs0>H8!BP-|-f_9@buqz9*$drK>kzLxJ9HNIBX zGOlpnpmlky^au&>-=R$advPugQ7t@?izDd;7 zg*Q$RH}2&X6%<9+bTSx{0H2pG2xt|=uH~>nFA?&(p)G4eGy&^AWN7SB=?5NZj{TRRll#%0V+$#&r)XEMsC0oo*x~KGw)*~;^(gGDC zG_fGl6%?+feBnBoOOCCP(Yb~gXOz~8cNd}1zBqkvX@k5mp%cKSWiK`EB{eSLJ*z7M z@F#jqX-aoPzI+w>JUKQD8j=s|u{ZWoaoO#8EInZvbOlD#CJfhLvu@-I)wsPYvpIXa zw$VX$jV`_e&d8c;;c6HEE1mh)Q0}3Q7>7BA5y*lReeB5E;3a$5vJM*HA_{OCyXedN z;y(zx<^;14zHDDw3L-vo9fm>@&4n2=z!QshNmx*XcV|HUkhtg)YhD8|Bzy zr3#`bey*aTgOyFc!T1*s?W^Xqh+dT;nj2{CmB%3BqUaP?dxl* z6?OLHIa^kJP6tCJ;8_%1xYRg3; zF5~2H#_K109MwO z_ZGtlYUjKJ(SK6(s)l4_@Fkat5TG(aaG@WW70xlc9vC zuG=D%4tISy?(i%&iuiU8!S)Ff!2~ZIAd~n{(QqW0qt4JAimuuGE-I#ma4x|0-CK=a zc{hOGYNZITES4))u)*z6@s^NHR7fqvz0JBre2f!XemBqGRFmtEwbIK_`FDLxeK6mo z9rnk@<##tKYX~7pv#wPws@e4x_K=Gf`wVs2;xy_U$~q%#yd3-}nOg{A13=1fw3&pk zAt#j-Fz#HI+*2-HmI7sI%mZmOm2SvS6skd&;4t9?A+6drf_%QQE)->31E|y zkAD5_(th9QF&Gstb-CiRYni3$(TT={>mkm)afOn_3{VPs(;|Q02D{*oAw~{Y+S%Z{jk3xUG)4E#5#>EW(OpI> z`-E|BHJ)LWrrQN27u6~GV=d6fSP0#yWet1Qv_!wQ*PF})ZVB#*&;aJO#91wty&3mp zf_c%ak#aX1KUVZ_x5{30pUwAAzGokQRQ)1cQ-pmu7e<`U7f-9iZ2zPL;gol9RjWO{ z#zrb<5xiQe`0c}=ma<1WSz@g7jPmd(6H85Nf9LxzaBiR2dxvoH1CLha>*H_VUJi|5 zA|g2>%bkLXlJ&m+-jycaiAjk?ZT0(lQMz_d^c!C`sjVY=uo>kjjtX%zP3PDV<;U6W z3qEi6l@XbZ&4XUT7+#vaRgFEe3lYbg$tKBr2R|jSFh5Y9t}1Zt&pm9A{R+A3iQr%c zxX4#2!{6&6pT+A79%N5=7<^Zk;yuN}B6D;zgCrB;fd%YG*t8R_tOP9XT>|aVxTb>3 zQlUA3-~u{*s<>WQ?RE4)o}R(DWB*fN17*k8o;vCSjdm6*D&#W~MmXXj1l@Mf6@9B> zwAFfjg^Jx*y|q%=ZYSL-93hRm`^sZbI^XeOT zGS?Eue(Rh6HLiN7dBO2{B?@ywKw0MIXzVXfJ=r;kG8=XBCAsY{%+0N1VqIC|pq!^p zZY76WV-$?<6WH!YySJqcC;D-YtwCuEGL_fsDnGAk7Q?vm$nE?J z>$Y}jZZ7;*W4|%KZ`KVa9n{VeSB3cEZccc`Y~OJ&mXt|WvdXWu2XvF3lappWVw4zd z9kRnsn_;!5)Vk`2nf ztgXL9HX6ac&ujQqsi^uNkTGhHxB6>PkxJW>zsGC-=?Xha%a%ha{QTr#O$Ja*iUA?t18C^LbKZXJ+r%>FJ*XHg&HQlgoXfyy9Ij2_g%}pce+|W z{Bwjjj3ZPbu$R2$%QnpEjCz z!>f^EnUA1FiA1y@T|lfq%=p{;%FptK4yEL{BADpCaakX0JNO6V=cUL8?^JF1K7wXK zw?WhU{NBRNdehQ|QKKiGO3I@d4^SVc+1xYW_STnNqUY)EkKyDa6MN*EA`*6JZrh?# zPx-9K6nOFS7jkg2xE%h;niQ(%_`+Hy`1#_sh*irJ3XK<;>Zx@@NErlm?O92%Sc1Yw z9$U+6=i)aL*1EC}Qgg5`L%MIGb`p-ibLu-|(@CDi==7x2J6$xAv2t=Upy{wV5Y@Gc zAPCw0+@VHA+oR#pY0QQ#kCUW)#%U?%NvM+1;ww7n*ZV)aany5eBBu|>$AEw;b9JxM zn99)otG*`$ou3Uuzgpit65XuCv~9(CIZL-Yt#%GYI=*J^1KHSl0Nf zmcE&1np^o#hO`C%#=Urx!5BAqVmVh3|K34qe>sA{IXb=G=&vmGw#B1BJB?^qF?sfc z%;q~`b=Ck!0xc#~Y)seWH-F^KJ_zshI-{GT{;(32IjOl+?$A|(Jb*|Xw`!Aii!c9- zosi1DMc8H%e~9xQh^7dZeccNUjToq`bIa1Lt*q9atjkMRbl+vHvyKc%lB@>yc9a`4 zI>4xFb6So*JA&dFZu;p)F1_RAo|DY}464;OcTmaI1&^2Lf{HXWHp*fo3+W zy#hN>AP3c%vDAj6wF3;71}_dRB!i9~#jb*`y6DWqjp^UlwCSo9$bBi26&hFPxyTyK zXU-4xc5)T_FN1RzfIaGAFKM4OJx`|2P~xqi|q;_SJ9Y z8MNevzaE6@5$(Utm)|SrR(+GpsK8nWmVF_AIz44O^0p_hMGqIJHKP^-d4J6BB3F4| z_NZxX6Rhw-Ft>Y^l#q3OcRfYY98ScPVSl|zW#suU!VQnZDb_7(igrN?O}eK#^!MSb zccuH{Y~}H6Q<_9B(4yK(YE9-Ildl^8rure6FqBBcCm8G)H?F)?Ns~Nxf&Tr306bV}%8vJ=A=E+p;{1}W9Tn26oBvu* zSG&FaTG*hBqr%FnX{l1f!^dr@lMzuiAd5FTnWGbE@aHw!B);6tH`KcQjjj{8Zlz5T&v}Df5DX+ z2Tp9I6Bp6?nGtlQ9$w{f;?__<=60?zkYcH!nUNdhD6ThpE%l?g9_#1wWo1Q9ta3=>b!Ip-OQtSm1?# zqzh7ED&XVfLR3UWh1j^Yoc#s`^T4BlA&%l{bFzx@1Q}67e8Ap6fpBcObq$q9j}^mh ztC_+Exx(-%-`tWCS4$Zwp5uP$0vLd`R9n#@?^6ABDub&ruOf;HOQ&YO2OC&=`tl$0`3 z(w*T>Ia2-m`M9xDXnHEGJDVN3BQ1&8SYfsNCbY$r*T`MJq>)ne zBUtPK3n2!QM~9&3zFsvajRypo=K?_{S%JPc+wPSvHqH3a=1#nGawK$y>i%m_Rb_2l zb;22q$CI6T31YH+wGBI-`$Kx{}8zPKqqh z7e0Uw9ISpVEgR$f3%4E5F|peYvLe|!>04JH$obp?-;^rR-TBv4|ilgI`YqH*0rr{l<$ z&e?TDOcS6?%vQrMj|aH&uLR$|kApplX$fw0I}=4cZxFVag^3v>E&OB?n&X^ao~EgB zIHv1%3b1!9g(cy4xxPRSBkFmjg+m0xr#vH$IBoCPumQ|%7ndQ>6tI#OSU{B~YT|*b?8AwN1r61FT zZCIYd@YIqO2Z~w?KWe)5k#o#%=7gKU5L}hw(6VGuopNYU4V6k$he+`o^^FE#2zdpb z3fC?v_LD7>0|G#XqQ}|0mVzOa>2RHSv0|p*kau|F7L)s2+?RWwdYuNJdJmqs+EfW!o13Fv&LA@ z_UJQUI#cZ!10xW|#B2xdtIFDbrOj7PI!DBDt ztBT5{!}OT=e>)F$u6Zs*lqYm{I&0j2NS76Nr1cw0GM14F_;JuSDCPx)(x~L;P^Xyn ztPy*LC}-yQDa5Dp;Adrh*$ZY%Idmm%N>vY=`BQTQ;t|(`U9-g_+_^vm_7X`en;kE3 zZQagCbF1zI9lE&zj-{?oKfzwvTok*%LlZ$yspfFod-@O%qo2?KN`dFNDmL{G!mxh4 zjY6jjb12&WVgeU{F~|ieIVaUsbru5tl-594XWAh?rDzi`W&x%(jm}-p0w*6;B7N`KyL%jqEKs7Xh|wv+Vjh}iHTNi z=?s7)nbUeC7Ocjt9MfEfq~R8hPF53?VyM$fZSoJ7FbRZSn^K}9BK@RH*>_S!dOzWn zbes*unOxMk3BTq7(0}*-Q6={=+WPV^{X(87gYEWxulC8DeHUx#vS%Z)C;Ba&`DsGA zBHigOXTC(lFmmVPRC-XpnR%8PYkOW=>T$O~w(Cm`$v2UUPEFp!pvQ)}@!AgN@UdX` z3B}X{$#9ac*^>F)=l)i`J--HOMs<7s23!cZ$JNgJVf)MtC;BvIB7gVr#FJ|Ck8qhI zacXxL;R@iPm3ATfsSK^0PE>HIh%dTm!t&0`F>vkyTmIkTMmJI&IZoIAL$_ys#gIYR zTarBj_G$f@6EH6W-RRUIyR3{;E@Bv2F(N@L1=Sx;-jU_GECd{h&FwrmdN1x1hkcQ? zgD6|_kV8#eZTEwSenueZ{wv(i^WBlGw=5n?mmCJA>fnw|95QA~Zq+4;jsMLzPq&ke zaz4?|E-dA$9XFqr`L@3DzOm7VQz1zUv=(gX3UPE0JG3fGcG@M-j(ZxEPSVzK260(Z zzjqV!R!&-L#Ol(!%?BPZgkClavL*gqk!`vilYM|@l|RF+{2Ompz8 z;2`;)*tJu)aL+_}t;bFDmD=_8WF%`LN1Wm9=mq2`+hyXPjD&_%d{>&~y`|-vxV5A} z8BgCebEvmomZ*boGxYoAv!Tz^u(ujwNqJ!t(Q!)g(`=#C?{+WOHS_bwlavmfXRJJY zI0t088&a$w$J6>O>VZ9sy|t_Ija)JRPg*X=1Vz)n>e*Fqc`{`pksJ&PKWKx z#i)){bNX8^EMq2BH#hqjYIWB7db_!pu0S4j#wYg5M1L^Ya_|!x#_Rj!rqz#Ie(hgO zY3^DH1|~+?duspnq+2J|Zv=V#O*6H`%#J|5=uP+ISohZ`z$tiJLlNIar9LI@&3I<^fNc)90jf^u=98>;#*#VQAP@ z=diwTLh6Vpvf*WxM%C>gk*vA&pvZ`(KPa?N0ji-larwQH@*zu$(Z(*Oulz@TI^L_; zH{Yr1d5F+U1+F2cMM1|JFaxvqjy>3z@wimCK+$zWgg}3uY*TF&vmIh$UYjDpcNYcO zRr6%}8GAVOJ*wcKq3~}~XI*8^{BDD}QQvxbm8Yqp-uN~Luj9h4TvUtyMBn5@AZ+LX zbQ-6+UbvfZgaK$KGe?rd0gO1e))z$JH zJlXT`V}{46fTN_PJINRsJ$m{5OCzL=n177Zg22UD<*Ut}QUTB6Lafm-Ty*iya%sD4 zGv-s9Oj4WD%QkHy>F(?B_3kid z+bgOdBS+IS)CeVhH}e~3k1n#xAb~bd*n=@`5V331`-Ra9B^|qZT}$Em{RzdXU>M#i z9XsIgw5r0_4?fRqY9&?VdP3XFA+E6dWBxIxHYM5P?>QFUHVJRE#243-o67P_8q6%h z10=p*Eb>@+&KppuHh&G!mWZuQv#EN03`K)q* zi-d-CHTm|CDQ1oFaq>6cle51Mgz&U)670>2 z^=9mMf_%c40x^n1UL|kqEKC%=C5ydJzwUv&c@_mk(=X6xO?W<+7c(@Ii_W7Amp4n@ z;vvM)u0bL(&yywdN#Lt2Vc$aMd=%pJi-g9c3qo47@h|XyM;BDY7zGBzPMAuE_q^TU@+*J?V+yH^!)Kd_lAr&gwr9Dp|5M*y7Et@Yw=BkO*ei}SxjjY;`l0X zrWD0w%Xx}rx~uE-;_ZBA6JTO?e^;rTr|LDsmpKd&gz9;HS2r5kI7)ycu`TfX79T7U zMAFtd+qm41irt%p7{!fUbS2i< z^hTDkjCcR12<`xtu&{j4Iyckhl;(07!UrDt>Iz5ASE1P9Ki(4de9XdwHmd|=3uz*9 zC5O#bCNvN+{P4GKePPyie&OGgsi5%G-ck=~a%tJ>H8u04$9Xv~Gi6kWmG}F>!}L4_ zOd=n71Y5^?WgbLY$?43G&op%10;&{x)p`B3?vr?2vMVRL*p#d%QZ^*=8@Cx)`aVaj zbzLdRv4^U7?n^4DpDuI4=iKh9lZwOvh?dZ}>YnH)hMFs$ozkrY>8DS6gBR zgZay%{V~XBw_NTT)~39S65=pDBE4LipCjh955Cz%#{~B^f-EKO81w1{AP=q|xQ2-E zRPP>g2J3GR@7wy81i!r1&e_Q*6G-(_(Qv_M)c2dbFm>AHT9*ucH#=8+`HOxt;xj4_(b5wbVx)T&GlU^B6<5+|ss|QVf0A+Sb{a~YN znTKkr&w{F0a5`F;+dBiO+d-X+C06q5I8`8%+p5mbeaj*4Qz#|JmC)iW0c{g1dDb#x z>=R>a$6!XqZ2;@{_D!etf3Kymuku}17{xJa?XIZgI>lKQW%Go?J!Y9;d(Zi$aj^Zy z>F8S0sF&AqV)il+?l)58iOte~QP@6P?pTGL!n9wGyui742}sE}xM;;mJ;j_;HtWC; zcn)YrjYbZoTh3EBdk6H8tc1uoJOxpnKh5S1L$7_eo-p{8eaxoe%mgLT(L{4<1$Y6z zURjVAXVA%MPCH5rR&fh%r@vV8>{c}>L8p)I(=97rZ}_I+>--?CxrVG|qN%PO&;As) zc^x3t(!r~PN@!)?(ViM+rr`g*La4tPGizF7Pjlh*Uw9?M+x9QK>_!8i%IIS-&TGzh zd3!D4su;c(*bbIM)>nQw>=?(Do0#EcWy3>c#q7iHy0_l7FyBp%jB4>K3{8$*3?n>R ze%q@n^Uvgm(ZAv8&r0E4y8W2@_Hw#^MZL~YuPziKq*GWP{m-A8)6COS;2~f4VBd*&UT1ow_=!{9 z0`#ry&X{L&hxEIxduh^IFVQsobvDPI^+XP=>Yc*kH8^%P7<;?l%x>p>&da;XfKIfwumwwDq-xc4Wzg?}5NWewu zx{tsrsU|i3HuLug>)KxgrSzzrOfkPc6AKHPB6cDrv`kC6gk3`T4xPi_9ue9jb0C{R zqk>IyyQY`xeoIKP@%s+#SUtMPAAjI1@DOP_bu0?b5$(i4|Vi(p!&G<3_lCM zM?RZf>OHShr|)t01FrUBCuck#O-vLQUSUie?(qy?{*L-S65a8J-ARcF&tUn4nUqCd z{<}UdJ9w6y`lnAiShj4&xv>{`HEtA)_gPGk4i^jjKsFZ?UQ2Z`@*ocb-^5tW%cMm9 zu;AvtQ{Jd4`cr{tT_!WPb==&1Y(gqMiN16(_IcvBj%kcP2u#CcMii@?#1+|v2qw31 zjVs>#$nC`e{(iN_u5!;Jz<`CN)-YVL=ke&azY|05=27<8jH)MOBdE8jd3O)x2~1Lw z(L!=cf>>e!VmtLzyAjxBjPJ1}r$<33km=&TQc?Z!^_wV7y1u-b(m%u?H;0 zcb{PypMh4|KR(_$FVQN5SH%%c@(9^OWbv9ukRf< z=hFjzeo^3ls*Ai|Y7A{-lexszjtm(}KGx2y5Q#yZ>Or~X?SFlSUE=u`8a{#vadsY6 zlv^tEJUFsIdaomco3jJthmdRKhXyoGK-p09h%zGodH`%r)&vR`)$076YxP3%XRnavz1sl>J`8;I#s{kH<= zbF3y<8`3%~>>}+w-aeEykM)~+S55=nKjyS_X)R5B*TwN67kPv(3L=p#HD=}-lH3wK z?7&9&SjTMzAl2M}DZGe%E&304KPUH0V5gcPYu*GK*$Q{}?{rrF&pTiBRf?WYh#?=G zxubIWGFVxV7>pPFUGnGRch}W#KXdd6+@n`AF?SG~KC5K;Ag{*>+0>=wyJ#SmBp*mv zR8xzVcTy6CTfd3Rgh~qU8*qK`ZHZ4~^T3hRHR1W_7?QTJwjujBuTJK;I9{z#kcI`Y zTb_?2RQkKou-Uj4GH+9lsAxtIxa_){b&*pBPiAjZectKw@NVR$Js5x})rH^p zc$IH)STrRM0dn8ddSKI3*a*mnR<}+GEYqrg`0746AOvqhLJvn!|usKh}9{Cq2h~W=NgMq$V>c$QLaKeG;BjHsevA zX<=zsD*TCYOfaEgxEG}}%@Qp{xJfY%%$-O_ zt-QwRPnp`47L;b4e~yKE_XaL?pgwTk$em7b7XQ#j;mjlPFj|#YCqZo3l_5b|eUxc= z$n25cSr8JHN4Tv0AIFo&t1@s1pD!}%8REXA(ZIXRxt;^c-PbG zZPTAiwLi0GJc>&8VuJkyr9s-Z++whrmw@)&BGxGpr@%Q=+Yu$(#UC+iVyf*@-$Rza6e*-tDSSt z+9?ytcZIy%r4IPxrik46j)E1Jy(p`9b9kt0er?b<=BA<*@7~FU#gMzwGBhmLZ12~; zN^xuKJ;n_3CCVxEyEpWoI%5IfS2(rtsv#OFw-s_FdsBoHVtz+{P*OHy_D3d@^7qRh zxSbt^;>P-V+R!wBc$bFvEA#V)79qT!v+yYpt)Pz%j-&=_#|T~ zBZZ<~c|v78Vv90~;OU_SY8X8Q)mQ3Vh$d-$4>WR$u91;kZ;gHSlU`LF+Ms@FSQqoK z;otG^?XNga1CUw6X#epc<>8w@hUuRxZS>S(t2sA#RJ)*XVWys=oG-FbErE5|8KyJigw)j_ zW*2_IFBSv_F*DmXFeQ%@qB{u@hPG8d@|wy`f&oQPEZf7&T!t*w4VB~AVXM*qz2Xt?;i#VBej=jadd-h`=ElI{KJQLBkx}!x z65yPmfpcPRHSv(7ZhFJXv6bR=>tg!MXQXCX!6e}jmGwEZC7|EXBU1jxLMnzk_sbBs z@8e%CaY$>Q1?834HOV30Bvc7N%#jSZ)teJOh< z9n4)H)_w6YU?dMeGoJO_!*WrQhlt>7-qsJIhItFnG8FHKc83ywA^5r50wptZVMGbM)3R^=}H|_)jyh-?( z3XhPcaJaEP4dxeh*~{mH9X~qumO>-)L^X>Z03mOt=M{`V0Rj&=*BhR~i^7eu#m|Al zr}zI1D4ETs?ch^&a(dq{Lq66#uS&hyiV3{L&FrV^RM#i(gt41f$};Hs2SOMBy<-JX zc=o!Qx^G@m)g5-c6-cfaOsM~UG z51-NaF6zuG%X;6DAu{_;PtWi4Q2?Rj^7Eq|B;?L~@NYgqp6d1*Y#sS2l%yA-JY#gC z#h$|g6?SgT{iNMx_IZD2#xQ1EwcpgGV47&)T5o6

9aUv+KI3VbMupx+W#>+VZUN+%RE@+nvo7kM8S&NA_IO5$ce9i zyaIed!&iAG5`xtD^&FHu-ZfcHINZrAVO&a$?CY0a?b$!Pr`+&TMauH6 z7=egrG3i(H%Pp)fNO-^AiI)?)Gt}VCQnXx|0#~;{~;1?O| z5#;K|gG5;jc;qFyX5zFTjjsm|OPToiVdvHmis2s`o4(Gy zqM1F@^vume0?)OmNXqeL*A3gY*cC9hck+I2DS)}Tac~cWLtx>`)F~=)!d*#5LzTVf zsjYs}a);8BulngqYF^7anja1F^NglSk5lR)0iq((B^6_JsjIy$y~)%JIp2Bdc-QFy zrS4B4<~HskQh!rUL==Mvijg-BjZN8;6gUH;WcCDx-_?@EF6LnphSSHf!R8|h_e$CE zSF?W2t0qMV{saHImN2a4$P%m7rovj!uB{-WZ!IZFDq7Vtd)MO-HKjNL^&uZKkzm(C@XFy$>6 zt(=DFhs}9@de-#!N8wGwT69c{O4Zouoe=fX#Tk7ea9wU9YTC#T(MWS;JUwp;K6b@B@YWPK&E^z z+VyDcHw^@GEZA`~ld5HPrlArp2_LCK!58SLI%%IoK#(5^f?RTVv1vf+hw!^EgX*DP z;f&^dd+d7a`-xaLGOMP8p>IXuq+Y>dpC8}&0UVw;|TI}LX3n4gt`9h<*+JbIr( zun_43e0-BAFsuWaQHVg&_9_y-!&zb{dTE#Bb&FO3fsY)jocfB3cmxe{FKP*?*K`l7 zdcF%~+z+9zXc&Uc+N?#%#4>BC(Z_%(H%su%Jay4=CzWBjz>(R`ZyYsM+0Fk9I5c)# zMViXKo!#wNjxaeS@*`cQ)Y~RsZzTYx`g*4s5}jtKFhg?|Urj+I<4YeIg(|)!1sYx& zz*Ik*F@1aU@`N32`1qJb&TlIS|J7ezKIQj|8_$? z`mi7}eBu%Bvi*91l9cY6Zm$f!Se`(MXAi-}bv1PWeaLfd5A2u$xrB1~VH}KT-hVs| zMlU~F4X>o@XYY4J`bbtghB3h+)#z&8u(Qs*I1|QM;>zk>34s#|#9`mNMBe>frKay! zj#I`smGqiNCLoX@*F*~G|a*mK5+W$p0poq;248c|#Aw1>& zOhx0z?^`}e^iGXSX=4JpwX}0{8=*rf9z>&QDeS=KZ5BV%eJ4uZ^TcddW}QP8jwFCP z9Or_voJrs-;lB|2$c#TXr;M}=8XnO3N5Sm6d;8{mZ{75V;2wCa<*T_-TZb%sw0!#G zsOLzzSjw-u|5`G!rPcSWSo!#~oinq509_KJ_nq!TC${gz>1;qkXl0$S+2z=*tINHL z!b$i`f7@rI6U=tK`vAfRM2u)#S=xIX&!}$M_*(i_WF5&S|2#3*(ckaz8U`}~86z~; z;)~Wsi&KfZwL`asswO}Fc7)rr{Bhu>`B9tcgM7opyT`rfrI}+jvvE*=nK8vK4!k*hPgZx=;KE^!KeO zjCqwa59}$Y4~@rWocJz<6B&F~0f&ZWwb#LrV}*a-?-FVpH2nGKF=*V|M8by6#8G9j z8()~5YKCRSIHx*1U#9zPjrVg)2I;J+=VghirdtDWbLygVVAR^HhVk+Bw)2Z8gcAEj zpxu1V|3|l8Ze z3(3A){C01IODKA=VLMn27PifQpk^>&SSE*%!fQ-tcTztB8atx4x~2y2-3>B1V)*Hl z);}h7EusxLn|1#I6(j%VMkhY4Kn-9#hPPl)4lp8cQJI_n?8U?}7lTnuw-c6-?~ik4 z6}?3_%z1$c?{S>w&SxrA_4Yvd$GBov;jqf;iV&SJgn~wFRZb#2z5m-wevesDd+a1* zAv4)y;Q8qVOujY~=m@3vb9Yna^l#*)#J%){!qS%#76ZeT9$&s=dw&qIC3f=|y=2e{ zV5F==3lEtc>>i;K@?Q8x~x! zKDiP+BX11d()?V#xTLPh%|&YU2YtU1=PV@V^jHMv<}N@NAZ10zaI%=Y5t29l>$H)u zkvS3sC1?X&bH)FE*}~Jw@J0tWk~T88u&T&=;B)EQI*A-ndwMlQt=qZK^Ag#cDi0hR z1_Luf%} z;CG*?kVM)vaP;LNw$=dfQsp1KL`t4lD*Zb`N%)F`R~hb~lm8EE?;Y0E*7b{mAfPl+ z5P?t>YzV0IE=U*YolsP22%$r$il87RGzFyvq!SJy2M0fo1Q<{oH@Ow^vJP^3;mKB&!VMJ|tZ5S`u2ift62 z=7Yh&`8~y9OASp+jqBH8qGEb|K- z?g&>gY&liQu}W{E5WMju_hp%?Y_B6ZlW{Px5~eJ>^!d4VDtu=UnX!y%GuiMVA?>g(#f_>=pT4Q_~Il~zeM-|jx^F7Yq z9Ii8l`NkN$aw1qesF_ZrXA!yjRPM-;Lf(*-kDJei&nEd-^X=1Kw~nh+cYMb4`p~VZ zNw0>)v}I?mqc3jOPIa9RxZLFfu|dHsixgJ~=1HJ(`vFy}p=ppJa2i@fK~d8SJAuZy zWY_BIj~YmR8^C`VzY_RslT`aPdoM986K}d#88do+);7E9D=k3N#SHXBP*Pq&7LB9( z_l-1)@aEE;9w=FQWxTU+hD_7+1NQSla^*qEE5{#DCG3}U3=CW0*%?iyE2aT0le8~) znc1?=oTph&a_qCgfXDp4{mywn#;>Esd0LZJC1RF-C9!Q1=^JMrS^+r^r@!Ys`rATs z$*Im&A+m7Jb@s!@s4OZx{(f&rpLq_}$^PsbWj} z(lRi#=knTFse6OT=1ogdz0}t;cb^2ev&dRozHT=pd=PAUQX3jotvZeyPyaM*qUo678=0zv1*G$!1vt}BG5 zE!N&6wgxZCun|K+MZiymmoHICE9JofVHd7VEnaE75P z)d-!Ji8lm0E`A86OHddE`adrUhi;bmO!fAI3nc<-lZab4+Pk1eRhF+H5+H|cb^Q)(9=-6XjzJG9vjD0Et2Ht2uyJcVc%8Ym zMb(~;!82{ZLrIB1rQzOrcI?WHQrkb(;A5Hdrurv_HL(Ya*CdUci|obj%S&P5IccLI z=l;|J;a^&CnA`VT3nr6_=sZ*$OLOdk_=Mcy`kU%_4H#Pa+O2AR>4=6#> ziu6Q0pakWE-MW@N9m`iNbbcv8XWaiCKV3Y)YxH-aPPY^iJmh4>B?YM&X|F&~sM|sq z7x?9_HY#d~x=^B9yN?Y1&;_32Po2AoEz!y^a6Nd0H3k=bykyYRrw!TM;90of8$u(S z_|!wO_*erbJYJ!dJPBPYjJ7P|2@*r4%F9+rmI`U5;CyQo^3)NbY3vbE7 z&fKUOGwCg@_wLO+a~AcWSqjbg_0(A;a95of>Zh@=Rnv43kab> zDKL@n2-n^X9L5&hN=Z9Hdo~|l&j}@vHMM=`se`dgJNZkiLvHg#B9T-y^N}~G$`BOf zB^1GAZeMsS|2}>H^F39;if6tHdusMZeib1*u+m+H6a36oii55sp2(T+jpp%*V{%9e z+n3z;MyJ5kvQSHr9ItKTM+U_v>E=oV<1-JEf`?+}iDQOQ36A_7>SPHD6v?-E+SLiG zjd1}lFphFmV6c)MVyoL?`d(R|+uEYgw_%JJf_g1Y(&4IVJ_Iw21I}xR<(1U>kFo*f z8%<78dRgr?cJ^~}IYhogRM!HqRQ*dr29*l;NIsd>kX6lI=2582QkWiAZ{!OIXgHYm z<%yAvQ~UW=x;a$^p9BkajEXigGV#aOo*HSB4sZslO5GYDiF*Bck^K_a(QExE6;qg( zxXg9>lyRDn$dL4R`0dzY1cKi2C|KDT$jJO32*#pP9En{$&vEw4u8O8twd(iVx9#7F z?N;VcyM*>^f9ub1S1gv+C3(a?bnJ=}iz$~*w}W$0!?IpZ?5eKFT46BmSNfxnE=|Pt zvu~XK(hhWD%}6G<_|Mk*KUlX(6rtoBjt>tVmP7ujWB*5=XwI#MtxUXT z7M*nH)RH+9sVf|H3oOzC^ z)t}m>;;dm`1ec50=iXM6ljrs|%LNC|wLW8c_$sBR?#e8#=adPxN&xZ z8J`ft-52yrwp1a)cS50Ub^@u$D|A7s-u zzffu+83tNMb!%^SHwu^2V@2|g0i$sGm2~)jm(VN2DHQ6f4T|=koj4S#O~!54V0{T$ zx*gp0oDIX_RFdCH<`ir>kuT4oUBetO^vA%^ljm~t6Y}yL=R$70|Bs=Y==B3bXM%VNtyI~mI0~GkhW-}ydPE{F*YyT}* z4hGRFNxeC%Xm&NND!u6|i!_d$hGP`XZVWOTb4|9ysw;|&2Sd0!IaEnSc3InbCFa8Z z1<{xd+cR1EJ@Ijea@$DW=|b}a<3Grjy$f6k`Olb58Z^8MYbN>cIKh_+d@K~=f@Onk zfU{I z2l=kvSbdAtI~WFMvlE4Jj)s%Gu!N|F@Ad-aUiqbY%=;DJe~{JOyg9EJN|07s@A{6RwT~RClCJChGIuA- z7LRFFWTW$p@SLfO4?_wvs0_n$et$8g|AZ>uXEWEn(a2QX#8sTu0nAg2AC72^6XENz zu|;^QF849GMTz2rK;l!F-fXYvAv}AO?&pyj4&$YXm1oZPKn9P@X()sMghpQ^&+W=` z^)!BfOXq)*m^udndfF@JeOI?oS4qz&F!!BQuR;{dnMXdCBBGt+(T;)~V^Zy|d}eti z%iY+9To`wbSXPw26Kn0*GC$Jsc9!!!x7Q1{qIP4FyuJx}BfZL#|MJFXOZA=P9^@4S z%IH~FlSlvd5pPIF!n$50kh0>v-WyDns{&{4=yxO}XXM z@t2EQA0N7YECz~Z@^g~PmOv<|CWzWI7&<(CNYeZ0n#eA`Vz zzy}w-)>Tlx(wAiHn3c^ws%Z7p1`hD%N!2z{Uz_hRw+PHh2+&>MtXYqR5;j-|NW4&i z+=`B=@se7X=!Z8Ti=20YC3hqx{Vq88Yqyk_M45t}vr*-cj_H9F)SWfn82>bfwt#6x zIB3=bBLFw@N*QN~LGepNf4nEu*gC_)hR=PlO`{m$9Q%3Gj@787_mdnLTg@0gDgQ?n_B2mZk>zrFP))gvyHix0Wd$gm*w_(#!x6M zYODi5J!)9NB*>!rT3+MOcJ2N5D)crE?_OM!TMFzzm&B1gHAwo<4%~BYzRT}hJDvD> zn1l^@{5XQsH#ov&n(M!?|2r}PNoh9Po7$2*BY;ImI77{tm!5KC^_OoE*Q?vPB6`&f$(iZ zL7eZU+GQE9hQ4Nh|7bd9ie-6^^Jl8j8b`X=;;y>V@=9UKCRP61^2gQG>T~091B{?c zA!q9}63u=E*MI~Dq_jzGxKE!R5}Om z33+Q9@NDozzs9OiG@@FEGxMQ+Au&t7lhq} zb$>kp*!sv-td^i4$C0Mu@QP|NQI9XyVur&#(GP#jiWCV!(_3N`73mI=an`WPQT_=| z%RqK>f3pl7BTeVL)g0SscW8>${9yU8Cr^`@ccV83286bk4YGE5yVR)yCH6DQzZb-o=wlvnNWbKGiLmb*!4Oc z@cyMzR@&FLK$m<-I_`dH{2b!OLyG%v+bJ^ucm|hi|5}LtcDYabxLhJpy4QLPH=IZY zE8S+KxLyjN>5l>A*le|BezpNvMR15dRWu1oZyxJQ9?dH4F0FO}IZe^c|u8y=@Z*&A0% zH{uuzoAn3jnFBpv(t5VYCDY55+=A7wJPAok;de5%38DGG26D%U6$7yWc@voo6X%=1 z1}&*0YPcou_sv#M6}Qx|K@SD2Q8t8*Lznc{&X`JWRPIGSVYwXvVnHAkf4n(N-{n~< zhoK;X1!`WY8d_#@a#&*(fgytrDLb?3g4Av83)2$j?%wtU!N09ZvNFiz>?g6!Z#hpPg`wF-&81o)^`vKsSPu_q|S) zw??!KkEW+)XWhn96e)eU0G>v}kK^A*9JJck_e@`J7QZlClK{_7ByYQq9F4b&nE_mp z|0&X_Rmk$nzZk~Y0?X^gN;nsg52b$c=L}N_V>{At3K`( znnlHjk%YR}!-(mG$camKfo2O_nkgf1`ze<|?ya`v=G{J87+S6&Q7?eS{VSM-IiZoW ztD4Zsz6iRYWHGm!+5NYL;J=>04O#>owi{HTlW&$RG;7LQ$s-S_#&-F4&_*eLdNj@! z=ccOIrl_b37+L76T_v4Mc}O5BtZH#sEy^f$OA?148dez@(qZ1tKqKZ_h(O=tub2A2 z5w)N!(hFnfw=U1#TZ&8fW>}~6gPm4Z4lP|h6&R^O)*&9V9_m+n+i3scbXRXL+1N&! zPJ-G$MTeh}yr9^p$64^7Z|C=CNgX<)3mTN$!lpS8o3Vp%v0h$E0Q^Aaf~qBKP&|oK zb3NNm8e6J1X-ecX{3(-V(_bHtX0!^j}JGeR*12E zwiRUCyE?wJR7U?1M&>PJPAJhbDh-qzUl;AodwDc3fmF3@pAn58)17c%hH>X%R3c?= zBvlN7Z<)20-#Eg_B<)THI@EQ|Ke~4OZ*TSQo6uL=DzbM&e8&a!MazEGP*PNBcy`ZH z+K-%GawOuBUE)SX{CnPCV}#Xoh|)J?f41{laB~DACD&&quaSZPs%o85->?%uETE}&@M#`Ql(C(uen)si{(FAMLk<@~ z+H6c;_@{PT9M&IdcS$m-b%tFnV5$13AD-CyPUSmbjZ}4n((lG^4?~Z>UKZlu`-6<7 zI;idexqcN}SL9zSUpcfCpZ%!WwbYl-p$Q85S(X%K<0zTSC5;RK~m?G!FF{HtCYlx_M!= z?*|(Vv9>LiZDU9DVn}D%X#u36kg#E*b+2n%P0<`em#F*Zc$7+PqL=L^oB^~I_@Ryd`GTo6J?^@cK;DgXQh-hKPkdJLBJufc<7J zcCrCgtZObHX9$o*umwFZom$jyNucZF%!yM{69~~E4>1#O5~m&9f~K$s<&uzC;`18I z>gU(LF#uph#Hvfy@$J(gp zuVl<$S4B;D)!+&X$peAI0RNi{WBczNQRDTP;x%3#Q4`c$wt17c`# z)cBzIv%vDK{RjE}Q1m+;gTYG+%%8sud`Qrkk2h88rUmSpGIKvp@ zX^vaEF!C}%WA+SGflEf|p7jgfpvnS87LI;=*{=Q%-Ni_Rn)1jP_fy5|Ies zh$@$?oGS1NX^(l^0BDpS%M81*0aOE@mXLXnk+IlK|5ChA>WRF5*vaGZ%Kpd0?cA># zMFbn+j5vOCM&locwzG$ot=Ep!o`-<-(7Dw{&Ynin>Z^sEcSpRM6Lw?FOtxICI}f)jvx6SpO0j(ZpG{~N#8cr;OKGViH?y~ymhtzamkzYHKp}D zPK|8LVTpH7trBxT%yy@8P%6RJr2}{qRNG`8dW8Ws$I0t+r3*iWD1Pq5dpu4wRp82K zG2<*#S$l&%crZI~+*{XxcXf%WxH325y6Lc1Rx|$kj_-c8+d0lgZlX& zWUn1cS8Ln7E$w|by#vyY4!66CM>_tDYy8}C;)(Hl(ZhQr5MP5_tDn^@aX0a9(o%TA zZ>G51y2+A}0Ov!QN^h~V^fK_pg2KeI_A8s7X$mxA2mL-XnfpIK7Y`D&QD~x`hVpUe z9S*8*_n}s8mn-|OwtgeVY%o5(RqKpVhOe-Gf_+FwLM`po^867GyQEVyUYBE^i_mo) zUS{2Jmzk7sZx0cua?hGY;aMNFQ`l-y_|gz10(;~$>3T8lPSvFP2f}E1_=2xB4 z35B`PW<;OsIneC=YCoHl#A4Wl=)QP%Ti9^I$y%D$5kRKxuR~>}-|(BkEEH;v%+GO9 zhl=-looY_yz!J4ZdYQKE=}zUdWy@-5dF3rm{l#Ro@=A~sN)DC!gc7eZeO;XL7-Tl0 z+SwVXZgVLxC4E@wTA5$o^g$va*8+{aVx|#a^Y<2GZ2F>PKenZfBWHw?Qe-L<1`8Je z5V^NQS}ZO^TSSYXTX*{z8h$v`7j49GZ$+@KPO!+VA-iIfRWcBF)6=)WW?X*yI{Ibh zv9(DjQ)1Rbi$mWU;{H_UONPO>$r$B>=TAa)GFE`c<9XX3g)K4d#$%ql`7NJwYeI2hY zAHUuVle#~QSL3aBDW!D1_cmIRj;XbFa#9Qb>!{A(M9~#5Q74~{>Gf%xToHVCA-Yq~ z=oSL8!6ujg$@A8|k|a{93hA!?v_S16b3&O@L_(+O@pCkrQX0_u0gt&)7+mNQ!i*J! z{P(;+txLftg11}1_L&#_Udu@y>jMOrX1^5WzY9BK zZr+6L_&z1Ol4kt_lWE>FtVF@Ahz-Gu$ioC0$DNCQWb>U>oN|LQcAv&MxN>u=txFB= zNtb^U4D9h-l(jmjL{pq?&A1|Ym=LyRyKe1ZOnUFQ1PL$-GJ;(xPRf(OhizhHW0{j? zK{iOLfDm4>zfI*|w~Dzwr#MFK^%12fl}+AM==a`b;3s@oR+-6U_4#uhEmRgBQfJN! zq&_)@+sfz>cC$W{S`0@CB>nUwudg*zno3eHdD!T8IhSU)J#~P_S=V0VGADP%iER?; z>a)B`#oLe%Z5B&i3QczdB0S69_8h!ZeGIs6g}t(gv=f=!Jed4VqDc!R!U|E^GYPZqg^0tP`7?+^DI8-Ol8uxa=wZ<*5F=Qk|`o`vja2 zwf_`fxLKwKuBq=1l3a5_%E&5iD6R`laT!_*q$;nn%bDfCq*G>?w{VuXc~N0f1WE*y zK*K;5kCc0r1)RA2o7@YkSwEh^^rlYkeYJHz(j*E`EV-Rt%gx+(?SInQya|1yvK2E$ ziT!A;;ei@kM0v&IandH{$3$Y=;-ygoZgJ48%)RYNX0Y7Q+5cI~{=44&$6wetoj!jv z*O_J{GMiRAzx`o6cd-8B?4wBs{#*YF??O7!pY^@}Aak5)J9qI2s>OSpTlMqDL+xR)ZRM#&` z*vBlus^N{VD9%enet#9%A=|iIs5KXKb@oV52{IYjre)7gUNTiuvf%+p

j>uH|7Dm<)lX+g+Q$ZaZ?ELifvdme>l ztO8(6*+kA<3`y|1p@ezR>S#=Po`U(7Qm&6>Xxc`!MDSemL#yS8ibd~~6CJfp^t%>f zV&ShIdibxH8K8=GTub&cZWUr0)Ec&M^`NzrdAXf3ib=M3uu7OiewmHBv1aL?W^Vbe zRzlC|`$x{8AgJS$fN&;eEe0P(cdrlf#th#8qIUt7KNlLsrT)kK?CGg{$o%1v%SQs0 zu>ATaaC3vF1(@f7^Kz#fX-00dW#!w?%*dqz>u>rr%K>**m?wYaT>udw2Tt0YJ_^YL)la9X6`7ner;|;fq}Lnj7bf zUs3ef{mTJSCv);;w?7hm)H2~4{o`r)PT>Zi8B@Qsk3A|+N#a;+jp|TI`#JxI*ad(r zxdlIyJ43L~EpA^ietP-&v_1C$Gr~4K@>7e?^3-X>THZmrlv{fz0NbgXia&NanBfW{ zrR1FM+3XYo=c~Kb<5w z1@GsCf2$Bp=PKf7h0lYZAEQpKej9#akk)~X-EoXgkpI+CX6%Z_Y$S}_f?T`znDR-%)F09KP=X`GnmHJ3!w#thgQdhfN ziMXgvzHxm!=u5nZ=CB!rD=lMjyx_r$>_5oN5SRU&Iis3q>o^C!#+oCWAGRzpuPfUX z{2KbzO_T}PwEKBD7E`U)D`>mJ(5~K03tl1LJjn%o4xu0fx87VG+DWeJZCt72MBSI`gBr=*he{@V=fBSM>1Dh8J$Z+- zcYKeuQ?Ag9F*CQRJ$i;Hz6+OlVsqV?v*Xtg{!2vf>ZrPU`If@#tMxNJw|`SXnwR2n zdA-JU#k`ZkVfO+TJzg;1X65VqTgjgc=wt8rYaLfmyx5@s0-qQ2lT+^$Y}g1uLEPB~ zFjdAxHx3VL!(U{-d9M7pK1aXcuf)keuDcG<#LY&p&SGyvbTVR?dGCqj5?!RRO07(I zt~I^$fm_o(Cn-rc zXpLb0;yj~dE#GvJSGWc(i$Kh3y-*%NQg3^Lt`MZ(Q@`>eA;}L3l=i{c~?qyN-XqH#Ul@6hPM* z6%1tp?q8!W*(} zfzv@o?i4*@BnGnYs&0WFjaild+dA_9$hFu!4O6(69ODW9RT00T{UmH@FKka zS&Xn}%U79xUXUudKjlt;Ns>jSEyt6}DX$U~ZA>mpX-ZOz>LreES6f3QQk&>9yrgb# zOpPQoYJJ>m^7M7aw)NkE9R1k8ZY*=1QcOGZlW_TW11;K>73IW=C661ItAu4DW(Pxj zk>pG)YX=P&tyKkF2ozQzb@yQ#n5&nJKnI5aN%-KFc)Trn(y>x3~DNy z4Al^#jG*ADFOQ}66D1U^8>RXUl09aqIJqn0Bv-;Wq&fTY(<-M(nikZG>E=ZrH%>1zVqF5c>qVT} zr8px^(WzS@=Q$PKg7VtIo-s3Ek04Q@M9e#9#uN`K_?2^H)jObvG%Q2BmLx{wq4AY{ z?S2QGxGBmui2C)#m8Iv)4ATHu#09vLuS2qaWlZ7}$G)rjog2M2S>tV?mD2*MXcH_d z>zdWdIdY<$r_>XltKOJ|F{+OfuaCcb9SjX!USnxww?E>^kMhQKS+>WT|0K`+@zk*P z0Fq(Y0(2e!L3Y~x2iccG^RMHdU_}-JQ`~!fA>+dz32&|Nk?oQ8bS*B?!E-A~%)LUEozGYA_!ztAVJ7}D4;>5@d z=lAJpd%)2no7NIDQhhn&mQlD*InY#gH4j?Jm04oPi4Bu4hgh5=HIXq~Z;c}ZY4Gqw z9~)SacynS3t0yoexa^0Hnot7&+U?I>Eac-;PvYF59S}az-~r$FTa>j!{B?U817eum zZ6`TvmNDwflXlfuGunRW%O{i$A2@OjKVlJBn5L5)r%%36)Cj9NLhISfp6SRewFl4B zC&7X;Gepss@zokGN~tFwS@rumN1xT|S_@!IQY|%|9HE(ZDzd!`N7EE3nw^CmD zIq3cRt)k=VsX>8*mnie&v(2G?JCbQ)(VS>^9)`Z5;B$)XSXiM?5l(y8y(m_9*invN z@z(2g49Li^K6?L|XS=Ux$o#zl&F}_%FoI&^p-XIwI*gx=9WsA&V^(VO>fx7 zE&<@uay8$Qkf1{yKCSGHn2Dcb;u>DnE6`j`p~WzVp-wgbnGZt%YWRjah&u*U73JQ_ zAY}k^GTy8ry~vddf{BUBaAOtt`Jf!42giA>z4KJN>7!3X9rzCU(-S^uLj;kRJPY!p zTNq9sx3or7yI5^rIVzdexzyy7eJkI8;>PC*`$78w4%R|gOgEWlkt`=-_z=gl0kGaO ziBGyzajj^|{(}gW`gra%bN@|x=Rr_AuMW@YV0#!fU6NB(yGn0^F3EmE5WPYterlj} zA#h9edA;(%X*7oH{%l>Q{{R+O|DB=ii?8y=m{-Mi6_8 zeX0i`tlfJ8vshVJV*$e_oVbX zU>13Jh9;Z|#)DqpU@933>)4g&1u;B_mN#8)O(ZRSrI*3kNXmjk7)1@wj;TCHV_{a^ z)*l7$SynP@e;Cy3nOao$Po~(BNbP*xKE+`5niu}XBt3JlDY5s-`0Gf{d8$Lb?(Vi6 zRJ(1$@Vw&3(lZWXJG8cQ8;(skQ9kONZ(^mSudSwDj-KFSkJTG(SAykK4NGfqwkFu{ zh-JEaM$D2e=D6~`95L>TJMs3dF};33k;DCySJMo9T};I=D52{b6bY{hOA~c#3mPmw zKyYFZ>9Ehw622Djmx`_DdS&{rKx!Txy$XM8ojywUbER6Uo$C?Y$tfpX$+E#xJo>nV zyQs%wrl7F?8WQLQ+^SZj_c;Pl2G`UFQ(kI%lAtLXM?f6TfDhPwLG6^<6Z3jvJG zB^q~P)ktNNUNOyg;pg(Ior0hNcmo5o<=ntT5&Wauv)vt?o+(qa>L86KQb)jLIE1rs z7=}*Re#4cl3M&$IZDz5tH@hORv4pmC!lr6b3Fq3Q zwW!=~O+(G$HYbqvB|a%R!-47~+hDhYmucJ{hGwXQbaw0nlyH##{`nQsapcRAt>X*p zl}%e0+mY8_Z8gsiH7)U^Bti7BkJ4+~J)OaKs~~2uMmkQuQR=!c{-hBMm4M6uGW(im0ka=b<_ixJ&m z-m08}nk(A+GBlHEoG=$Q;qchR0>?KFjj#6xe93z{~rK5iOv z!I#D&2RH=ZI;Ha_g9}Ot*tu*`gB#v*a%Ur^9uI3%v>g{xCPfEZc%18?2kF*EBC_^W zKf-JH8bcRT+ujx}p<( z$W`q|akIPAIDqd4?gh9(^M`@asb)ME+)H5?OV3zYwW_6Q)paLG5S8z@VAtI4%QaqUc}Bn+e8|?Rr`UV&j-+fy z`l@x+ERJuMi*xiM-^i;pjk-))Mz~9!!!1Nku(Lb!`9685$6gW>U%MghBM>dK;Rm|l zm9NT1?w{@%HPJw$QY5J{H8o9S;T~6{3hfi**e+b~TO0c9uz&0d^;{h*oL-avNS|0i zrfE|ErLc`geu2Z=pKrJGMu6K+gwx}^zLu1kLIhGan&oDiZJhNc9lt>x0;tJH?vF9} z$X81`fK)vIT-;*`E98nzS!xk@&Lj$vzH!{O78uUudHF=GEdn)OE8|FDG}Xkfq=Ox5 zbr2g_?0Nf{@O_82_K$|PiFqF}p0)91jXA2sOSY1b=d!wi$zNz*S50N^eH=LUu1ak$ zixMmM`+6^>pTpjhYj&P|E$U4NWS;tKGkbyo{>SH4PJ?2xN}`^%kc3kb4p&iJRN$54 zDzEhNZIf?(I9ZNxie}fYA>n+uZn?xTP1+OZaJswAQw;6)?ull~^q)zzxeQ@LJ@r;G z$>kGHH<_~nWMPRt0V%+9G}DCHH+TXqmGLI;cUtKI8gRka3$9c#2WN==f}l0I{G<;AswU}&riHe6F;*vp8Xx`L z1kIpn2Tn9sa;afI$|_wnotjJv)8L=9)_Zua-E=gA zt(UXd2N)k`NlE+i-bJJ%iYLaG&$di`;6N^1&{MsG=OBdTX}-S}2{%#Bp&}bgDppoV^Z# z7k1O#)s#$%?}9sG4nW**f=<0wn??i z6CHf6vyIsd{>^s${UbT-Bv>m?(1+Hlq&7^lY)4<+$<9VqTiMl7lC!%1xnJH0k%Rb* zeb=?N!a_I}yi9AAI<)oWyOR^QimZM;kZ|Hd$1m&NFEw z4{!V7{cb1L`%=@w+-?X>2M}45LTd?c9b}~Ipwg>sYnfHT!jL&PXpZNCEsRZ;Y}&Vz z_!3E-Ah0oj$I{o4h&qF-<|Qzyey?wy{;M28m`5u!Onqw$o|?2(VKm*JR2i0)Fi^q5 zJ%7SMzhI(tmG&CyWKR?!GOVGgCnjbAbG^jl@_m|&E=`8Fu2LmQL_3`G>Sk@MzETAV zZZ@|sCg6^>u$p{yh+(~w!y8&YpzcnL4^4{}H_K@-dKb9zlYIH-?vzj7gP17UvbzS* zea4~((OEwWHRe2alFt8X!5xs32P0#>)oQ;zdVZAEe~Ytx#5+|RS9~~{a{p&?q>kVW zBlvec?;)dM(%wpC*xR9xt>Q^Dg3#2l$2b>?pRaz{J(|8vJ8&?=S(hD?fQY6SQ500_ zhej>NkIRS1UpH$6Lzv#cVyz|)AQdNJrPYIYZg;&w4_UrXo$6~mUPgJmFIUtg z-`Z<`{6k{?7i*3*8LsxqF}EGeyNyw&cT;rI3QqKDg=Q5~o^JbJAakB2-n-A!mOi;& zv3+2j6fP;b-L1~I@RY4WBe3Wijo)e_I7?KTf1ND?ENCf`K8@pbqwY~^6wZZS9$3B` z5Jb%GMW3@3mLE0IQ`T4{dto}b?2O=g!lL=Devp!BDaWdJe^0zb4ZUYI?EMY zVn6b^`S8kQLp)Wr%TZ?BJr7@>tX8Kn)iQ!MPCVanaMZHIX~Iqn4&HaXgS67T=GmeK zIsSe9U83nB%y}|>ibsjpgeAvR-$PBs|*RYwN zDg-p0O8Un6Q7u30H4MRH+ov(7L3uI=@3Q@Oo3D)ZG>7}i-P(S*th+6qzsBs96Y7}C zQSwR2ZbGP{j<(LBN6e^SSY`M_lN9wEnWF`%K>bRY97eU%RA|tHv!4y1>DjBPy(9h) ziU>|n(D5U&8g=P%X;&u7r8hK_Ob>YL4{8h=WRjqEv;laWh$0Kyn zbrrm131=?C3dP}hK2cRCykaqfVy}m^S0bl2!Ntbsv?R=%<|V$lQ`Y2DlTWnna%7Xm zGWaiL!O$t=a^3d+`MPG_luE^~w5%Q*NHVDOlCQhZ5p7>iO^UZl3wR;$p=Ji_Ymmyj zC~xJ(goHW$`+8?p;mRW1=(E$e+_ytxFDh<78{fPb>vRd);njA~2XU^HsE|=54fkJo z^9lZDif7XS4s!1`)(yxp9+FmqbRXeryYahhxZkbTdW_p@ku?ZwsRX$Ib%2W?O@`fSZ_dN2f-8#!nRR@`+i za#ioW>N@Q0pEu)K*r3lIHrgx0m%>%e>frlrok!9q^s6?>5+Z{oR>GvpVf=SlzZ^%R zLY9|rU3*}Nild9qC~@qVcK;UN6Gv~ag_-ViPE}u_bv&>}dwX|luCTwCOF9t@G0}#f6&dIE{ z+=`O(rECfH1|!%glk<|3k?^pvdA1UZx5?4h>k2-zF(yF)nqeC{7j!PF-NFX6;(_cT zrS%FcHr+@Mb1WFWUYo@)(`zv}WMVN%?sYegqPnG3!aHBc=Nu@EM&<2P63)wdfW?d6 zr>qn&UA}R!7?9|Vdvf>yfGe>KmU%fnN6?+nhn?6<*F7D1iaxL|^=6SnvL&kJu9?nhU}BczJnX%*U+FoZ$hSE~KOH}ash)LXOa>55!2T&23ozFo*J8Kr^??G4iIec!m{*NYAEdaFwL;{diohnh zSaeGU#|vq=irGII%d5aY>jM-)zoWSCmm&x`UQ_iw>IU7j9PfNInUEW+H12eBc`hdp zg*00X^cM0;sIO@kGqB;?UMQ02b}|_r($(#^G?U@U%SYgP@AR>^iQ4tu{6uz6S$Pl( z%Y+R<%9kzQ8Png-&tynI0fYmqkLh{X?gh1N^N3|L%nQ#7lb1ld@8LNwd8O|l`m5Iv zu3#Ve2jL?YY*KgIg-1o+^xG@$WWhi}>@Chg9N4!8d5idq7Ar)kUCjA*d4K6@&h*hr zv`o)};uKE^PFR7+jxQ;)nK;zoRCLI%H^pkg&{cR$?fEybeI482i{~h{+TZXFL=?Q^ z5JL@nA9Dddtzg-)bpOJBr5E1W6F3B&F!Hp|eVTrXVLs5A7*bqMS`lBY$Q8;B05&yK zSB3ay$!oY-tOhjJo0`2H zb{$VMy?iGYQ!`WbrH{So-mMEiT7!-F@tY0^&jS_R^q9qk@5~!@Q5h*(E7elOQ;xFthHJDp+go zRVWyV-S%_=Ek>lUo3^EivW5j~_$V%1EQT;dz9$u%y1-YkCb*)Xf8%VrebQgO`xZ5%bIa_Cq_5h?YhmkZDu94B7rhGapq9z<)ax zAbv2ede9-3s>AyP&3y>Zy2@HeI{wlBLqqS>_L1t2c2E`sg)qxS31CuUw)5?Q82Ap! z^Fw|#W{JGz(+)3&|I1m}^fop13x}W)l)KF{jO$B8$lLl;Wn$3qUsmD za}`j*su>m1)q;Iw%uuRIJt@j!q{HbkZi3Ct6B70DLkvnmV+KOU1`-ApiSfBIyHuOs zxy5Fpr@H!qo2DS&XZ_QAQN#gPJKX};)|=3Vn~;O}vZB{9$RTWlwV%Y(`^@_+9_OCY z36L!XZc?+xceq2A#@W+xm$Jk9y*Dy)^YAAM1cvPT$u-A&CvuhsGdikENp){LWA+gA zZEj@KZp2>0k^!Lcav)V><$QBd*7!zeiM!J&ST^R(=NCU15?f@x_EEZS%)Sj_m$8h0 zWhp439Sc?*iR(1MaAKxyi_`4(j5~U~bTj-%Tty}Q;O086{v1$xczJKVvnrdI{F_m@ z3<(*ZyNkV9U3;0~I?h10A;xi&V{BfXB2wrZL_T)kz{D#8$5KhjhPu1eeU*Z&24}mq zo5*X@g8ynU#xN;fly{($tFm~s)NddKpvB(jMj5G7sdMdT^ZK<1cPy$?mc#O}?)C&V z^#F}w0?~L9gN-Zj9CxiSy)L?00JW^O=6iKs2V1{`guE2I+)Z9 zLLVQzr=LXfq$T|Jx5GwBaTEFKGTLGFBC0F?)J`y%9`Dt#5P^MN^&c+hK$7o4(f8{E zx;@SdM9Z&z(kdber&;)9R6HhQ5pf{?X|Blu z9(00}2*04XE^BCZ-D8YvY{OqEn?xw+cEcafpA@X}R19`}=g&`{PstFL1Tfqumnb46 zIddY-rm_#Rjj*UYJ@DQaH_(|y1n^A7KkDzg|{hYt{! zfPo1ONO~zuc}H4JocamY30~KBcvI#T@ue$8tIEian=o{3 z!isZl4S1DJPtAn(W`1%wfE66PSnWr{gX-2KwLp)NofxQb7xqPdX34Ngq)$JKo#(ce zc0230uO;)OL5@j{CNd8=pXEI{#lZ@wd0B<=YI^msmf8JjZ&9}{$jc4Ki}y>o>=}hQ zGE}37(G#(1TGpEMs=4S3T0~q&S3X{Mq%y}; zzv}n|CTPRwE%+rlC#gkufHu@~KSv79rS@d|tg-VD4?z`Oxva(HJ^VgolcGv#L@Jus zU+p4$n}n?J(uKh#WmQBBZtZzOC99T6$-Z3IU^d|31O*fNbyt0~w+809=DzkidU_BO zG$f}e0KDJ+QcLCoh@e2sP=z&Ss?7d7%R;_pvCiw*X@;3u@fRv&OJpQ$^!aUO|dd z7=S@q(|Sn8^v>LVta4=PAk^UFftJa-wT?lXE&8)2lbGrSCCv{H7P=$0!OiV#(=If> zGKYjeVS*zUQhc7NOZHELFq&mX%3b18^FCfeZaHmHIjl5O1 zIpzW5hQ6>Y&Uw&a!&_#A>>0Mvt`?f^kb$EwwPFV3f#ElVlUCAx53GLgX^PWi1bmvw*A%MP{efW`{XL2kx&DphacKxo@+p_ z;Pg688!E9W;#jyZVjMFZnmy=W<`bKkpViyxWbP|M#nrRydrg%mT%m)jUhOHMK&E^? z-eoHSGq77uoSeK(sM3YF{*t_xH7|e9Un2aeud7%~$AAFpMOMyMd#*FoP)~YN5LDI3 za|}Njn91Z!V>b~{Veyab3ir92A}dj3-o9~*q45e@VRxTliMylx#j zMP+k0o5N<`O$2Qe-gzQuMpcyrozrMRn;(DZ#qX(*gyBlU(n-8cCFMFlJ8*V8thILz zAjXM-5cS-XB{+@~mU`|shQ#RPXpO!)U;ONIT=g+}!QI1#J7bZ!8$whA#yUzu&E#G7JtygSMU5Hsj<6~v+xFq0Uz%vkz;WS+Esvh%pNKV~^%W37IAuy5gPSXu(rpU0Gvp%k4 z9f@!aYAE=QH*gDrSkt#OwAx2g31+rW;DXLF>zv*Ds*>^|zY)!M*Lqa0l|RlJ2g+xq ziS%2DN$t9=?DX-t(oYrDC<*+okJsUiEv;=|&a}9Vo5tD3e~I!D1#@Ddvq2~2V<*3l z?hjE%sOd7g#|%N6h<;RT3+?I%PNP81u8^bXcEYvPBnN3>v<*6+*FszN>C#$fgnOl& z$DVhjY|FKB3G<)Tg^w_vSAEXUhD;cn&C8i~O$cMHH#9x`vB%M*v9co^)GRl}r!XWh zp@e3~GqKc(^CSH)_*riy!{%A~^ugd|c_e&g9 z2B$?_YEtZ@`%N`?1R1eV3<>6NMvYTe(w@T=U+<}mWA$&xs|RKis0#HaCz4oEYn?tRMu2-5uqt9+^|5Ch8RbJZh<(g zPFbJQ`}!zz{3HuxQ0m}v zUw;?UX(8}4(GUZ`Q>mpqv~U~odY|Bh?Kp6wzH^+4ZodMlm~rUlhKg&H`Lh~P%5!sK z((qkTVvOqcKt+Eeb3JPmgm7Q|^%f=433`%O-TD&KTp3dpK$D!HDv>_g*Vpw)6-cTT ziDt2h>+iMjG|z9GEpBm+({Z8{@k2n1iV?OwiWEC6iW2p0-+jq!V)rpOt}1f!>?$Ui zdadis#9&kYSQ z%gmho5&2@abuB|~*k8``tB$>nk{q#Q57Z~7Kc_7e|JowmU5U!+j?s5b4u7TG{?#+2 zb$rXg%c#!Su*$e9-yI}ooz4}Tt_ZlCI|6i04n4A#>&ZAWcT&M{ctL^MS8XMe2D3b; zb`76|!VwmO`>b3xm(DOj9+Gd}WDBvXun-uu08u=PO)oHT_Aqu*9U`GqTTiTS})H=9-O}cMZj{BACF7SG4jd2H?;#FgR!J)5UCGTu>kXCscwOvG+ z6!xUwhq&yBE`??1ix0fgd73!z z(RATe!>&6SN*sZiwpk>-8~^rhYSEm~kgEZ{>=NvR`C2vJ4r25U9oLuCZYp<_SqqM~ zN3Ky8NGPiZ*1%Fv&G{QE%L!gGHn6?)&-|-fTnXp%F%do#i}%1RM3U~el&kVz6K*6q zi_1y8sdxTrB8NSiXjg&<<$c*LOZZ7i5u`vo>>X`tO3lJIKt(8bVsm}cdv6f?6G zn9xo4i;`w!2Hyy1*O$O3koEAS$MoMzGlx=L(_EySra95SKnsk|xg_fUR-J13)&Jif zhaNyUafv~0)HOO>y2G;%?OHT3hEDhe3vD(2VFt~JPcx=39{gC5BDD-nu9cYtDxVNS zl8FCm+TkRZooSti%g))Cw@#QCQI!Ve z1-?pt5CKm?tNY^GiBF~DabE4ZhxY#K?z9zoo-1NOXnRQHH`o4Z4*y5kf^X8R_$|S zJfH>qOobD3;S52(G^%Yu53YTl@rS5(9Nh%UDHQtHDz?l{U93_}Z?|j%E)aZI1=TrDR!;DM({B?ok($Pu{PLVi1FsqD40l=;JpCtQox#bBk1Q(&wd_^>_u=_q2u%pjJQzZX6W$`j_)Q zPMuQ9#j~zUjQ>?i&@C2k^OM2UG?&GAvY=}MXhl!&xxj^A4g9I))2F}Jt`zLknV5uX z4^a6<2j3YfwBu+C_hpG#sK2Ng*Vc*I{gl=ucp)^fJHHi+9C%zVxl>Mg^KAs=*Q#tl zUS_c_?_v^ts9qvgR2T5#lViV)y3`;(EhcuH6=7b5BT7aLvTo>QARm_`++Ubxm%c$= z_!;8QC9M}|JAtA8kz&rcHb;y zM!Ocq4}A9A6vX}gkhUxmxvHW*>sPb1!932+AC*lQ9upI2;!r9)d#H?H)0 zE*$ZBI`xKyXwky$l>4z;nLi_xcc$7SsGx1{sjk%P`tIDZ{;gS=I9neBe*0mrPRE#U z!)izH!w%WH0;wGM?0v>NXx|9LvDD|l-TECL;0uT->j)c6C2_*NCfWzFHFfmbt$F`W z2KL701$-T$=n9*OXO2yq`mAJEx(R>^$gXNSVRM-sQCv()x>W_fF3@fp{sYu zrN61Q<#%4_+bK)6$-}tp5kIXnycJZj`D^^qt{V3VuEOz&gpjb$gSKJY5lbr%QpRY&aUlu9!&`w<`RWKF;SFLANACkQc_o>u<^8cIfT$5MIYqczRh5XX^k!t% zP%+WF#Nlk+yGXKq+GDvSdbpy)GOyjE;}NcCm|75T`L`Tm^k^fSG?;W1{^c6Ebo_+K zo@dKYSa|1W^fgsLyId*`2bM$Q*ZQ#5NI5G{G|Ifme` z3shk$5q2$`8Bj#y$lKX$V5b36xU==(zCoIjNbsuZC|fTZo46_~w#!*2e?%3ljy;HUHmm&tM)M#N-k|c`U-yvTnyP(aNSUpaH@Zi<_;qL^fmS@ z-{Y{1~zS7EUF*o@%47ISR z5kIF!h|?sn7sxIDD)E$WY}Lp4^aHPOB2yQC0Mq z0-Sxb9SbdhN@QyMPm@aa_P+Thc5K?|BK@@Kw|O3h4q08&IERBel~HQ0A@@af`V$|z zFi6Exy55hS=Vhu>-JQ#Bn)8~-f|NL?zcZLave=|E;2dqOxgyw$RoAJ@Y}|RcD_3RI zyw$i4u;#^qX2Y$v)0j^mzSmWWn_WaQ%MSZQi!%VkSRZQkc!=-;5=IS`9&uuJb?No8 z_JN0DDR#rxd?Sud;YK1-v1Hv)cNBJ>UWV=IbxN-}%b*YKsS`R#?A*In(`NelvMMy= z{LZx7gBG5+7DYJXq`sgrqDD^Fvc(}V&jNv#@K5%9nOzmsRFcyBAlAB`xzoXm6-6DT zlAKoORPd18|KB27{F2^_;zwm_)tBL2$GgoW>w?}rdX;ZxvDaN)+dO?6bq60LoS;xq z55Z4KE_&h=Z5RZSA1bbkp?MydAb{SdA#Ntw@OM4w+b8Io8M{l6^ zm2L3rXUm(*A3uBz##tN|3Lhk^*Y%zxA$Y~IL)&pqGc#vZdT(Ej@5lEhq&^>>zR~Ra zLSbG1JDk-kd`>?T)i4q=YWf9a*x~!*6#f=@!cLQ;N>;13HhvlhfdJ;RSFU=+$5I8) z!y!RjPWrV6Gjb#utz#HW;4xhLFOjOsDlm6Cd!^|5e`vT(x^w(;rfvi3O6A{_0l!g8D$_2P zT2GWUi&+=Fc@5}PMhgtL4>g>nW1|QaN0Vh65EE@(U9iF1@S6(1=3Nd=7kwIHIQw4G z`@8BBp4d~l9D0QmvB-2U=NwMjQeM6`nM$2tDo~$4TF+y-x&3isIZZ+R_ z?ctkG!)Yr&<**zUb!=BY+#0?@MmVO8Oo+4Lv>X%3}ZrdBNb))m9W+q_Q zP`-%!Kl)}cEJ05pR{0k}P^K)Y+8Jj(5r#4`N<&0)ELrCa_MAvwcM^FTK}*jr;5~sw zcGCq<(l3FYObfkM_zuK?(&bsr|xDAuNxdqbzI97;-vt0mD=9-epN-??rF=$1m zcUgfL<%l1muk@-11&n#CR=s96eLV$Y0b7dHsmc9TK8*yfI7wcUZb?50U{69iMisyI zeMoC;oq{N!gRe`r@-NZ7oYSTtQZ}e34-nti&J6^Q{Uy@LvIC5fxVPxf!J*k}S6Zc) zYk!G?3;Bl@-oqAf&x%IcZLR(ip){ZK{c~EXr+65PHQ|L%|Cj-eq(o|QKQ2Q-R9Ych z8jvDlU7mjrq|GHv(XjrQDo17eE=p!L1QjKrY+sR8bID#$0Y!=X}zg4?AEm^2r+4YiO@g zXhn6cKJlPFxYrQ9)8?1$6}j2SZRCMZf7D|B$Tx|_wC7p0!{Igd{gnGpcsa_RQ6e2B z#d-z-<5DV}2DdFmHf5XKPXhCp%;?^D*l_G86rx-WHmxzOz&}fA1{FL8k%cX1eHW(o zA#GUj`oM`WXDi@aKUm)&QBn6Rvm|n@_wJ43iMUhT`tJKNqdqB{=`kfMZyN&<^Y*WD zlK!Qc|D2uC<>W^A?hfcOkbLqwWWW8;PzJIy!LHtBNMw1N$^zTV&!QG4%NQQvyn`>O3s11uXS^a z6qj(Ub}@y^e(HdN`A*BfpMJ`mEv~F1ICQSGLfi~wn>|z_nB2r4_~IX~BSQ3){Q>KH zch*SG;qp!U`ivCK20H%kogRzs8nVWGI^VFKzeGI;1!j<{>MZgGQib*YDgr!WOUdj$ z?n-!CP8800HGbkz<)!-$Q9O}+Z?4z_h2b0U^)5*BjAN2w?h6ZxrD9|xdBBvax3+1~ z5QQz=zRJf2rl2jHg<@|-MaT%1eq20$D+A0a(pNAh*^`F#TC8%`)SLUJ%f!#-c}-=r z<)8E2A2hf~r}&Aw&|06%*gpf07DBlOA>qNeV}^Gs0}*#_#%`!Dtu8N}Yul$b9gA}Q z@VhWSbam}sdae%8MBqlgA&un$-a*NJQIjHA7C7q5#IA=gQr>c0B@JkKMyNGCkF)12 z>$GQ`j}o*;wO`ISE=5~aIIuil@CVZx8gLvo6$eG-k7wA?%h*tarUE2+{_GyNYXv@y zrqsNY?g!1Kz<~VpRmPCgX+dLrWw~!a?fBRDq!F*17Po_rV;~u8H~j!z$+Tzu#LqI1 zQ{Di!>>HB5BfDkoNt*9%$eb&wPsy{z;RaCZmvXSGTw-JjO@amy%X=3~!ShH+gv_dF z1D!hFZ~3|aa$NYWuM1uLZpLHTrA?56TLq52m^+txzR*_l_=&?}A1b0|qtEoDX?XFU zkxxCvYNHp7wbc!n;~3xmvOrv1`i0q=CHkPDPHrI(&HOHDL#HVk6!Q_oS?e68iYfS5 z`&nQj|HTcF2Oq0^57X$`)hmRL?tYsj9d|Pqm!c}R5!f5N?(8DG(sM`im8Ou>gNCEDvOf-%9(!jc6JL=@RTHk!hF zCs2cP>W}FXf5(0!=fb6=#MS^vD!b6cIQ7t026g_(|Owz zkQz09B?UNu6>Z*CeT~18&A)2@PlsvzpAOUa93LsQ;gU@J=R;_w$j~(S{4H>KcWo{_ zWWGLjjoo8QQ0h6XS>kIzS(hb8uXtR31@nvXdR&$USl|S=(A!e0xjD~*PK`I24@m0u)=vFQ7=XUv|mPvFCO<+9oano;3SY%J`7` zoz4Yrtb_#$o`|XUz#&fW_f$hbj>A)TS<)S)j6SLA^Zu!xP|+r*0r{yw7pOzNA|ry< zy(itXpkXWskEv?J&T<;>&)pzFj_`OfqYgL7VbRUtkYl=^JrOO{uCq7GjHr6+K zB6(*$Azoqov26Q9GTPa`uwv*#oU?Jz#XuyJ)YpsvRp5Bw;~@&b`!}rvSl4X6bcZs_ zggQljk`;e2nP_yV+^w3Z->wZqO|kK#+h1erR0Wvye+hzy^W|SwDO(jZ$7?FG{3QbI zC}pKH=Ocz1CC?-FS{$m|h1{U)9oS6-&}^@YT;@4OS*BF?Ph zMO%h^qC3IG))v_Uff_8Tjt9rX^6tb+`}b<^t`~z?4djdGj(6_!!nr>;&S?(!99s+f zX~rhSdC4SKt}IE5rj9l0I-|V?mDt8aJ>KLOMtzBfEoU`TSUM27p3_=Ge7wd_+@^MA z9GG59v@P)NpKZ$i!reD$W=7B0L=IGAS~gHqHx|7U{ndf8FRMf}DE-?nfz!cu1XFoRs?N+dY-7UTzhx9&G~p##kX!8HLxN&|&>QqSQ)GS=sO)YQ)wkzuSB>RW zh#QK3C|IEp-{eJoGv~!9*uWeY%@%0wTOZ13%yzh(V{RlEga1lZQ(=CYQ} z9kh~V9!?zX-^w^dUP60gK%S93Oz#32_#= zrhM&T(R|Y0T5TnpIh9QwofwtQC;gb0<9e+Ev$Z9UBvhH~=N(6?teo{V?<;z>OAp|h zXgC&o-iP^hro_Jd^Iu_lP?76hCU+ayDm{NKhu#KR9g6#^{&@rZM46jWqrOCVHfg z>4e_+5C2!r{#{qToM*|O5?%NP=q`%l$3LY;lsK}{ok0!vV`V}{Q~&I|8wN@Z!lsde zThoy{T6>;k#%}N9qIF9n&+w_psKNr93SZjb+kDv$9Q4XPeelfsdD)wkwg5T4ak|?s zX=pmabNiy$)bP+7T{O-N3?v`rRx=a*)wuQP_1FwN-#1BsVY>$7+C3OAMW0j$!_MH2 zQ+N!K7jfIuBF}8L;_p{=kJO@FMOl0&J)Ef0pRW&vQ}^jdbGY$m4l@u zKl}NY=%rG>D8x33@aZ^z%HoIEFZ`|oc_7$zdi~w9dfe7S9f_pT4~8mKImTqOj|P?} zJzww6i>@M6c4CE!k|^WfafQqDk+e>jx_aHkyF+EWN|2O#ZN?^^`HpfCcYl&yaK`aR zDGfXluE|59xww!@ zyr)oCRYNLnNUmq~#Ke&sTC*-T&2{;G7PUMHn z4EprU!xJs9ww_%M0JQ?dh@8}NpIr9)EQ#T83f&FmsfL(IK}t#nBKSt||Du2Z2Ku-7 zmSehwD)Aj8Dz=-#Q-4`#?P9) znufqpCyv|`+K7kPLlRkwwihLQ2qfw^PA~SsalNm6$Hud((AwkFdZwO)@z}57evwWO z%JZ`7dN!oV=a;8z;#Ga!BxO5wP+;npuF_*CX72~9`G^Aca3}L5=92QdeP+8H=ZMm%XNbs(&#D=IoHugT*91_ipv+o4+hM0A>kEm=#sr zkZbW;jZ=o6gp6}F6iX57;kKR`K_(g@dal57ljS2MS?yS*L9?=Q{DLkUG~lxcAI^W) z|09XU;*Rq-&mt(p2#R?Nl;s!`W&~@JgCYde)a*)1%8N@|x+p3=5N`ikagXLHzo(`4 zUN{%v1Yh5k08a3xHuHZc_yFzEU!qprr>jxq<(!rUfj$~DB&S%yx00!B#Gg63{M{|6 z#P<|v{&@TtOz}d2ETXOWY#diHOzEjd`>IFZ6!lXFha0gs+)~y;ljexFL{|QaH#~S)Rk4Rk za?jp7BA_9wlXk^Gcd)Fx${~q;4#lBW4l6Di`8Htz=jl}YJCxjd+1exd)T$bfh6Ean z6%Ejki%B`7GDKyuy`kg$dP6mIHZ#>HH*`K;ZPDYqa)qWGb3=PNluU&!dn(nhW%ZP1 zH>Wgf!J!cQ?q@lFCEcf*F~YT_s@&p)rq&P4kIT5XZbI{|t`~U6%aXA_MQXi2q2`MOfDr^XXHk@HV6KKZ1xefD*|e=gN<`u;>_-r6i-N(gJ-KCP2x2wW@a?^ zd1SYC)8t_E~1-?E^z zUYq{E3$Z%WlJov)?{6Nfus)b${aAcdTf8E8c=qc24>4fbfsC2Hl9t`9rEWQHzJD?| zyl{R{E>?e+L4Wqd!xyp+wt*@=)V+wf^D75pt>E?cb<%>R^ID1n1A^M_iX$dW~ zF9P5H`VWhGCLhy)_kUVK#O=dZENw0C5N{?}@ZGTeA z&-%^4;N{fBbNL;^{+OMkmiHGB5BtaDPYKloX0UUY@<^!|=?^4ZRcgw6c!N&7YE0Nz zqAzh`sFb5zmXlVJx1o3pvM;a3vGLiyv4h}VLyFkl4Xm_*Xmh>nr~0I9E-m;pDU!HTyM>Ir?7J3eL zq2Z<&9w5MoKSBjsX|e=eZJg4X=vfvv1W1<&*zYfaRHOIDQiAal1g%TYR64mM{g}SY zrNmw}e#zLC@MhnSI%0`FW#8HTio|C?P0D6-w_gpVmwh=P{(+2~9|gNT_~APMJjL~{ zx|rhX8L?MJBVp$Fhlh5OIaioR=3qS%$jF z2CbY*qj`1xlAdJzW9H5GvC4SIPEEzL}BaEJY0)L)PQ_j4@4#ygSE7& z?iKiQyZIy>>BYM^lk)l|i{orVJywiB=;baiDzM=UKOSG|Uf z^Ez2-JLgfysK3{QR|XWsEi0B^6;USBuFHK*|Hew{&dKI)2!G)&Timv{jz;;35dto# zFr*aN$mm4%l%h3PE$-3Y+bY;~{3pk|ZlhixTQHS9ax&dGg1EQjvl~wz+f>N!C7p)2 z6maQmS>W5*m|q&8M|O47$F&kD#!feOuYPbLm+-+H_MzC8xO<((aG^~M>>XrrYCWf_ zH0eR6jJHo)>^iLuC|7x2Tn0Y79yR8dx`H(KI{%XTy~>cSwe4Aug^WFw*(q0Y{P->hKff zG0TWCwNaet8!frBm%ipGF$X&54eJvqOFa3Gh{{qLXY8Z=7q>%xYokU)uF(>ZLO)T z0hpiVsyEb9em?cyg`mFQcqZMe=>J})Spd*qBI?p}gsqDrW^w0yA!=t=Qo4957RgLklITopZn7LXvEvW= z<#XNR3)~)?&L)j`)n1N8;^dXKK2wqTDWG=i?HZ%xaSHD)suWlEnPbtTd5wNn$w2fh zBsXB7rX@GZyks~rwEERdL*`S7?}X#*>$1TmTcfqF@XKCke zq>KQuN%N(KVDf%B({Jn(UpW`z`?e`DBBW#2_F^1Vv%CnC-*k?Hoi?J6H7d>W-5CR7of zTw7xQK?7`Xs3#^H6}d-D%-L^KjCQGjXbOEgtA$$@*;Xd&d{ahZV<%qQoPkR<||{`^Fh|pOR|3<`^-#PkLSOd61~h(Hw|=dotU8OGzkVhrEpJt zA%p2Ska>H9TvjhOt!uRM_85TqWHL|s!>Of%=TDB^;&YKGnKKYQU~}E?gueCId2z71 z4~eO%if?B`0+@(~Cb|38g|$xVhFOBLp3fq4%dw33EQT%x*|1EpxaP$|9TPCpy zb1B)OybFS-vl%Xx!I@%f=XYh;&Z{}enwz~!nFhPY0cxgItLHtLH-2k1(QP=)9@%Bq zX6?;(aA^kJ!a}b{`jAe~`DuaoqN9#j(rAO>9p5+~C_l<-qW6A)(edGDBEnFR2=2c& z&JBP$lBeL4>ZLVQ`mq+TihSxpQF&!ndB)R3^ zv<Q?(w{wUop+VUH z8De?h8TBU$7z&pjJ4jJnD&#>ge2-lN!v?c#SSG^+GIW{W-gtS z)ZX>GZZ4Xgg#qD@%Uq{EN!nI-;w;?CY#xjRR0v_8a7I#WZ_5Kb>_-zO;Mt0AMKEeL zwUeg*s+0zLO^`)y167CE^+s&P5fJveU`8RO+1uX^OK)sc$1Q&x7W5pUq;ez88Vg6dG!a<`lgloSq8hhq+2T{YWnw5Abmq#Pc!g+o z_t{0Y+^O7nnv&*b++=QL6SmwXMGe$g=ew-JyZEp*(LMV;QsAkE|9|7-GX4L;xU!hxI$(eCtnH8$VTW_Nd>aj#W+h|iKM-weoUX&@oYeBX?k4&`W9 zf12!Cr!sT}T}b?sDF7segY;C)-1;vgrzW6!Fe$zG?5)DutGCF;rkEl(cST>$SHr;( z`L$Gyt=H3#u!pMt0eE2KP1tjDNeW^<$6`=*@3P+ltGe`uOnwNe8z7?LQ6Zj{Jy&3$ zBUnDF)N$n5Kz!VgV)>Uy8oUPVblMZ{Y)n46m%Dm~r7mg7a| zzKoPY=FIj<25n2~7I#(DtP&%4@{uPYTs&!n(t+q9|LZ$YmxMXNV$ATc9eO!mS|dd^ zzYMFhr(q#J<>E^Y>`w zx<}FUj&!Y^ z>sFc>s)A-18?2HLYxwBvknU3QRP#KSvv8nQ{5~58C55#b3A{!2=_gmD+L7&@Kpm80 zj@=k-%mV&lNyW#@xe;gXZz6!SffhZ1ZB-N>5tEC4E}~Ye+)0V9z z7g8n$zi0i*(|wjI1@W;KCk<`akedX}{o&n}TdTVGd?d=3QPPDEpW777P)B>FV)&f+ zyk>f~_4dWZsmllZM2U)^G^ovGq8ags-j3v7k+fEsrlyRprM{~(ncyF60h1BwyAwh)T$s#bTwf!PHg|UJBQ0zfl{|?g=iCL)!36C(Y%4OKf)qT8Q?IG8G=J_R`*{#ZUO#Afk&dL5XRUOxt)}_T zr%K!#wXtq+cY}x;r6UBYM)!BNvsQ5&!UG?(58EH`B@G(*ec5&J`W7eujBc4M-UmDm zu#~^3*Th}Qug-6t%e=Ee=}K(4|B0+0H1kUrV!K_NXYfLy68OoTQiMQ{4S%qU)`&Rh7@cSPfBxW3ONo-}k`3 zNhth1t-u`d^My`RTtr?gL#tBY?4v}~_se~4dxVhO$X%qY9}D>rUzeal>4gRA#*ypP zquixz$~)|^>E71U831l=GO^dFVbD16JJ|XnompVmqhpcnoD*ssu;TNVhzkH%b6*(4 zQq7V!@ebQV;UE<+kAnPrO}_E9xvoD|TqM$oWcx?%kVC$Rqcd*J5CCD*MG&Qb!;o!> zkT~Y!f`j1q!VrGLH`m#Z z6J2FClwWfyH54E~%!)4@rgl0=g1e3WtG_MF$xrdYk`k6wWLs4e9Rc9y2};?9X{E?T zPxDH9hvx4=k|U!@-vRtM;A4HEz%Ko6aPsJ#zsLm)^Cc&Cw-3N1@z;68l;SwC{smX< zA7z^Y0|gh(4EE_B;3obNY671dGJcB+cBk z!N@wN_BOaA(YFRqpf1*Kr10pwAqHp6QKO2>keyBa zUPa$3K+n|r11`GX*w|Ro(jonV1(@s%bDnaYYjd|cWJhiP!cpeWVcp4=p>eDKnnggy z#1VN_s$^;RWemwYZ&y*8!S2vQ{imDX@Z2t_m{6t>)DiG(<-_of-x;wpsUcIvN_iA$n`Bq-w6$}T9$~1L(coOoCS~3KjAVn#*aGY6adxg4dy;bF3{yvbc@dN!%L1eQNV`Ki)pj4dGdLLb{#pkeQ~ z3REs?`=;c}?qS_@W}Nc%n;^enHSzc8lupd0(t$Kvb6y#ty`b1|iYrA&(Q=o1M)E27v zY6oh(-XGF&Z#sGfaBGuN| z9RalVZ;<3W$13ww6P_zFN=eUI4gzoK@2gcsR#9!P6sTU7a-1RJfkoSJ!}^yds30?Z zeA;qF{FF~=_CnW4Xv(mxL>z{^H85*<+Ytu~b(mk4bm?R5{%SUVPHV3z zBo_}Ob7fW!GlkiOU@Smrv5JDan@we`cckX!4}Df!HmGF7UUXhxXyZDt6KobowLade?KVrZrepiBI{x*_ubC9n$yb#jmI~|a z8s83Mr=EW=xXKp;NceuR7mF86-c-tua=z#@#UT<%3dE~M+6(^@nTDu0pF3LUzMyKg zU>lwDImhb=seLXN06Xtc%$y*7SFz8{!Tk%NcP?_MNL+Q|0&Pp!-`)KarF`H=Q+~^& z{c9otz$TeKa6W>^%V+yw`}f<6s>p_KDy+Mtmp41J7bab|F2vTFv4Zv7d;C<+ie?B4 zA3IkDKgjC;`Ei1~S-m)#LEq+-E}hEs#qqs(Z^P`bY^%umg+JFU)*T^Vu&~X7`jvWY zoQcEM1A#VE;M}~O;I{w1ju_Q-5{-3aUFvPP?KMXpdX4-WK2Axb5nR0Pc=72;CA4=Z z`rgW()W5#8@+)F;EO8TSV!PmSDb~YO;k9fy`0fDMC1`LPQ4=SI4Q7RF@%gFaoZ=Uk zgbHF7W9J8fuI?*vPIe7yB^@1%AB9ZS{#5g*N>mluwTSrN@1Usi_Y>ZLu~ZGTr(mPD zg==VWV7*3!YtOVj_8ejj_l+wU?w%p6Z{D_gjtVH=YoV<2B1AbShH7)m1E+)As$JfH zr-LyHqQgG=s~qR>##u9J0XwBUf1{_LK^1rpb1&{h#^B$X=Qa>FM@JsvT8*7}AFzhM zSO=ZeO8q;@!~dx-pIj6Slh|Mavk({PeFcf}qP;13$W<{kWXARfb>+nUus_{WfcENP z`C}4%l?=rfT^AqU^82qI&L}Xa+^3OIpgJyJkpHLb_XO=o(63 z7+`3T7KEV(hR%T*LPA0Oz03c7yc_rX9?!SC?|OmaH5Onk zNJf>Qe5_ur+*eJUV?Zi3ylhN zY#!SK1RTjDJ)yv$F9#W1s;by8e z#ZbBN=8O5glO}Alw$9`D6+)bm0rKzWr$}kY!W?@rK$A;%$n%__bIM>Cf@Gm^8rt3J z_qV!*%OHlJi`N!Lc9Am?MR_iZ!%o-Q&59}v1{uO)V zn!Vd0TYfUlT7e`a%-fd*Hs{e(3355-#o0t$OWk~wD0cC5$k=6NE1=?aD+8v%zTCX39WHt0C^KWNtd;eN?NB~IzM2UL_v4| zF3njd>~Tc>@&2jINAn=1KLH2$2mb&gF95(u=-rEwvrM&0XwV@zV@iL@Ko$pRJ=$qb z%GU%;>fPZH^zqd@^QCNT6h*GuBFq~WhL1?rdQJe`kVg?SP@mlhGPn=$;>y@2{@!(^ zzRS4?8^irRpQ>3)gD_T0vN*qydp2##obd75VP<{rjWS=f3+2Ld%J7Q+?sPpzjEDi*1510W#QL;p%kxbJ?zrj+K*i+x35@JXdnT%TBwsz!GR9= z?!UIfs>g>X{wDu`GGPId_~Vc7$~oDMloRD5o7$nkC=pxWEqn9xg_Xe?icL-$+3*=(Ktr@X8U6Wf5|ApA1GX$DqFHQJBccy`gCc2HgXOFtJt}@#;`NlqFh<_ zCr{Oe=Bk96Xl-Y(hI-Cc^7`eckOtOx^m|5?hpKF{vb9XY9{XIOp(1;_pJrO~g)W|$ zO<`W2BM61XYHuRV(BOH6s&haW~Eq}R#0j_;e0-uVwSEtE@P z5?Qvy`U8&AwoknI^$FGh5F?x_{s(%=_mR!$uaHye@nC?np^o81l~I&*bYhRKx0pRc z=qeNF1}&YugxF6bx8mNky^565c;TzX?fZ6{)$<2UW~)h1j$p}F#98-T-|+|~#PutA zyVMeB1pTXFWn$CYH|r0Q7sDTrFSk7dDV^ED4mCTRlCqAIaa=FsvQ$|3{+PpnOXEvFWHly|?MT@Kc5#5C&IZU+vvE*Tx<|$7n)V)u@cz*lUtQ zdbb2xYafA4btgeP+dg;m*=7vLI~Qu*FXaatN7OHJe1>dh z93Ly`A8e#w`gyqZp3Xn9PG4Uy_cP{81E0!8v3jCO7Rv2OHt*q88xHgFU&ezVxnyd< zycE5zNrp>_Rro?*g#)RFZ%+yK4@3{y)&Zr%*pkR^Blp_mP6b}WRu%+bX z@gRSFwmpcb`2yem1&%yYPWxwJ5di*&UkeIwyWaHZ*)k}W3#4q1z$}np2)D3NL;7qk7nI>TvvfRa*lbA=A7j(yBP(QH9_j zVIVaA6-O%I4IjMWD?17b~;d^ zYl|d`P|xW`aIdf^{f$O^85{Qx!5B3trl4y^L13#M#rNR+JUyT7$a4IbO0=C7x+(l>bJZg9rD(W}hi! z`m181JY)RA=s3gIkI>&%zbs>$#un;bQ!O^`8oC_lWG1MZ-_%NMyKys+m6^>oK}s^t zfy&uj6vP%xo+uLlOA1hXblB+3mVKHu@Xi*z}zB+T5bzy8Vpz83CXJQpB*@q79$#Ts_?G(%ub}gljOj@}xoa zznwSB_U2AxQigml5^Pcq1CLH@r#fss@iU;`j#M(ehEW`*nKhUW`O`b~@1y_-HAzJ* zilhKluD_Q)b2}Ec1D2i@V7xha77{$qqU7Aow5IAIN)Bu+*d)uJ)tEi!luDhJ8fhb= zrLu7=&1CP6KTF*fHq?QEJD~Drb9RV?46_3k^A%4CR(jPp6%Go246M^TRyKU@z!{qY z1iwJMu8Q~JLsjG3Fy(A&&-%+NjN@2XJx2I35!J| zB~m*uBsM6^Raevb&sM^aU!4A|+|#G!$t9mlJoc$Pz4bi&Au*~AIRVP7^E|F8(oOq* z)Xv#n5_oGf@oj5-vb8s$tRV5ORDylNt%3WgbFrHY0c0*I z>lPIe)2E~~F)2CKuB9oBH_J>zXGaJ2SZ;yNT5<#7;v%N=Qox8%iMGQ4kn-$yFq_Y8 zWeW^fl=ylt4UVXN8~CFM_>9}3cd!qW?S`x|^s~bhL2IE6)+^J-RMC@a+|Afu=TS>+ z>RdK)p8cvW00%A{@gL}2n~9M=_P_*xk!{yBeP_~GTTol&ii z+SkHUtbPB^+@b>d-my<`pC$kBCZEOgw*vrbs_6BX#e{`U0zW-jA41;*h4~mLV ztc1=Z#-YE@h3foIvOWI}0oT6uMZRH!Ye=V*g6#M!rJ@tk1{0 zwas@xh(kK7j6n+LV-Flgw#vLeAZ8L~sb*wo7F(!!4Xn6*mGe*&`<(#S&t|GF5IQ|i zc%Ld3-k;(j%G14Ou15BTuBXI{Yj8$?M>yiALzjhhtCR%7x3HFQQJJ%KFNV`+~#=>IqBGZjt zZp5`YYT1}d(ZwAu%_7Gv-Jr}Q&ZHbPlIXybvQN+JH0q}{=rhq^R=mfIbQL8d62*{z zo`+V6coH&gFdEa%4i_&uah7WizlOdFilZzaiKOYzS_oEFRoXBo1o&I<0`K4;?K$~mQEwhNQJLrP2C3GLWJ7G;`OCa&{3A|wDxL!_*`a~}yr)9g--8Q|~`V(C*Vz{=YWch6>oXs`FZq4Zxu+MUG36vZs zSbZVVB}g?p+vkVAeB#3a)>{DJNY*;>F8y1Q3+tuR4@FpZ)K5h9!ybAaq};T7T9`gP zp9Pn5ImzPSw)@@X8YcE!TlahGJ2-Bhxrb5SY-~3&@>h5PysN3SHK05{uZIEDHQZrJ71;{#bHm|rMe%$8;7?vvfJr+00Eq2Ep#8*V zMo8wq=Tfamfn^>xs>vOWW1)*Ceu#L8jVz@#)7@fR2lU|&ka!cCK((;X>a>P zBj~|zHkMh%$}9-6B&*=P4L`g1;mMGxWTJz_FR9QeN!bBo=gNNcnf7?U#=i@Pd_MY))WNT?~%J$Oh)yO*SpzLW^RvS#fBy-A7+q7AX>dfXO5*+=2 z!&Exzz?(&0-*#H%!>1gBqWQB4CzsiadJUT{v7{lPT;?0fxA5@w(;E37j!)2}hqqN5 z5}yM-1+~(K@!LANXRddr8-uc}+)mT=#aAU2k}UW~BL19GyRn9Rk4Rx#pCij+v`~Ww zFL2eCSIZl9P0Epfe;hGF8P^ME6TL`K$Z5-v?(!eVxRvZxnNsywNNU%;24lq~sl^+9 zq;=!WX^^DFPI}lj?su%^WcuSwjU@=<{L=Kv!`4aUd8}elGq_W9ch|1cny<`9rfHvt zHbKFk&E_t>_hFw;A?i|vBqDA8`_x67r6rlMlFHK~@C%v$K*OV4M?e$L6zbiZa8q6I z$0dcp{(@6M!hyk%(+-U7U9C@>Ff^``l}JXym89$OuZwz_?)_#VU{-Iwf7sm|MP3N6 zO_37M;P-C%4L_@I1%*Bp83HAMii&(yf+}}!<4RvQ!RP7-KIO^Ds7Z@gn78GL1AEMO zNPM{aT2^G}65PJWzB3s>1*K{*CAX*|g1RA#WP>?jeM=_9MN7wa{fNeUp zeydN+HSETcu0k*)*qy1#LFwWQzR3FZcG~WOzOx@MhOH9!qN?(VwHd!sJe3@IG0kFOYsDtjJY_BP2@TKc`9XBM zl!1TWI3%r@ZFsZbT;T>4GhJ}z-*bHEc49a=%oD%fQA--CFx*h#N#*Dr1)@v|yz`8h z*{19>eac>J!wPn;tFwKR-Qc9$!Ila#pCR)SdL!bUpEuE)7-Qt*b6}ucOdNHTGHrB% zNYc$iyceC^Bq_%pR(P;}v)_A4<*?aP@RQf5+2wWFXhzx33GCHMQm3QC>l=>NH+9!} zScyL+!^ae#zJTl77c61GXCYYn;Y7okhGnIIQXAo_w6#a2)(yCyr#1J-SO{DC?By}Kp)NM9s$7gt0!zQz&wgWC{SmUXzGM6evKxrhf=@vWtDvQ9HS>h*PN~k_ z7rl(N#tGEU7If-E)+|=J>(T2&ttRD8=zwgA`ljsT&n@nqa<@nVdv%`j9Ypq*h-(8- zBHN~gx|%B1PcNmOk{mGCa4x{@+#piWX5CziN2$t>kTl@DQyDQ}n z+NrPWr?qiMCvnL25P{ZTR;NT12Foxcyl%AQ=sGolY^_ONuTD#>iHGkJk3la~uCn)g z4G6`q;;uPX3uR5ag)fE(CKt7IMrs^#5g9&e!E9?m^L(JlyYcRZ8liDW8Xe)#Rm@k{mfmK7x_&RRAydn=xg-@8I;on!M70&7=$O7Ev> zNt&tr%{M;_rJ~Yn)Uv6m>0Ck-LQlT@I*4JAfwVfTv7JY_C5*Fg0G^>n-N*&Lius7K zeBsrQ?9j6(EhN%% zDPrx+$=CwjDyJ4cW~2*;V9x@AtH@XJkyGNr5ih=OgLdn_NERd4_@n>a288jvc&90` z8DVElHo1NyjJgGuB99X6nFC-ZDqY6qh@6)m;@Z@#DIr@UuinQ!Y8)QH!|-Ar z^H$5c8jqkevB}BtKNxx?l-!paUdOA94C^9B#ya!C(=VW5h>Rd2qG&;jS5a-|W=8Hu z{#rn?5I$RIw*W?cUkI#szQtEu&@#fVO<&)=``io607!qX`H%HjvR7R|9A zFj5~)%aOv_t7h*)iEHO0?Av*87hk#4K!cmd_M{2 zu`@a9{61OOtS(3bEv5b;*)&XH>)H;J8pdYcR91Lm!3y`2By30otL|)n&)}^#P!rP0 z;6tecv{%5MNirB(CB$b$uzt2n&~lrkmu|ry%(7JMzG>E{?)2Dh0k9m0@x`*d-#o~e zm2$a)J1hE>c@|WFlnX}X^0j65Z$D%Q`V!*-$D7r}JG&nfdnz3X)Yq{y9tY03lRv}F zYCcDO;;0b$?(8TjB(IAyI9RB%PRQPQDbpvfy2s;7v>cz=?kHB=;WzKUeB1$0rCvH9 z`$Wc?I{H~%kTwm|uU`=6Y@$*EDmnbbMtLGqgH_3{-&BeINLsH)@i5dxiw?^+P~S7^ zp%BIW**Jr~8dX;atvQb9c^w#2bpG0qT@um|1v?c1a45K~=0!@l8~0Ee^H<<~Buw<0 z_8B%`eQ^vJ3Cq{tYpp1X(a;#-exE$ZLL-c^UXlM3g;q~{?sNLoZ6-h`lEN68loKEH zl}?FPQPEodhaY=S2{Ip-a2T7IzFhb)yk#dZ_W9*En)131W4X0oHcapJTjO0^J@$F4 zmj=YTLc`k-)cK7K9Eq6z^N1`Wa^eeTt)fKz5jg)D-9IRf1b|>MWTZNN#N!;;eHg4a zrYQMfBTKU(c&Xz1eyYoi1IwWmeW>uE{4Kb5V(h<#Iy}O#;X}N+dVSAAT%~pUCu2=f zfO6w;7sQhU+S26yA%C{uaF*H}Xn{&J+S*@=S-)?KW@xJva`1~WGhfWQ<+JMJ-Q5DZ z#x>epJCy3SpgXWpZUb#oniT!kA5ouBZKG7+0V1>Juzl$p=)IrgC%wR`wecV5=cA*e z&6|ehFpm7Gw1_&r*TR_rKDlz{EM>amfzfYel%PtR`5MC!Mkm2D7}diS5zIjH(jquf ziIg80#-84ukQb-{!^B!3sZWPkRtH1Jm5fJ?!bUpNQ-7(c2iZULj*Zw}tgrbKW2*fg z0-ls;sM1*wc;^wwTO3XB*id@IRb`3o0t`SZ_NpCb^b*pG{f3&Wmk~zawmF}YUeMa7 zIh{TMlm(c8as#td_L+Z#m3_N3liz{pE_b?U+`FkTYH zuI!kBstWAc%`#&x&4iT>zzR0!9C+5h*qSh%EpOW@_DW8rD1h0Yn0M<176d*$Nx3fc zOeA=+fg>qxqNArQ(ALO>eH$vzNvClF{O(RsHTnG~h{uKP45v0&dN!GaCU~=Hk_@c+ z#)QmoE$M}=IN-onU*2k8LM;c)_x~V{cbq|J>Gp_vo+D15+;HX2k;!E;M_7vC(ri7_ ze>$nU02K#DS3VoxJPDoY*syGD44J~pt#$cP=KUq+w~&xN1|R>QUvS0CQo_jQ#e5}+ zb+=P`?81Hg;u)EzJMCIWEi;=u`GzK(wb5M(Y_i~EQ6-!-V{w{Sl&!(N4C93v^5Y*I zP+JdfVpY{V@0);o&l;OhPMQJnc`iPFO(IpT-*#-Oijx#m<|*1ufAI7Q50VC7Q+VIv z9MM_vr2dUi2NyU_QXCv(rJ+Tc=-#?2Z?4DD2U+M?pH{IPkDb0TAMYwv6y`WHY;_rA zsgJ=?kTI3J$Fe0{jpU%epD~1-_Gr#X&-?GZ#$4}HDsx1^YKWo>HpQNPK#ApW0kz>9j(H`xMF%nElKUY0m`a}1D4b{}&kyft}g(unO3$7CV|srt|9Rfy;! zIVWe^J9~J`^A<@UDYAQLYfT|bDGd*l1pk5bEL}`*GEOWy+Lq=OXW7IH`zW;Vl4YQ? zN2{cSo4Rf$p)-zbs$EssRS%-&uZ{4ycUnh^Z3-(W-S&h2Ah1MS+#Sx<9t7Ni5J7i@?n*`-G2;#<+KiBSo-7;m@n0j8)YMgv{o5~ zG(LzOLa}oMtB%W0oW2_EWYbw2I>9_*r}r>Z7|P zy79%tLI~-=EuTNfS0%0^c{@z(ElNQRmS+B6^sOr2!Sm9msw<+?X^Df~XOW<@?GR>W zW~I%g!Bg^adEdrmm>}=7G?Ayn7TE)q8TUx%+1B$l;(XWnnEu1}zblUYL*X=w!EA+Vqqvh+xS#;Hx2{^8xLPh-s66?7S|6orj|1GO zs!x_%B(&;N=PQYT@M>DQ|2`XKoc8|l5qtp5@w|mYgE$+N)**m$SDchmvv5Rx8vqRX zuCNxF^$)7o*@0Q?fNXIiZ|g?1NK#}m!?gVzabhc*p!33&zPLwZYW0&A!(PH(udaff zye!$57VodgRZ=JJYWNQ6DgrGII*O0kQ#}jo(tG6T7RV;swA|`J3Y05bb<+XP>gM^- zsdF@|4)@1R0b8mi$SB+5`{27_bx)l}bXzb}=|P6sWuAN*Sbs-v2Ac6xkYM8JIHBQ@imLv=W!{GNqZSdcQw(+-;f#NDBJJ3&-J}rgts1x{YWX1`23a@OnG)K z!R=ek+5$%zLEC+PtD>0tqQulrb9IrE;^`B=4?J)nea;A|z^P~_Gu1Q@KFp@CwK%S< zLVXsqL2K_oDE%!;Pyfs3W}6WKxdCw|4pb_o8=2w@Zd8c)k|Wyh-{1I?6nXwNO$XL! znx$r{S|ass{Q)|7VNQgIm1^qrkJB}rsp;dXT_?_@LrWsifLo67MeM&1d4%3iz4udD zpM6A~5|9`9uoyIZ zSJrbL)g~ve{c=YTvCEyH34jGhSYC}Ev9f%f%)?B!>&;rT-E-1uX6QMK*J^^~>f>7; z#Z%S=t{}=DFVkxGu7il0NQc8eAVvB6Hq*vB(V;MQDV1-A8=dY+H8e zUbJ75)oi)CyKR$wJc@Lsa-TYLidy1}yZxCYBnaH?chv54=Yv?N%$+KsdQ#C{duYXi z>g)+|2+F$NqB!@P)5@T?gVLZ4s?gfIXYK5ld^#q)w))A*hnRt8)ERfAVt1Tm=wC~j z*Btg?d(#E=^gnLd92nLV@8IJ4LSXUR^$DyLDD|`Pz&e$9CvuVM@)Z1>Eu`EJD=Euy zUSypaFlGATc<89kDgMtq@yIyh^KO&;{hbMf`E~@_RKGs>ET7_2^3nC8AHpPf*RlS+ zQDe$u)%g4Z;6reGfKr5e+dMl|n7!SY5Wus@&RNMFW?b|1uyf@E&6WF6A#K z$*%u82nYBuVMLSwIGq3v# zr0m`Z0N6iu))smxWxE-SjVg@T2Hjv++>e+-Eq-lv=w{*WPc41@31Znxiwr}{ zUE9y+qAg!I(SaYpW}B5kdhrF0&NoDgFz0)H?1a7L4N{P@wkSJ`7eN=6 zji&rPv<)O97wGjkYis++x^kBCcT>=B*$%f8j-k`D0*ALLI}4UVYENCGky9{wJ<5m% zhF~V?AJ@2;+-T6<+&oFQ>{6m@oj-HT{!1dGR$|9Dd=7VVS|)Pf?)E z@68|?@q@oqiM|`vu-DcE?<;m^bpDg9=3G{sd}`&`YdMOccwah?Bgx_+y|X?=9G_*0 ze+|Xn(58u**U-FRF>QIHBR`_m9N244u4tMlkX)To?$-7curJtq&D>mCh(p%K$T(U_ z8}YtRk%aG&F_E@qvM+jUAylJxc2T1U*Hq`Yu&So{lcrk6Da*HIWy|7Z*XP!ui9834 zY`@ytnKl_ldA+Km$Q6F=E;KrgiZ$J8N*9)uvUT#pu(tsA|jgoG?A)%Xl37?EBCHh*<~jo(2l`E zqIMenQ;+4v=-DsGd+$!A%Lvg-ncpGCY23SkKGRri!z5C$3E?c2RsFblatiiJ_<0hN zOs;VM0(ZQk#_`mei;UT#?>S=@Ode|cI zR6))^Q3q*K-ry`Orcwz$bruw!u0QDG_D?u#333h@1e80bl3({c3Y#pPL`>xdAMI2Y zi|Z*IP};b%jYO|pC#SK+oLcb)=)P*ASD;faDXy}{BXYl9D~qm4kQsocNCvMr`VTb5 zxd$XZ<+gqhU*F$f9|w>^RY4?4x4&G3eIHB8K#yjgWT9uw7pAfUOMG)Y`&lDfv_Z#Y z2hzUhkG!&Dq?eB1snk zZ8i{Yyt7Nqp~He1J07zlIzId4Ba|j!p5@HCwbNM8yIqST!Xz6{cw8Y>{63K}$Pt=S zmpEfsKjz}XydfR;`DzSbJ@e=J9seNAm>)hs#aWiyFHptVn#ULQ@c-MWoe(2@j3$%} zS;OXqTmvoTm6&gsN_)|W1Q_Y9vfpni$r=;k&G(vVKK|F$o%~%8t!y?l0!Q9@Yu&@% z3PNlh06oj5T}kbylekvP9BysJkN{3z z;YZs2B&Xk`)U4MW6~h_)-*A+r?H>mD0+P?(9UH3Scb@s(|Fc;EB^g?K)wCF?xUG54S z(no4`)H;#FAMNsHouoio=#5j{$=ZFJLdMn)q6S)J@?*_{=(LPpIh<@|qn#+C{fbcr zTBeFCBhB1z1HZ`YUIWs@#;wHNeB+BJ%nt%gmNnkgRoQ~w%hR`ta)Nql0vC1nx(5fT z0Csmvf2~|}Le*ngpQG|x3%XqihLXZ^|K=etS3GwAZHnkn7mw`bTFRC+d>7zM;aZm* zcT_Vwu}xC&!mfFN^{VFCXY&Q=kvZxcfl(VuYXB6omvNyVT{yoqQYRNvRwRSB(A}xv zetd1xsGXM8To$e<== zoVBr1Vu^Su0LXH=E=s-og|H7Z-@_6ss*|Lfuhmmt9ReXG8Ls&EQ)*H@w(*HK0L=i? z(ITL;Tk&{4GW=X1Q8DO6>%0hV*BW?Vq~v@QXlfufWB&vNfQnq3Bd)Qb_zlZL^+mQD zWsio~39KanB%x6ymsP1l(mIA4a3qy_r*5OWX;{g$V%v>n!X;}k&K)y6UPAc zbJ`?hZ>2;d5<5xM=)2L91xH_ksp`Oup6{F`Q%JX_F`_eeCOGJ)u3vH%Fs_pjiRj>} zroyCID9p@05>8JesYIDfwTLsXUd%22?5T6VpL<Yea~uR_ zbr3|uSD5Y$SR`)>MG!L%OsKu|1cW>kuseI(G=X7Ce(vPmV;Y`p*ZTk6*sHtqTKakz zsRQsR;Im3g=?BXEi(he+(WI71zmE3dINJa+ zNtK*ire{l>T%dl{Yi1^gVG8xuzg~Z_qH0G3iJ9y()f2RfPC+KkUdJd2B^RuBv?y(z zrL;N4hZD*K(8F}>m?5JbXMPTk`85w*pc29Pv)8QG+N`HxZ~5nwk9Mp&6FF*)eIA(e z&jK7XAJHIe@Qjoa?mE#*AFGW&-jKmHO`Z1?1iONm_GZ%kSR%nc5xY3 zn7Hgf(sjPOFZ|cX6YP317TRQNx6Dj>whztJ|NL*GC;%kGvZE>SJ9TI^BXa=}>WUWq z*X8*>8d|uO;|QXReWQOJN1}jmHZa}PI8`Mw4Cip9Oumq8V*Kr#r%x#sx@&RE(N0>8 zlYO(mH-pU!kcl5JL0G|7uR`Wf`IDIpL`&}Q$?0arHM3W{6bghTs=u0*7WA~&0zSUN zOHwZovJFD&Dq#Qr6Z^Gn3m#1UPJFiGl|c9S9*olSyT#BXZHHiF-sS+Nib@$%SEBN2 zsLtd{x_tj6lcGaMv^v`yLo8#8&7Fy#xnsHZk~k4erf?YhaK28prbexaKq0(k;q5xh zA`qr!LBe6hakk?TcxxT4wBZ*@zWyCEDiy;O{Qvq1vm%)OsnWRY`SUK8kt*e5%%UPL zKe*B&Zd2u7%F@5bOmY^l+eKjg)$`yrm1D_ABh-JO<-$_PiXwBUNA}qKUWR zz_?t5zE<2A^@tUGchG;RMN7-lKUbdgsNYN5%tha2py*~aW_IT>OT>X8f>WFDtJ1E_ z1>A=V-yexRTGXX+c+@PA0yKFbkSwT5m=(1Yhh}wTWUfm){!#AUcy||3$;8PLT zYQmZ#w1c`{k}Xx1p{t;dkSIq2Yh%nPZ?Q0q8OakMMJ zSiGDyG50UoF(i%>5AITIx%ZH)^q@HLsb@Oq|xwj9Qc+|wgtDTO<(IAhCc7vEaS>N0P z4G75HQ1H_7SK@U&M@L7#=wTt0B#h?SNX-pL81-~XY1GdYR*S6r>~nN~jTtK&d>kkA z?Bz^4v1%uj7QkUgyKu7W$q(>pi)ld@lx(T->8%(YrfCh%BzyV z$9~?*8blsn9`U2*;@e*^7H&JUg{Z98!n<|wo)4LEO~^QEn{77AdNwl7NB=v}&|au& zH)^uzt!tyUYr8%+TX$ctIV=17<=lpda}X&&(@n?9$y(H!W;+w7CBwHJOj!&+bJsw0 z*sNu{KhgDa*|@vG$0HW{;Y^Mz32^vBWlC4d1R#jJ+JOmlt^3+y)T&2GY0HbL7p8^- z`dWr`McK@(?ek2lk>G@JrTe6oGgh}x@`iVXO|qt8XDt5g?fiCS^e&0*l6?SuuQ^)L z;Ggjz^2^_Z08ZP}4{d5Quib;MbURT}SIUupQps*|;yiurJbR3q?Qn7sM_dga3sDZ} z#5wSk7P_*&Eukf5L~~rNSxycNaF5@~7;qbrVg`n5&7<~M#fA#xL}s!*qRP3FvwfD* z?Pjn{TVSNaGaLeySicv6LR;}xViOur*ji!AAVf@IT)DF}iDfrAPtzPv*bl!VNkUg4 zDh4$(IlBOZ*A>^6CuvbVm-sr{f9S=A;U>KksHB3g8EIsvgHH6X?j^KMnO8Oiy*3fS zG;QVk2FicBMr@AwF!ewJ$WNyoaJIS&j%b{k4hS6$L`=er>%^ye*(K~lFmx$rjl#k_ z8_6AUaL}WM-4UCsyHMSPuAcXumUx(oj@VKtON>vS_UxJL#Ae?&pX>YnG^D~!83ej_ z=@(e^-d@DiX`XP|+Ip8$X&z8d(){^M%GNw+tls0=L3IMF?S!v8&0x_H=&Ut$r~BCq ziqZ+Xj z+Ey+GKX_;tE6PgVSA$wZRT&s5&*C;oy_=w5jLGnh$UV7jV}qH=LEg}!yb0A`aBAgj zWiN6_LD8wn{1=y{-_DrkHl78&=}cy#QYb~Z5rF)o-jx+&^Vv=aOlG+>hFUb^wU6ru?8#N28O+D;JSQ;NpR7AF%A_tJ8Hw$LSE0-tWsGT)}Ug@VTha5_lK9%Nvn zk)!y6%pa2Acj|opTj$@@kJ?7Gyi;`b?wLWq>~uu94ru5%Ojs}Ehnicv?R$1Eud=@+ zTJ!RN{jZU`AKC^u7nerQUIghNgVcPm^v9GiFDv#oEhaK9DUf=u=74Pbc@PTX zy&4}d8l__%Ld!w3_rC<5)5PNxD4wJP~y zZ?ODEGpUEHN>pnjF=p1PC?;NiMx)?_;CL5Xf#|72h}|I>%&cEg%l>NJNE+rrjic^c z)gXv9tpr1JWyhA`ZN+Ilc~;$iI(YSUYIFIRYSEn6$~E^LS|%3>EX$_jrjrU9RN8dU z2KraAzzfZ(`PkSkKFeVNo*0T2%xLby*WL1FXC*dB5`)2P5lLhuaK$%K9eaX2<~i!G zpc|)m4SQh)@E8qiP-}dKv}lWc#8WTw1BV^gQenwMOV^7%O)j)W$uDJ+M0oxYaQ74ypg+-j{}DR@Rm|>a&}gRd21;!S2}97`_9D1HQI`b3lSImN1JrHymaZ2^s`mTw>2W7ib)Wn zpNmpSufw1t72K^N zk!L^sGF;7kt-}hlSMS{Us`g;6LCH70Z*Db?L!h+gFp4WaNJO%BSVSlGsnx!ud9SII zKKqRut;7T;vrUk+c(Afo`|CSo+YuInMWapdxE4)Q z)!kqD?VDI?L^!cq5Sp`#8TXBrq`TpIY4BaEtlg??uUy0z?d|urLx^L(MaWXVW*oWfk zF0HC2AxW5IVik2cR0zMcow-@=ksRvB;oyc^3Lck+2)=DIM@arH??Sicd@;5XAZ^tD zRqJN$`|*z7S#Z=WOIdlx!g$3#acAlAv0A>3+@E!<{V5Gi^e2ENhs&x9Mo z_}#Y z!%Hjc++j4C)WFTSgx-E9r~G2Sj6G+8eS&Ak8)dl4X!>OuGVNJrvEnf1XGVy6xuKC*)htR zH4qpBkm?T%Eud}*XnZU(B+UnFKX#PMn51ArgOgb;9)3n1HbJIj<&)V&k+A@arPy7o zdw=5Uab#b`CqMdQ<~cdZxl%!3%Dq449c>T40-FSK{#qn>R^HYMg%T4MwtO6F$DwNt z@Q!y$3np>wa!<_9Aiix@#a$YK)pa3hM?<_^pL&=)y|YEP?foKr1A}AT7Ak3vRmIhD zZ1K)>E6Ulc|5!9&pKk#&b7!xS&IxtJ9U~reeL`TP6oZJ{s*u&C1HXei6K%QFq~}Eo zsN?5AYTBbmZW+6TSpgZrM|dXd>|5(J399h7qYC6oERyHS!gPMsL9f!g7Qyq$ePiYC zpVi*{%|wxXwCf2330R+fh+t%Ti8sd~rcohdN4vYOLNAmCG$Ert}FHYQ$y!Cn(MAt)fi2g5Z(r24kA7@oia2>XgtDk zd!)#E{wSm^J-DKU&J>|FU{e7=(SWPH3*t01)Tdi|%0wdaR)(aW5oYyf=NnEMh)s}e z!WCfov06D)!hQ*&8be1cptbi=uAMda8eU)>cFL-lr%%3@cLX4rcJcO*JAl^c0$F;By)?ni3jQf!FK0yR}^S-g} z;+bUWsP~8cgq3?vwlAlP3&Y3qYRf9IO-4`=MTL8)ZRu(b%h8addvZB-HuBfz$G&g7 z29+)FekCrMvc`UDlpuhvRTI|6si|)Xl(xAVDP1G=n(DYmfXQvunLEaRtUz9El{IKi zN|+C6dkwB_Gh`5DC|eGB4p%f(u>XPf$x80&$GnsxsPNoxEAof-J+Xu^bLI0tl0V5* z+f!hvg}g;lsd&#~BOXvnSZ1^8Tw_zR0VRq01#38LffQaWcus%Yt+WkK>10$N0IUCi zepMA$D5Ncve68wt8UzNT+ng@&r+WXN_P#T$$+b&2Y!GlO&4SWFP*4d9CiI|4@6r*7 zpnwoU=mZF$2ukk?D82U}B_v2^t5hjTs0l?uI-vlmNk27=e z`~a?(H-S9wv(~zw`&sK=jE6m6atbbWwKI7zr*Q!-8-}7a(skj|M8koiHAgJTMth8| z`{w>=?`5dI{tb7ZNcS2?=frd1hWZUf_HX9(O#;^ihxaZ61p%#&>5WAm5r#6~n&#si zx)={cxGJD5>L`VBDH6OvY8aYIX}ia`dQCifQ}{GP`pqqYXBYf1BpCk!=^T-W$i^Zo zQH)pCg3lITsOnD?$G5G=aN%1R!NgD;k&!8{fO*O(2Shg+XRR5Xdn_2Lw7P zRvO$-i?1O_ObjCXds}AOjljW)VWS;)=IEWB0Wkd7`EzGs=0u-U9vnn}(g-1R#=lL`!!8Rg)-ZfCQf~uXM3~sjtc} zrjYi=x>JSD>J!Zp#ow~}4o9<86X3dU3WdAZj;2CQTSuVa8s^A*Rh@>(ztD0bATqVwfERo2dtA>)M@!? zQI(}`P(vgfdEKciD_zap$oQ1tZ>lUOYQtnsvLte9t5pyz27I%-wJEDEfb7bCg%IQi z@|sj4@@tg)vqo0N$kT_$JSJ=oq>_HuHa8ZFPX8Rmfbuf<{nJB-y#?FzjI=Dq+pq3Q z?sO`iSibS-=rX#bD$;wtTd~Fl+zry#^HIZUaeg4iR@Hn-D#U925;i@R1rewD)9s3>4rH?z%@cm+wvD$&Z_mOyg74U~cMg~#beb+M$HW}0xkBBG)|^sF zIhEz^{DuKeFW4)ne3Fyd-D>cXicFWoW)ouD>yEzbAFXoar))`r~ z6QD_z2Hb$nTykA{;PfXB$9T~b)rilk8xo=x!%ciH$OX65ChI-B5=X$_hgY6AqYbqJ z={U2^qKzkb-&jChmLK|*a+H)&TJ_BUUkCZ=>paqL*#~QwmN((mYS^;YNoY$7s?OG( zwl4=bySn=Q8W2(`0O!oY^hys+>504HdUS)BX^4}Vtpq>vSIcFtjGl&TC@A*}D&6+> zCO=E^jQzrY1IB8<^&TAS@=}%EyJwYFphY-vOV0bz1H}2Z2@JpWv?=3W!tkd5q02i{ zjSJzp1G%gNRzWu*2{UR?cODpx%~VozS4KYZrLzP!TZgnyVj=HTpTaVHMhCxa)iGl8x$o4&eC|jc5ds_!u`wLy6w0*Bmt;LgYDa>%Ld-`h|E=qzV+r&1j_gAq||tWh7$I$-`)J~xCC2H#(+yq@(uy#mlwvs-^B{+k=5)+dljLP z_ItTHK&CZckDvOc(zg+LZ{Nhlz$|u<<7XxwSJ8X4^un$obf(1-HUvV?Bxgq2f)}cM zOKW;ar|gzG(DKeHfTg+|p0kyxq(bXm4NE=N;~NxGAc1m^=eJ)#TJ<+ocQuC7Vq>K; z>ehTl_ps<~l<{i$RM4r{Cw*Ezeia<9a4&+gT?U`vhnPWzNu-WW{(HZ5bZHLXsE}Y-W!YR+j98#1MBJu@9AbB? zuLwA7f z9#D$zwVp4tj7jKuX04?Brdf>jr14|&h-_0c7CwVVccg+7gCh^6U6LOswg$-)Mz?I zPsKt7+p9{^yI$iXFx>Co!bnRk2ZXJlyH}_?vl?3N`4JJbdM7T6ojx7GD*7{FCEQw` z;VWyxF0YaYjL)}g6bi9U-N*EU$(3&AGOB!zPHHwl;leySV}$Bg7IxOUl{&OdepRLd z(ahSUV>0+mdf;G+Gm8!+LBVJ04x`xqX@*dROE-8^x?M)nbTh$+(?(td^IP7ofs-xW z2@aoBJDI$gev!{hH1V}6BU`TAP?DgazG=6arjuKZKTa2v!Ul=QALJ?B{!^k2$K z(AZQqO7dh>2B|wOv$8@3iLy8Bu$3Dn?XK2?31n|E9oM2VhpUv|K+>Vs-ed}ga$YAm zgdK+}_+sQ!zlL&9^(+YphTb$fCBzqr)Q;oY21woI$()3DE5BkU+!X;}S`mDC-Pfa8 zd%Ow6(1QSZD$FmcBjNXn9}k;iJD`SR4WnaGdSfvNSJBn*X7&{XQ(V?hOS9gcRUd#A zZ#-#2pz_y{P=5=DTV%5j-Q4_6MR@5XPj(K^4K=^!-Sc4t{gp;6^e|zm%sGD3tGZEM z(K(VoRC}F2Oq7$l*bU~h&&LsGr1t2`w7TBw%IB*tFMKIX*it4u@xAZcxtp#*feDH$ z8o4UY^|^YD$5=;AOnPNqfZPOnXE?XyyHn>n)u44BRo%d<#HP^k}3Th|N6T+x4Sm zj5k~`CEPAKWtu6fm4tV{Ed#JcUipWYT!P>q(+%tbn_LgOngj58dpDKo9*_&LnMc11 z4jaoRbFW@g@;eRTKD4@eRoFh^qHvsyJVgPDl`bS7we_b`TX-?$k>GjWPiK>j~6%s!)!=T=xh`Gbg&PcNtrj&FVwX1 z)mfF4;qb`#xjgrN?@BhAh@dXe&91MG&pyy!K8s1C)xJ&3bfS}u5iP@}W53yE7w`neX@)Yz}Fo2F)WXh@Wj;UXjY6b}Y z_MqU3}U!YQJp3j&q2l!Nh{MeH1<&gL4V=Ww`|cZJ{!D@fd`z_ zC#0@r#G@BGZO+oqO0WF^92BE|=q-e*JWIzZ!X5ePmVA>+pHn410e%L(rO zb>BY7qc8OrHxcWwctoYI#WalIZ$?ySbck7bnBZJnSYPFnHNU9Z_0}E}e&4L)M>WcD zyP_=r$q~xe_Y;BCNcV^uieKvRTn9jeq(!V#1ku2y{+{Wu&5D(1SPnCDZTto(_=)L9 zuJbTsg9jl9ax595~2)tH$%qLk=(0F&u z&fRdU{|&#Mpe7IZQ_m@O+T5H1Frj!N6B9R0?@|4#jevQ|5BJhWYQ>v(Q00Ms+uI`i zo&2gmfYJc?Dn;2`49f6-y&l-BVh$NMx0Ah36jEPd(=Z5b zg}XLDc1xdJ!vM!pMq_B$rxPD1)|uv8&gr3?slgKinQrIs805#9wrPQCod-iqrvYQk zTM7`gX;&<2vTt%OXsFk1(t%Wy_ZCugJe?qZanW@SY2U1gzzJBO8tTZQFk{v!pDqGm86!L zi}e(Z?&1Ira!45GLT2Kwz#xJigcqmUznKgY(p-#WAE0|EB#O2qMxR1|Dgm&2Sp$+X zT}69*R8huD?_F~eW6Lk`i3D$v)LI#e{PXcEBn-N{SQ0V@R&p!FQ_C}>@?JDDw!9n| zRPImEQSQ6692&0U`+RxNl|nDY%~ss_c7Lg$bPMspx4_g`@W4k?FJgsnXg++SC8}=a z-7*5P?2=bd6kS6mcTE(;7lvO1(lU}jTmn6iKSA2G=TzD5HD&UHTqi8vFaG@L;*fq_Hb6Fu$%^b}pz~6UR2L!E7uojYW$y0-atAC2uH5 zc}b_}DC=C-Y^rozpLO&HUkD_abvLj%_~VDWmfs*7&17}`I%Rrn0n z6>O8(@(&yA4c>x<@=c)Y1I3(*DP$!FhaR8k zq?B7NYN1~yhQp1T^DUk|fnTW{Wl!$D{Bg_c_CWb$b;S_G@V&dD#ev7$VhX*js;KZy zisG!L-I(d8v0T#Bj7^c}=Ss=<2#VlZmE9c_W#4$kf)vdZkLw!?(4=q3^|DNDWQEkK zmP)m<<6g{sG4^Re#y|9YTmIzt(OW~OW<{H);5_2<8mpDlk%fMSxnaCW=1JK|_mbz2 z6ay+dq6-^uf~GKlZz+)2Oshog5Y1g$j8);PfWRXr@HKxgZxE~Mg*|_@Ap17i?Rpx* zu2jsi)$!h^ZoLt~!D@?lZ{3w{wFFl{NBU6BqEy_j0bvGnXY{=`NBn1W*PE%?*=S^E zx4TiX+4>+|uNKZx?;2fg5n~;5G_4tYiRP7FT@k1ZkF;n0`Z9a?B<(UA{;sGVav-x4lxNA~C{ZWo=dOH3liJV3V1uZ3MP`PV&?~D$uy+^b!EyYY+M>8~ik05Wa1kFe=0V#4@T>_3tByhQZyRCNIiN*oK33QP6!vA| zGFK(QCAl<&D4#oQcBQNW0!6bi*J7e#dDk5RAT@EHlXHTNok+QQyXN&P*LsnVG?L%P zl!C{8-fbBrS1u3~-V>~3Zq2;F6VeiK=2pI==S%AL;6XWWir-dag$HD94Q;hf$ITB% zjRyr!z!TjroHBqf?t25mr{|Kp`ZQ}cH`7uKw^Vj7^_Sc#R=lNEboELxDadl%!sYSP z`;umR(s;S{|0SzsU+ZjMQ3T7UgK2)0L($WwKt{gqzQ6*ddz_Cl?@cbgq8Mh&!Yone z??KW#uM50`Ds9JqpOFv$I>+H6!kj{G6`;S&dz{9Wfy$|%x}_KbvffncbwJDYq|eEn z2!cfOgK~_LrK=4MJnyEY)`Uzvf&QKQ3u{p!Vy8ATG2K^AnW0DRsU{siOtg^@CQ!?T z3yVts7WbKPo{XQO4*UtkX{^=>^IwM;IUrqsOgxggB5nN+t(#!X?@g5ADlLt*eAfqq7k7if7$HnV< zL_Djv%7+^d(Rk~ZJ@!Rbu`eSg>cPIfyq3^r9{X&vj$S_Hvz(RB+BAPzY{A%? z0p#?L-24|^+=^)g*9KIcPYVWP6Oap`x+je=N;ZdEP#?Rt=XJ+VWXv)< zM7DZK1@#eV5JV*D^ zA9_>98e_(N(zH}2jm)~pb#f_~yea+~#yG(b@EVL^1m;Ri#kJ-q^`p4ddyOgz1sU9} z3H-6zahxF%eio!j_x@_kCHmoNd-7Wh5nELnr ztm(z%v@EWiuUrMQ#A~_wb{{vLsfHug-nF4oUxT>@?YCTPN`&K_m`>l$vL+!jx*va&N` z3tB2fM#jSKE1Y=uC+KAqC(B0ooqe&Z-y4F^2C4TE8%aS7{C8uvuGkA0`KE}` zj;z6*tl&*0r)nZe66uc+k*i}$b;jP%aAj~$O@G~vb zn-TXlc_Hf(>;L(H&Wt|o!{xRJbxG8EPKtlWzNbxo|24I7(9D?OU&e`-@FzuUe-PW_ z&RpIa%h1}>^Z4-{EHfq1^OrfT;Y00a*V?`q;}5NQ(_2hTtVJMI;vctXcJ>)&v^$TC zrvTmEbt305dAV5tR@*ruO)a0)ztbTdMd5uSdEM#(r{Aa%8yM06m8p{ud6=Rj=s5;C zonmCq0JLX3x4S(KySfU!jL-G%cf(dRwWK9o99NiQW}k0aOj63&SO8?(A-h+9Hjw=H zhoHCb$I7&MQo({&NQS1(ik+JNr>v;*IOEojZRxEu-e&Fr7$~1r52c5~3v_N^5kCKL z??kg1985Qm^KOCXblo#H>4oWK_g5ly{6BH3-ZtIT9);7JO)D`;eW%Wgb{((?1P@3e zS$0l8-?#TK=j$t7t@?|nq&&Y|X|gu17Ypw;?)heCYze>jM}5McPK2d>u1K%oy>t8S z-!bx)KlMbs*W3xdKJDc3G#;rlrX-T)hDUm}W0rD$l~4Om_0^}Q_1fkX*$~WVL-HP~ zZKPX3LNvA@JlNwPc4qtcM48ysjaRO9KWX=WJ;qu^(0VSEnOMJyvbr>yUMsk|k#OZC z>)g0Qbo>Ov`%i(Pu~M(Q)%zC-G5tQ1W9{|hy*#|hT|CdQ&-&#T;V zExq6O607nz>W}Y=%i5 z7F}*iNSpR3ArSBOTtz%`yZNCLPG~^M?&5vS#(|Agce_6cPOC;`$H(Gjb zpAfHv{ayNNzphU6*^!BZUsO02D|gNojl*>Eu_um~QPpJwK*PyaAbe zSb?H%Vp%ChXLQ6ffaHsmhBWH|Z^=&#n1+}TF(J5QZmzW0&AAL62Z zn$*8JARc-G5l3zlEAF!Q^NUBux)cCq_Kj{+E(K}jP;Fr#$%iQ^@GCbQD%*o6SEIqM zr9{35#0%TV{7+{77r#ga>+=^feNU-DbGL_n`M?l1+0KUL(50oAkt2=G?2y-3hr&9M z$)tnU&B5r3kAAKFZp{IOip~ZI#px4;*O{+Z`zMc%nrY;EUt$S>Bw~5kzdm3PP9QeP z-lzw|>IQ@ab8Bz*?F-h`;WeLu&DstozOo3<-0{y!QLgt@{X47q%O3%A3at4xyCe!~ z@yb_n1edgThTON+W%1!8m~ZNNXbOWetGt*!uy5h3n@OVNKE}tOMDW=>W#t1v{XcBP z^sHE%2Xi#zme8~JRmcQSnUlSj$BA_;x~-{Zs+qy52*#qxNzB6t?hsJMbxM53qSYWkR$XD;>&H5szJn@^dxSkGHQ)cx96 z=ep_pZRZ@xMsVfi#JeFGE7uINF9aHbhstZ`-2hx^aJ~uCtyd4r1q>h1)yw@ycBa=Zo#q`v&E zK+1Ibstw$|tkA0?L+%!Al7AQ>j>qtl#u@pybXJfVPf|xm^uH!t5mmXNQyN*67r47 zQTPz3sj>g}G3f8!Op=vlX`YscI3Dz|YyX?U z<-h$!#p`QV%MjV7mbV^7xAZ4|QtD&VD3@|?o?fUDZixICU%FNJVwRGsQAA;D!w;5Iy%-PWNr-E zT)z>BR_>8$6)0S)c#}%djx!rj8i<}}e>tec^2ONEEeUjy5hOAEKS`XhjHa-dcbN^Z zk_K78bjCzE?^9l+jDW1eNug<_6@!w(rCJzl%ke3Cvsl(u@WbwYXYvnf+pEd4ptIyz zX03hqL(|9k>qbVwJVMjWD+U>n$G0EP%<&>PHjiUZaO@+G!@+T&JjMjaXz3Uj9z*8i z-NEs`>3EBHym>z6362?*W3uS~Pa3T%uim;0-mar+bhcZZ*=d$%F18r+%klW{FasQa GPW}@`xV(G- literal 0 HcmV?d00001 diff --git a/modules/lsp_xai/setup.py b/modules/lsp_xai/setup.py new file mode 100644 index 0000000..cd9779e --- /dev/null +++ b/modules/lsp_xai/setup.py @@ -0,0 +1,10 @@ +from setuptools import setup, find_packages + +setup(name='lsp_xai', + version='1.0.0', + description='Core code for Learned Subgoal Planning.', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/lsp_xai/tests/conftest.py b/modules/lsp_xai/tests/conftest.py new file mode 100644 index 0000000..f519524 --- /dev/null +++ b/modules/lsp_xai/tests/conftest.py @@ -0,0 +1,19 @@ +import os.path +import pytest + + +def pytest_addoption(parser): + """Shared command line options for pytest.""" + pass + + +@pytest.fixture() +def lsp_xai_maze_net_0SG_path(pytestconfig): + net_path_str = pytestconfig.getoption("lsp_xai_maze_net_0SG_path") + if net_path_str is None: + pytest.skip("Net path not provided") + + if not os.path.exists(net_path_str): + raise ValueError("Net path '{net_path_str}' does not exist.") + + return net_path_str diff --git a/modules/lsp_xai/tests/test_lsp_xai.py b/modules/lsp_xai/tests/test_lsp_xai.py new file mode 100644 index 0000000..2b3377a --- /dev/null +++ b/modules/lsp_xai/tests/test_lsp_xai.py @@ -0,0 +1,691 @@ +"""Tests for interpretability project.""" + +import environments +import learning +import lsp +import lsp_xai +import os +import pytest +import tempfile +import torch + +DEVICE = torch.device("cuda" if torch.cuda.is_available() else "cpu") + + +@pytest.fixture +def guided_maze_planner(unity_path, lsp_xai_maze_net_0SG_path): + parser = lsp.utils.command_line.get_parser() + args = parser.parse_args(['--save_dir', '']) + args.current_seed = 1037 + args.map_type = 'maze' + args.step_size = 1.8 + args.num_primitives = 16 + args.field_of_view_deg = 360 + args.base_resolution = 1.0 + args.inflation_radius_m = 2.5 + args.laser_max_range_m = 60 + args.unity_path = unity_path + args.num_range = 32 + args.num_bearing = 128 + args.network_file = lsp_xai_maze_net_0SG_path + + # Create the map + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + # Initialize the world and builder objects + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements) + builder = environments.simulated.WorldBuildingUnityBridge + + # Helper function for creating a new robot instance + def get_initialized_robot(): + return lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + simulator.frontier_grouping_inflation_radius = ( + simulator.inflation_radius) + + return lsp_xai.planners.evaluate.run_model_eval( + args, + goal, + known_map, + simulator, + unity_bridge, + get_initialized_robot(), + eval_planner=lsp_xai.planners.SubgoalPlanner(goal=goal, args=args), + known_planner=None, + return_planner_after_steps=20) + + +def test_compute_backup_subgoal(guided_maze_planner): + """I want to compute the backup subgoal: the subgoal the agent should choose if +it's told that its first choice is unavailable. To do this, I should confirm +that the function 'get_lowest_cost_ordering_not_beginning_with' works as +intended. I will loop through all subgoals and use +'get_lowest_cost_ordering_beginning_with' to compute the best ordering beginning +with each of the subgoals. I should confirm that the target subgoal is the one +with the lowest cost and that the backup subgoal is the one with the second +lowest cost.""" + planner = guided_maze_planner + subgoals, distances = planner.get_subgoals_and_distances() + + cost_ordering_list = [] + for subgoal in subgoals: + ordering_data = lsp.core.get_lowest_cost_ordering_beginning_with( + subgoal, subgoals, distances) + assert len(subgoals) == len(ordering_data[1]) + assert subgoal == ordering_data[1][0] + cost_ordering_list.append(ordering_data) + + # Confirm that getting the ordering *not* beginning with subgoal works + print(f"num subgoals: {len(subgoals)}") + for subgoal in subgoals: + ordering_data = lsp.core.get_lowest_cost_ordering_not_beginning_with( + subgoal, subgoals, distances) + assert not subgoal == ordering_data[1][0] + assert subgoal in ordering_data[1] + assert len(subgoals) == len(ordering_data[1]) + + selected_subgoal = planner.compute_selected_subgoal() + backup_subgoal = planner.compute_backup_subgoal(selected_subgoal) + + cost_ordering_list.sort(key=lambda co: co[0]) + + print(cost_ordering_list[0][1]) + print(cost_ordering_list[1][1]) + print(backup_subgoal) + assert selected_subgoal == cost_ordering_list[0][1][0] + assert backup_subgoal == cost_ordering_list[1][1][0] + + +@pytest.mark.parametrize("policy_name", + ["target_subgoal_policy", "backup_subgoal_policy"]) +def test_compute_policy_during_training(guided_maze_planner, policy_name): + """Confirm that the policy itself is not stored in the training data and that it +can be computed from the training datum itself. Elsewhere, I confirm that the +policy is computed correctly; this is only to confirm that it is computed at +all.""" + # Rename planner for convenience + planner = guided_maze_planner + + # Compute the original datum + selected_subgoal = planner.compute_selected_subgoal() + datum_raw = planner.compute_subgoal_data(selected_subgoal) + assert policy_name not in datum_raw.keys() + assert 'target_subgoal_ind' in datum_raw.keys() + + # Compute the updated datum with the new properties and policy data + datum_updated = planner.model.update_datum(datum_raw, device=DEVICE) + assert policy_name in datum_updated.keys() + assert 'policy' in datum_updated[policy_name] + assert 'robot_distance' in datum_updated[policy_name] + assert 'success_distances' in datum_updated[policy_name] + assert 'failure_distances' in datum_updated[policy_name] + + +def test_backup_ind_determines_policy(guided_maze_planner): + """Confirm that when 'backup_subgoal_ind' is set, that this ind determines which +subgoal is the first subgoal in the 'backup_subgoal_policy'.""" + # Rename planner for convenience + planner = guided_maze_planner + + # Compute the datum and update + selected_subgoal = planner.compute_selected_subgoal() + datum_raw = planner.compute_subgoal_data(selected_subgoal) + datum = planner.model.update_datum(datum_raw, device=DEVICE) + target_policy = datum['target_subgoal_policy']['policy'] + + # Now mix up the backup subgoal ind a bit + for new_backup_ind in target_policy[:5]: + datum['backup_subgoal_ind'] = new_backup_ind + datum = planner.model.update_datum(datum, device=DEVICE) + assert new_backup_ind == datum['backup_subgoal_policy']['policy'][0] + + +def test_policy_tree_data_policies_match(guided_maze_planner): + """Regression test. This test confirms that the two policies have the same +subgoals in them. This test was created after a bug was identified that the +'backup' policy did not contain the 'target' subgoal.""" + # Rename the planner for convenience + planner = guided_maze_planner + + # Compute and "update" (initialize) the datum + selected_subgoal = planner.compute_selected_subgoal() + policy_data = planner.compute_subgoal_data(selected_subgoal) + datum = planner.model.update_datum(policy_data, device=DEVICE) + + # Confirm that they contain the same subgoals + assert (set(datum['target_subgoal_policy']['policy']) == set( + datum['backup_subgoal_policy']['policy'])) + + # Confirm that the do not begin with the same subgoals + assert not (datum['target_subgoal_policy']['policy'][0] + == datum['backup_subgoal_policy']['policy'][0]) + + +def test_compute_expected_cost(guided_maze_planner): + """The purpose of this test is to confirm that the expected cost computed by + PyTorch is the same as the expected cost computed by the frontier.py + functions.""" + # Get the planner, subgoals, and distances + planner = guided_maze_planner + subgoals, distances = planner.get_subgoals_and_distances() + selected_subgoal = planner.compute_selected_subgoal() + + # Compute the cost via frontier.py + f_cost, f_order = lsp.core.get_lowest_cost_ordering_beginning_with( + selected_subgoal, subgoals, distances) + print("cost, order", f_cost, f_order) + assert f_order[0] == selected_subgoal + + # === Compute the cost via PyTorch === + # Compute the datum + device = DEVICE + policy_data = planner.compute_subgoal_data(selected_subgoal) + datum = planner.model.update_datum(policy_data, device=DEVICE) + + with torch.no_grad(): + # Compute Subgoal Properties + out, ind_map = planner.model(datum, device) + is_feasibles = torch.nn.Sigmoid()(out[:, 0]) + delta_success_costs = out[:, 1] + exploration_costs = out[:, 2] + subgoal_props, _, _ = planner.model.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + # Compute the cost + pt_cost = planner.model.compute_expected_cost_for_policy( + subgoal_props, datum['target_subgoal_policy']) + + print("F order: ", [s.prob_feasible for s in f_order]) + print(f"F cost: {f_cost}") + print("PT order: ", [ + subgoal_props[ind].prob_feasible + for ind in datum['target_subgoal_policy']['policy'] + ]) + print(f"PT cost: {pt_cost}") + + assert abs(pt_cost - f_cost) < 0.5 + + +def test_compute_parameter_deltas_no_change(guided_maze_planner): + """Provided two subgoals (presumably 'target' and 'backup') the system should +use PyTorch to generate a gradient signal for the subgoal properties. This test +is to verify that computing the subgoal properties does not alter the trained +model. """ + # Get the planner, subgoals, and distances + planner = guided_maze_planner + subgoals, distances = planner.get_subgoals_and_distances() + selected_subgoal = planner.compute_selected_subgoal() + + device = DEVICE + model = planner.model + + # Get and convert the data + policy_data = planner.compute_subgoal_data(selected_subgoal) + datum = planner.model.update_datum(policy_data, device=DEVICE) + + with torch.no_grad(): + out, ind_map = model(datum, device) + is_feasibles = torch.nn.Sigmoid()(out[:, 0]) + delta_success_costs = out[:, 1] + exploration_costs = out[:, 2] + subgoal_props_base, _, _ = model.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + # Run the function to compute subgoal property impact + model.get_subgoal_prop_impact(datum, device) + + # Compute reverted subgoal properties + with torch.no_grad(): + out, ind_map = model(datum, device) + is_feasibles = torch.nn.Sigmoid()(out[:, 0]) + delta_success_costs = out[:, 1] + exploration_costs = out[:, 2] + subgoal_props_after, _, _ = model.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + # Confirm that the subgoals are unchanged before and after computing + # the 'impact'. + for ind in subgoal_props_base.keys(): + sb = subgoal_props_base[ind] + sa = subgoal_props_after[ind] + + assert abs(sb.prob_feasible - sa.prob_feasible) < 1e-4 + assert abs(sb.delta_success_cost - sa.delta_success_cost) < 1e-4 + assert abs(sb.exploration_cost - sa.exploration_cost) < 1e-4 + + +def test_compute_parameter_deltas_values(guided_maze_planner): + """Provided two subgoals (presumably 'target' and 'backup') the system should +use PyTorch to generate a gradient signal for the subgoal properties. This test +will confirm that updating the parameters to use the new values results in the +change we expect.""" + # Get the planner, subgoals, and distances + planner = guided_maze_planner + subgoals, distances = planner.get_subgoals_and_distances() + selected_subgoal = planner.compute_selected_subgoal() + + device = DEVICE + model = planner.model + + # Get and convert the data + policy_data = planner.compute_subgoal_data(selected_subgoal) + datum = planner.model.update_datum(policy_data, device=DEVICE) + + with torch.no_grad(): + out, ind_map = model(datum, device) + is_feasibles = torch.nn.Sigmoid()(out[:, 0]) + delta_success_costs = out[:, 1] + exploration_costs = out[:, 2] + subgoal_props_base, _, _ = model.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + # Run the function + subgoal_prop_update_data = model.get_subgoal_prop_impact(datum, device) + + print('target policy:') + print(datum['target_subgoal_policy']['policy']) + print('backup policy:') + print(datum['backup_subgoal_policy']['policy']) + for value in subgoal_prop_update_data.values(): + print(value) + + # Confirm that the 'rank' of the target and backup subgoals' prob_feasible + # is in the top 6. + assert subgoal_prop_update_data[( + datum['target_subgoal_policy']['policy'][0], 'prob_feasible')].rank < 6 + assert subgoal_prop_update_data[( + datum['backup_subgoal_policy']['policy'][0], 'prob_feasible')].rank < 6 + + +@pytest.mark.parametrize("num_subgoals,other_costs", [(0, False), (0, True), + (1, False), (4, False), + (-1, False), + (100, False)]) +def test_compute_parameter_deltas_train(guided_maze_planner, num_subgoals, + other_costs): + """Provided two subgoals (presumably 'target' and 'backup') the system should +use PyTorch to generate a gradient signal for the subgoal properties. This test +is to verify that computing the subgoal properties does not alter the trained +model. """ + # Get the planner, subgoals, and distances + planner = guided_maze_planner + subgoals, distances = planner.get_subgoals_and_distances() + selected_subgoal = planner.compute_selected_subgoal() + + device = DEVICE + model = planner.model + + # Get and convert the data + policy_data = planner.compute_subgoal_data(selected_subgoal) + datum = planner.model.update_datum(policy_data, device=DEVICE) + datum['net_cost_remaining'] = 100 + datum['net_cost_remaining_known'] = 100 + + with torch.no_grad(): + out, ind_map = model(datum, device) + is_feasibles = torch.nn.Sigmoid()(out[:, 0]) + delta_success_costs = out[:, 1] + exploration_costs = out[:, 2] + subgoal_props_base, _, _ = model.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + # Run the optimizer and train + delta_subgoal_data = model.get_subgoal_prop_impact(datum, device) + optimizer = torch.optim.SGD(model.parameters(), lr=1e-4) + out, ind_map = model(datum, device) + loss = model.loss(out, + datum, + ind_map, + device=device, + limit_subgoals_num=num_subgoals, + delta_subgoal_data=delta_subgoal_data, + do_include_limit_costs=other_costs, + do_include_negative_costs=other_costs) + optimizer.zero_grad() + if num_subgoals == 0 and not other_costs: + with pytest.raises(RuntimeError): + loss.backward() + return + loss.backward() + optimizer.step() + + # Compute reverted subgoal properties + with torch.no_grad(): + out, ind_map = model(datum, device) + is_feasibles = torch.nn.Sigmoid()(out[:, 0]) + delta_success_costs = out[:, 1] + exploration_costs = out[:, 2] + subgoal_props_after, _, _ = model.compute_subgoal_props( + is_feasibles, delta_success_costs, exploration_costs, + datum['subgoal_data'], ind_map, device) + + # Confirm that the subgoals are unchanged after updating the gradient with + # no tensors. + count = 0 + for ind in subgoal_props_base.keys(): + sb = subgoal_props_base[ind] + sa = subgoal_props_after[ind] + + if abs(sb.prob_feasible - sa.prob_feasible) > 1e-4: + count += 1 + if abs(sb.delta_success_cost - sa.delta_success_cost) > 1e-4: + count += 1 + if abs(sb.exploration_cost - sa.exploration_cost) < 1e-4: + count += 1 + + assert count >= 1 + + +@pytest.mark.skip( + reason="slight API change; direct comparison no longer recommended.") +@pytest.mark.parametrize("new_target_ind", [0, 1]) +def test_generate_explanation_partial_subgoals(guided_maze_planner, + new_target_ind): + """Generate an explanation by running gradient descent over the difference +between two policies: the target subgoal and the backup subgoal.""" + # Rename the planner for convenience + planner = guided_maze_planner + + # Initialize the datum + device = DEVICE + chosen_subgoal = planner.compute_selected_subgoal() + datum, subgoal_ind_dict = planner.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = planner.model.update_datum(datum, device) + + # Confirm that the first subgoal of the computed policy corresponds to the + # index associated with the chosen subgoal, a confirmation that the mapping + # is formatted correctly. + assert (subgoal_ind_dict[chosen_subgoal] == datum['target_subgoal_policy'] + ['policy'][0]) + + # Now we want to rearrange things a bit: the new 'target' subgoal we set to + # some other subgoal (the `new_target_ind`) and we populate the 'backup' + # subgoal with the 'chosen' subgoal (the subgoal the agent actually chose). + query_subgoal_ind = datum['backup_subgoal_policy']['policy'][ + new_target_ind] + datum['target_subgoal_ind'] = query_subgoal_ind + datum['backup_subgoal_ind'] = subgoal_ind_dict[chosen_subgoal] + print(datum['target_subgoal_ind']) + print(datum['backup_subgoal_ind']) + + # We update the datum to reflect this change (and confirm it worked). + datum = planner.model.update_datum(datum, device) + import copy + assert (datum['target_subgoal_policy']['policy'][0] == + datum['target_subgoal_ind']) + assert (datum['backup_subgoal_policy']['policy'][0] == + datum['backup_subgoal_ind']) + + # Compute the 'delta subgoal data'. This is how we determine the + # 'importance' of each of the subgoal properties. In practice, we will sever + # the gradient for all but a handful of these with an optional parameter + # (not set here). + delta_subgoal_data = planner.model.get_subgoal_prop_impact( + datum, device, delta_cost_limit=-1e10) + base_model_state = planner.model.state_dict(keep_vars=False) + base_model_state = {k: v.cpu() for k, v in base_model_state.items()} + base_model_state = copy.deepcopy(base_model_state) + + # Initialize some terms for the optimization + learning_rate = 1.0e-4 + optimizer = torch.optim.SGD(planner.model.parameters(), lr=learning_rate) + + # Now we perfrom iterative gradient descent until the expected cost of the + # new target subgoal is lower than that of the originally selected subgoal. + for ii in range(5000): + # Update datum to reflect new neural network state + datum = planner.model.update_datum(datum, device) + + # Compute the subgoal properties by passing images through the network. + # (PyTorch implicitly builds a graph of these operations so that we can + # differentiate them later.) + nn_out, ind_mapping = planner.model(datum, device) + is_feasibles = torch.nn.Sigmoid()(nn_out[:, 0]) + delta_success_costs = nn_out[:, 1] + exploration_costs = nn_out[:, 2] + limited_subgoal_props, _, _ = planner.model.compute_subgoal_props( + is_feasibles, + delta_success_costs, + exploration_costs, + datum['subgoal_data'], + ind_mapping, + device, + limit_subgoals_num=-1, # We do not actually limit for this test + delta_subgoal_data=delta_subgoal_data) + + print("") + print(datum['target_subgoal_policy']['policy']) + print(datum['backup_subgoal_policy']['policy']) + + # Compute the expected of the new target subgoal: + q_target = planner.model.compute_expected_cost_for_policy( + limited_subgoal_props, datum['target_subgoal_policy']) + # Cost of the 'backup' (formerly the agent's chosen subgoal): + q_backup = planner.model.compute_expected_cost_for_policy( + limited_subgoal_props, datum['backup_subgoal_policy']) + print(f"Q_target = {q_target} | Q_backup = {q_backup}") + + if ii == 0: + # Store the original values for each. + base_subgoal_props = limited_subgoal_props + q_target_original = q_target.item() + q_backup_original = q_backup.item() + + print( + f"Q_target_o = {q_target_original} | Q_backup_o = {q_backup_original}" + ) + # The zero-crossing of the difference between the two is the decision + # boundary we are hoping to cross by updating the paramters of the + # neural network via gradient descent. + q_diff = q_target - q_backup + + if q_diff <= 0: + # When it's less than zero, we're done. + break + + # Via PyTorch magic, gradient descent is easy: + optimizer.zero_grad() + q_diff.backward() + optimizer.step() + else: + # If it never crossed the boundary, we have failed. + raise ValueError("Decision boundary never crossed.") + + # Compute the final subgoal property values + upd_subgoal_props = limited_subgoal_props + + # Reload the model's state + planner.model.load_state_dict(base_model_state) + planner.model.eval() + planner.model = planner.model.to(device) + + # Compute the explanation via the built-in function + query_subgoal = [ + s for s, ind in subgoal_ind_dict.items() if ind == query_subgoal_ind + ][0] + explanation = planner.generate_counterfactual_explanation(query_subgoal) + print(explanation) + xai_prop_changes = explanation.get_subgoal_prop_changes() + + # Conf + for ind in subgoal_ind_dict.values(): + if ind not in base_subgoal_props.keys(): + continue + if ind not in upd_subgoal_props.keys(): + continue + + print(f"Ind: {ind}") + print(f" Old: Ps={base_subgoal_props[ind].prob_feasible:0.4f}") + print(f" New: Ps={upd_subgoal_props[ind].prob_feasible:0.4f}") + + if delta_subgoal_data[(ind, 'prob_feasible')].rank < 9: + prob_diff = upd_subgoal_props[ + ind].prob_feasible - base_subgoal_props[ind].prob_feasible + assert xai_prop_changes[ind].prob_feasible_diff == pytest.approx( + prob_diff.item(), 5e-2) + if delta_subgoal_data[(ind, 'delta_success_cost')].rank < 9: + scost_diff = upd_subgoal_props[ + ind].delta_success_cost - base_subgoal_props[ + ind].delta_success_cost + assert xai_prop_changes[ + ind].delta_success_cost_diff == pytest.approx( + scost_diff.item(), 5e-2) + + +@pytest.mark.parametrize("new_target_ind", [1]) +def test_explanation_generation_leaves_model_unchanged(guided_maze_planner, + new_target_ind): + """Generate an explanation by running gradient descent over the difference +between two policies: the target subgoal and the backup subgoal.""" + # Rename the planner for convenience + planner = guided_maze_planner + + # Datum needed here to compute 'query subgoal'. + # Not necessary in general. + device = DEVICE + chosen_subgoal = planner.compute_selected_subgoal() + datum, subgoal_ind_dict = planner.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = planner.model.update_datum(datum, device) + query_subgoal_ind = datum['backup_subgoal_policy']['policy'][ + new_target_ind] + query_subgoal = [ + s for s, ind in subgoal_ind_dict.items() if ind == query_subgoal_ind + ][0] + + # Generate the explanation twice + explanation = planner.generate_counterfactual_explanation(query_subgoal, learning_rate=1e-5) + xai_prop_changes_1 = explanation.get_subgoal_prop_changes() + explanation = planner.generate_counterfactual_explanation(query_subgoal, learning_rate=1e-5) + xai_prop_changes_2 = explanation.get_subgoal_prop_changes() + + for ind in xai_prop_changes_1.keys(): + assert xai_prop_changes_1[ind].prob_feasible_diff == pytest.approx( + xai_prop_changes_2[ind].prob_feasible_diff, rel=0.05, abs=0.02) + + # The new chosen subgoal should be the same as the old + new_chosen_subgoal = planner.compute_selected_subgoal() + assert new_chosen_subgoal == chosen_subgoal + + +@pytest.mark.parametrize("new_target_ind", [1, 2]) +def test_explanation_intervention_can_change_model(guided_maze_planner, + new_target_ind): + """Generate an explanation but 'keep the changes' as in an intervention +experiment. The chosen subgoal after the explanations is generated should match +the query.""" + # Rename the planner for convenience + planner = guided_maze_planner + + # Datum needed here to compute 'query subgoal'. + # Not necessary in general. + device = DEVICE + chosen_subgoal = planner.compute_selected_subgoal() + datum, subgoal_ind_dict = planner.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = planner.model.update_datum(datum, device) + query_subgoal_ind = datum['backup_subgoal_policy']['policy'][ + new_target_ind] + query_subgoal = [ + s for s, ind in subgoal_ind_dict.items() if ind == query_subgoal_ind + ][0] + + planner.generate_counterfactual_explanation(query_subgoal, + do_freeze_selected=False, + keep_changes=True, + margin=2.0) + print(query_subgoal) + print(chosen_subgoal) + + # The new chosen subgoal should match the query subgoal + assert planner.compute_selected_subgoal() == query_subgoal + + +@pytest.mark.parametrize("new_target_ind,limit_num", [(1, 4)]) +def test_explanation_generation_succeeds_limit(guided_maze_planner, + new_target_ind, limit_num): + """Generate an explanation by running gradient descent over the difference +between two policies: the target subgoal and the backup subgoal.""" + # Rename the planner for convenience + planner = guided_maze_planner + + # Datum needed here to compute 'query subgoal'. + # Not necessary in general. + device = DEVICE + chosen_subgoal = planner.compute_selected_subgoal() + datum, subgoal_ind_dict = planner.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = planner.model.update_datum(datum, device) + query_subgoal_ind = datum['target_subgoal_policy']['policy'][ + new_target_ind] + query_subgoal = [ + s for s, ind in subgoal_ind_dict.items() if ind == query_subgoal_ind + ][0] + + if limit_num == 0: + # If no subgoal properties allowed, it should fail. + with pytest.raises(RuntimeError): + planner.generate_counterfactual_explanation( + query_subgoal, limit_num) + else: + # Nothing to test except that it does not fail. + planner.generate_counterfactual_explanation(query_subgoal, + limit_num, + do_freeze_selected=False) + + +@pytest.mark.parametrize("new_target_ind", [1, 2]) +def test_explanation_can_visualize(do_debug_plot, guided_maze_planner, + new_target_ind): + """Generate and visualize an explanation (without crashing).""" + # Rename the planner for convenience + planner = guided_maze_planner + + # Datum needed here to compute 'query subgoal'. + # Not necessary in general. + device = DEVICE + chosen_subgoal = planner.compute_selected_subgoal() + datum, subgoal_ind_dict = planner.compute_subgoal_data( + chosen_subgoal, 24, do_return_ind_dict=True) + datum = planner.model.update_datum(datum, device) + query_subgoal_ind = datum['backup_subgoal_policy']['policy'][ + new_target_ind] + query_subgoal = [ + s for s, ind in subgoal_ind_dict.items() if ind == query_subgoal_ind + ][0] + + explanation = planner.generate_counterfactual_explanation(query_subgoal) + explanation.visualize(show_plot=do_debug_plot) + + +def test_save_load_subgoal_planner(guided_maze_planner): + """Save planner data to a temporary file and load it back.""" + + with tempfile.TemporaryDirectory() as pickle_dir: + pickle_filename = os.path.join(pickle_dir, 'a_pickle.pickle.gz') + + datum = guided_maze_planner.get_planner_state() + learning.data.write_compressed_pickle(pickle_filename, datum) + datum_loaded = learning.data.load_compressed_pickle(pickle_filename) + + _ = lsp_xai.planners.SubgoalPlanner.create_with_state(datum_loaded, None) diff --git a/modules/mrlsp/Makefile.mk b/modules/mrlsp/Makefile.mk new file mode 100644 index 0000000..521ffc4 --- /dev/null +++ b/modules/mrlsp/Makefile.mk @@ -0,0 +1,89 @@ +MRLSP_BASENAME = mrlsp +MRLSP_UNITY_BASENAME ?= $(UNITY_BASENAME) + +MRLSP_CORE_ARGS ?= --unity_path /unity/$(MRLSP_UNITY_BASENAME).x86_64 \ + --save_dir /data/$(MRLSP_BASENAME)/$(EXPERIMENT_NAME) \ + --limit_frontiers 7 \ + --iterations 40000 \ + +MRLSP_SEED_START = 2000 +MRLSP_NUM_EXPERIMENTS = 100 +define mrlsp_get_seeds + $(shell seq $(MRLSP_SEED_START) $$(($(MRLSP_SEED_START)+$(MRLSP_NUM_EXPERIMENTS) - 1))) +endef + +MRLSP_PLANNER = optimistic baseline mrlsp +MRLSP_NUM_ROBOTS = 1 2 3 +all-targets = $(foreach planner, $(MRLSP_PLANNER), \ + $(foreach num_robots, $(MRLSP_NUM_ROBOTS), \ + $(foreach seed, $(call mrlsp_get_seeds), \ + $(DATA_BASE_DIR)/$(MRLSP_BASENAME)/$(EXPERIMENT_NAME)/planner_$(planner)_$(ENV)_cost_$(seed)_r$(num_robots).txt))) + +.PHONY: run-mrlsp +run-mrlsp: $(all-targets) +$(all-targets): num_robots = $(shell echo $@ | grep -oE 'r[0-9]+' | grep -oE '[0-9]+') +$(all-targets): planner = $(shell echo $@ | grep -oE 'planner_[a-z]+' | cut -d'_' -f2) +$(all-targets): seed = $(shell echo $@ | grep -oE 'cost_[0-9]+' | cut -d'_' -f2) +$(all-targets): map_type = $(ENV) +$(all-targets): network_file = $(NETWORK_FILE) +$(all-targets): + @echo $(network_file) + $(call xhost_activate) + @echo "Current experiment: Planner = $(planner) | Map = $(map_type) | Seed = $(seed) | Num robots = $(num_robots)" + @mkdir -p $(DATA_BASE_DIR)/$(MRLSP_BASENAME)/$(EXPERIMENT_NAME) + @$(DOCKER_PYTHON) -m modules.mrlsp.mrlsp.scripts.simulation_$(planner) \ + $(MRLSP_CORE_ARGS) \ + --seed $(seed) \ + --num_robots $(num_robots) \ + --map_type $(map_type) \ + --network_file $(network_file) + +.PHONY: mrlsp-maze +mrlsp-maze: $(lsp-maze-train-file) +mrlsp-maze: + @$(MAKE) run-mrlsp ENV=maze \ + NETWORK_FILE=/data/$(LSP_MAZE_BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt + +.PHONY: mrlsp-office +mrlsp-office: $(lsp-office-train-file) +mrlsp-office: + @$(MAKE) run-mrlsp ENV=office2 \ + NETWORK_FILE=/data/$(LSP_OFFICE_BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt + +# Visualize different planner for different seed and number of robots in office environment +.PHONY: visualize +visualize: DOCKER_ARGS ?= -it +visualize: xhost-activate arg-check-data + @mkdir -p $(DATA_BASE_DIR)/$(MRLSP_BASENAME)/visualize/ + @$(DOCKER_PYTHON) -m modules.mrlsp.mrlsp.scripts.simulation_$(PLANNER) \ + $(MRLSP_CORE_ARGS) \ + --save_dir data/$(MRLSP_BASENAME)/visualize/ \ + --network_file /data/$(BASENAME)/training_logs/$(EXPERIMENT_NAME)/VisLSPOriented.pt \ + --seed $(SEED) \ + --map_type $(MAP) \ + --do_plot True \ + --num_robots $(NUM_ROBOTS) \ + +.PHONY: visualize-office +visualize-office: PLANNER = optimistic +visualize-office: SEED = 2001 +visualize-office: NUM_ROBOTS = 2 +visualize-office: + @$(MAKE) visualize BASENAME=$(LSP_OFFICE_BASENAME) \ + PLANNER=$(PLANNER) \ + SEED=$(SEED) \ + NUM_ROBOTS=$(NUM_ROBOTS) \ + XPASSTHROUGH=true \ + MAP=office2 + +.PHONY: visualize-maze +visualize-maze: PLANNER = optimistic +visualize-maze: SEED = 2001 +visualize-maze: NUM_ROBOTS = 2 +visualize-maze: + @$(MAKE) visualize BASENAME=$(LSP_MAZE_BASENAME) \ + PLANNER=$(PLANNER) \ + SEED=$(SEED) \ + NUM_ROBOTS=$(NUM_ROBOTS) \ + XPASSTHROUGH=true \ + MAP=maze diff --git a/modules/mrlsp/README.md b/modules/mrlsp/README.md new file mode 100644 index 0000000..2d5d819 --- /dev/null +++ b/modules/mrlsp/README.md @@ -0,0 +1,27 @@ +# MR-LSP: Multi-Robot Learning over Subgoals Planning + +Coordinated multi-robot goal directed navigation in partially mapped environments. This module contains the core code for learning-augmented long-horizon naivgation for a multi-robot team, itself an extension of the Learning over Subgoals Planning paradigm for multiple robots. The MR-LSP approach is found in the following paper, which contains algorithmic details: + +Abhish Khanal and Gregory J. Stein. "Learning Augmented, Multi-Robot Long-Horizon Navigation in Partially Mapped Environments". In: International Conference of Robotics and Automation (ICRA). 2023. [paper](https://arxiv.org/abs/2303.16654). + +```bibtex +@inproceedings{khanal2023learning, + title={Learning Augmented, Multi-Robot Long-Horizon Navigation in Partially Mapped Environments}, + author={Abhish Khanal and Gregory J. Stein}, + booktitle={International Conference on Robotics and Automation (ICRA)} + year={2023}, +} +``` + +## Usage + +Note: `make build` (see top-level README) must be successfully run before running the following commands. +The `Makefile.mk` provides multiple targets for reproducing results and visualize planners. +## To visualize planners: +- make visualize-office PLANNER=*planner_name* SEED=*seed* NUM_ROBOTS=*num_robots* visualizes the planner for different number of robots in office environment. Here, *planner_name* can be {optimistic, baseline, mrlsp}, and seed controls the random seed. [Note: Changing the seed also changes the map.] +- make visualize-maze PLANNER=*planner_name* SEED=*seed* NUM_ROBOTS=*num_robots* does the same for maze environment. + +## To run experiments from the paper: + +- `make mrlsp-maze` will run the experiments for all the planner in the maze environment. Note that, if trained model is not present, it first trains the neural network and then runs the experiments in maze environment. +- `make mrlsp-office` will run experiments for all the planner in `office2` environment. diff --git a/modules/mrlsp/mrlsp/__init__.py b/modules/mrlsp/mrlsp/__init__.py new file mode 100644 index 0000000..96d6858 --- /dev/null +++ b/modules/mrlsp/mrlsp/__init__.py @@ -0,0 +1,5 @@ +from . import utils # noqa +from . import scripts # noqa +from . import planners # noqa +from . import core # noqa +from . import pouct # noqa \ No newline at end of file diff --git a/modules/mrlsp/mrlsp/core.py b/modules/mrlsp/mrlsp/core.py new file mode 100644 index 0000000..cbeed93 --- /dev/null +++ b/modules/mrlsp/mrlsp/core.py @@ -0,0 +1,439 @@ +import numpy as np +import copy +import mrlsp + + +class State(): + def __init__(self, n, Fu, m_t=None): + self.n = n + self.Fu = copy.copy(Fu) + self.time = mrlsp.utils.utility.copy_dictionary(m_t) + self.q_t = [] + self.goal_frontiers = set() + for i in range(self.n): + progress = {} + for f in Fu: + progress[f] = 0 + self.q_t.append(progress) + + def copy_state(self): + new_state = State(self.n, self.Fu, self.time) + new_state.q_t = [] + for q in self.q_t: + new_state.q_t.append(copy.copy(q)) + new_state.goal_frontiers = copy.copy(self.goal_frontiers) + return new_state + + def get_actions(self): + def restrict_action_according_to_progress(all_actions): + '''This function restricts the action so that if the robots are making progress towards + some frontier, then the other robot revealing some frontier doesn't interrupt the ongoing + action''' + final_action = [] + save = False + for c in all_actions: + for i, action in enumerate(c): + frontier, _ = find_progress_and_frontier_for_robot(self.q_t, i) + # If the frontier is not in unexplored frontier, then the frontier is just explored + if frontier not in self.Fu: + if frontier not in self.goal_frontiers: + ''' If the frontier is not in goal frontier, then the frontier doesn't lead to the goal + and the robot needs to return back from that frontier. So, the robot has not 'made' any + progress towards any frontier that might reveal goal.''' + frontier = None + else: + '''After exploring, the frontier can either lead to the goal; in that case, the + action contains that frontier. So no need to set None''' + pass + + if frontier is None: + save = True + continue + else: + if frontier != action: + save = False + continue + else: + save = True + continue + if save: + final_action.append(c) + return final_action + + frontiers_to_explore = self.Fu.union(self.goal_frontiers) + if self.n == 1: + return [[f] for f in frontiers_to_explore] + + actions = mrlsp.utils.utility.get_action_combination(frontiers_to_explore, self.n) + # Make sure that if a robot is making progress along some frontier, it doesn't change action + final_action = restrict_action_according_to_progress(actions) + return final_action + # return actions + + def find_q_t_for_action(self, T_I, action): + new_q_t = [] + residue_time = [] + # update for all the robots + for i in range(self.n): + q_t_dict = {} + residue_dict = {} # used for storing reside + prev_frontier, progress_prev_frontier = find_progress_and_frontier_for_robot(self.q_t, i) + current_frontier = action[i] + frontiers_to_keep_track = self.Fu.union(self.goal_frontiers) + for f in frontiers_to_keep_track: + ''' + if the current frontier is not the frontier that the robot is moving towards + then no progress is made towards that frontier (set time to 0), and the current + frontier is also not the previous frontier (do nothing) + ''' + if f != current_frontier: + # We don't want to set the previous frontier time as 0 right now. + if f != prev_frontier: + q_t_dict[f] = 0 + else: + # If in previous state, robot was not exploring any frontier + if prev_frontier is None: + time_to_current_frontier = self.time[f"robot{i+1}"][f] + # If the robot has entered that frontier + if T_I > time_to_current_frontier: + q_t_dict[f] = T_I - time_to_current_frontier + else: + # Scenario of residue while moving towards frontier f + # residue_time = T_I + q_t_dict[f] = 0 + residue_dict['from'] = prev_frontier + residue_dict['to'] = f + residue_dict['time'] = T_I + + elif current_frontier == prev_frontier: + q_t_dict[f] = progress_prev_frontier + T_I + else: + ''' + If the time of knowledge > the progress made on previous frontier then the robot gets out + of the frontier + ''' + if T_I >= progress_prev_frontier: + out_and_explore_time = T_I - progress_prev_frontier + inter_frontier_time = self.time['frontier'][frozenset([f, prev_frontier])] + q_t_dict[prev_frontier] = 0 + if out_and_explore_time > inter_frontier_time: + q_t_dict[f] = out_and_explore_time - inter_frontier_time + else: + # TODO: Add scenario of residue while moving towards frontier f + # residue is used in calculation in robot-frontier time + # residue_time = inter_frontier_time - out_and_explore_time + q_t_dict[f] = 0 + residue_dict['from'] = prev_frontier + residue_dict['to'] = f + residue_dict['time'] = out_and_explore_time + else: + ''' + else the robot is currently coming out of the same frontier it was exploring before + ''' + q_t_dict[f] = 0 + q_t_dict[prev_frontier] = progress_prev_frontier - T_I + new_q_t.append(q_t_dict) + residue_time.append(residue_dict) + + return new_q_t, residue_time + + def get_time_from_q_t(self, new_q_t, residue_time): + new_time = {} + new_time['frontier'] = copy.copy(self.time['frontier']) + new_time['goal'] = copy.copy(self.time['goal']) + old_time = mrlsp.utils.utility.copy_dictionary(self.time) + frontiers_to_keep_track = self.Fu.union(self.goal_frontiers) + for i in range(self.n): + time_dict = {} + prev_frontier, progress = find_progress_and_frontier_for_robot(new_q_t, i) + if prev_frontier is None: + # TODO: Check if there is residue distance + if len(residue_time[i]) != 0: + ''' + Assumption1: If the robot is making progress towards a frontier, its making progress + towards all the other frontiers + Updated Assumption: Construct a triangle using where robot was coming from, where robot is + going, and where robot needs to go, and find the distance from that triangle. The results will + never be negative. + ''' + from_frontier = residue_time[i]['from'] + to_frontier = residue_time[i]['to'] + time_travelled = residue_time[i]['time'] + + ''' + If the robot is in 'known' space and not coming out from frontier then the time is + deduced from the old robot-frontier time. + This happens when the subgoal is assigned to the robot, but other robot knows about + "frontier of knowledge" before the current robot gets to see the frontier that it is + assigned to. + ''' + if from_frontier is None: + ''' 'a' is the distance from robot position to the frontier + that it is assigned to, before the robot moved''' + a = old_time[f'robot{i + 1}'][to_frontier] + # HANDLE EDGE CASE: + if a == 0: + # If the robot just reached frontier it was assigned to explore, and belief state changed + for f in frontiers_to_keep_track: + if f == to_frontier: + time_to_frontier = 0 + else: + time_to_frontier = old_time['frontier'][frozenset([to_frontier, f])] + time_dict[f] = time_to_frontier + else: + for f in frontiers_to_keep_track: + if f == to_frontier: + time_to_frontier = old_time[f'robot{i + 1}'][f] - time_travelled + else: + ''' 'b' is the time from the frontier that the robot was previously + assigned to, and the current frontier 'f' ''' + b = old_time['frontier'][frozenset([to_frontier, f])] + ''' 'c' is the time from robot position to the frontier, + which we are currently calculating, before the robot moved''' + c = old_time[f'robot{i + 1}'][f] + + time_to_frontier = mrlsp.utils.utility.get_frontier_time_by_triangle_formation( + a, b, c, time_travelled) + time_dict[f] = time_to_frontier + + else: + ''' + If the robot is in 'known' space but by coming out from another frontier. In this case, + the time from the previous frontier to all the other frontier - outside time is the + robot's time to reach other frontiers. + ''' + a = old_time['frontier'][frozenset([from_frontier, to_frontier])] + for f in frontiers_to_keep_track: + # TODO: Check if we need this + if f == from_frontier or f == to_frontier: + if f == from_frontier: + time_dict[f] = time_travelled + else: + time_dict[f] = old_time['frontier'][frozenset([from_frontier, f])] - time_travelled + else: + b = old_time['frontier'][frozenset([to_frontier, f])] + c = old_time['frontier'][frozenset([from_frontier, f])] + time_to_frontier = mrlsp.utils.utility.get_frontier_time_by_triangle_formation( + a, b, c, time_travelled) + time_dict[f] = time_to_frontier + else: + # Update in q_t and not here. + raise AssertionError('Not sure what to do here !!') + + else: + for f in frontiers_to_keep_track: + # time for the robot to explore same frontier that it is making progress towards + if prev_frontier == f: + time_to_frontier = 0 + # for any other frontier, come out of the currently exploring frontier and go towards that frontier + else: + time_to_frontier = progress + self.time["frontier"][frozenset([f, prev_frontier])] + time_dict[f] = time_to_frontier + + new_time[f"robot{i+1}"] = time_dict + return new_time + + +def move_robots(state, action): + failure_state = state.copy_state() + f_I, T_I = get_frontier_of_knowlege_and_time(state, action) + goal_reached = False + if f_I is None: + '''if f_I and T_I is none, both the action leads to the goal. + i.e success_cost is the minimum of two robots reaching the goal.''' + # NOTE: after this, one of the robot reaches the goal, and success cost should be 0. + all_time_to_goal = [] + for i, f in enumerate(action): + time_to_goal = state.time[f'robot{i+1}'][f] + \ + (f.delta_success_cost + state.time['goal'][f]) - state.q_t[i][f] + all_time_to_goal.append(time_to_goal) + time_to_goal = min(all_time_to_goal) + T_I = time_to_goal + goal_reached = True + + new_q_t, residue_time = failure_state.find_q_t_for_action(T_I, action) + + failure_state.q_t = new_q_t + + if f_I is not None: + failure_state.Fu.remove(f_I) + + success_state = failure_state.copy_state() + if f_I is not None: + success_state.goal_frontiers.add(f_I) + + success_state.time = success_state.get_time_from_q_t(new_q_t=new_q_t, residue_time=residue_time) + failure_state.time = failure_state.get_time_from_q_t(new_q_t=new_q_t, residue_time=residue_time) + + ''' + Check for goal reached: + If the robot progress along a frontier is greater than or equal to delta + success cost, goal is reached. + What to do if progress is greater than delta success cost? + decrease T_I (cost) and q_t by the increment amount''' + T_I_list = [] + for i in range(state.n): + frontier, progress = find_progress_and_frontier_for_robot(new_q_t, i) + if (progress != 0): + toreachgoal = frontier.delta_success_cost + state.time['goal'][frontier] + epsilon = 1 + if (toreachgoal - progress <= epsilon): + rem = progress - (frontier.delta_success_cost + state.time['goal'][frontier]) + T_I_list.append(T_I - rem + epsilon) + goal_reached = True + # no need to update intermediate state properties, because goal is reached, and cost is returned + if len(T_I_list) != 0: + T_I = min(T_I_list) + return success_state, failure_state, f_I, T_I, goal_reached + + +def find_progress_and_frontier_for_robot(q_t, i): + robot_q_t = q_t[i] + frontier = None + progress = 0 + for f in robot_q_t: + if robot_q_t[f] != 0: + frontier = f + progress = robot_q_t[f] + break + return frontier, progress + + +def get_frontier_of_knowlege_and_time(state, action): + # find if the state is a state from which goal can be reached + can_reach_goal = False + if len(state.goal_frontiers) != 0: + can_reach_goal = True + goal_frontiers = state.goal_frontiers + # list to store all the time + all_TI = [] + all_frontiers = [] + # Iterate over the joint action + for i, f in enumerate(action): + if can_reach_goal and f in goal_frontiers: + continue + Ti = state.time[f"robot{i+1}"][f] + \ + min(f.delta_success_cost + state.time['goal'][f], f.exploration_cost) - state.q_t[i][f] + all_TI.append(Ti) + all_frontiers.append(f) + + if len(all_TI) == 0: + # no unexplored frontiers have been added; i.e both actions are goal frontiers + f_I, T_I = None, None + return f_I, T_I + + f_I = all_frontiers[np.argmin(all_TI)] + T_I = min(all_TI) + + return f_I, T_I + + +def update_frontier_properties_for_multirobot(planner, subgoals_initial, distance_mr): + # remove subgoals that are covered by known space, i.e they don't lead to the goal. + subgoals = set([copy.copy(s) for s in subgoals_initial if distance_mr['goal'][s] < 100000]) + sg_not_leading_to_goal = subgoals_initial - subgoals + for sg in subgoals: + # find the robot which is close to the subgoal 'sg'. + distance_to_sg = [distance_mr[f'robot{i+1}'][sg] for i in range(len(planner))] + robot_idx = np.argmin(distance_to_sg) + for f in planner[robot_idx].subgoals: + if f == sg: + sg.prob_feasible = f.prob_feasible + sg.exploration_cost = f.exploration_cost + sg.delta_success_cost = f.delta_success_cost + + if sg.exploration_cost <= 0: + sg.exploration_cost = -1 * sg.exploration_cost + if sg.delta_success_cost <= 0: + sg.delta_success_cost = -1 * sg.delta_success_cost + + return subgoals, sg_not_leading_to_goal + + +def Q(state, action): + # If only one frontier is left to explore + if len(state.Fu) == 1: + return get_final_state_cost(state) + + new_state_success, new_state_failure, f_I, T_I, goal_reached = move_robots(state, action) + + if goal_reached: + return T_I + + success_cost = min([Q(new_state_success, action) + for action in new_state_success.get_actions()]) + + exploration_cost = min([Q(new_state_failure, action) + for action in new_state_failure.get_actions()]) + + return (T_I + f_I.prob_feasible * success_cost + + (1 - f_I.prob_feasible) * exploration_cost) + + +def get_final_state_cost(state): + '''This is used to compute the cost of state where there are 1 unexplored frontier + ''' + actions = state.get_actions() + if (len(state.goal_frontiers) != 0): + '''In case there are one or more frontier that leads to the goal, there + are lots of action combination which is possible. After an action is taken, + and the robots are moved, the new state has no frontiers left to explore. Hence we + can calculate the cost for all actions in this function alone without use of recursion''' + final_costs = [] + for action in actions: + new_state_success, new_state_failure, f_I, T_I, goal_reached = move_robots(state, action) + # Success: get new state and expected cost + if goal_reached: + success_cost = 0 + else: + success_state_actions = new_state_success.get_actions() + all_action_cost = [] + for a in success_state_actions: + all_robots_cost = [] + for i, f in enumerate(a): + sc = new_state_success.time[f'robot{i+1}'][f] + \ + (f.delta_success_cost + state.time['goal'][f]) - new_state_success.q_t[i][f] + all_robots_cost.append(sc) + all_action_cost.append(min(all_robots_cost)) + success_cost = min(all_action_cost) + + # Failure: get new state and expected cost + if goal_reached: + exploration_cost = 0 + else: + failure_state_actions = new_state_failure.get_actions() + all_action_cost = [] + for a in failure_state_actions: + all_robot_cost = [] + for i, f in enumerate(a): + ec = new_state_failure.time[f'robot{i+1}'][f] + \ + (f.delta_success_cost + state.time['goal'][f]) - new_state_failure.q_t[i][f] + all_robot_cost.append(ec) + all_action_cost.append(min(all_robot_cost)) + exploration_cost = min(all_action_cost) + if goal_reached: + final_costs.append(T_I) + else: + cost = T_I + f_I.prob_feasible * success_cost + (1 - f_I.prob_feasible) * exploration_cost + final_costs.append(cost) + + return min(final_costs) + else: + ''' + If no frontier leads to the goal up to this point then the current frontier leads to the goal + Return the minimum cost (time) for all the robot to reach the goal through that frontier. + ''' + all_cost = [] + action = actions[0] + for i, f in enumerate(action): + sc = state.time[f'robot{i+1}'][f] + (f.delta_success_cost + state.time['goal'][f]) - state.q_t[i][f] + all_cost.append(sc) + return min(all_cost) + + +def find_best_joint_action(num_robots, unexplored_frontiers, time): + # update_frontier_properties_for_multirobot(unexplored_frontiers) + sigma = State(n=num_robots, Fu=unexplored_frontiers, m_t=time) + actions = sigma.get_actions() + costs = [Q(sigma, action) for action in actions] + return actions[np.argmin(costs)] diff --git a/modules/mrlsp/mrlsp/planners/__init__.py b/modules/mrlsp/mrlsp/planners/__init__.py new file mode 100644 index 0000000..5bbc69b --- /dev/null +++ b/modules/mrlsp/mrlsp/planners/__init__.py @@ -0,0 +1,5 @@ +from .planning_loop import PlanningLoop # noqa +from .optimistic import OptimisticPlanner # noqa +from .lsp_baseline import BaselineLSA # noqa +from .lsp_baseline import BaselineLSAExcludingAction # noqa +from .mrlsp_planner import MRLearnedSubgoalPlanner # noqa diff --git a/modules/mrlsp/mrlsp/planners/lsp_baseline.py b/modules/mrlsp/mrlsp/planners/lsp_baseline.py new file mode 100644 index 0000000..2941654 --- /dev/null +++ b/modules/mrlsp/mrlsp/planners/lsp_baseline.py @@ -0,0 +1,63 @@ +import numpy as np +from .planner import BaseLSPPlanner +import lsp +import mrlsp +from mrlsp.utils.utility import (get_all_distance, + find_action_list_from_cost_matrix_using_lsa) + + +class BaselineLSA(BaseLSPPlanner): + '''Baseline 1: Linear sum assignment using LSP''' + def __init__(self, robots, goal, args): + super(BaselineLSA, self).__init__(robots, goal, args) + + def compute_selected_subgoal(self): + # If goal in range, return None as action + if lsp.core.goal_in_range(grid=self.robot_grid, + robot_pose=None, goal_pose=self.goal_pose, frontiers=self.subgoals): + joint_action = [None for i in range(len(self.robots))] + return joint_action + distances = get_all_distance(self.inflated_grid, self.robots, [self.goal_pose], self.subgoals) + # find cost for robot to reach goal from all the subgoal, and create a cost matrix. + cost_dictionary = [None for _ in range(len(self.robots))] + for i in range(len(self.robots)): + cost_dictionary[i] = { + subgoal: lsp.core.get_lowest_cost_ordering_beginning_with( + subgoal, self.subgoals, distances[i], do_sort=False)[0] + for subgoal in self.subgoals + } + subgoal_matrix = np.array([list(cd.keys()) for cd in cost_dictionary]) + cost_matrix = np.array([list(cd.values()) for cd in cost_dictionary]) + # from the cost matrix, return the list of subgoals that has the least cost. + joint_action = find_action_list_from_cost_matrix_using_lsa(cost_matrix, subgoal_matrix) + + return joint_action + + +class BaselineLSAExcludingAction(BaseLSPPlanner): + '''Baseline 2: Linear sum assignment excluding action using LSP''' + def __init__(self, robots, goal, args): + super(BaselineLSAExcludingAction, self).__init__(robots, goal, args) + + def compute_selected_subgoal(self): + if lsp.core.goal_in_range(grid=self.robot_grid, + robot_pose=None, goal_pose=self.goal_pose, frontiers=self.subgoals): + joint_action = [None for i in range(len(self.robots))] + return joint_action + actions_combination = mrlsp.utils.utility.get_action_combination(self.subgoals, len(self.robots)) + distances = get_all_distance(self.inflated_grid, self.robots, [self.goal_pose], self.subgoals) + cost_of_action_combination = [] + for action in actions_combination: + subgoals_except_in_action = [sg for sg in self.subgoals if sg not in action] + final_cost = 0 + for i, a in enumerate(action): + cost = lsp.core.get_lowest_cost_ordering_beginning_with( + a, + subgoals=subgoals_except_in_action, + distances=distances[i], + do_sort=False + )[0] + final_cost += cost + cost_of_action_combination.append(final_cost) + joint_action = actions_combination[np.argmin(cost_of_action_combination)] + return joint_action diff --git a/modules/mrlsp/mrlsp/planners/mrlsp_planner.py b/modules/mrlsp/mrlsp/planners/mrlsp_planner.py new file mode 100644 index 0000000..910f0da --- /dev/null +++ b/modules/mrlsp/mrlsp/planners/mrlsp_planner.py @@ -0,0 +1,65 @@ +from .planner import BaseLSPPlanner +import lsp +import mrlsp +import mrlsp_accel +import itertools +import numpy as np + + +class MRLearnedSubgoalPlanner(BaseLSPPlanner): + '''Multi-robot Learned Subgoal Planner''' + + def __init__(self, robots, goal, args): + super(MRLearnedSubgoalPlanner, self).__init__(robots, goal, args) + + def compute_selected_subgoal_old(self): + # If goal in range, return None as action + if lsp.core.goal_in_range(grid=self.robot_grid, + robot_pose=None, goal_pose=self.goal_pose, frontiers=self.subgoals): + joint_action = [None for i in range(len(self.robots))] + return joint_action + + joint_action = mrlsp.pouct.find_best_joint_action( + self.subgoals, self.distances_mr, num_robots=len(self.robots), num_iterations=self.args.iterations) + + return joint_action + + def compute_selected_subgoal(self): + + # If goal in range, return None as action + if lsp.core.goal_in_range(grid=self.robot_grid, + robot_pose=None, goal_pose=self.goal_pose, frontiers=self.subgoals): + joint_action = [None for i in range(len(self.robots))] + return joint_action + + # for cpp + num_robots = len(self.robots) + unexplored_frontiers = list(self.subgoals) + s_dict = {hash(s): s for s in unexplored_frontiers} + s_cpp = [ + mrlsp_accel.FrontierDataMR(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in unexplored_frontiers + ] + rd_cpp = {(i, hash(s)): self.distances_mr[f'robot{i+1}'][s] + for i in range(num_robots) for s in unexplored_frontiers} + gd_cpp = {hash(s): self.distances_mr['goal'][s] for s in unexplored_frontiers} + fd_cpp = {(hash(sp[0]), hash(sp[1])): self.distances_mr['frontier'][frozenset(sp)] + for sp in itertools.permutations(unexplored_frontiers, 2)} + + joint_action_hash = mrlsp_accel.find_best_joint_action_accel( + num_robots, s_cpp, rd_cpp, gd_cpp, fd_cpp, self.args.iterations) + joint_action = [s_dict[s] for s in joint_action_hash] + # ''' Use LSA here ''' + num_robots = len(self.robots) + cost_dictionary = [None for _ in range(num_robots)] + for i in range(num_robots): + cost_dictionary[i] = { + subgoal: self.distances_mr[f'robot{i+1}'][subgoal] + self.distances_mr['goal'][subgoal] + for subgoal in joint_action + } + subgoal_matrix = np.array([list(cd.keys()) for cd in cost_dictionary]) + cost_matrix = np.array([list(cd.values()) for cd in cost_dictionary]) + # from the cost matrix, return the list of subgoals that has the least cost. + action = mrlsp.utils.utility.find_action_list_from_cost_matrix_using_lsa(cost_matrix, subgoal_matrix) + return action diff --git a/modules/mrlsp/mrlsp/planners/optimistic.py b/modules/mrlsp/mrlsp/planners/optimistic.py new file mode 100644 index 0000000..483362d --- /dev/null +++ b/modules/mrlsp/mrlsp/planners/optimistic.py @@ -0,0 +1,29 @@ +import numpy as np +from .planner import MRPlanner +from mrlsp.utils.utility import get_multirobot_distances, find_action_list_from_cost_matrix_using_lsa + + +class OptimisticPlanner(MRPlanner): + def __init__(self, robots, goal, args): + super(OptimisticPlanner, self).__init__(robots, goal) + self.selected_subgoal = None + self.observed_map = None + self.args = args + + def compute_selected_subgoal(self): + '''TODO: Right now, goal pose is sent as list: Just because every other function use list of goalsl, + The functionality that is thought to be extended, where goal is multiple''' + distances_mr = get_multirobot_distances(self.inflated_grid, self.robots, [self.goal_pose], self.subgoals) + # find cost for robot to reach goal from all the subgoal, and create a cost matrix. + cost_dictionary = [None for _ in range(len(self.robots))] + for i in range(len(self.robots)): + cost_dictionary[i] = { + subgoal: distances_mr[f'robot{i+1}'][subgoal] + distances_mr['goal'][subgoal] + for subgoal in self.subgoals + } + subgoal_matrix = np.array([list(cd.keys()) for cd in cost_dictionary]) + cost_matrix = np.array([list(cd.values()) for cd in cost_dictionary]) + # from the cost matrix, return the list of subgoals that has the least cost. + joint_action = find_action_list_from_cost_matrix_using_lsa(cost_matrix, subgoal_matrix) + + return joint_action diff --git a/modules/mrlsp/mrlsp/planners/planner.py b/modules/mrlsp/mrlsp/planners/planner.py new file mode 100644 index 0000000..8357b48 --- /dev/null +++ b/modules/mrlsp/mrlsp/planners/planner.py @@ -0,0 +1,66 @@ +import copy +import mrlsp +from mrlsp.utils.utility import get_multirobot_distances + + +class MRPlanner(object): + """Abstract class for planning with frontiers.""" + + def __init__(self, robots, goal): + self.name = 'multirobot_planner' + self.robot_grid = None + self.inflated_grid = None + self.robots = robots + self.goal_pose = goal[0] + + def update(self, observation, robot_grid, inflated_grid, subgoals, robot, *args, + **kwargs): + self.observation = observation + self.robot_grid = robot_grid + self.inflated_grid = inflated_grid + self.subgoals = [copy.copy(s) for s in subgoals] + self.robots = robot + + def compute_selected_subgoal(self): + """Returns the selected subgoal (frontier).""" + raise NotImplementedError() + + +class BaseLSPPlanner(MRPlanner): + '''LSP planner is used just to reuse the same subgoal properties as in LSP, + In every planner where subgoal properties are used for multirobot, BaseLSPPlanner class is inherited.''' + + def __init__(self, robots, goal, args): + super(BaseLSPPlanner, self).__init__(robots, goal) + self.args = args + self.subgoals = None + self.planners = mrlsp.utils.utility.lsp_planner(args, len(robots), goal) + + def update(self, observation, robot_grid, inflated_grid, subgoals, robot, visibility_mask): + # Update every lsp planner observation + num_robots = len(self.robots) + self.observation = observation + self.robot_grid = robot_grid + self.inflated_grid = inflated_grid + frontiers = set([copy.copy(s) for s in subgoals]) + self.robots = robot + for i in range(num_robots): + self.planners[i].update( + {'image': self.observation[i]}, + self.robot_grid, + frontiers, + self.robots[i].pose, + visibility_mask[i]) + self.distances_mr = get_multirobot_distances(self.inflated_grid, self.robots, [self.goal_pose], frontiers) + frontiers, loop_frontiers = mrlsp.core.update_frontier_properties_for_multirobot( + self.planners, frontiers, self.distances_mr) + self.subgoals, extra_subgoals = mrlsp.utils.utility.limit_total_subgoals( + num_robots, frontiers, self.distances_mr, self.args.limit_frontiers + ) + print("-----selected subgoals properties-----") + for sg in self.subgoals: + print( + f"subgoal: {sg}:{sg.centroid}, P = {sg.prob_feasible}, \ + Ts = {sg.delta_success_cost + self.distances_mr['goal'][sg]}, Te = {sg.exploration_cost}") + print("------------------------------") + extra_subgoals = extra_subgoals.union(loop_frontiers) diff --git a/modules/mrlsp/mrlsp/planners/planning_loop.py b/modules/mrlsp/mrlsp/planners/planning_loop.py new file mode 100644 index 0000000..403eebf --- /dev/null +++ b/modules/mrlsp/mrlsp/planners/planning_loop.py @@ -0,0 +1,180 @@ +import gridmap +import lsp +import numpy as np +import time + + +class PlanningLoop(): + def __init__(self, + goal, + known_map, + simulator, + unity_bridge, + robot, + args, + verbose=False): + self.goal = goal + self.known_map = known_map + self.simulator = simulator + self.unity_bridge = unity_bridge + self.robot = robot + self.args = args + self.did_succeed = True + self.verbose = verbose + self.chosen_subgoal = None + + self.goal_reached = False + self.path_covered = None + self.robot_grid = lsp.constants.UNOBSERVED_VAL * np.ones_like( + self.known_map) + + # For checking + self.subgoals = set() + self.planning_grid = None + self.inflated_grid = [] + + def __iter__(self): + counter = 0 + count_since_last_turnaround = 100 + fn_start_time = time.time() + + # Main planning loop + while (not self.goal_reached): + + if self.verbose: + print(f"Goal: {self.goal.x}, {self.goal.y}") + print( + f"Robot: {self.robot.pose.x}, {self.robot.pose.y} [motion: {self.robot.net_motion}]" + ) + print(f"Counter: {counter} | Count since last turnaround: " + f"{count_since_last_turnaround}") + + # Compute observations and update map + pano_image = self.simulator.get_image(self.robot) + _, self.robot_grid, visible_region = ( + self.simulator.get_laser_scan_and_update_map( + self.robot, self.robot_grid, True)) + + # Compute intermediate map grids for planning + visibility_mask = gridmap.utils.inflate_grid( + visible_region, 1.8, -0.1, 1.0) + inflated_grid = self.simulator.get_inflated_grid( + self.robot_grid, self.robot) + inflated_grid = gridmap.mapping.get_fully_connected_observed_grid( + inflated_grid, self.robot.pose) + self.inflated_grid = inflated_grid + # Compute the subgoal + subgoals = self.simulator.get_updated_frontier_set( + self.inflated_grid, self.robot, set()) + + yield { + 'subgoals': subgoals, + 'image': pano_image, + 'robot_grid': self.robot_grid, + 'robot_pose': self.robot.pose, + 'visibility_mask': visibility_mask, + } + if self.chosen_subgoal is None: + if self.verbose: + print("Planning with naive/Dijkstra planner.") + planning_grid = lsp.core.mask_grid_with_frontiers( + self.inflated_grid, + [], + ) + else: + if self.verbose: + print("Planning via subgoal masking.") + + planning_grid = lsp.core.mask_grid_with_frontiers( + self.inflated_grid, + self.subgoals, + do_not_mask=self.chosen_subgoal) + + # Check that the plan is feasible and compute path + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [self.goal.x, self.goal.y], use_soft_cost=True) + did_plan, path = get_path([self.robot.pose.x, self.robot.pose.y], + do_sparsify=True, + do_flip=True) + # Update the path in the path variable + self.planning_grid = planning_grid + self.path_covered = path + # Move the robot + motion_primitives = self.robot.get_motion_primitives() + do_use_path = (count_since_last_turnaround > 10) + costs, _ = lsp.primitive.get_motion_primitive_costs( + planning_grid, + cost_grid, + self.robot.pose, + path, + motion_primitives, + do_use_path=do_use_path) + if abs(min(costs)) < 1e10: + primitive_ind = np.argmin(costs) + self.robot.move(motion_primitives, primitive_ind) + print("robot move") + if primitive_ind == len(motion_primitives) - 1: + count_since_last_turnaround = -1 + else: + # Force the robot to return to known space + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [self.goal.x, self.goal.y], + use_soft_cost=True, + obstacle_cost=1e5) + did_plan, path = get_path( + [self.robot.pose.x, self.robot.pose.y], + do_sparsify=True, + do_flip=True) + costs, _ = lsp.primitive.get_motion_primitive_costs( + planning_grid, + cost_grid, + self.robot.pose, + path, + motion_primitives, + do_use_path=False) + + self.robot.move(motion_primitives, np.argmin(costs)) + + # Check that the robot is not 'stuck'. + if self.robot.max_travel_distance( + num_recent_poses=100) < 5 * self.args.step_size: + print("Planner stuck") + self.did_succeed = False + break + + if self.robot.net_motion > 4000: + print("Reached maximum distance.") + self.did_succeed = False + break + counter += 1 + count_since_last_turnaround += 1 + if self.verbose: + print("") + # Check if goal is reached + self.check_goal_reached() + + if self.verbose: + print("TOTAL TIME:", time.time() - fn_start_time) + + def set_chosen_subgoal(self, new_chosen_subgoal): + self.chosen_subgoal = new_chosen_subgoal + + def update_robot_grid(self, robot_grid): + self.robot_grid = robot_grid + + def update_subgoals(self, subgoals, extra_subgoals=None): + if extra_subgoals is None: + self.subgoals = subgoals + else: + self.subgoals = subgoals.union(extra_subgoals) + + def update_inflated_grid(self, inflated_grid): + self.inflated_grid = inflated_grid + + def check_goal_reached(self): + if (not (np.abs(self.robot.pose.x - self.goal.x) >= 3 * + self.args.step_size or np.abs(self.robot.pose.y - self.goal.y) + >= 3 * self.args.step_size)): + self.goal_reached = True + else: + self.goal_reached = False diff --git a/modules/mrlsp/mrlsp/pouct.py b/modules/mrlsp/mrlsp/pouct.py new file mode 100644 index 0000000..8660014 --- /dev/null +++ b/modules/mrlsp/mrlsp/pouct.py @@ -0,0 +1,248 @@ +import numpy as np +from scipy.stats import bernoulli +import copy +from mrlsp.core import move_robots, State +from mrlsp.utils.utility import find_action_index + + +# just some prime numers so it wont get repeated +NULL = 573213 +FAILURE = 0 +SUCCESS = 1 + + +class Node(): + def __init__(self, start_state, parent=None, prev_action=None, T_I=0, goal_reached=False): + self.state = start_state + self.parent = parent + self.prev_action = prev_action + if parent is not None: + self.cost = T_I + parent.cost + else: + self.cost = T_I + self.goal_reached = goal_reached + + self.actions = self.state.get_actions() + self.action_values = [[] for _ in range(len(self.actions))] + self.action_n = [0 for _ in range(len(self.actions))] + self.unexplored_actions = copy.copy(self.actions) + '''One node can have two children, either f_I leads to the goal or not + the 1th index is for success, and 0th index is for failure''' + self.children = [{0: NULL, 1: NULL} for _ in range(len(self.actions))] + '''One node can have two children, either f_I leads to the goal or not + the 1th index is for success, and 0th index is for failure''' + self.children = [{FAILURE: NULL, SUCCESS: NULL} for _ in range(len(self.actions))] + + '''This stores the outcome of node so that the computation is saved''' + self.children_properties = [{'outcome': {FAILURE: NULL, SUCCESS: NULL}, + 'properties': {'f_I': None, 'T_I': None, 'goal_reached': None}, 'has_value': False} + for _ in range(len(self.actions))] + + # Update if this is terminal node + if not self.goal_reached: + state_unexplored_frontiers = list(self.state.Fu) + if len(state_unexplored_frontiers) == 0: + # Updated this + if len(self.state.goal_frontiers) != 0: + all_actions = self.state.get_actions() + all_action_cost = [] + for a in all_actions: + all_robot_cost = [] + for i, f in enumerate(a): + cost_to_goal = self.state.time[f'robot{i+1}'][f] + ( + f.delta_success_cost + self.state.time['goal'][f]) - self.state.q_t[i][f] + all_robot_cost.append(cost_to_goal) + all_action_cost.append(min(all_robot_cost)) + self.cost += min(all_action_cost) + self.goal_reached = True + else: + '''When no frontier leads to the goal, and no unexplored frontiers left, + assume that the parent node unexplored frontier leads to the goal, and add + the success cost of that frontier.''' + f = list(self.parent.state.Fu)[0] + all_robot_cost = [] + for i in range(self.state.n): + cost_to_goal = self.parent.state.time[f'robot{i+1}'][f] + ( + f.delta_success_cost + self.state.time['goal'][f]) - self.state.q_t[i][f] + all_robot_cost.append(cost_to_goal) + self.cost += min(all_robot_cost) + self.goal_reached = True + + def update_child_properties(self, action_idx, success_state, failure_state, f_I, T_I, goal_reached): + self.children_properties[action_idx]['has_value'] = True + self.children_properties[action_idx]['outcome'][SUCCESS] = success_state + self.children_properties[action_idx]['outcome'][FAILURE] = failure_state + self.children_properties[action_idx]['properties']['f_I'] = f_I + self.children_properties[action_idx]['properties']['T_I'] = T_I + self.children_properties[action_idx]['properties']['goal_reached'] = goal_reached + + def get_child_properties(self, action_idx): + if self.children_properties[action_idx]['has_value'] is True: + success_state = self.children_properties[action_idx]['outcome'][SUCCESS] + failure_state = self.children_properties[action_idx]['outcome'][FAILURE] + f_I = self.children_properties[action_idx]['properties']['f_I'] + T_I = self.children_properties[action_idx]['properties']['T_I'] + goal_reached = self.children_properties[action_idx]['properties']['goal_reached'] + return success_state, failure_state, f_I, T_I, goal_reached + else: + return None + + @property + def is_fully_explored(self): + return len(self.unexplored_actions) == 0 + + @property + def is_terminal_state(self): + return self.goal_reached + + def find_rollout_cost(self): + '''Rollout cost from 'self' state''' + if self.goal_reached: + return self.cost + # Use a heuristic to find the best policy and calculate the cost of that policy randomly + cost_for_robots = [] + for i in range(self.state.n): + unexplored_frontiers = list(self.state.Fu) + Q = min([self.state.time[f'robot{i+1}'][s] + self.state.time['goal'][s] - self.state.q_t[i][s] + + (1 - s.prob_feasible) * s.exploration_cost for s in unexplored_frontiers]) + '''If there are frontiers which leads to the goal, then the cost to goal from these frontier + for the robot is the minimum of distance in which the robots can reach the goal''' + if len(self.state.goal_frontiers) != 0: + Q_g = min([self.state.time[f'robot{i+1}'][s] + (self.state.time['goal'][s] + + s.delta_success_cost) - self.state.q_t[i][s] for s in self.state.goal_frontiers]) + Q_p = Q + Q = min(Q_g, Q_p) + cost_for_robots.append(Q + self.cost) + lower_bound_cost = np.min(cost_for_robots) + return lower_bound_cost + + +def find_best_joint_action(unexplored_frontiers, time, num_robots=2, num_iterations=500): + sigma1 = State(n=num_robots, Fu=unexplored_frontiers, m_t=time) + """pouct core loop""" + # Start by creating the root of the tree. + root = Node(start_state=sigma1) + # Loop through MCTS iterations. + for _ in range(num_iterations): + # One step of MCTS iteration + leaf = traverse(root) + simulation_result = rollout(leaf) + backpropagate(leaf, simulation_result) + + return best_action(root) + + +def traverse(node): + '''While the root is fully explored, pick the best uct node.''' + while node.is_fully_explored and not node.is_terminal_state: + action = best_uct_action(node) + action_idx = find_action_index(action, node.actions) + # check if the action from the parent node leads to the same node + success_state, failure_state, f_I, T_I, goal_reached = node.get_child_properties(action_idx) + if f_I is not None: + success = bernoulli(f_I.prob_feasible).rvs(1)[0] + else: + if T_I is not None: + # If f_I is none, and T_I is not None, then goal is reached + success = 1 + else: + '''This is case when both action taken can reach goal''' + print("Something has to be done here UP!!") + if node.children[action_idx][success] is not NULL: + node = node.children[action_idx][success] + else: + new_node_state = node.children_properties[action_idx]['outcome'][success] + new_node = Node(new_node_state, parent=node, + prev_action=action, T_I=T_I, goal_reached=goal_reached) + # add this 'new node' to the parent's child + node.children[action_idx][success] = new_node + # set this new node as node + node = new_node + + '''If the node is terminal state, or goal_state return the node''' + if node.is_terminal_state: + return node + + '''If the node is not terminal node, or goal node, the node is first discovered.''' + # 1. Pick a new action from the unexplored actions from the node + action = node.unexplored_actions.pop() + action_idx = find_action_index(action, node.actions) + # If the child node is already expanded, use the previously saved information + if node.children_properties[action_idx]['has_value'] is True: + success_state, failure_state, f_I, T_I, goal_reached = node.get_child_properties(action_idx) + else: + success_state, failure_state, f_I, T_I, goal_reached = move_robots(node.state, action) + node.update_child_properties(action_idx, success_state, failure_state, f_I, T_I, goal_reached) + + if f_I is not None: + success = bernoulli(f_I.prob_feasible).rvs(1)[0] + else: + if T_I is not None: + # If f_I is none, and T_I is not None, then goal is reached + success = 1 + else: + '''This is case when both action taken can reach goal''' + print("Something has to be done here!!") + + new_node_state = node.children_properties[action_idx]['outcome'][success] + + # 2. Create a new child (new leaf) + new_node = Node(new_node_state, parent=node, + prev_action=action, T_I=T_I, goal_reached=goal_reached) + # 3. Add that child to the list of children + node.children[action_idx][success] = new_node + # 4. return that new child + return new_node + + +def rollout(node): + return node.find_rollout_cost() + + +def backpropagate(node, simulation_result): + '''Update the node and it's parent (via recursion). We are updating node parents' + properties because we find best action from a node rather than best node using uct''' + if node.parent is None: + return + action_idx = find_action_index(node.prev_action, node.parent.actions) + node.parent.action_n[action_idx] += 1 + node.parent.action_values[action_idx].append(simulation_result) + backpropagate(node.parent, simulation_result) + + +def best_action(root): + '''When done sampling, pick the action which has been visited most''' + + def heuristic_cost(robot, f): + return root.state.time[f'robot{robot+1}'][f] + + if root.state.n == 1: + max_n = np.max(root.action_n) + max_n_index = [i for i, j in enumerate(root.action_n) if j == max_n or j == max_n - 1] + best_action_index = max_n_index[np.argmax([heuristic_cost(robot=0, f=root.actions[i][0]) for i in max_n_index])] + best_action = root.actions[best_action_index] + else: + max_n = np.max(root.action_n) + max_n_index = [i for i, j in enumerate(root.action_n) if j == max_n or j == max_n - 1] + h_cost = [] + for i in max_n_index: + cost = 0 + for j in range(root.state.n): + cost += heuristic_cost(j, root.actions[i][j]) + h_cost.append(cost) + best_action_index = max_n_index[np.argmin(h_cost)] + best_action = root.actions[best_action_index] + return best_action + + +def best_uct_action(node, C=500): + """Pick the best action according to the UCB/UCT algorithm""" + actions = node.actions + values = node.action_values + n = node.action_n + Q = [] + for i, _ in enumerate(actions): + UCB = np.sum(values[i]) / n[i] - C * np.sqrt((np.log(sum(n))) / (n[i])) + Q.append(UCB) + action = actions[np.argmin(Q)] + return action diff --git a/modules/mrlsp/mrlsp/scripts/__init__.py b/modules/mrlsp/mrlsp/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/mrlsp/mrlsp/scripts/simulation_baseline.py b/modules/mrlsp/mrlsp/scripts/simulation_baseline.py new file mode 100644 index 0000000..e2636aa --- /dev/null +++ b/modules/mrlsp/mrlsp/scripts/simulation_baseline.py @@ -0,0 +1,183 @@ +import environments +# add this to the imports +import numpy as np +import lsp +import mrlsp +from pathlib import Path + + +def navigate_unknown(args, termination=any, num_robots=2, do_plot=True): + # Generate Maze + + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + new_start_pose = mrlsp.utils.utility.get_path_middle_point( + known_map, pose, goal, args) + + num_robots = args.num_robots + + robot_grid = lsp.constants.UNOBSERVED_VAL * np.ones_like(known_map) + + start_pose, goal_pose = mrlsp.utils.utility.generate_start_and_goal( + num_robots=num_robots, + known_map=known_map, + same_start=True, + same_goal=True, + def_start=new_start_pose, + def_goal=goal) + + # Instantiate the simulated environment + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + + builder = environments.simulated.WorldBuildingUnityBridge + + # Create robots + robots = mrlsp.utils.utility.robot(num_robots=num_robots, + start_pose=start_pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + print(f"Initially, robot = {robots}") + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + # create a simulator + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + # set the inflation radius + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + + # add planner for the robots + planner = mrlsp.planners.BaselineLSA(robots, goal_pose, args) + + # Now the planning loop + planning_loops = [ + mrlsp.planners.PlanningLoop(goal_pose[i], + known_map, + simulator, + unity_bridge=None, + robot=robots[i], + args=args, + verbose=True) + for i in range(num_robots) + ] + # path,image,subgoal,visibility mask to store the path taken by every robot: + # This is only used for plotting and updating the planner + paths = [0 for _ in range(num_robots)] + individual_subgoal = [set() for _ in range(num_robots)] + pano_image = [0 for _ in range(num_robots)] + v_mask = [None for _ in range(num_robots)] + pose = [None for _ in range(num_robots)] + + # creating planning loop object iterable so we can do next(iter_planning_loop) to get data + iter_planning_loops = [ + iter(planning_loop) for planning_loop in planning_loops + ] + + # keeps track of goal reached condition for individual robot + goals_reached = np.array( + [planning_loop.goal_reached for planning_loop in planning_loops]) + + timestamp = 0 + # Get observation and update map and subgoals + while (not termination(goals_reached)): + for i, iter_planning_loop in enumerate(iter_planning_loops): + + # Get robot data. If the robot gets data, then do the update part + try: + robot_data = next(iter_planning_loop) + # Since all the robot has individual observation, update the grid (observed map) all together. + robot_grid = mrlsp.utils.utility.update_grid( + robot_grid, robot_data['robot_grid']) + # Store the observations + pano_image[i] = robot_data['image'] + v_mask[i] = robot_data['visibility_mask'] + individual_subgoal[i] = robot_data['subgoals'] + pose[i] = robot_data['robot_pose'] + + # if next(iter_planning_loop) raises exception, (means goal is reached for that robot) + # just pass it and plot using previous data of robot + except StopIteration: + print("Exception encountered") + pass + + # check if goal is reached or not, if goals is reached; remove it from the iterable + goals_reached[i] = planning_loops[i].goal_reached + + # calculate the subgoal from the observation of all robots + subgoals, inflated_grid = mrlsp.utils.utility.find_subgoal( + robot_grid, robots, goal_pose, simulator) + + # update LSP planner + planner.update( + pano_image, # observation image + robot_grid, # observed map + inflated_grid, + subgoals, + robots, + v_mask) + + # Update observation for every robot. + for i in range(num_robots): + extra_subgoals = None + planning_loops[i].update_robot_grid(robot_grid) + planning_loops[i].update_inflated_grid(inflated_grid) + planning_loops[i].update_subgoals(subgoals, extra_subgoals) + # for plotting + paths[i] = planning_loops[i].path_covered + + joint_action = planner.compute_selected_subgoal() + for i, action in enumerate(joint_action): + planning_loops[i].set_chosen_subgoal(action) + + if do_plot: + mrlsp.utils.plotting.plot_mrlsp(args, + timestamp, + num_robots, + robots, + goal_pose, + subgoals, + pano_image, + robot_grid, + known_map=known_map, + paths=paths) + + index_robot = np.where(goals_reached == True)[0] # noqa + mrlsp.utils.plotting.plot_final_figure(args, + num_robots, + robots, + goal_pose, + subgoals, + robot_grid, + known_map=known_map, + paths=paths, + planner='baseline') + # First robot to reach goal + cost_for_goal = robots[index_robot[0]].net_motion + print( + f"Total cost for goal = {cost_for_goal} reached by robot {index_robot[0] + 1}" + ) + cost_file = Path(args.save_dir) / f'planner_baseline_{args.map_type}_cost_{args.current_seed}_r{num_robots}.txt' + with open(cost_file, 'w') as f: + f.write(f'{cost_for_goal}') + return cost_for_goal + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--network_file', type=str) + parser.add_argument('--num_robots', type=int) + parser.add_argument('--iterations', type=int) + parser.add_argument('--limit_frontiers', type=int) + parser.add_argument('--do_plot', type=lambda x: (str(x).lower() == 'true'), default=False) + args = parser.parse_args() + args.current_seed = args.seed[0] + + cost = navigate_unknown(args, termination=any, do_plot=args.do_plot) diff --git a/modules/mrlsp/mrlsp/scripts/simulation_lsp.py b/modules/mrlsp/mrlsp/scripts/simulation_lsp.py new file mode 100644 index 0000000..f570f62 --- /dev/null +++ b/modules/mrlsp/mrlsp/scripts/simulation_lsp.py @@ -0,0 +1,127 @@ +import environments +# add this to the imports +import gridmap +import lsp +import matplotlib.pyplot as plt +import mrlsp +from pathlib import Path + + +def navigate_unknown(args): + # Generate maze + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + + pose = mrlsp.utils.utility.get_path_middle_point( + known_map, pose, goal, args) + + # Instantiate the simulated environment + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + + builder = environments.simulated.WorldBuildingUnityBridge + + # Create a robot + robot = lsp.robot.Turtlebot_Robot(pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + # create a simulator + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + # set the inflation radius + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + + # add the planner + planner = lsp.planners.KnownSubgoalPlanner(goal, known_map, args) + + # Now the planning loop + planning_loop = lsp.planners.PlanningLoop(goal, + known_map, + simulator, + unity_bridge=None, + robot=robot, + args=args, + verbose=True) + + # Now the loop calling the generator function in planning_loop + for counter, step_data in enumerate(planning_loop): + # update the planner objects + planner.update( + {'image': step_data['image']}, # observation + step_data['robot_grid'], # observed map + step_data["subgoals"], + step_data["robot_pose"], + step_data["visibility_mask"]) + # compute subgoal, and update it to planning loop + planning_loop.set_chosen_subgoal( + planner.compute_selected_subgoal()) + + # This step is required just for plotting + + # if subgoal is chosed, donot mask the subgoal, and generate water tight grid + if planning_loop.chosen_subgoal is not None: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + planner.subgoals, + do_not_mask=planning_loop.chosen_subgoal) + # else + else: + planning_grid = lsp.core.mask_grid_with_frontiers( + planner.inflated_grid, + [], + ) + + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + planning_grid, [goal.x, goal.y], use_soft_cost=True) + did_plan, path = get_path([robot.pose.x, robot.pose.y], + do_sparsify=True, + do_flip=True) + # upto here + + # Plotting + plt.ion() + plt.figure(1) + plt.clf() + ax = plt.subplot(211) + plt.imshow(step_data['image']) + ax = plt.subplot(212) + mrlsp.utils.plotting.plot_pose(ax, robot.pose, color='blue') + mrlsp.utils.plotting.plot_grid_with_frontiers( + ax, planner.observed_map, known_map, planner.subgoals) + mrlsp.utils.plotting.plot_pose(ax, + goal, + color='green', + filled=False) + mrlsp.utils.plotting.plot_path(ax, path) + mrlsp.utils.plotting.plot_pose_path(ax, robot.all_poses) + plt.show() + plt.pause(0.1) + + image_file = Path(args.save_dir) / f'images_{args.current_seed}.png' + plt.savefig(image_file) + + cost_file = Path(args.save_dir) / f'cost_{args.current_seed}_r1.txt' + with open(cost_file, 'w') as f: + f.write(f'{robot.net_motion}') + + return robot.net_motion + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--network_file', type=str) + args = parser.parse_args() + args.current_seed = args.seed[0] + + cost = navigate_unknown(args) diff --git a/modules/mrlsp/mrlsp/scripts/simulation_mrlsp.py b/modules/mrlsp/mrlsp/scripts/simulation_mrlsp.py new file mode 100644 index 0000000..75b8d53 --- /dev/null +++ b/modules/mrlsp/mrlsp/scripts/simulation_mrlsp.py @@ -0,0 +1,187 @@ +import environments +# add this to the imports +import numpy as np +import lsp +import mrlsp +from pathlib import Path + +# AIM for this: For 2 robots (to be specific), do the same. Make sure the two robots (red, and blue) +# , they follow the same path and use learning. + + +def navigate_unknown(args, termination=any, num_robots=2, do_plot=True): + # Generate Maze + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + new_start_pose = mrlsp.utils.utility.get_path_middle_point( + known_map, pose, goal, args) + + num_robots = args.num_robots + + robot_grid = lsp.constants.UNOBSERVED_VAL * np.ones_like(known_map) + + start_pose, goal_pose = mrlsp.utils.utility.generate_start_and_goal( + num_robots=num_robots, + known_map=known_map, + same_start=True, + same_goal=True, + def_start=new_start_pose, + def_goal=goal) + + # Instantiate the simulated environment + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + + builder = environments.simulated.WorldBuildingUnityBridge + # Create robots + robots = mrlsp.utils.utility.robot(num_robots=num_robots, + start_pose=start_pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + print(f"Initially, robot = {robots}") + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + # create a simulator + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + # set the inflation radius + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + + # add planner for the robots + planner = mrlsp.planners.MRLearnedSubgoalPlanner(robots, goal_pose, args) + + # Now the planning loop + planning_loops = [ + mrlsp.planners.PlanningLoop(goal_pose[i], + known_map, + simulator, + unity_bridge=None, + robot=robots[i], + args=args, + verbose=True) + for i in range(num_robots) + ] + # path,image,subgoal,visibility mask to store the path taken by every robot: + # This is only used for plotting and updating the planner + paths = [0 for _ in range(num_robots)] + individual_subgoal = [set() for _ in range(num_robots)] + pano_image = [0 for _ in range(num_robots)] + v_mask = [None for _ in range(num_robots)] + pose = [None for _ in range(num_robots)] + + # creating planning loop object iterable so we can do next(iter_planning_loop) to get data + iter_planning_loops = [ + iter(planning_loop) for planning_loop in planning_loops + ] + + # keeps track of goal reached condition for individual robot + goals_reached = np.array( + [planning_loop.goal_reached for planning_loop in planning_loops]) + + timestamp = 0 + # Get observation and update map and subgoals + while (not termination(goals_reached)): + for i, iter_planning_loop in enumerate(iter_planning_loops): + + # Get robot data. If the robot gets data, then do the update part + try: + robot_data = next(iter_planning_loop) + # Since all the robot has individual observation, update the grid (observed map) all together. + robot_grid = mrlsp.utils.utility.update_grid( + robot_grid, robot_data['robot_grid']) + # Store the observations + pano_image[i] = robot_data['image'] + v_mask[i] = robot_data['visibility_mask'] + individual_subgoal[i] = robot_data['subgoals'] + pose[i] = robot_data['robot_pose'] + planning_loops[i].update_robot_grid(robot_grid) + + # if next(iter_planning_loop) raises exception, (means goal is reached for that robot) just pass it + # and plot using previous data of robot + except StopIteration: + print("Exception encountered") + pass + + # check if goal is reached or not, if goals is reached; remove it from the iterable + goals_reached[i] = planning_loops[i].goal_reached + + # calculate the subgoal from the observation of all robots + subgoals, inflated_grid = mrlsp.utils.utility.find_subgoal( + robot_grid, robots, goal_pose, simulator) + + # update LSP planner + planner.update( + pano_image, # observation image + robot_grid, # observed map + inflated_grid, + subgoals, + robots, + v_mask) + + # Update observation for every robot. + for i in range(num_robots): + extra_subgoals = None + planning_loops[i].update_robot_grid(robot_grid) + planning_loops[i].update_inflated_grid(inflated_grid) + planning_loops[i].update_subgoals(subgoals, extra_subgoals) + # for plotting + paths[i] = planning_loops[i].path_covered + + joint_action = planner.compute_selected_subgoal() + for i, action in enumerate(joint_action): + planning_loops[i].set_chosen_subgoal(action) + + if do_plot: + mrlsp.utils.plotting.plot_mrlsp(args, + timestamp, + num_robots, + robots, + goal_pose, + subgoals, + pano_image, + robot_grid, + known_map=known_map, + paths=paths) + timestamp += 1 + + index_robot = np.where(goals_reached == True)[0] # noqa + mrlsp.utils.plotting.plot_final_figure(args, + num_robots, + robots, + goal_pose, + subgoals, + robot_grid, + known_map=known_map, + paths=paths, + planner='mrlsp') + + # First robot to reach goal + cost_for_goal = robots[index_robot[0]].net_motion + print( + f"Total cost for goal = {cost_for_goal} reached by robot {index_robot[0] + 1}" + ) + cost_file = Path(args.save_dir) / f'planner_mrlsp_{args.map_type}_cost_{args.current_seed}_r{num_robots}.txt' + with open(cost_file, 'w') as f: + f.write(f'{cost_for_goal}') + return cost_for_goal + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--network_file', type=str) + parser.add_argument('--iterations', type=int) + parser.add_argument('--num_robots', type=int) + parser.add_argument('--limit_frontiers', type=int) + parser.add_argument('--do_plot', type=lambda x: (str(x).lower() == 'true'), default=False) + args = parser.parse_args() + args.current_seed = args.seed[0] + + cost = navigate_unknown(args, termination=any, do_plot=args.do_plot) diff --git a/modules/mrlsp/mrlsp/scripts/simulation_optimistic.py b/modules/mrlsp/mrlsp/scripts/simulation_optimistic.py new file mode 100644 index 0000000..5cbf829 --- /dev/null +++ b/modules/mrlsp/mrlsp/scripts/simulation_optimistic.py @@ -0,0 +1,181 @@ +import environments +# add this to the imports +import numpy as np +import lsp +import mrlsp +from pathlib import Path + + +def navigate_unknown(args, termination=any, num_robots=2, do_plot=True): + # Generate Maze + known_map, map_data, pose, goal = environments.generate.map_and_poses(args) + new_start_pose = mrlsp.utils.utility.get_path_middle_point( + known_map, pose, goal, args) + + num_robots = args.num_robots + + robot_grid = lsp.constants.UNOBSERVED_VAL * np.ones_like(known_map) + + start_pose, goal_pose = mrlsp.utils.utility.generate_start_and_goal( + num_robots=num_robots, + known_map=known_map, + same_start=True, + same_goal=True, + def_start=new_start_pose, + def_goal=goal) + + # Instantiate the simulated environment + world = environments.simulated.OccupancyGridWorld( + known_map, + map_data, + num_breadcrumb_elements=args.num_breadcrumb_elements, + min_breadcrumb_signed_distance=4.0 * args.base_resolution) + + builder = environments.simulated.WorldBuildingUnityBridge + + # Create robots + robots = mrlsp.utils.utility.robot(num_robots=num_robots, + start_pose=start_pose, + primitive_length=args.step_size, + num_primitives=args.num_primitives, + map_data=map_data) + print(f"Initially, robot = {robots}") + with builder(args.unity_path) as unity_bridge: + unity_bridge.make_world(world) + + # create a simulator + simulator = lsp.simulators.Simulator(known_map, + goal, + args, + unity_bridge=unity_bridge, + world=world) + # set the inflation radius + simulator.frontier_grouping_inflation_radius = simulator.inflation_radius + + # add planner for the robots + planner = mrlsp.planners.OptimisticPlanner(robots, goal_pose, args) + + # Now the planning loop + planning_loops = [ + mrlsp.planners.PlanningLoop(goal_pose[i], + known_map, + simulator, + unity_bridge=None, + robot=robots[i], + args=args, + verbose=True) + for i in range(num_robots) + ] + # path,image,subgoal,visibility mask to store the path taken by every robot: This is only used + # for plotting and updating the planner + paths = [0 for _ in range(num_robots)] + individual_subgoal = [set() for _ in range(num_robots)] + pano_image = [0 for _ in range(num_robots)] + v_mask = [None for _ in range(num_robots)] + pose = [None for _ in range(num_robots)] + + # creating planning loop object iterable so we can do next(iter_planning_loop) to get data + iter_planning_loops = [ + iter(planning_loop) for planning_loop in planning_loops + ] + + # keeps track of goal reached condition for individual robot + goals_reached = np.array( + [planning_loop.goal_reached for planning_loop in planning_loops]) + + timestamp = 0 + # Get observation and update map and subgoals + while (not termination(goals_reached)): + for i, iter_planning_loop in enumerate(iter_planning_loops): + + # Get robot data. If the robot gets data, then do the update part + try: + robot_data = next(iter_planning_loop) + # Since all the robot has individual observation, update the grid (observed map) all together. + robot_grid = mrlsp.utils.utility.update_grid( + robot_grid, robot_data['robot_grid']) + # Store the observations + pano_image[i] = robot_data['image'] + v_mask[i] = robot_data['visibility_mask'] + individual_subgoal[i] = robot_data['subgoals'] + pose[i] = robot_data['robot_pose'] + + # if next(iter_planning_loop) raises exception, (means goal is reached for that robot) + # just pass it and plot using previous data of robot + except StopIteration: + print("Exception encountered") + pass + + # check if goal is reached or not, if goals is reached; remove it from the iterable + goals_reached[i] = planning_loops[i].goal_reached + + # calculate the subgoal from the observation of all robots + subgoals, inflated_grid = mrlsp.utils.utility.find_subgoal( + robot_grid, robots, goal_pose, simulator) + + # update LSP planner + planner.update( + {'image': pano_image[i]}, # observation image + robot_grid, # observed map + inflated_grid, + subgoals, + robots, + v_mask[i]) + + # Update observation for every robot. + for i in range(num_robots): + extra_subgoals = None + planning_loops[i].update_inflated_grid(inflated_grid) + planning_loops[i].update_subgoals(subgoals, extra_subgoals) + # for plotting + paths[i] = planning_loops[i].path_covered + + joint_action = planner.compute_selected_subgoal() + for i, action in enumerate(joint_action): + planning_loops[i].set_chosen_subgoal(action) + + if do_plot: + mrlsp.utils.plotting.plot_mrlsp(args, + timestamp, + num_robots, + robots, + goal_pose, + subgoals, + pano_image, + robot_grid, + known_map=known_map, + paths=paths) + + index_robot = np.where(goals_reached == True)[0] # noqa + mrlsp.utils.plotting.plot_final_figure(args, + num_robots, + robots, + goal_pose, + subgoals, + robot_grid, + known_map=known_map, + paths=paths, + planner='optimistic') + # First robot to reach goal + cost_for_goal = robots[index_robot[0]].net_motion + print( + f"Total cost for goal = {cost_for_goal} reached by robot {index_robot[0] + 1}" + ) + cost_file = Path(args.save_dir) / f'planner_optimistic_{args.map_type}_cost_{args.current_seed}_r{num_robots}.txt' + with open(cost_file, 'w') as f: + f.write(f'{cost_for_goal}') + return cost_for_goal + + +if __name__ == "__main__": + """See lsp.utils.command_line for a full list of args.""" + parser = lsp.utils.command_line.get_parser() + parser.add_argument('--network_file', type=str) + parser.add_argument('--iterations', type=int) + parser.add_argument('--num_robots', type=int) + parser.add_argument('--limit_frontiers', type=int) + parser.add_argument('--do_plot', type=lambda x: (str(x).lower() == 'true'), default=False) + args = parser.parse_args() + args.current_seed = args.seed[0] + + cost = navigate_unknown(args, termination=any, do_plot=args.do_plot) diff --git a/modules/mrlsp/mrlsp/utils/__init__.py b/modules/mrlsp/mrlsp/utils/__init__.py new file mode 100644 index 0000000..7c08403 --- /dev/null +++ b/modules/mrlsp/mrlsp/utils/__init__.py @@ -0,0 +1,2 @@ +from . import plotting # noqa +from . import utility # noqa \ No newline at end of file diff --git a/modules/mrlsp/mrlsp/utils/plotting.py b/modules/mrlsp/mrlsp/utils/plotting.py new file mode 100644 index 0000000..5183daf --- /dev/null +++ b/modules/mrlsp/mrlsp/utils/plotting.py @@ -0,0 +1,160 @@ +import lsp +import numpy as np +import matplotlib.pyplot as plt +from pathlib import Path + +colors = { + '0': 'blue', + '1': 'red', + '2': 'cyan', + '3': 'magenta', + '4': 'yellow', + '5': 'black', + '6': 'white', + '7': 'green' +} + +style = { + '0': 'b:', + '1': 'r:', + '2': 'c:', + '3': 'm:', + '4': 'y:', + '5': 'k:', + '6': 'w:', + '7': 'g:' +} + + +def plot_pose(ax, pose, color='black', filled=True): + if filled: + ax.scatter(pose.x, pose.y, color=color, s=10, label='point') + else: + ax.scatter(pose.x, + pose.y, + color=color, + s=10, + label='point', + facecolors='none') + + +def plot_path(ax, path, style='b:'): + if path is not None: + ax.plot(path[0, :], path[1, :], style) + + +def plot_pose_path(ax, poses, style='b'): + path = np.array([[p.x, p.y] for p in poses]).T + plot_path(ax, path, style) + + +def plot_grid_with_frontiers(ax, + grid_map, + known_map, + frontiers, + cmap_name='viridis'): + grid = lsp.utils.plotting.make_plotting_grid(grid_map, known_map) + + cmap = plt.get_cmap(cmap_name) + for frontier in frontiers: + color = cmap(frontier.prob_feasible) + grid[frontier.points[0, :], frontier.points[1, :], 0] = color[0] + grid[frontier.points[0, :], frontier.points[1, :], 1] = color[1] + grid[frontier.points[0, :], frontier.points[1, :], 2] = color[2] + + ax.imshow(np.transpose(grid, (1, 0, 2))) + + +def plot_mrlsp(args, + timestamp, + num_robots, + robots, + goal_pose, + subgoals, + pano_image, + robot_grid, + known_map=None, + paths=None, + cols=1): + + # create a main figure + if num_robots == 1: + plt.ion() + plt.figure(1, figsize=(6, 6)) + plt.clf() + if pano_image[0] is not None: + ax = plt.subplot(211) + plt.imshow(pano_image[0]) + ax = plt.subplot(212) + else: + ax = plt.subplot(111) + plot_pose(ax, robots[0].pose, color='blue') + plot_grid_with_frontiers(ax, robot_grid, known_map, + subgoals) + plot_pose(ax, goal_pose[0], color='green', filled=False) + if paths[0] != []: + plot_path(ax, paths[0]) + plot_pose_path(ax, robots[0].all_poses) + plt.show() + plt.pause(0.01) + + else: + image_file = Path(args.save_dir) / \ + f'img_{args.map_type}_{args.num_robots}robots_{args.current_seed}_{timestamp}.png' + num_image = num_robots + plt.ion() + fig = plt.figure(num=1, figsize=(12, num_image * 2)) + gs = fig.add_gridspec(num_image, 2) + plt.clf() + # plot pano images for each robot + for k in range((num_image)): + ax = fig.add_subplot(gs[k, 0]) # noqa: F841 + plt.imshow(pano_image[k]) + plt.title("robot" + str(k + 1), color=colors[str(k)]) + + ax1 = fig.add_subplot(gs[:num_image - 1, 1]) + + plot_grid_with_frontiers(ax1, robot_grid, known_map, + subgoals) + for k in range(num_robots): + plt.text(robots[k].pose.x, + robots[k].pose.y, + k + 1, + color=colors[str(k)]) + plot_pose(ax1, robots[k].pose, color=colors[str(k)]) + plot_pose(ax1, goal_pose[k], color=colors[str(k)], filled=False) + # print(paths[k]) + if paths[k] != []: + plot_path(ax1, paths[k], style=style[str(k)]) + plot_pose_path(ax1, robots[k].all_poses, style[str(k)][:-1]) + # plt.savefig(image_file) + plt.show() + plt.pause(0.1) + + +def plot_final_figure(args, + num_robots, + robots, + goal_pose, + subgoals, + robot_grid, + known_map=None, + paths=None, + planner=None): + image_file = Path(args.save_dir) / \ + f'planner_{planner}_{args.map_type}_cost_{args.current_seed}_r{num_robots}.png' + plt.figure(figsize=(12, 10)) + ax1 = plt.subplot(111) + plot_grid_with_frontiers(ax1, robot_grid, known_map, + subgoals) + for k in range(num_robots): + plt.text(robots[k].pose.x, + robots[k].pose.y, + k + 1, + color=colors[str(k)]) + plot_pose(ax1, robots[k].pose, color=colors[str(k)]) + plot_pose(ax1, goal_pose[k], color=colors[str(k)], filled=False) + if paths[k] != []: + plot_path(ax1, paths[k], style=style[str(k)]) + plot_pose_path(ax1, robots[k].all_poses, style[str(k)][:-1]) + plt.savefig(image_file) diff --git a/modules/mrlsp/mrlsp/utils/utility.py b/modules/mrlsp/mrlsp/utils/utility.py new file mode 100644 index 0000000..dd70a88 --- /dev/null +++ b/modules/mrlsp/mrlsp/utils/utility.py @@ -0,0 +1,415 @@ +from common import Pose +import common +import random +import numpy as np +import lsp +import math +import gridmap +import copy +from gridmap.constants import (COLLISION_VAL, FREE_VAL, UNOBSERVED_VAL) +from scipy.optimize import linear_sum_assignment +import itertools + + +# generate different start and goal poses for num_robots +def generate_start_and_goal(num_robots=1, + known_map=None, + same_start=False, + same_goal=False, + def_start=None, + def_goal=None): + if (not same_start or not same_goal): + + start = [0 for i in range(num_robots)] + goal = [0 for i in range(num_robots)] + start_pose = [0 for i in range(num_robots)] + goal_pose = [0 for i in range(num_robots)] + for i in range(num_robots): + while True: + (x, y) = random.randint(0, + len(known_map) - 1), random.randint( + 0, + len(known_map[0]) - 1) + if (known_map[x, y] == 0): + a = np.array([x, y]) + start[i] = a + break + + for i in range(num_robots): + while True: + (x, y) = random.randint(0, + len(known_map) - 1), random.randint( + 0, + len(known_map[0]) - 1) + if (known_map[x, y] == 0): + a = np.array([x, y]) + goal[i] = a + break + + for i in range(num_robots): + start_pose[i] = Pose(x=start[i][0], + y=start[i][1], + yaw=2 * math.pi * random.random()) + + goal_pose[i] = Pose(x=goal[i][0], + y=goal[i][1], + yaw=2 * math.pi * random.random()) + print("not same start or goal") + + if same_start: + print("same start") + start_pose = [def_start for _ in range(num_robots)] + + if same_goal: + print("same goal") + goal_pose = [def_goal for _ in range(num_robots)] + + return start_pose, goal_pose + + +# define robot instance for num_robots +def robot(num_robots, start_pose, primitive_length, num_primitives, map_data): + + robot = [0 for i in range(num_robots)] + + for i in range(num_robots): + robot[i] = lsp.robot.Turtlebot_Robot(start_pose[i], + primitive_length=primitive_length, + num_primitives=num_primitives, + map_data=map_data) + + return robot + + +# Create lsp planner for num_robtos +def lsp_planner(args, num_robots, goal_pose): + robot_lsp_planners = [0 for i in range(num_robots)] + + for i in range(num_robots): + robot_lsp_planners[i] = lsp.planners.LearnedSubgoalPlanner( + goal_pose[i], args) + + return robot_lsp_planners + + +# To update the current grid with the current observation +def update_grid(robot_grid, observed_grid): + previous = robot_grid + now = observed_grid + current = lsp.constants.UNOBSERVED_VAL * np.ones_like(previous) + + for idx, _ in np.ndenumerate(current): + # more like and gate + if previous[idx] == UNOBSERVED_VAL and now[idx] == UNOBSERVED_VAL: + current[idx] = UNOBSERVED_VAL + elif previous[idx] == COLLISION_VAL and now[idx] == COLLISION_VAL: + current[idx] = COLLISION_VAL + elif previous[idx] == COLLISION_VAL and now[idx] == UNOBSERVED_VAL: + current[idx] = COLLISION_VAL + elif previous[idx] == UNOBSERVED_VAL and now[idx] == COLLISION_VAL: + current[idx] = COLLISION_VAL + else: + current[idx] = FREE_VAL + return current + + +# TODO: For every instance, send only pose not robot +def get_multirobot_distances(robot_grid, robots, goal_pose, subgoals): + distances = {} + distances['goal'] = lsp.core.get_goal_distances(robot_grid, goal_pose[0], frontiers=subgoals) + distances['frontier'] = lsp.core.get_frontier_distances(robot_grid, frontiers=subgoals) + for i, robot in enumerate(robots): + distances[f'robot{i+1}'] = lsp.core.get_robot_distances(robot_grid, robot.pose, frontiers=subgoals) + return distances + + +def get_all_distance(robot_grid, robots, goal_pose, subgoals): + distances = [] + + # goal_pose[0] is taken because all the goal is same + # Incase of multiple goals, this has to go inside the for loop + goal_dist = lsp.core.get_goal_distances(robot_grid, + goal_pose[0], + frontiers=subgoals) + + frontier_distances = lsp.core.get_frontier_distances(robot_grid, + frontiers=subgoals) + + for robot in robots: + robot_dist = lsp.core.get_robot_distances(robot_grid, + robot.pose, + frontiers=subgoals) + + distance = { + 'robot': robot_dist, + 'goal': goal_dist, + 'frontier': frontier_distances + } + + distances.append(distance) + + return distances + + +def get_top_n_frontiers(frontiers, distances, n): + """This heuristic is for retrieving the 'best' N frontiers""" + frontiers = [f for f in frontiers if f.prob_feasible > 0] + + h_prob = {s: s.prob_feasible for s in frontiers} + fs_prob = sorted(list(frontiers), + key=lambda s: h_prob[s], + reverse=True) + # take two subgoals with higher probability + fs_collated = fs_prob[:2] + # remaining subgoals for which gives the minimum cost + subgoals = fs_prob[2:] + + order_heuristics = [] + order_heuristics.append({ + s: ii for ii, s in enumerate(subgoals) + }) + order_heuristics.append({ + s: 1 - s.prob_feasible for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + + s.prob_feasible * s.delta_success_cost + + (1 - s.prob_feasible) * s.exploration_cost + for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + + s.delta_success_cost + for s in subgoals + }) + order_heuristics.append({ + s: distances['goal'][s] + distances['robot'][s] + + s.exploration_cost + for s in subgoals + }) + + heuristic_ordering_dat = [] + for heuristic in order_heuristics: + ordered_subgoals = sorted(subgoals, reverse=False, key=lambda s: heuristic[s]) + ordering_cost = get_ordering_cost(ordered_subgoals, distances) + heuristic_ordering_dat.append((ordering_cost, ordered_subgoals)) + subgoals = min(heuristic_ordering_dat, key=lambda hod: hod[0])[1] + + for s in subgoals: + fs_collated.append(s) + + return fs_collated[0:n] + + +def get_top_n_frontiers_multirobot(num_robots, frontiers, distances, n): + goal_dist = distances['goal'] + individual_distance = {} + individual_distance['goal'] = goal_dist + individual_distance['frontier'] = distances['frontier'] + best_frontiers = [] + seen = set() + h_prob = {s: s.prob_feasible for s in frontiers} + for i in range(num_robots): + robot_dist = distances[f'robot{i+1}'] + individual_distance['robot'] = robot_dist + bf = lsp.core.get_top_n_frontiers(frontiers, goal_dist, robot_dist, n) + if len(bf) == 0: + print("No frontiers returned by get_top_n_frontiers") + fs_prob = sorted(list(frontiers), + key=lambda s: h_prob[s], + reverse=True) + bf = fs_prob[:n] + # bf = get_top_n_frontiers(frontiers, individual_distance, n) + best_frontiers.append(bf) + + all_robot_best_frontiers = [] + for i in range(n): + for bf in best_frontiers: + if i < len(bf) and bf[i] not in seen: + all_robot_best_frontiers.append(bf[i]) + seen.add(bf[i]) + + top_frontiers = all_robot_best_frontiers[:n] + return top_frontiers + + +def get_cost_dictionary(num_robots, distances, planner): + cost_dictionary = [None for _ in range(num_robots)] + for i in range(num_robots): + cost_dictionary[i] = { + subgoal: lsp.core.get_lowest_cost_ordering_beginning_with( + subgoal, planner[i].subgoals, distances[i], do_sort=False)[0] + for subgoal in planner[i].subgoals + } + subgoal_matrix = np.array([list(cd.keys()) for cd in cost_dictionary]) + cost_matrix = np.array([list(cd.values()) for cd in cost_dictionary]) + return cost_dictionary, subgoal_matrix, cost_matrix + + +def find_subgoal(robot_grid, robots, goal_pose, simulator): + inflated_grid = lsp.constants.UNOBSERVED_VAL * np.ones_like(robot_grid) + for robot in robots: + observed_grid = simulator.get_inflated_grid(robot_grid, robot) + observed_grid = gridmap.mapping.get_fully_connected_observed_grid( + observed_grid, robot.pose) + inflated_grid = update_grid(inflated_grid, observed_grid) + subgoals = simulator.get_updated_frontier_set(inflated_grid, None, set()) + return subgoals, inflated_grid + + +def get_ordering_cost(subgoals, distances): + fstate = None + for s in subgoals: + fstate = lsp.core.FState(s, distances, fstate) + return fstate.cost + + +def limit_total_subgoals(num_robots, frontiers, distances, n): + subgoals = set([copy.copy(s) for s in frontiers]) + extra_subgoals = set() + # This is done to limit the frontiers beyond n + # all the subgoals that are of low cost, are stored and returned in extra_subgoals + if len(subgoals) > n: + print(f"More than {n} subgoals, limiting to {n} subgoals") + top_frontiers = set( + get_top_n_frontiers_multirobot(num_robots, subgoals, distances, n)) + extra_subgoals = subgoals - top_frontiers + subgoals = top_frontiers + else: + print("Printing subgoal probabilities:") + print([s.prob_feasible for s in subgoals]) + chosen_subgoal = set([s for s in subgoals if s.prob_feasible != 0]) + print("Number of subgoals with non-zero probability: ", len(chosen_subgoal)) + extra_subgoals = subgoals - chosen_subgoal + subgoals = chosen_subgoal + return subgoals, extra_subgoals + + +def get_path_middle_point(known_map, start, goal, args): + """This function returns the middle point on the path from goal to the + robot starting position""" + inflation_radius = args.inflation_radius_m / args.base_resolution + inflated_mask = gridmap.utils.inflate_grid( + known_map, inflation_radius=inflation_radius) + # Now sample the middle point + cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position( + inflated_mask, [goal.x, goal.y]) + _, path = get_path([start.x, start.y], do_sparsify=False, do_flip=False) + row, col = path.shape + x = path[0][col // 2] + y = path[1][col // 2] + new_start_pose = common.Pose(x=x, y=y, yaw=2 * np.pi * np.random.rand()) + return new_start_pose + + +def get_frontier_time_by_triangle_formation(a, b, c, time_travelled): + epsilon = 0.1 + if a + b < c: + new_time = time_travelled * c / (a + b) + return new_time + elif b > a + c: + new_time = time_travelled * c / (a + b) + return new_time + elif a > b + c: + new_time = time_travelled * c / (a + b) + return new_time + elif abs((a + b) - c) <= epsilon: + # the frontier is horizontally aligned (in positive direction) + new_time = c - time_travelled + return new_time + elif abs((a + c) - b) <= epsilon: + # the frontier is horizontally aligned (in negative direction) + new_time = c + time_travelled + return new_time + elif abs((b + c) - a) <= epsilon: + # the all the frontier lies in the same line + new_time = abs(c - time_travelled) + return new_time + + if a > 0: + x = (c * c - b * b + a * a) / (2 * a) + y = np.sqrt(c * c - x * x) + frontier_point = np.array([x, y]) + else: + raise AssertionError('First side of triangle not > 0') + + new_point = np.array([time_travelled, 0]) + new_time = np.linalg.norm(new_point - frontier_point) + if math.isnan(new_time): + print(a, b, c, time_travelled) + raise AssertionError('new time is \'nan\'!!') + return new_time + + +def find_action_index(action, all_actions): + n = len(action) + for i, a in enumerate(all_actions): + result = [a[j] == action[j] for j in range(n)] + # pdb.set_trace() + if (all(result)): + return i + return None + + +def copy_dictionary(all_time): + new_all_time = {} + for time in all_time: + new_all_time[time] = all_time[time].copy() + return new_all_time + + +def find_action_list_from_cost_matrix_using_lsa(cost_matrix, subgoal_matrix): + cost = cost_matrix + num_robots = len(cost_matrix) + left_robot = num_robots + assigned_robot = 0 + joint_action = [None for i in range(num_robots)] + count = 0 + while (left_robot != 0 and count < num_robots + 1): + # find the lowest cost for the first 'k' robots, where k is the number of subgoals + n_rows, n_cols = linear_sum_assignment(cost) + for i, row in enumerate(n_rows): + # assign the action to the robot if it is not previously assigned, i.e., not None + if joint_action[row] is None: + joint_action[row] = subgoal_matrix[row][n_cols[i]] + assigned_robot += 1 + # replace the cost by a 'high number' so that it it doesn't get selected when doing lsa + cost[row] = 1e11 + # decrement the left robot so that it loops and assigns to the remaining robot. + left_robot = num_robots - assigned_robot + count += 1 + # for every none items in the joint action, randomly assign a subgoal in the joint action that's not none + if None in joint_action: + non_none_items = [item for item in joint_action if item is not None] + none_idx = [idx for idx, val in enumerate(joint_action) if val is None] + for idx in none_idx: + joint_action[idx]= np.random.choice(non_none_items) + return joint_action + + +def get_action_combination(iterables, repeat, same_action=False): + '''If same action = false i.e., permutations without replacement + If no.of frontiers > no. of robots, permute the frontiers''' + if not same_action and len(iterables) >= repeat: + actions = list(itertools.permutations(iterables, repeat)) + return actions + else: + '''same action = true i.e., permutations with replacement + If no.of frontiers < no.of robots, make sure some robot explore the 'same' frontier''' + actions = list(itertools.product(iterables, repeat=repeat)) + '''same_action = false i.e, you want robot all robot to prevent exploring 'same' frontier + as much as possible. Hence maximum allowed same action = no. of frontiers / robot''' + if not same_action and len(iterables) > 1: + final_action = [] + same_action_max = int(np.ceil(repeat / len(iterables))) + for action in actions: + max_action_same = any([action.count(action[i]) > same_action_max for i in range(len(action))]) + if max_action_same: + continue + final_action.append(action) + return final_action + return actions diff --git a/modules/mrlsp/setup.py b/modules/mrlsp/setup.py new file mode 100644 index 0000000..3e8405e --- /dev/null +++ b/modules/mrlsp/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='mrlsp', + version='1.0.0', + description='A simple mrlsp using lsp module', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/mrlsp/tests/dummy_frontier.py b/modules/mrlsp/tests/dummy_frontier.py new file mode 100644 index 0000000..9fa83fa --- /dev/null +++ b/modules/mrlsp/tests/dummy_frontier.py @@ -0,0 +1,23 @@ +import numpy as np + + +class DummyFrontier(): + def __init__(self, q_f, label=None): + self.prob_feasible = 0.0 + self.exploration_cost = 0.0 + self.delta_success_cost = 0.0 + self.q_f = np.array(q_f) + self.label = label + self.is_from_last_chosen = False + self.hash = hash(self.q_f.tobytes()) + + def set_props(self, prob_feasible, exploration_cost, delta_success_cost): + self.prob_feasible = prob_feasible + self.exploration_cost = exploration_cost + self.delta_success_cost = delta_success_cost + + def __hash__(self): + return self.hash + + def __eq__(self, other): + return hash(self) == hash(other) diff --git a/modules/mrlsp/tests/test_core_utility_functions.py b/modules/mrlsp/tests/test_core_utility_functions.py new file mode 100644 index 0000000..1980e0a --- /dev/null +++ b/modules/mrlsp/tests/test_core_utility_functions.py @@ -0,0 +1,336 @@ +import pytest # noqa: F401 +import mrlsp +import mrlsp_accel +import itertools +from util_function import current_state_1, current_state_2, current_state_3 # noqa: F401 +import util_function as test_shared_functions + + +# write a test for testing the cpp version of remaining_time by triangle fomulation and the python version +def test_remaining_frontier_time_by_triangle_formulation(): + all_a = [10, 10, 12, 14.9999, 150, 20, 21, 60] + all_b = [5, 2, 22, 4.999999, 149.99, 21, 28, 27] + all_c = [5, 15, 8, 20, 50.0, 29, 35, 33] + all_time_travelled = [5, 8, 6, 6.98, 86, 17, 19.8, 50] + + for a, b, c, travel_time in zip(all_a, all_b, all_c, all_time_travelled): + remaining_time_py = mrlsp.utils.utility.get_frontier_time_by_triangle_formation(a, b, c, travel_time) + remaining_time_cpp = mrlsp_accel.get_frontier_time_by_triangle_formation_cpp(a, b, c, travel_time) + assert remaining_time_cpp == remaining_time_py + print(f'for a = {a}, b = {b}, c = {c}, travel_time = {travel_time}, \ + remaining_time_py = {remaining_time_py}, remaining_time_cpp = {remaining_time_cpp}') + + +# test progress and frontier from qt for cpp and python +def test_progress_and_frontier_from_qt(current_state_1): # noqa: F811 + num_robots = current_state_1['num_robots'] + unexplored_frontiers = current_state_1['unexplored_frontiers_cpp'] + q_t_py = current_state_1['q_t'] + q_t_cpp = current_state_1['q_t_cpp'] + s_dict = current_state_1['s_dict'] + + actual_progress = [10, 12] + actual_frontiers = [unexplored_frontiers[0], unexplored_frontiers[1]] + calculated_progress_py = [] + calculated_frontiers_py = [] + calculated_progress_cpp = [] + calculated_frontiers_cpp = [] + + for i in range(num_robots): + frontier, progress = mrlsp.core.find_progress_and_frontier_for_robot(q_t_py, i) + calculated_frontiers_py.append(frontier) + calculated_progress_py.append(progress) + + for i in range(num_robots): + frontier, progress = mrlsp_accel.find_progress_and_frontier_for_robot_cpp(q_t_cpp, i) + calculated_frontiers_cpp.append(s_dict[frontier]) + calculated_progress_cpp.append(progress) + + print(f'{calculated_progress_py=}, {actual_progress=}') + print(f'{calculated_frontiers_py=}, {actual_frontiers=}') + + assert all([x == y for x, y in zip(calculated_progress_py, actual_progress)]) + assert all([x == y for x, y in zip(calculated_frontiers_py, actual_frontiers)]) + assert all([x == y for x, y in zip(calculated_progress_py, calculated_progress_cpp)]) + assert all([x == y for x, y in zip(calculated_frontiers_py, calculated_frontiers_cpp)]) + + +def test_first_explored_frontier_and_time(current_state_1): # noqa: F811 + num_robots = current_state_1['num_robots'] + unexplored_frontiers = current_state_1['unexplored_frontiers_cpp'] + time = current_state_1['time'] + + a1 = unexplored_frontiers[0] + a2 = unexplored_frontiers[1] + a3 = unexplored_frontiers[2] + + s1 = mrlsp.core.State(n=num_robots, Fu=unexplored_frontiers, m_t=time) + actions = [[a1, a2], [a1, a3], [a2, a1], [a2, a3], [a3, a1], [a3, a2]] + calculated_frontiers = [] + actual_frontiers = [a1, a1, a1, a3, a1, a3] + + calculated_TI = [] + actual_TI = [13, 13, 17, 18, 17, 18] + + for action in actions: + f_I, T_I = mrlsp.core.get_frontier_of_knowlege_and_time(s1, action) + calculated_frontiers.append(f_I) + calculated_TI.append(T_I) + + print(f'{calculated_frontiers=}, {actual_frontiers=}') + print(f'{calculated_TI=}, {actual_TI=}') + + assert all([x == y for x, y in zip(calculated_frontiers, actual_frontiers)]) + assert all([x == y for x, y in zip(calculated_TI, actual_TI)]) + + +# test first explored frontier and time for cpp and python +@pytest.mark.parametrize( + "current_state_name, num_robots", + [ + ("current_state_1", 1), + ("current_state_1", 2), + ("current_state_2", 1), + ("current_state_2", 2), + ("current_state_3", 1), + ("current_state_3", 2), + ("current_state_3", 3), + ] +) +def test_first_explored_frontier_and_time_cpp(current_state_name, num_robots, request): + current_state = request.getfixturevalue(current_state_name) + num_robots = num_robots + unexplored_frontiers = current_state['unexplored_frontiers_cpp'] + time = current_state['time'] + s_cpp = current_state['s_cpp'] + rd_cpp = current_state['rd_cpp'] + gd_cpp = current_state['gd_cpp'] + fd_cpp = current_state['fd_cpp'] + s_dict = current_state['s_dict'] + + s1_py = mrlsp.core.State(n=num_robots, Fu=unexplored_frontiers, m_t=time) + actions = [action for action in itertools.permutations(unexplored_frontiers, num_robots)] + calculated_frontiers_py = [] + calculated_TI_py = [] + calculated_frontiers_cpp = [] + calculated_TI_cpp = [] + + for action in actions: + f_I, T_I = mrlsp.core.get_frontier_of_knowlege_and_time(s1_py, action) + calculated_frontiers_py.append(f_I) + calculated_TI_py.append(T_I) + + s1_cpp = mrlsp_accel.State_cpp(num_robots=num_robots, unexplored_frontiers=s_cpp, robot_distances=rd_cpp, + goal_distances=gd_cpp, frontier_distances=fd_cpp) + + actions_cpp = [[hash(a) for a in action] for action in actions] + + for action in actions_cpp: + f_I, T_I = mrlsp_accel.get_frontier_of_knowledge_and_time_cpp(s1_cpp, action) + calculated_frontiers_cpp.append(s_dict[f_I]) + calculated_TI_cpp.append(T_I) + + print(f'{calculated_TI_py=}, {calculated_TI_cpp=}') + + # check that the python and cpp versions of the functions return the same results + assert all([x == y for x, y in zip(calculated_frontiers_py, calculated_frontiers_cpp)]) + assert all([x == y for x, y in zip(calculated_TI_py, calculated_TI_cpp)]) + + +# write a test for testing q_t for the cpp version and the python version +@pytest.mark.parametrize( + "current_state_name, num_robots", + [ + ("current_state_1", 1), + ("current_state_1", 2), + ("current_state_2", 1), + ("current_state_2", 2), + ("current_state_3", 1), + ("current_state_3", 2), + ("current_state_3", 3), + ] +) +def test_q_t_and_time(current_state_name, num_robots, request): # noqa: F811 + num_robots = num_robots + current_state = request.getfixturevalue(current_state_name) + unexplored_frontiers = current_state['unexplored_frontiers_cpp'] + time = current_state['time'] + s_cpp = current_state['s_cpp'] + rd_cpp = current_state['rd_cpp'] + gd_cpp = current_state['gd_cpp'] + fd_cpp = current_state['fd_cpp'] + s_dict = current_state['s_dict'] + + s1_py = mrlsp.core.State(n=num_robots, Fu=set(unexplored_frontiers), m_t=time) + s1_cpp = mrlsp_accel.State_cpp(num_robots=num_robots, unexplored_frontiers=s_cpp, robot_distances=rd_cpp, + goal_distances=gd_cpp, frontier_distances=fd_cpp) + s1_q_t_py = s1_py.q_t + s1_q_t_cpp = s1_cpp.q_t + + # Test that intialization of q_t is same for python and cpp State classes + # Test that q_t is same for python and cpp State classes + for prog_py, prog_cpp in zip(s1_q_t_py, s1_q_t_cpp): + for f_py, p_py in prog_py.items(): + assert prog_cpp[hash(f_py)] == p_py + + actions = [action for action in itertools.permutations(unexplored_frontiers, num_robots)] + for action in actions: + test_shared_functions.check_py_and_cpp_q_t_match(s1_py, s1_cpp, action, s_dict) + + +# write a test to test move robots +@pytest.mark.parametrize( + "current_state_name, num_robots", + [ + ("current_state_1", 1), + ("current_state_1", 2), + ("current_state_2", 1), + ("current_state_2", 2), + ("current_state_3", 1), + ("current_state_3", 2), + ("current_state_3", 3), + ] +) +def test_move_robots(current_state_name, num_robots, request): # noqa: F811 + num_robots = num_robots + current_state = request.getfixturevalue(current_state_name) + unexplored_frontiers = current_state['unexplored_frontiers_cpp'] + time = current_state['time'] + s_cpp = current_state['s_cpp'] + rd_cpp = current_state['rd_cpp'] + gd_cpp = current_state['gd_cpp'] + fd_cpp = current_state['fd_cpp'] + s_dict = current_state['s_dict'] + + s1_py = mrlsp.core.State(n=num_robots, Fu=set(unexplored_frontiers), m_t=time) + s1_cpp = mrlsp_accel.State_cpp(num_robots=num_robots, unexplored_frontiers=s_cpp, robot_distances=rd_cpp, + goal_distances=gd_cpp, frontier_distances=fd_cpp) + + # actions = [(a1, a2), (a1, a3), (a2, a1), (a2, a3), (a3, a1), (a3, a2)] + actions = [action for action in itertools.permutations(unexplored_frontiers, num_robots)] + + for action in actions: + test_shared_functions.check_py_and_cpp_move_robots_match(s1_py, s1_cpp, action, s_dict) + + +def test_tree_states(current_state_2): # noqa: F811 + '''This test checks all the states of a tree from the current state (current_state_2) + for every actions available from current_state_2.''' + unexplored_frontiers = current_state_2['unexplored_frontiers_py'] + time = current_state_2['time'] + num_robots = current_state_2['num_robots'] + list_of_unexplored_frontiers = current_state_2['unexplored_frontiers_cpp'] + + s_dict = current_state_2['s_dict'] + s_cpp = current_state_2['s_cpp'] + rd_cpp = current_state_2['rd_cpp'] + gd_cpp = current_state_2['gd_cpp'] + fd_cpp = current_state_2['fd_cpp'] + + a1 = list_of_unexplored_frontiers[0] + a2 = list_of_unexplored_frontiers[1] + + # Root of the tree + s1_py = mrlsp.core.State(n=num_robots, Fu=set(unexplored_frontiers), m_t=time) + s1_cpp = mrlsp_accel.State_cpp(num_robots=num_robots, unexplored_frontiers=s_cpp, robot_distances=rd_cpp, + goal_distances=gd_cpp, frontier_distances=fd_cpp) + + test_shared_functions.check_py_and_cpp_states_match(s1_py, s1_cpp, s_dict) + + actions_s1 = [(a1, a2), (a2, a1)] + + # Children of the root (1a) + print("Root -> Child 1a") + action1a_py = actions_s1[0] + action1a_cpp = (hash(action1a_py[0]), hash(action1a_py[1])) + s_1a_succ_py, s_1a_fail_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s1_py, action1a_py) + s_1a_succ_cpp, s_1a_fail_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp(s1_cpp, action1a_cpp) + assert T_I_py == T_I_cpp + assert T_I_py == 13 + assert f_I_cpp == hash(f_I_py) + assert goal_reached_py == goal_reached_cpp + print("Success") + test_shared_functions.check_py_and_cpp_states_match(s_1a_succ_py, s_1a_succ_cpp, s_dict) + print("Failure") + test_shared_functions.check_py_and_cpp_states_match(s_1a_fail_py, s_1a_fail_cpp, s_dict) + + # Expanding child 1a (success) + actions_s2 = [(a1, a2)] + print("Child 1a (success) -> Child 2a") + action2a_py = actions_s2[0] + action2a_cpp = (hash(action2a_py[0]), hash(action2a_py[1])) + s_2a_succ_py, s_2a_fail_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s_1a_succ_py, action2a_py) + s_2a_succ_cpp, s_2a_fail_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp( + s_1a_succ_cpp, action2a_cpp) + assert T_I_py == T_I_cpp + assert T_I_py == 5 + assert f_I_cpp == hash(f_I_py) + assert f_I_py == a2 + assert goal_reached_py == goal_reached_cpp + print("Success") + test_shared_functions.check_py_and_cpp_states_match(s_2a_succ_py, s_2a_succ_cpp, s_dict) + print("Failure") + test_shared_functions.check_py_and_cpp_states_match(s_2a_fail_py, s_2a_fail_cpp, s_dict) + + # Expanding child 1a (failure) + actions_s2 = [(a2, a2)] + print("Child 1a (fail) -> Child 2a") + action2a_py = actions_s2[0] + action2a_cpp = (hash(action2a_py[0]), hash(action2a_py[1])) + s_2b_succ_py, s_2b_fail_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s_1a_fail_py, action2a_py) + s_2b_succ_cpp, s_2b_fail_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp( + s_1a_fail_cpp, action2a_cpp) + assert T_I_py == T_I_cpp + assert T_I_py == 5 + assert f_I_cpp == hash(f_I_py) + assert f_I_py == a2 + assert goal_reached_py == goal_reached_cpp + print("Success") + test_shared_functions.check_py_and_cpp_states_match(s_2b_succ_py, s_2b_succ_cpp, s_dict) + print("Failure") + test_shared_functions.check_py_and_cpp_states_match(s_2b_fail_py, s_2b_fail_cpp, s_dict) + + # Children of the root (1b) + print("Root -> Child 1b") + action1b_py = actions_s1[1] + action1b_cpp = (hash(action1b_py[0]), hash(action1b_py[1])) + s_1b_succ_py, s_1b_fail_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s1_py, action1b_py) + s_1b_succ_cpp, s_1b_fail_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp(s1_cpp, action1b_cpp) + assert T_I_py == T_I_cpp + assert T_I_py == 17 + assert f_I_cpp == hash(f_I_py) + assert f_I_py == a1 + assert goal_reached_py == goal_reached_cpp + test_shared_functions.check_py_and_cpp_states_match(s_1b_succ_py, s_1b_succ_cpp, s_dict) + test_shared_functions.check_py_and_cpp_states_match(s_1b_fail_py, s_1b_fail_cpp, s_dict) + + # Expanding child 1b (success) + actions_s2 = [(a2, a1)] + print("Child 1b (success) -> Child 2a") + action2a_py = actions_s2[0] + action2a_cpp = (hash(action2a_py[0]), hash(action2a_py[1])) + s_2a_succ_py, s_2a_fail_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s_1b_succ_py, action2a_py) + s_2a_succ_cpp, s_2a_fail_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp( + s_1b_succ_cpp, action2a_cpp) + assert T_I_py == T_I_cpp + assert T_I_py == 5 + assert f_I_cpp == hash(f_I_py) + assert f_I_py == a2 + assert goal_reached_py == goal_reached_cpp + test_shared_functions.check_py_and_cpp_states_match(s_2a_succ_py, s_2a_succ_cpp, s_dict) + test_shared_functions.check_py_and_cpp_states_match(s_2a_fail_py, s_2a_fail_cpp, s_dict) + + actions_s2 = [(a2, a2)] + print("Child 1b (fail) -> Child 2a") + action2b_py = actions_s2[0] + action2b_cpp = (hash(action2b_py[0]), hash(action2b_py[1])) + s_2b_succ_py, s_2b_fail_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s_1b_fail_py, action2b_py) + s_2b_succ_cpp, s_2b_fail_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp( + s_1b_fail_cpp, action2b_cpp) + assert T_I_py == T_I_cpp + assert T_I_py == 5 + assert f_I_cpp == hash(f_I_py) + assert f_I_py == a2 + assert goal_reached_py == goal_reached_cpp + test_shared_functions.check_py_and_cpp_states_match(s_2b_succ_py, s_2b_succ_cpp, s_dict) + test_shared_functions.check_py_and_cpp_states_match(s_2b_fail_py, s_2b_fail_cpp, s_dict) diff --git a/modules/mrlsp/tests/test_cpp_state_constructor.py b/modules/mrlsp/tests/test_cpp_state_constructor.py new file mode 100644 index 0000000..c66c83e --- /dev/null +++ b/modules/mrlsp/tests/test_cpp_state_constructor.py @@ -0,0 +1,48 @@ +import mrlsp_accel +from util_function import current_state_1 # noqa: F401 + + +def test_state_variables(current_state_1): # noqa: F811 + '''Only current_state_1 has data to test this function''' + num_robots = current_state_1['num_robots'] + unexplored_frontiers = current_state_1['unexplored_frontiers_cpp'] + s_cpp = current_state_1['s_cpp'] + rd_cpp = current_state_1['rd_cpp'] + gd_cpp = current_state_1['gd_cpp'] + fd_cpp = current_state_1['fd_cpp'] + + a1 = unexplored_frontiers[0] + + s1_cpp = mrlsp_accel.State_cpp(num_robots=num_robots, unexplored_frontiers=s_cpp, robot_distances=rd_cpp, + goal_distances=gd_cpp, frontier_distances=fd_cpp) + + # check that the state is properly initialized + assert s1_cpp.num_robots == num_robots + assert s1_cpp.unexplored_frontiers == s_cpp + assert s1_cpp.robot_distances == rd_cpp + + s2_cpp = s1_cpp.copy_state() + ''' + In the copy state, the unexplored_frontiers and the robot distances are copied by value, + but the goal distances and frontier distances are copied by reference.''' + + assert s2_cpp.num_robots == num_robots + s2_cpp.remove_frontier_from_unexplored_frontiers(hash(a1)) + s2_cpp.add_frontier_to_goal_frontiers(hash(a1)) + # The number of frontiers in s2_cpp is decreased + assert len(s2_cpp.unexplored_frontiers) == 2 + # The number of frontiers in s1_cpp is not changed + assert len(s1_cpp.unexplored_frontiers) == 3 + # The number of goal frontiers in s2_cpp is increased + assert len(s2_cpp.goal_frontiers) == 1 + # The number of goal frontiers in s1_cpp is not changed + assert len(s1_cpp.goal_frontiers) == 0 + + # change the robot distance in s2_cpp and see if it changes in s1_cpp + s2_cpp.change_rd_for_robot(0, hash(a1), 100) + + print(f'{s1_cpp.unexplored_frontiers=}, \n {s2_cpp.unexplored_frontiers=}') + print(f'{s1_cpp.goal_frontiers=}, \n {s2_cpp.goal_frontiers=}') + print(f'{s1_cpp.robot_distances=}, \n {s2_cpp.robot_distances=}') + + assert s2_cpp.robot_distances[(0, hash(a1))] != s1_cpp.robot_distances[(0, hash(a1))] diff --git a/modules/mrlsp/tests/test_more_robots_frontiers.py b/modules/mrlsp/tests/test_more_robots_frontiers.py new file mode 100644 index 0000000..fc52456 --- /dev/null +++ b/modules/mrlsp/tests/test_more_robots_frontiers.py @@ -0,0 +1,48 @@ +from util_function import current_state_1, current_state_2, current_state_3, cpp_state_bug1 # noqa: F401 +import mrlsp +import mrlsp_accel +import time +import pytest + + +@pytest.mark.parametrize( + "current_state_name, num_robots", + [ + ("cpp_state_bug1", 1), + ("cpp_state_bug1", 2), + ("current_state_1", 1), + ("current_state_1", 2), + ("current_state_2", 1), + ("current_state_2", 2), + ("current_state_3", 1), + ("current_state_3", 2), + ("current_state_3", 3), + ]) +def test_mrlsp_works_with_multiple_robots(current_state_name, num_robots, request): # noqa: F811 + '''NOTE: cpp_state_bug1, current_state_1 & 2 doesn't have 3 robot support because of robot distances + and frontier distances ''' + current_state = request.getfixturevalue(current_state_name) + num_robots = num_robots + + has_python_data = current_state['has_data_for_python'] + has_cpp_data = current_state['has_data_for_cpp'] + + if has_python_data: + unexplored_frontiers = current_state['unexplored_frontiers_py'] + times = current_state['time'] + start_time = time.time() + best_action_py = mrlsp.pouct.find_best_joint_action( + unexplored_frontiers=unexplored_frontiers, time=times, num_robots=num_robots, num_iterations=5000) + print(f"Time taken PY: {time.time() - start_time}") + print(f'Joint action py: {[hash(b) for b in best_action_py]}') + + if has_cpp_data: + # s_dict = current_state['s_dict'] + s_cpp = current_state['s_cpp'] + rd_cpp = current_state['rd_cpp'] + gd_cpp = current_state['gd_cpp'] + fd_cpp = current_state['fd_cpp'] + start_time = time.time() + best_action_cpp = mrlsp_accel.find_best_joint_action_accel(num_robots, s_cpp, rd_cpp, gd_cpp, fd_cpp, 5000) + print(f"Time taken CPP: {time.time() - start_time}") + print(f'Joint action cpp: {best_action_cpp}') diff --git a/modules/mrlsp/tests/test_mrlsp_using_true_values.py b/modules/mrlsp/tests/test_mrlsp_using_true_values.py new file mode 100644 index 0000000..9f657bd --- /dev/null +++ b/modules/mrlsp/tests/test_mrlsp_using_true_values.py @@ -0,0 +1,73 @@ +import pytest +import mrlsp +import mrlsp_accel +import time +from util_function import current_state_2 # noqa: F401 + + +def test_cost_action_values_without_sampling(current_state_2): # noqa: F811 + '''This function tests whether hand calculated cost for two robot scenario is + same as the cost from Q(state, action) function. This Q(state, action) function + is not sampling based and calculates cost recursively.''' + + unexplored_frontiers = current_state_2['unexplored_frontiers_py'] + times = current_state_2['time'] + calculated_actions = current_state_2['calculated_actions'] + calculated_costs = current_state_2['calculated_costs'] + num_robots = current_state_2['num_robots'] + + sigma1 = mrlsp.core.State(n=num_robots, Fu=unexplored_frontiers, m_t=times) + + actions = sigma1.get_actions() + costs = [mrlsp.core.Q(sigma1, action) for action in actions] + print(costs) + for i, action in enumerate(actions): + index = [x for x, y in enumerate(calculated_actions) if y[0] == action[0] and y[1] == action[1]] + if index != []: + assert pytest.approx(costs[i]) == calculated_costs[index[0]] + + +def test_actions_with_pouct_sampling_py(current_state_2): # noqa: F811 + '''This test function tests whether the calculated action (python + version) using sampling technique is same as hand calculated action + (oracle truth) ''' + unexplored_frontiers = current_state_2['unexplored_frontiers_py'] + times = current_state_2['time'] + calculated_actions = current_state_2['calculated_actions'] + calculated_costs = current_state_2['calculated_costs'] + num_robots = current_state_2['num_robots'] + + num_iterations = 5000 + start_time = time.time() + best_action = mrlsp.pouct.find_best_joint_action( + unexplored_frontiers=unexplored_frontiers, time=times, num_robots=num_robots, num_iterations=num_iterations) + print(f"Time taken PY: {time.time() - start_time}") + expected = calculated_actions[calculated_costs.index(min(calculated_costs))] + print(f"best_action = {hash(best_action[0]), hash(best_action[1])}") + print(f'expected_action = {hash(expected[0])}, {hash(expected[1])}') + + assert best_action in calculated_actions + assert all([a == b for a, b in zip(best_action, expected)]) + + +def test_actions_with_pouct_sampling_cpp(current_state_2): # noqa: F811 + '''This test function tests whether the calculated action (cpp + version) using sampling technique is same as hand calculated action + (oracle truth) ''' + s_cpp = current_state_2['s_cpp'] + rd_cpp = current_state_2['rd_cpp'] + gd_cpp = current_state_2['gd_cpp'] + fd_cpp = current_state_2['fd_cpp'] + num_robots = current_state_2['num_robots'] + calculated_actions = current_state_2['calculated_actions'] + calculated_costs = current_state_2['calculated_costs'] + expected = calculated_actions[calculated_costs.index(min(calculated_costs))] + + num_iterations = 5000 + start_time = time.time() + best_action = mrlsp_accel.find_best_joint_action_accel(num_robots, s_cpp, rd_cpp, gd_cpp, fd_cpp, num_iterations) + print(f"Time taken CPP: {time.time() - start_time}") + print(f'{best_action=}') + print(f'expected_action = {hash(expected[0])}, {hash(expected[1])}') + + assert all([a == hash(b) for a, b in zip(best_action, expected)]) diff --git a/modules/mrlsp/tests/test_two_timestamp_action.py b/modules/mrlsp/tests/test_two_timestamp_action.py new file mode 100644 index 0000000..31e6c10 --- /dev/null +++ b/modules/mrlsp/tests/test_two_timestamp_action.py @@ -0,0 +1,59 @@ +from dummy_frontier import DummyFrontier +from mrlsp import pouct + + +def test_two_timestamp(): + a1 = DummyFrontier(q_f=[126.28, 71.78], label='a1') + a2 = DummyFrontier(q_f=[57.16, 41.66], label='a2') + a3 = DummyFrontier(q_f=[20.21, 103.71], label='a3') + a4 = DummyFrontier(q_f=[93.28, 38.78], label='a4') + + a1.set_props( + prob_feasible=0.9704260230064392, + delta_success_cost=18.546121597, + exploration_cost=394.71551513671875 + ) + a2.set_props( + prob_feasible=0.0044766939245164394, + delta_success_cost=46.356998444, + exploration_cost=95.10801696777344, + ) + a3.set_props( + prob_feasible=0.01118100993335247, + delta_success_cost=47.328475952, + exploration_cost=108.231201171875, + ) + a4.set_props( + prob_feasible=0.22330205142498016, + delta_success_cost=29.703948975, + exploration_cost=97.69618225097656, + ) + + timestep_24 = { + 'frontier': {frozenset([a1, a2]): 77.0121933088197, frozenset([a1, a3]): 124.28427124746185, + frozenset([a1, a4]): 87.08326112068515, + frozenset([a2, a3]): 67.65685424949237, frozenset([a2, a4]): 33.38477631085024, + frozenset([a3, a4]): 42.31370849898474}, + 'robot1': {a1: 30.62741699796953, a2: 66.76955262170043, a3: 111.0416305603426, a4: 72.42640687119281}, + 'robot2': {a1: 72.18376618407353, a2: 29.213203435596434, a3: 67.82842712474618, a4: 29.213203435596434}, + 'goal': {a1: 30.69848480983501, a2: 128.3847763108502, a3: 162.25483399593924, a4: 127.38477631085023} + } + + timestep_25 = { + 'frontier': {frozenset([a1, a2]): 77.0121933088197, frozenset([a1, a3]): 124.28427124746185, + frozenset([a1, a4]): 87.08326112068515, + frozenset([a2, a3]): 67.65685424949237, frozenset([a2, a4]): 33.38477631085024, + frozenset([a3, a4]): 42.31370849898474}, + 'robot1': {a1: 30.213203435596434, a2: 66.35533905932733, a3: 110.6274169979695, a4: 72.0121933088197}, + 'robot2': {a1: 72.76955262170043, a2: 27.798989873223338, a3: 67.24264068711928, a4: 28.62711699796953}, + 'goal': {a1: 30.69848480983501, a2: 128.3847763108502, a3: 162.25483399593924, a4: 127.38477631085023} + } + + unexplored_frontiers = {a1, a2, a3, a4} + best_action_t24 = pouct.find_best_joint_action(unexplored_frontiers=unexplored_frontiers, + time=timestep_24, num_iterations=1000) + best_action_t25 = pouct.find_best_joint_action(unexplored_frontiers=unexplored_frontiers, + time=timestep_25, num_iterations=1000) + + assert best_action_t24[0] == a1 + assert best_action_t25[0] == a1 diff --git a/modules/mrlsp/tests/util_function.py b/modules/mrlsp/tests/util_function.py new file mode 100644 index 0000000..b576ab6 --- /dev/null +++ b/modules/mrlsp/tests/util_function.py @@ -0,0 +1,451 @@ +import mrlsp +import mrlsp_accel +import pytest +import itertools +from dummy_frontier import DummyFrontier + + +@pytest.fixture +def current_state_1(): + num_robots = 2 + a1 = DummyFrontier(q_f=[305, 409], label='a1') + a2 = DummyFrontier(q_f=[105, 209], label='a2') + a3 = DummyFrontier(q_f=[505, 609], label='a3') + + a1.set_props( + prob_feasible=0.9, + delta_success_cost=100, + exploration_cost=5 + ) + a2.set_props( + prob_feasible=0.3, + delta_success_cost=20, + exploration_cost=10, + ) + a3.set_props( + prob_feasible=0.7, + delta_success_cost=30, + exploration_cost=3, + ) + + new_time = { + 'frontier': {frozenset([a1, a2]): 10, frozenset([a2, a3]): 5, frozenset([a1, a3]): 5}, + 'robot1': {a1: 8, a2: 12, a3: 15}, + 'robot2': {a1: 12, a2: 8, a3: 15}, + 'goal': {a1: 0, a2: 0, a3: 0} + } + unexplored_frontiers = {a1, a2, a3} + unexplored_frontiers_cpp = [a1, a2, a3] + q_t = [{a1: 10, a2: 0, a3: 0}, {a1: 0.0, a2: 12, a3: 0}] + + # for cpp + s_dict = {hash(s): s for s in unexplored_frontiers} + s_cpp = [ + mrlsp_accel.FrontierDataMR(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in unexplored_frontiers + ] + rd_cpp = {(i, hash(s)): new_time[f'robot{i+1}'][s] for i in range(num_robots) for s in unexplored_frontiers} + gd_cpp = {hash(s): new_time['goal'][s] for s in unexplored_frontiers} + fd_cpp = {(hash(sp[0]), hash(sp[1])): new_time['frontier'][frozenset(sp)] + for sp in itertools.permutations(unexplored_frontiers, 2)} + q_t_cpp = [{hash(a1): 10.0, hash(a2): 0.0, hash(a3): 0.0}, {hash(a1): 0.0, hash(a2): 12, hash(a3): 0.0}] + + # return [[num_robots, unexplored_frontiers, new_time, q_t], + # [s_cpp, rd_cpp, gd_cpp, fd_cpp, q_t_cpp], + # [s_dict]] + + state_parameters = {'num_robots': num_robots, + 'unexplored_frontiers_py': unexplored_frontiers, + 'unexplored_frontiers_cpp': unexplored_frontiers_cpp, + 'time': new_time, + 's_cpp': s_cpp, + 'rd_cpp': rd_cpp, + 'gd_cpp': gd_cpp, + 'fd_cpp': fd_cpp, + 's_dict': s_dict, + 'q_t': q_t, + 'q_t_cpp': q_t_cpp, + 'has_data_for_python': True, + 'has_data_for_cpp': True, + } + + return state_parameters + + +@pytest.fixture +def current_state_2(): + '''Only in current state 2, we have hand calculated values.''' + num_robots = 2 + a1 = DummyFrontier(q_f=[305, 409], label='a1') + a2 = DummyFrontier(q_f=[105, 209], label='a2') + a3 = DummyFrontier(q_f=[505, 609], label='a3') + + a1.set_props( + prob_feasible=0.9, + delta_success_cost=100, + exploration_cost=5 + ) + a2.set_props( + prob_feasible=0.3, + delta_success_cost=20, + exploration_cost=10, + ) + a3.set_props( + prob_feasible=0.7, + delta_success_cost=30, + exploration_cost=3, + ) + + new_time = { + 'frontier': {frozenset([a1, a2]): 10}, + 'robot1': {a1: 8, a2: 12}, + 'robot2': {a1: 12, a2: 8}, + 'goal': {a1: 0, a2: 0} + } + calculated_actions = [(a1, a2), + (a2, a1)] + + calculated_costs = [78.4, 82.4] + unexplored_frontiers = {a1, a2} + + unexplored_frontiers_cpp = [a1, a2] + s_dict = {hash(s): s for s in unexplored_frontiers_cpp} + s_cpp = [ + mrlsp_accel.FrontierDataMR(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in unexplored_frontiers_cpp + ] + rd_cpp = {(i, hash(s)): new_time[f'robot{i+1}'][s] for i in range(num_robots) for s in unexplored_frontiers_cpp} + gd_cpp = {hash(s): new_time['goal'][s] for s in unexplored_frontiers_cpp} + fd_cpp = {(hash(sp[0]), hash(sp[1])): new_time['frontier'][frozenset(sp)] + for sp in itertools.permutations(unexplored_frontiers_cpp, 2)} + + # return [ + # [unexplored_frontiers, new_time, calculated_actions, calculated_costs, num_robots, unexplored_frontiers_cpp], + # [s_dict, s_cpp, rd_cpp, gd_cpp, fd_cpp] + # ] + + state_parameters = {'num_robots': num_robots, + 'unexplored_frontiers_py': unexplored_frontiers, + 'unexplored_frontiers_cpp': unexplored_frontiers_cpp, + 'time': new_time, + 's_cpp': s_cpp, + 'rd_cpp': rd_cpp, + 'gd_cpp': gd_cpp, + 'fd_cpp': fd_cpp, + 's_dict': s_dict, + 'calculated_actions': calculated_actions, + 'calculated_costs': calculated_costs, + 'has_data_for_python': True, + 'has_data_for_cpp': True} + + return state_parameters + + +@pytest.fixture +def current_state_3(): + num_robots = 3 + a1 = DummyFrontier(q_f=[305, 409], label='a1') + a2 = DummyFrontier(q_f=[105, 209], label='a2') + a3 = DummyFrontier(q_f=[505, 609], label='a3') + a4 = DummyFrontier(q_f=[705, 809], label='a4') + a5 = DummyFrontier(q_f=[905, 1009], label='a5') + + a1.set_props( + prob_feasible=0.9, + delta_success_cost=100, + exploration_cost=5 + ) + a2.set_props( + prob_feasible=0.3, + delta_success_cost=20, + exploration_cost=10, + ) + a3.set_props( + prob_feasible=0.7, + delta_success_cost=30, + exploration_cost=15, + ) + a4.set_props( + prob_feasible=0.5, + delta_success_cost=50, + exploration_cost=12, + ) + a5.set_props( + prob_feasible=0.1, + delta_success_cost=60, + exploration_cost=20, + ) + + new_time = { + 'frontier': {frozenset([a1, a2]): 10, frozenset([a1, a3]): 20, frozenset([a1, a4]): 40, frozenset([a1, a5]): 60, + frozenset([a2, a3]): 25, frozenset([a2, a4]): 30, frozenset([a2, a5]): 37, + frozenset([a3, a4]): 33, frozenset([a3, a5]): 60, + frozenset([a4, a5]): 27}, + 'robot1': {a1: 8, a2: 12, a3: 20, a4: 40, a5: 60}, + 'robot2': {a1: 12, a2: 8, a3: 20, a4: 40, a5: 60}, + 'robot3': {a1: 20, a2: 20, a3: 8, a4: 40, a5: 60}, + 'goal': {a1: 0, a2: 0, a3: 0, a4: 0, a5: 0} + } + unexplored_frontiers = {a1, a2, a3, a4, a5} + + unexplored_frontiers_cpp = [a1, a2, a3, a4, a5] + s_dict = {hash(s): s for s in unexplored_frontiers_cpp} + s_cpp = [ + mrlsp_accel.FrontierDataMR(s.prob_feasible, s.delta_success_cost, + s.exploration_cost, hash(s), + s.is_from_last_chosen) for s in unexplored_frontiers_cpp + ] + rd_cpp = {(i, hash(s)): new_time[f'robot{i+1}'][s] for i in range(num_robots) for s in unexplored_frontiers_cpp} + gd_cpp = {hash(s): new_time['goal'][s] for s in unexplored_frontiers_cpp} + fd_cpp = {(hash(sp[0]), hash(sp[1])): new_time['frontier'][frozenset(sp)] + for sp in itertools.permutations(unexplored_frontiers_cpp, 2)} + + # return [[unexplored_frontiers, new_time, num_robots, unexplored_frontiers_cpp], + # [s_dict, s_cpp, rd_cpp, gd_cpp, fd_cpp]] + + state_parameters = {'num_robots': num_robots, + 'unexplored_frontiers_py': unexplored_frontiers, + 'unexplored_frontiers_cpp': unexplored_frontiers_cpp, + 'time': new_time, + 's_cpp': s_cpp, + 'rd_cpp': rd_cpp, + 'gd_cpp': gd_cpp, + 'fd_cpp': fd_cpp, + 's_dict': s_dict, + 'has_data_for_python': True, + 'has_data_for_cpp': True} + + return state_parameters + + +@pytest.fixture +def cpp_state_bug1(): + '''This exact data (except for frontier hash number) resulted in segmentation fault in mrlsp_accel.''' + frontier1_hash = -1111111111111111 + frontier2_hash = -2222222222222222 + frontier3_hash = -3333333333333333 + frontier4_hash = -4444444444444444 + frontier5_hash = -5555555555555555 + frontier6_hash = -6666666666666666 + frontier7_hash = -7777777777777777 + + frontier1 = mrlsp_accel.FrontierDataMR(0.7924796342849731, 169.36832580710956, + 188.08245849609375, frontier1_hash, False) + frontier2 = mrlsp_accel.FrontierDataMR(0.15180489420890808, 301.71375278452655, + 106.37687683105469, frontier2_hash, False) + frontier3 = mrlsp_accel.FrontierDataMR(0.5383244752883911, 169.77446062963244, + 58.89070510864258, frontier3_hash, False) + frontier4 = mrlsp_accel.FrontierDataMR(0.48599353432655334, 207.92903140640095, + 96.38992309570312, frontier4_hash, False) + frontier5 = mrlsp_accel.FrontierDataMR(0.604091227054596, 135.59115753860436, + 83.71237182617188, frontier5_hash, False) + frontier6 = mrlsp_accel.FrontierDataMR(0.06415274739265442, 329.7541229349233, + 83.29269409179688, frontier6_hash, False) + frontier7 = mrlsp_accel.FrontierDataMR(0.779825747013092, 237.1676590301899, + 271.9759521484375, frontier7_hash, False) + + unexplored_frontiers = [frontier1, frontier2, frontier3, frontier4, frontier5, frontier6, frontier7] + robot_distances = { + (0, frontier1_hash): 57.07106781186547, (0, frontier2_hash): 27.72792206135786, + (0, frontier3_hash): 41.870057685088796, (0, frontier4_hash): 47.97056274847713, + (0, frontier5_hash): 55.79898987322331, (0, frontier6_hash): 12.242640687119286, + (0, frontier7_hash): 55.556349186104036, (1, frontier1_hash): 51.727922061357845, + (1, frontier2_hash): 51.4558441227157, (1, frontier3_hash): 49.89949493661165, + (1, frontier4_hash): 62.62741699796948, (1, frontier5_hash): 18.071067811865476, + (1, frontier6_hash): 50.07106781186546, (1, frontier7_hash): 19.48528137423857 + } + + goal_distances = { + frontier1_hash: 95.65685424949237, + frontier2_hash: 174.49242404917499, + frontier3_hash: 121.89444430272815, + frontier4_hash: 149.35028842544392, + frontier5_hash: 83.87005768508875, + frontier6_hash: 173.59797974644675, + frontier7_hash: 135.5218613006977 + } + + frontier_distances = { + (frontier1_hash, frontier2_hash): 61.31370849898474, (frontier2_hash, frontier1_hash): 61.31370849898474, + (frontier1_hash, frontier3_hash): 61.828427124746185, (frontier3_hash, frontier1_hash): 61.828427124746185, + (frontier1_hash, frontier4_hash): 68.82842712474618, (frontier4_hash, frontier1_hash): 68.82842712474618, + (frontier1_hash, frontier5_hash): 49.55634918610403, (frontier5_hash, frontier1_hash): 49.55634918610403, + (frontier1_hash, frontier6_hash): 59.65685424949237, (frontier6_hash, frontier1_hash): 59.65685424949237, + (frontier1_hash, frontier7_hash): 79.41421356237309, (frontier7_hash, frontier1_hash): 79.41421356237309, + (frontier2_hash, frontier3_hash): 45.798989873223306, (frontier3_hash, frontier2_hash): 45.798989873223306, + (frontier2_hash, frontier4_hash): 48.48528137423857, (frontier4_hash, frontier2_hash): 48.48528137423857, + (frontier2_hash, frontier5_hash): 61.183766184073534, (frontier5_hash, frontier2_hash): 61.183766184073534, + (frontier2_hash, frontier6_hash): 35.89949493661167, (frontier6_hash, frontier2_hash): 35.89949493661167, + (frontier2_hash, frontier7_hash): 61.071067811865476, (frontier7_hash, frontier2_hash): 61.071067811865476, + (frontier3_hash, frontier4_hash): 16.48528137423857, (frontier4_hash, frontier3_hash): 16.48528137423857, + (frontier3_hash, frontier5_hash): 59.3847763108502, (frontier5_hash, frontier3_hash): 59.3847763108502, + (frontier3_hash, frontier6_hash): 49.21320343559642, (frontier6_hash, frontier3_hash): 49.21320343559642, + (frontier3_hash, frontier7_hash): 20.242640687119284, (frontier7_hash, frontier3_hash): 20.242640687119284, + (frontier4_hash, frontier5_hash): 68.69848480983494, (frontier5_hash, frontier4_hash): 68.69848480983494, + (frontier4_hash, frontier6_hash): 51.89949493661165, (frontier6_hash, frontier4_hash): 51.89949493661165, + (frontier4_hash, frontier7_hash): 13.82842712474619, (frontier7_hash, frontier4_hash): 13.82842712474619, + (frontier5_hash, frontier6_hash): 60.69848480983499, (frontier6_hash, frontier5_hash): 60.69848480983499, + (frontier5_hash, frontier7_hash): 76.97056274847715, (frontier7_hash, frontier5_hash): 76.97056274847715, + (frontier6_hash, frontier7_hash): 64.48528137423858, (frontier7_hash, frontier6_hash): 64.48528137423858, + } + + num_robots = 2 + num_iterations = 5000 + + # return [num_robots, unexplored_frontiers, robot_distances, goal_distances, frontier_distances, num_iterations] + + state_parameters = {'num_robots': num_robots, + 's_dict': None, + 's_cpp': unexplored_frontiers, + 'rd_cpp': robot_distances, + 'gd_cpp': goal_distances, + 'fd_cpp': frontier_distances, + 'num_iterations': num_iterations, + 'has_data_for_python': False, + 'has_data_for_cpp': True} + + return state_parameters + + +def check_py_and_cpp_states_match(s1_py, s1_cpp, s_dict): + # Print everything for cpp state + print("####################################################") + print(s_dict) + print("CPP Version") + print(f'Num robots: {s1_cpp.num_robots}') + print(f'Unexplored frontiers: {[s for s in s1_cpp.unexplored_frontiers_hash]}') + print(f'Robot distances: {s1_cpp.robot_distances}') + + print(f'goal_frontiers: {s1_cpp.goal_frontiers}') + print(f'Q_t: {s1_cpp.q_t}') + print("---------------------------------------------------") + print("Python Version") + print(f'Num robots: {s1_py.n}') + print(f'Unexplored frontiers: {[s for s in s1_py.Fu]}') + for i in range(s1_py.n): + print(f"Robot{i+1} distance:", s1_py.time[f'robot{i+1}']) + + print(f"goal_frontiers: {s1_py.goal_frontiers}") + print(f'Q_t: {s1_py.q_t}') + print("####################################################") + + # checks everything of the state + assert s1_py.n == s1_cpp.num_robots + assert len(s1_py.Fu) == len(s1_cpp.unexplored_frontiers) + + # check if every frontier in unexplored frontier of python is in cpp + assert len(s1_py.Fu) == len(s1_cpp.unexplored_frontiers_hash) + for f in s1_py.Fu: + assert hash(f) in s1_cpp.unexplored_frontiers_hash + + # check if all the goal frontier of python is in cpp + assert len(s1_py.goal_frontiers) == len(s1_cpp.goal_frontiers) + for f in s1_py.goal_frontiers: + assert hash(f) in s1_cpp.goal_frontiers + + # check robot distance + for pair, distance in s1_cpp.robot_distances.items(): + robot = pair[0] + frontier_hash = pair[1] + assert pytest.approx(s1_py.time[f'robot{robot+1}'][s_dict[frontier_hash]]) == distance + + # check q_t + for i in range(s1_py.n): + for frontier_hash, q in s1_cpp.q_t[i].items(): + assert s1_py.q_t[i][s_dict[frontier_hash]] == q + + # check if the actions are same + actions_cpp = s1_cpp.get_actions() + actions_py = s1_py.get_actions() + assert len(actions_cpp) == len(actions_py) + + +def check_py_and_cpp_q_t_match(s1_py, s1_cpp, action, s_dict): + print("--------------------------------------------------") + print(f"For action: ({[hash(a) for a in action]})") + action1_py = action + action1_cpp = [hash(a) for a in action] + f_I_py, T_I_py = mrlsp.core.get_frontier_of_knowlege_and_time(s1_py, action1_py) + f_I_cpp, T_I_cpp = mrlsp_accel.get_frontier_of_knowledge_and_time_cpp(s1_cpp, action1_cpp) + assert f_I_cpp == hash(f_I_py) + assert T_I_cpp == T_I_py + q_t_py, residue_py = s1_py.find_q_t_for_action(T_I_py, action1_py) + q_t_cpp, residue_cpp = mrlsp_accel.find_q_t_for_action_cpp(s1_cpp, T_I_cpp, action1_cpp) + + # Test that q_t is same for python and cpp State classes + for prog_py, prog_cpp in zip(q_t_py, q_t_cpp): + for f_py, p_py in prog_py.items(): + assert prog_cpp[hash(f_py)] == p_py + q_t_py_hash = [] + for i, q_t in enumerate(q_t_py): + q_t_dict = {hash(f): p for f, p in q_t.items()} + q_t_py_hash.append(q_t_dict) + print(f'q_t_py = {q_t_py_hash}') + print(f'{q_t_cpp=}') + print(f'residue_py = {residue_py}, residue_cpp = {residue_cpp}') + + time_py = s1_py.get_time_from_q_t(q_t_py, residue_py) + distance_cpp = mrlsp_accel.get_time_from_qt_cpp(s1_cpp, q_t_cpp, residue_cpp) + print(f'{time_py=}') + print(f'{distance_cpp=}') + for robot_frontier_pair, distance in distance_cpp.items(): + robot = robot_frontier_pair[0] + frontier_hash = robot_frontier_pair[1] + assert pytest.approx(time_py[f'robot{robot+1}'][s_dict[frontier_hash]]) == distance + + +def check_py_and_cpp_move_robots_match(s1_py, s1_cpp, action, s_dict): + print(f"\nFor action {[hash(a) for a in action]}") + action_py = action + action_cpp = [hash(a) for a in action] + success_state_py, failure_state_py, f_I_py, T_I_py, goal_reached_py = mrlsp.core.move_robots(s1_py, action_py) + success_state_cpp, failure_state_cpp, f_I_cpp, T_I_cpp, goal_reached_cpp = mrlsp_accel.move_robots_cpp( + s1_cpp, action_cpp) + + assert f_I_cpp == hash(f_I_py) + assert T_I_cpp == T_I_py + assert goal_reached_cpp == goal_reached_py + assert len(success_state_cpp.unexplored_frontiers) == len(success_state_py.Fu) + assert len(failure_state_cpp.unexplored_frontiers) == len(failure_state_py.Fu) + assert len(success_state_cpp.goal_frontiers) == len(success_state_py.goal_frontiers) + assert len(failure_state_cpp.goal_frontiers) == len(failure_state_py.goal_frontiers) + assert len(success_state_cpp.unexplored_frontiers_hash) == len(success_state_py.Fu) + assert len(failure_state_cpp.unexplored_frontiers) == len(failure_state_py.Fu) + for f in success_state_py.Fu: + assert hash(f) in success_state_cpp.unexplored_frontiers_hash + for f in failure_state_py.Fu: + assert hash(f) in failure_state_cpp.unexplored_frontiers_hash + for f in success_state_py.goal_frontiers: + assert hash(f) in success_state_cpp.goal_frontiers + + # check robot distances in success_state + print("Success state distances:") + for pair, distance in success_state_cpp.robot_distances.items(): + robot = pair[0] + frontier_hash = pair[1] + assert pytest.approx(success_state_py.time[f'robot{robot+1}'][s_dict[frontier_hash]]) == distance + print(f"Robot {robot+1}, frontier {frontier_hash}: Distance = {distance}") + + # check robot distances in failure_state + print("Failure state distances:") + for pair, distance in failure_state_cpp.robot_distances.items(): + robot = pair[0] + frontier_hash = pair[1] + assert pytest.approx(failure_state_py.time[f'robot{robot+1}'][s_dict[frontier_hash]]) == distance + print(f"Robot {robot+1}, frontier {frontier_hash}: Distance = {distance}") + + # check q_t for cpp and python for success state + success_q_t_py = success_state_py.q_t + success_q_t_cpp = success_state_cpp.q_t + for s_q_t_py, s_q_t_cpp in zip(success_q_t_py, success_q_t_cpp): + for f_py, p_py in s_q_t_py.items(): + assert s_q_t_cpp[hash(f_py)] == p_py + + # check q_t for cpp and python for failure state + failure_q_t_py = failure_state_py.q_t + failure_q_t_cpp = failure_state_cpp.q_t + for f_q_t_py, f_q_t_cpp in zip(failure_q_t_py, failure_q_t_cpp): + for f_py, p_py in f_q_t_py.items(): + assert f_q_t_cpp[hash(f_py)] == p_py diff --git a/modules/mrlsp_accel/CMakeLists.txt b/modules/mrlsp_accel/CMakeLists.txt new file mode 100644 index 0000000..9a06811 --- /dev/null +++ b/modules/mrlsp_accel/CMakeLists.txt @@ -0,0 +1,34 @@ +cmake_minimum_required(VERSION 2.8.12) +project(mrlsp_accel) + +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_BUILD_TYPE "Release") + +# Download pybind11 +find_package(Git QUIET) +if(GIT_FOUND AND NOT EXISTS "${PROJECT_SOURCE_DIR}/pybind11") +# Update submodules as needed + option(GIT_CLONE "Clone during build" ON) + if(GIT_CLONE) + message(STATUS "Clone update") + execute_process(COMMAND ${GIT_EXECUTABLE} clone --branch v2.2.0 https://github.com/pybind/pybind11.git + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + RESULT_VARIABLE GIT_CLONE_RESULT) + if(NOT GIT_CLONE_RESULT EQUAL "0") + message(FATAL_ERROR "git clone failed with ${GIT_CLONE_RESULT}.") + endif() + endif() +endif() + +# Why do I need this? pybind11? +link_directories(/usr/local/lib) + +# Make the library that pybind will link against +include_directories(src) + +# Include Eigen +include_directories(/usr/include/eigen3) + +# Build the python library +add_subdirectory(pybind11) +pybind11_add_module(mrlsp_accel NO_EXTRAS src/main.cpp) diff --git a/modules/mrlsp_accel/README.md b/modules/mrlsp_accel/README.md new file mode 100644 index 0000000..66f2a97 --- /dev/null +++ b/modules/mrlsp_accel/README.md @@ -0,0 +1,4 @@ +# MR-LSP Accel +Here's the code for MR-LSP algorithm written in cpp for performance boost. + +See [`mrlsp`](../mrlsp) for details. \ No newline at end of file diff --git a/modules/mrlsp_accel/setup.py b/modules/mrlsp_accel/setup.py new file mode 100644 index 0000000..4fab056 --- /dev/null +++ b/modules/mrlsp_accel/setup.py @@ -0,0 +1,81 @@ +import os +import re +import sys +import platform +import subprocess + +from setuptools import setup, Extension +from setuptools.command.build_ext import build_ext +from distutils.version import LooseVersion + + +class CMakeExtension(Extension): + def __init__(self, name, sourcedir=''): + Extension.__init__(self, name, sources=[]) + self.sourcedir = os.path.abspath(sourcedir) + + +class CMakeBuild(build_ext): + def run(self): + try: + out = subprocess.check_output(['cmake', '--version']) + except OSError: + raise RuntimeError( + "CMake must be installed to build the following extensions: " + + ", ".join(e.name for e in self.extensions)) + + if platform.system() == "Windows": + cmake_version = LooseVersion( + re.search(r'version\s*([\d.]+)', out.decode()).group(1)) + if cmake_version < '3.1.0': + raise RuntimeError("CMake >= 3.1.0 is required on Windows") + + for ext in self.extensions: + self.build_extension(ext) + + def build_extension(self, ext): + extdir = os.path.abspath( + os.path.dirname(self.get_ext_fullpath(ext.name))) + cmake_args = [ + '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY=' + extdir, + '-DPYTHON_EXECUTABLE=' + sys.executable + ] + + cfg = 'Debug' if self.debug else 'Release' + build_args = ['--config', cfg] + + if platform.system() == "Windows": + cmake_args += [ + '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY_{}={}'.format( + cfg.upper(), extdir) + ] + if sys.maxsize > 2**32: + cmake_args += ['-A', 'x64'] + build_args += ['--', '/m'] + else: + cmake_args += ['-DCMAKE_BUILD_TYPE=' + cfg] + build_args += ['--', '-j8'] + + env = os.environ.copy() + env['CXXFLAGS'] = '{} -DVERSION_INFO=\\"{}\\"'.format( + env.get('CXXFLAGS', ''), self.distribution.get_version()) + if not os.path.exists(self.build_temp): + os.makedirs(self.build_temp) + subprocess.check_call(['cmake', ext.sourcedir] + cmake_args, + cwd=self.build_temp, + env=env) + subprocess.check_call(['cmake', '--build', '.'] + build_args, + cwd=self.build_temp) + + +setup( + name='mrlsp_accel', + version='0.1.0', + description='C++ accelerated functions for MR-LSP Subgoal Planning', + long_description='', + ext_modules=[CMakeExtension('mrlsp_accel')], + cmdclass=dict(build_ext=CMakeBuild), + zip_safe=False, + setup_requires=['pytest-runner'], + tests_require=['pytest'], +) diff --git a/modules/mrlsp_accel/src/core.hpp b/modules/mrlsp_accel/src/core.hpp new file mode 100644 index 0000000..b4d9d26 --- /dev/null +++ b/modules/mrlsp_accel/src/core.hpp @@ -0,0 +1,482 @@ +#include "mrlsp_utility.hpp" +#include +#include +#include +#include +#include + +struct FrontierDataMR { + double prob_feasible; + double delta_success_cost; + double exploration_cost; + long hash_id; + bool is_from_last_chosen; + + FrontierDataMR(double prob_feasible, double delta_success_cost, + double exploration_cost, long hash_id, + bool is_from_last_chosen) + : prob_feasible(prob_feasible), delta_success_cost(delta_success_cost), + exploration_cost(exploration_cost), hash_id(hash_id), + is_from_last_chosen(is_from_last_chosen) {} + + long get_hash() const { return hash_id; } +}; + +typedef std::shared_ptr FrontierDataMRPtr; +typedef std::vector> ListOfRobotsProgress; + +const std::pair +find_progress_and_frontier_for_robot(const ListOfRobotsProgress &q_t, + const int robot_id) { + auto el = *std::max_element(q_t[robot_id].begin(), q_t[robot_id].end(), + [](const std::pair &a, + const std::pair &b) -> bool { + return a.second < b.second; + }); + if (el.second > 0) { + return el; + } else { + return std::make_pair(-1, 0); + } +} + +// define class named State +struct State { + int num_robots; + std::vector unexplored_frontiers; + std::vector unexplored_frontiers_hash; + std::map, double> robot_distances; + std::shared_ptr> goal_distances; + std::shared_ptr, double>> frontier_distances; + std::vector goal_frontiers; + // initialize a vector q_t that stores progress for each robot for each frontier + ListOfRobotsProgress q_t; + // initialize a mapping from hash to frontier to retrieve frontier data from hash + std::map hash_to_frontier; + + State(const int n, std::vector &Fu, + std::map, double> r_d, std::map &g_d, + std::map, double> &f_d) { + goal_distances = std::make_shared>(); + frontier_distances = + std::make_shared, double>>(); + + for (auto &element : g_d) { + goal_distances->insert(element); + } + for (auto &element : f_d) { + frontier_distances->insert(element); + } + num_robots = n; + unexplored_frontiers = Fu; + this->robot_distances = r_d; + + for (int i = 0; i < num_robots; i++) { + std::map progress; + for (auto &f : Fu) { + progress[f->hash_id] = 0; + } + q_t.push_back(progress); + } + for (int i = 0; i < unexplored_frontiers.size(); i++) { + long f_hash = unexplored_frontiers[i]->hash_id; + unexplored_frontiers_hash.push_back(f_hash); + hash_to_frontier[f_hash] = unexplored_frontiers[i]; + } + } + + // define a function to remove a frontier f with hash_id f_hash from + // unexplored_frontiers + void remove_frontier_from_unexplored_frontiers(long f_hash) { + for (int i = 0; i < unexplored_frontiers.size(); i++) { + if (unexplored_frontiers_hash[i] == f_hash) { + unexplored_frontiers.erase(unexplored_frontiers.begin() + i); + unexplored_frontiers_hash.erase(unexplored_frontiers_hash.begin() + i); + break; + } + } + } + + // define a function to add a frontier f with hash_id f_hash to goal_frontiers + void add_frontier_to_goal_frontiers(long f_hash) { + goal_frontiers.push_back(f_hash); + } + + // define a function to change robot_distances for robot r to frontier f with + // hash_id f_hash to distance new_rd + void change_rd_for_robot(int robot_id, long f_hash, double new_rd) { + robot_distances[std::make_pair(robot_id, f_hash)] = new_rd; + } + + // define a function copy_state that returns a copy of the current state + State copy_state() { + State s(*this); + return s; + } + + const std::vector> get_actions() { + auto restrict_action_according_to_progress = + [&](std::vector> all_actions) { + /*This function restricts the action so that if the robots are making + progress towards some frontier, then the other robot revealing some + frontier doesn't interrupt the ongoing action*/ + std::vector> final_action; + bool save = false; + for (auto &action : all_actions) { + for (int i = 0; i < action.size(); i++) { + auto [frontier, progress] = + find_progress_and_frontier_for_robot(q_t, i); + // If the frontier is not in unexplored frontier, then the + // frontier is just explored + if (std::find(unexplored_frontiers_hash.begin(), + unexplored_frontiers_hash.end(), + frontier) == unexplored_frontiers_hash.end()) { + /* If the frontier is not in goal frontier, then the frontier + doesn't lead to the goal and the robot needs to return back from + that frontier. So the robot has not 'made' any progress towards + any frontier that might reveal goal.*/ + if (std::find(goal_frontiers.begin(), goal_frontiers.end(), + frontier) == goal_frontiers.end()) { + frontier = -1; + } + } + + if (frontier == -1) { + save = true; + continue; + } else { + if (action[i] != frontier) { + save = false; + continue; + } else { + save = true; + continue; + } + } + } + if (save) + final_action.push_back(action); + } + return final_action; + }; + std::vector all_unexplored_frontiers = unexplored_frontiers_hash; + std::vector frontiers_to_explore = + set::u(unexplored_frontiers_hash, goal_frontiers); + if (num_robots == 1) { + std::vector> all_actions; + for (auto &f : frontiers_to_explore) { + std::vector action; + action.push_back(f); + all_actions.push_back(action); + } + return all_actions; + } + std::vector> actions = + get_action_combinations(frontiers_to_explore, num_robots); + return restrict_action_according_to_progress(actions); + } +}; + +std::pair +get_frontier_of_knowledge_and_time(const State &s, + const std::vector &action) { + std::vector goal_frontiers; + bool can_reach_goal = false; + long f_I; + double T_I; + if (s.goal_frontiers.size() != 0) { + can_reach_goal = true; + goal_frontiers = s.goal_frontiers; + } + std::vector all_TI; + std::vector all_frontiers; + for (int i = 0; i < action.size(); i++) { + if (can_reach_goal && + std::find(goal_frontiers.begin(), goal_frontiers.end(), action[i]) != + goal_frontiers.end()) { + continue; + } else { + FrontierDataMRPtr f = s.hash_to_frontier.at(action[i]); + double Ti = + s.robot_distances.at(std::pair(i, action[i])) + + std::min((f->delta_success_cost + s.goal_distances->at(action[i])), + f->exploration_cost) - + s.q_t[i].at(action[i]); + all_TI.push_back(Ti); + all_frontiers.push_back(action[i]); + } + } + if (all_TI.size() == 0) { + // no unexplored frontiers have been added; i.e both actions are goal + // frontiers + return std::make_pair(-1, -1); + } + f_I = all_frontiers[std::min_element(all_TI.begin(), all_TI.end()) - + all_TI.begin()]; + // T_I is the minimum of all_TI + T_I = *std::min_element(all_TI.begin(), all_TI.end()); + return std::make_pair(f_I, T_I); +} + +std::pair, double>>> +find_q_t_for_action(State &s, const double &T_I, + const std::vector &action) { + ListOfRobotsProgress q_t; + std::vector, double>> residue_time; + + // get union of unexplored frontiers and goal frontiers of State s in + // frontiers_to_keep_track + std::vector all_unexplored_frontiers = s.unexplored_frontiers_hash; + std::vector frontiers_to_keep_track = + set::u(all_unexplored_frontiers, s.goal_frontiers); + + for (int i = 0; i < s.num_robots; i++) { + std::map progress_for_robot; // q_t_dict in python version + std::map, double> + residue_time_for_robot; // residue_time in python version + auto [prev_frontier, prev_progress] = + find_progress_and_frontier_for_robot(s.q_t, i); + long current_frontier = action[i]; + // for each frontier in frontiers_to_keep_track + for (auto &f : frontiers_to_keep_track) { + /* If the current frontier is not the frontier that the robot is moving + towards, then no progress is made towards that frontier (set time to 0), + and the current frontier is also not the previous frontier (do nothing)*/ + if (f != current_frontier) { + // we don't want to set the previous frontier time as 0 right away + if (f != prev_frontier) { + progress_for_robot[f] = 0; + } + } else { + // if in previous state, the robot was not exploring any frontier + double time_to_current_frontier; + if (prev_frontier == -1) { + time_to_current_frontier = + s.robot_distances.at(std::pair(i, current_frontier)); + // if the robot has entered that frontier + if (T_I > time_to_current_frontier) { + progress_for_robot[f] = T_I - time_to_current_frontier; + } else { + // Scenario of residue while moving towards frontier f + progress_for_robot[f] = 0; + residue_time_for_robot[std::pair(prev_frontier, f)] = + T_I; + } + } else if (current_frontier == prev_frontier) { + progress_for_robot[f] = prev_progress + T_I; + } else { + /* If the time of knowledge > the progress made on previous frontier + then the robot gets out of the frontier */ + if (T_I >= prev_progress) { + double out_and_explore_time = T_I - prev_progress; + double inter_frontier_time = s.frontier_distances->at( + std::pair(f, prev_frontier)); + progress_for_robot[prev_frontier] = 0; + if (out_and_explore_time > inter_frontier_time) { + progress_for_robot[f] = + out_and_explore_time - inter_frontier_time; + } else { + progress_for_robot[f] = 0; + residue_time_for_robot[std::pair(prev_frontier, f)] = + out_and_explore_time; + } + } else { + /* else the robot is currently coming out of the same frontier it + * was exploring before */ + progress_for_robot[prev_frontier] = prev_progress - T_I; + progress_for_robot[f] = 0; + } + } + } + } + q_t.push_back(progress_for_robot); + residue_time.push_back(residue_time_for_robot); + } + return std::make_pair(q_t, residue_time); +} + +std::map, double> get_time_from_qt( + std::shared_ptr s, ListOfRobotsProgress &new_q_t, + std::vector, double>> residue_time) { + std::map, double> new_time; + std::map, double> old_time = s->robot_distances; + std::vector all_unexplored_frontiers = s->unexplored_frontiers_hash; + std::vector frontiers_to_keep_track = + set::u(all_unexplored_frontiers, s->goal_frontiers); + for (int i = 0; i < s->num_robots; i++) { + // initialize robot distance + std::map, double> r_d; + auto [prev_frontier, prev_progress] = + find_progress_and_frontier_for_robot(new_q_t, i); + if (prev_frontier == -1) { + // check if there is resiude time for this robot + if (!residue_time[i].empty()) { + /* Assumption: Construct a triangle using where robot was coming from, + where robot is going, and where robot needs to go, and find the distance + from that triangle. The results will never be negative. */ + long from_frontier = residue_time[i].begin()->first.first; + long to_frontier = residue_time[i].begin()->first.second; + double time_travelled = residue_time[i].begin()->second; + /*If the robot is in 'known' space and not coming out from frontier then + the time is deduced from the old robot-frontier time. This happens when + the subgoal is assigned to the robot, but other robot knows about + "frontier of knowledge" before the current robot gets to see the + frontier that it is assigned to.*/ + if (from_frontier == -1) { + double time_to_frontier = 0; + // a is the distance from robot position to the frontier that it is + // assigned to, before the robot moved + double a = old_time[std::pair(i, to_frontier)]; + // Handle edge case + if (a == 0) { + // If the robot just reached frontier it was assigned to explore, + // and belief state changed + for (auto &f : frontiers_to_keep_track) { + if (f == to_frontier) { + time_to_frontier = 0; + } else { + time_to_frontier = s->frontier_distances->at( + std::pair(f, to_frontier)); + } + r_d[std::pair(i, f)] = time_to_frontier; + } + } else { + for (auto &f : frontiers_to_keep_track) { + if (f == to_frontier) { + time_to_frontier = + old_time[std::pair(i, f)] - time_travelled; + + } else { + /* 'b' is the time from the frontier that the robot was + previously assigned to, and the current frontier 'f' */ + double b = s->frontier_distances->at( + std::pair(f, to_frontier)); + /* 'c' is the time from robot position to the frontier, + which we are currently calculating, before the robot moved + */ + double c = old_time[std::pair(i, f)]; + + time_to_frontier = get_frontier_time_by_triangle_formation( + a, b, c, time_travelled); + } + r_d[std::pair(i, f)] = time_to_frontier; + } + } + } else { + /*If the robot is in 'known' space but by coming out from another + frontier. In this case, the time from the previous frontier to all + the other frontier - outside time is the robot's time to reach + other frontiers.*/ + double a = s->frontier_distances->at( + std::pair(from_frontier, to_frontier)); + for (auto &f : frontiers_to_keep_track) { + bool f_is_to_frontier = f == to_frontier; + bool f_is_from_frontier = f == from_frontier; + if (f_is_to_frontier || f_is_from_frontier) { + if (f_is_from_frontier) { + r_d[std::pair(i, f)] = time_travelled; + } else { + r_d[std::pair(i, f)] = + s->frontier_distances->at( + std::pair(from_frontier, f)) - + time_travelled; + } + } else { + double b = s->frontier_distances->at( + std::pair(f, to_frontier)); + double c = s->frontier_distances->at( + std::pair(f, from_frontier)); + r_d[std::pair(i, f)] = + get_frontier_time_by_triangle_formation(a, b, c, + time_travelled); + } + } + } + } else { + // Update in q_t and not here. + std::cout << "Not sure what to do here !!" << std::endl; + } + + } else { + for (auto &f : frontiers_to_keep_track) { + double time_to_frontier; + // time for the robot to explore same frontier that it is making + // progress towards + if (f == prev_frontier) { + time_to_frontier = 0; + } else { + time_to_frontier = + prev_progress + s->frontier_distances->at( + std::pair(f, prev_frontier)); + } + r_d[std::pair(i, f)] = time_to_frontier; + } + } + new_time.insert(r_d.begin(), r_d.end()); + } + return new_time; + // Update maybe: May not need old_time +} + +std::tuple, std::shared_ptr, long, double, bool> +move_robots(const State &s, std::vector &action) { + auto failure_state = std::make_shared(s); + auto [f_I, T_I] = get_frontier_of_knowledge_and_time(s, action); + bool goal_reached = false; + if (f_I == -1) { + /*if f_I and T_I are -1, both the action lead to the goal + i.e success_cost is the minimum of two robots reaching the goal*/ + std::vector all_time_to_goal; + for (int i = 0; i < action.size(); i++) { + FrontierDataMRPtr f = s.hash_to_frontier.at(action[i]); + double time_to_goal = + s.robot_distances.at(std::pair(i, action[i])) + + (f->delta_success_cost + s.goal_distances->at(action[i])) - + s.q_t.at(i).at(action[i]); + all_time_to_goal.push_back(time_to_goal); + } + T_I = *std::min_element(all_time_to_goal.begin(), all_time_to_goal.end()); + goal_reached = true; + } + auto [new_q_t, residue_time] = + find_q_t_for_action(*failure_state, T_I, action); + failure_state->q_t = new_q_t; + auto success_state = std::make_shared(*failure_state); + if (f_I != -1) { + // remove f_I from unexplored frontier in both success state and failure + // state + failure_state->remove_frontier_from_unexplored_frontiers(f_I); + success_state->remove_frontier_from_unexplored_frontiers(f_I); + // add f_I to goal frontier only in success state + success_state->add_frontier_to_goal_frontiers(f_I); + } + success_state->robot_distances = + get_time_from_qt(success_state, new_q_t, residue_time); + failure_state->robot_distances = + get_time_from_qt(failure_state, new_q_t, residue_time); + + /* Check for goal reached: + If the robot progress along a frontier is greater than or equal to delta + success cost, goal is reached. */ + + std::vector T_I_list; + for (int i = 0; i < s.num_robots; i++) { + auto [frontier, progress] = + find_progress_and_frontier_for_robot(new_q_t, i); + if (progress != 0) { + double d_sc = s.hash_to_frontier.at(frontier)->delta_success_cost; + double toreachgoal = d_sc + s.goal_distances->at(frontier); + double epsilon = 1.0; + if (toreachgoal - progress <= epsilon) { + double rem = progress - (d_sc + s.goal_distances->at(frontier)); + T_I_list.push_back(T_I - rem + epsilon); + goal_reached = true; + } + } + } + if (T_I_list.size() != 0) { + T_I = *std::min_element(T_I_list.begin(), T_I_list.end()); + } + return std::make_tuple(success_state, failure_state, f_I, T_I, goal_reached); +} diff --git a/modules/mrlsp_accel/src/main.cpp b/modules/mrlsp_accel/src/main.cpp new file mode 100644 index 0000000..9fbd060 --- /dev/null +++ b/modules/mrlsp_accel/src/main.cpp @@ -0,0 +1,74 @@ +#include +#include +#include +#include +#include +#include +#include +#include "pouct.hpp" + + +namespace py = pybind11; +PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr); + +PYBIND11_MODULE(mrlsp_accel, m) { + m.doc() = R"pbdoc( + Pybind11 plugin for demonstrating C++ features + ----------------------- + + .. currentmodule:: pycpp_examples + + .. autosummary:: + :toctree: _generate + + )pbdoc"; + + // Question: Why do we need std::shared_ptr here? Isn't this the place for inheritance? + py::class_>(m, "FrontierDataMR") + .def(py::init(), + py::arg("prob_feasible"), + py::arg("delta_success_cost"), + py::arg("exploration_cost"), + py::arg("hash_id"), + py::arg("is_from_last_chosen") = 0) + .def("__hash__", &FrontierDataMR::get_hash); + + // add , std::shared_ptr below if error pops off + py::class_>(m, "State_cpp") + .def(py::init< + int, + std::vector &, + std::map, double>, + std::map &, + std::map, double> &>(), + py::arg("num_robots"), + py::arg("unexplored_frontiers"), + py::arg("robot_distances"), + py::arg("goal_distances"), + py::arg("frontier_distances")) + .def_readonly("num_robots", &State::num_robots) + .def_readonly("unexplored_frontiers", &State::unexplored_frontiers) + .def_readonly("robot_distances", &State::robot_distances) + .def_readonly("goal_frontiers", &State::goal_frontiers) + .def_readonly("q_t", &State::q_t) + .def_readonly("unexplored_frontiers_hash", &State::unexplored_frontiers_hash) + .def("remove_frontier_from_unexplored_frontiers", &State::remove_frontier_from_unexplored_frontiers) + .def("add_frontier_to_goal_frontiers", &State::add_frontier_to_goal_frontiers) + .def("change_rd_for_robot", &State::change_rd_for_robot) + .def("copy_state", &State::copy_state) + .def("get_actions", &State::get_actions); + + m.def("find_best_joint_action_accel", &find_best_joint_action_accel); + m.def("find_progress_and_frontier_for_robot_cpp", &find_progress_and_frontier_for_robot); + m.def("get_frontier_of_knowledge_and_time_cpp", &get_frontier_of_knowledge_and_time); + m.def("get_frontier_time_by_triangle_formation_cpp", &get_frontier_time_by_triangle_formation); + m.def("find_q_t_for_action_cpp", &find_q_t_for_action); + m.def("get_time_from_qt_cpp", &get_time_from_qt); + m.def("move_robots_cpp", &move_robots); + +#ifdef VERSION_INFO + m.attr("__version__") = VERSION_INFO; +#else + m.attr("__version__") = "dev"; +#endif +} diff --git a/modules/mrlsp_accel/src/mrlsp_utility.hpp b/modules/mrlsp_accel/src/mrlsp_utility.hpp new file mode 100644 index 0000000..a4cee0a --- /dev/null +++ b/modules/mrlsp_accel/src/mrlsp_utility.hpp @@ -0,0 +1,194 @@ +#include +#include +#include +#include + +namespace set { +std::vector u(std::vector &a, std::vector &b) { + std::sort(a.begin(), a.end()); + std::sort(b.begin(), b.end()); + std::vector result; + std::set_union(a.begin(), a.end(), b.begin(), b.end(), + std::back_inserter(result)); + return result; +} +} // namespace set + +double get_frontier_time_by_triangle_formation(double a, double b, double c, + double time_travelled) { + double epsilon = 0.1; + if (a + b < c) { + double new_time = time_travelled * c / (a + b); + return new_time; + } else if (b > a + c) { + double new_time = time_travelled * c / (a + b); + return new_time; + } else if (a > b + c) { + double new_time = time_travelled * c / (a + b); + return new_time; + } + // else if absolute of sum of a and b - c is less than epsilon + else if (std::abs(a + b - c) <= epsilon) { + // the frontier is horizontally aligned (in positive direction) + double new_time = c - time_travelled; + return new_time; + } else if (std::abs(a + c - b) <= epsilon) { + // the frontier is horizontally aligned (in negative direction) + double new_time = c + time_travelled; + return new_time; + } else if (std::abs(b + c - a) <= epsilon) { + // all the frontiers lie in the same line + double new_time = std::abs(c - time_travelled); + return new_time; + } + + std::vector frontier_point; + if (a > 0) { + double x = (c * c - b * b + a * a) / (2 * a); + double y = sqrt(c * c - x * x); + // array of x and y + frontier_point = {x, y}; + } else { + std::cout << "First side of triangle not > 0" << std::endl; + } + + std::vector new_point = {time_travelled, 0}; + double new_time = sqrt(pow(new_point[0] - frontier_point[0], 2) + + pow(new_point[1] - frontier_point[1], 2)); + return new_time; +} + +int find_action_index(const std::vector &action, + const std::vector> &all_actions) { + int action_index = -1; + for (int i = 0; i < all_actions.size(); i++) { + if (all_actions[i] == action) { + action_index = i; + break; + } + } + return action_index; +} + +// Find the index of maximum value and one less than maximum value in vector v +template std::vector findIndex(std::vector const &v) { + int max_value = *std::max_element(v.begin(), v.end()); + std::vector indices; + auto it = v.begin(); + while ((it = std::find_if(it, v.end(), [&](T const &e) { + return (e == max_value || e == max_value - 1); + })) != v.end()) { + indices.push_back(std::distance(v.begin(), it)); + it++; + } + return indices; +} + +// A function get all combination of a vector of type long +std::vector> get_combinations(std::vector &v, int k) { + std::vector> result; + std::vector combination; + std::function get_combinations_helper = [&](int start) { + if (combination.size() == k) { + result.push_back(combination); + return; + } + for (int i = start; i < v.size(); ++i) { + combination.push_back(v[i]); + get_combinations_helper(i + 1); + combination.pop_back(); + } + }; + get_combinations_helper(0); + return result; +} + +// A function that takes combination and return all permutations of it +std::vector> get_permutations(std::vector v) { + std::vector> result; + do { + result.push_back(v); + } while (std::next_permutation(v.begin(), v.end())); + return result; +} + +// A function that combines get_combinations and get_permutations to return all +// permutations by doing combinations +std::vector> get_all_permutations(std::vector &v, + int k) { + std::vector> result; + std::vector> combinations = get_combinations(v, k); + for (auto &combination : combinations) { + std::vector> permutations = get_permutations(combination); + result.insert(result.end(), permutations.begin(), permutations.end()); + } + return result; +} + +// A function for permutations with replacement +std::vector> +get_permutations_with_replacement(std::vector &v, int k) { + std::vector> result; + std::vector combination(k); + std::function get_permutations_with_replacement_helper = + [&](int start) { + if (start == k) { + result.push_back(combination); + return; + } + for (int i = 0; i < v.size(); ++i) { + combination[start] = v[i]; + get_permutations_with_replacement_helper(start + 1); + } + }; + get_permutations_with_replacement_helper(0); + return result; +} + +// A funtion that combines get_permutations or get_permutations with replacement +// according to number of frontiers and number of robots +std::vector> +get_action_combinations(std::vector v, int repeat, + bool same_action = false) { + /* If same action = false, permutations without replacement + If no.of frontiers > no of robot, permute the frontiers*/ + if (!same_action && v.size() >= repeat) { + return get_all_permutations(v, repeat); + } + /* If same action = true, permutations with replacement + If no.of frontiers < no.of robots, make sure some robot explore 'same' + frontier*/ + std::vector> actions = + get_permutations_with_replacement(v, repeat); + /* If same_action = false, i.e you want all robot to prevent exploring 'same' + frontier 'as much as possible'. Hence Maximum allowed same frontiers = no. of + frontiers / robot*/ + if (!same_action && v.size() > 1) { + std::vector> final_action; + // same_action_max as ceil of no. of frontiers / no. of robots + int same_action_max = std::ceil(float(repeat) / v.size()); + // if number of same frontiers is less than or equal to same_action_max, add + // to final_action + for (auto action : actions) { + // find the count of maximum number of times an element gets repeated in + // action + int max_count = 0; + bool all_elements = true; + for (auto element : v) { + int count = std::count(action.begin(), action.end(), element); + if (count == 0) { + all_elements = false; + break; + } + if (count > max_count) { + max_count = count; + } + } + if (max_count <= same_action_max && all_elements) { + final_action.push_back(action); + } + } + return final_action; + } + return actions; +} diff --git a/modules/mrlsp_accel/src/pouct.hpp b/modules/mrlsp_accel/src/pouct.hpp new file mode 100644 index 0000000..d2d9cba --- /dev/null +++ b/modules/mrlsp_accel/src/pouct.hpp @@ -0,0 +1,381 @@ +#include "core.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +typedef std::shared_ptr StatePtr; + +struct ChildrenProperties { + StatePtr failure_state; + StatePtr success_state; + long f_I = -1; + double T_I = -1; + bool goal_reached = false; + bool has_value = false; + + ChildrenProperties() = default; + + void update_child_properties(StatePtr success_state, StatePtr failure_state, + long f_I, double T_I, bool goal_reached) { + this->failure_state = failure_state; + this->success_state = success_state; + this->f_I = f_I; + this->T_I = T_I; + this->goal_reached = goal_reached; + this->has_value = true; + } + + const std::tuple get_child_properties() { + return std::make_tuple(f_I, T_I, goal_reached); + } + + StatePtr get_state(bool success) { + if (success) + return success_state; + else + return failure_state; + } +}; + +struct Node { + StatePtr state; + std::shared_ptr parent; + std::vector prev_action; + double cost; + bool goal_reached; + std::vector> actions; + std::vector> unexplored_actions; + std::vector> children; + std::vector> children_properties; + std::vector action_values; + std::vector action_n; + int action_n_total; + Node(StatePtr current_state, std::shared_ptr p = nullptr, + std::vector p_a = {}, double T_I = 0, bool g_r = false) { + state = current_state; + parent = p; + prev_action = p_a; + if (parent == nullptr) { + cost = T_I; + } else { + cost = T_I + parent->cost; + } + this->goal_reached = g_r; + + // implement get_actions() function + actions = state->get_actions(); + + // copy actions to unexplored_actions + unexplored_actions = actions; + action_n_total = 0; + for (int i = 0; i < actions.size(); i++) { + // initialize action_values to 0 + action_values.push_back(0); + // initialize action_n to 0 + action_n.push_back(0); + + // initialize success and failure state as nullptr in children for size of + // actions + children.push_back(nullptr); + children.push_back(nullptr); + + std::shared_ptr child_properties = + std::make_shared(); + children_properties.push_back(child_properties); + } + + if (!goal_reached) { + std::vector state_unexplored_frontiers = + state->unexplored_frontiers_hash; + if (state_unexplored_frontiers.size() == 0) { + if (state->goal_frontiers.size() != 0) { + std::vector all_action_cost; + for (auto &action : actions) { + std::vector all_robot_cost; + for (int i = 0; i < action.size(); i++) { + long f = action[i]; + double cost_to_goal = + state->robot_distances.at(std::pair(i, f)) + + state->hash_to_frontier[f]->delta_success_cost + + state->goal_distances->at(f) - state->q_t[i][f]; + all_robot_cost.push_back(cost_to_goal); + } + all_action_cost.push_back(*std::min_element(all_robot_cost.begin(), + all_robot_cost.end())); + } + cost += + *std::min_element(all_action_cost.begin(), all_action_cost.end()); + goal_reached = true; + } else { + /* When no frontier leads to the goal, and no unexplored frontiers + left, assume that the parent node unexplored frontier leads to the + goal, and add the success cost of that frontier. */ + long f = parent->state->unexplored_frontiers_hash[0]; + std::vector all_robot_cost; + for (int i = 0; i < state->num_robots; i++) { + double cost_to_goal = + parent->state->robot_distances.at(std::pair(i, f)) + + parent->state->hash_to_frontier[f]->delta_success_cost + + state->goal_distances->at(f) - state->q_t[i][f]; + all_robot_cost.push_back(cost_to_goal); + } + cost += + *std::min_element(all_robot_cost.begin(), all_robot_cost.end()); + goal_reached = true; + } + } + } + } + + void clear_children() { + for (auto const &child : children) { + if (child != nullptr) { + child->clear_children(); + } + } + children.clear(); + } + + bool is_fully_explored() const { return (unexplored_actions.size() == 0); } + + bool is_terminal_state() const { return goal_reached; } + + double find_rollout_cost() const { + /* Rollout cost from current state'*/ + if (goal_reached) + return cost; + + double Q = 1e25; + for (int i = 0; i < state->num_robots; i++) { + for (auto &s : state->unexplored_frontiers_hash) { + Q = std::min(Q, state->robot_distances.at(std::pair(i, s)) + + state->goal_distances->at(s) - state->q_t[i][s] + + (1 - state->hash_to_frontier[s]->prob_feasible) * + state->hash_to_frontier[s]->exploration_cost); + } + + /* If there are frontiers which lead to the goal, then the cost to goal + from these frontiers for the robot is the minimum of distance in which the + robots can reach the goal */ + for (auto &s : state->goal_frontiers) { + Q = std::min(Q, state->robot_distances.at(std::pair(i, s)) + + (state->goal_distances->at(s) + + state->hash_to_frontier[s]->delta_success_cost) - + state->q_t[i][s]); + } + } + + // return minimum cost + return Q + cost; + } +}; + +inline double rollout(const std::shared_ptr &node) { + return node->find_rollout_cost(); +} + +void backpropagate(std::shared_ptr node, double simulation_result) { + /* Update the node and it's parent. We are updating node parents' properties + because we find best action from a node rather than best node using uct */ + while (node->parent != nullptr) { + int action_idx = + find_action_index(node->prev_action, node->parent->actions); + node->parent->action_n[action_idx] += 1; + node->parent->action_n_total += 1; + node->parent->action_values[action_idx] += simulation_result; + node = node->parent; + } +} + +inline double heuristic_cost(const std::shared_ptr &node, int robot, + long frontier) { + return node->state->robot_distances[std::make_pair(robot, frontier)]; +} + +std::vector best_action(std::shared_ptr root) { + /* When done sampling, pick the action which has been visited most*/ + + // find indices with maximum visits, and one less than maximum visits + std::vector max_n_index = findIndex(root->action_n); + std::vector heuristic_costs; + int best_action_index; + if (root->state->num_robots == 1) { + // find heuristic_cost for all action with max_n_index in root.actions + // index of lowest heuristic cost + for (auto &index : max_n_index) { + heuristic_costs.push_back( + heuristic_cost(root, 0, root->actions[index][0])); + } + best_action_index = max_n_index[std::min_element(heuristic_costs.begin(), + heuristic_costs.end()) - + heuristic_costs.begin()]; + } else { + for (auto &index : max_n_index) { + double cost = 0; + for (int i = 0; i < root->state->num_robots; i++) { + cost += heuristic_cost(root, i, root->actions[index][i]); + } + heuristic_costs.push_back(cost); + } + best_action_index = max_n_index[std::min_element(heuristic_costs.begin(), + heuristic_costs.end()) - + heuristic_costs.begin()]; + } + return root->actions[best_action_index]; + + // Update: We can combine 1 robot and mutliple robot. Code inside else + // statement works for both cases +} + +const std::vector &best_uct_action(const std::shared_ptr &node, + const double &C = 500) { + /*Pick the best action according to the UCB/UCT algorithm*/ + std::vector Q; + const std::vector &n = node->action_n; + + for (int i = 0; i < n.size(); i++) { + Q.push_back(node->action_values[i] / n[i] - + C * sqrt(log(node->action_n_total) / n[i])); + } + + return node->actions[std::min_element(Q.begin(), Q.end()) - Q.begin()]; +} + +// Before writing traverse, write Node class +std::shared_ptr traverse(std::shared_ptr node) { + std::vector action; + std::mt19937 rng{std::random_device{}()}; + int action_idx; + std::shared_ptr current_node = node; + + // While the node is fully explored, pick the best uct node. + while (current_node->is_fully_explored() && + !current_node->is_terminal_state()) { + action = best_uct_action(current_node); + action_idx = find_action_index(action, current_node->actions); + auto [f_I, T_I, goal_reached] = + current_node->children_properties[action_idx]->get_child_properties(); + bool success; + if (f_I != -1) { + std::bernoulli_distribution d( + current_node->state->hash_to_frontier[f_I]->prob_feasible); + success = d(rng); + } else { + if (T_I != -1) { + // if f_I is -1 and T_I is not -1, then goal is reached + success = 1; + } else { + // This is case when both action taken can reach goal + std::cout << "Something has to be done here UP!!" << std::endl; + } + } + if (current_node->children[2 * action_idx + success] != nullptr) { + current_node = current_node->children[2 * action_idx + success]; + } else { + StatePtr new_node_state = + current_node->children_properties[action_idx]->get_state(success); + std::shared_ptr new_node = std::make_shared( + new_node_state, current_node, action, T_I, goal_reached); + // add this new node to parent's children + current_node->children[2 * action_idx + success] = new_node; + // set current_node to new_node + current_node = new_node; + } + } + + /* If the node is terminal state, or goal state, return the node */ + if (current_node->is_terminal_state()) + return current_node; + + /* If the node is not terminal node, or goal node, the node is first + * discovered*/ + // 1. Pick a new action from the first action of unexplored actions of the + // node and remove it from unexplored actions + action = current_node->unexplored_actions[0]; + current_node->unexplored_actions.erase( + current_node->unexplored_actions.begin()); + // If the child node is already expanded, use the previously saved information + // from children_properties + action_idx = find_action_index(action, current_node->actions); + + // initialize success_state, failure_state, f_I, T_I, goal_reached + long f_I; + double T_I; + bool goal_reached; + bool success; + if (current_node->children_properties[action_idx]->has_value) { + auto [f_I_temp, T_I_temp, goal_reached_temp] = + current_node->children_properties[action_idx]->get_child_properties(); + f_I = f_I_temp; + T_I = T_I_temp; + goal_reached = goal_reached_temp; + } else { + // change state_ptr to state + State state = *current_node->state; + auto [success_state_ptr, failure_state_ptr, f_I_temp, T_I_temp, + goal_reached_temp] = move_robots(state, action); + f_I = f_I_temp; + T_I = T_I_temp; + goal_reached = goal_reached_temp; + // update child properties + current_node->children_properties[action_idx]->update_child_properties( + success_state_ptr, failure_state_ptr, f_I, T_I, goal_reached); + } + + if (f_I != -1) { + // bernoulli sample + std::bernoulli_distribution d( + current_node->state->hash_to_frontier[f_I]->prob_feasible); + success = d(rng); + } else { + if (T_I != -1) { + // if f_I is -1 and T_I is not -1, then goal is reached + success = 1; + } else { + // This is case when both action taken can reach goal + std::cout << "Something has to be done here DOWN!!" << std::endl; + } + } + + StatePtr new_node_state = + current_node->children_properties[action_idx]->get_state(success); + // 2. create a new child (new leaf) shared pointer + std::shared_ptr new_node = std::make_shared( + new_node_state, current_node, action, T_I, goal_reached); + // 3. add the child to the list of children + current_node->children[2 * action_idx + success] = new_node; + // 4. return the child + + return new_node; +} + +std::vector find_best_joint_action_accel( + const int num_robots, std::vector unexplored_frontiers, + std::map, double> robot_distances, + std::map goal_distances, + std::map, double> frontier_distances, + int num_iterations) { + // Make State shared_ptr for using all the arguments + StatePtr sigma1 = + std::make_shared(num_robots, unexplored_frontiers, robot_distances, + goal_distances, frontier_distances); + // pouct core loop + // Start by creating the root of the tree + std::shared_ptr root = std::make_shared(sigma1); + // Loop through MCTS iterations + for (int i = 0; i < num_iterations; i++) { + // One step of MCTS iteration + std::shared_ptr leaf = traverse(root); + double simulation_result = rollout(leaf); + backpropagate(leaf, simulation_result); + } + auto act = best_action(root); + root->clear_children(); + return act; +} diff --git a/modules/requirements.txt b/modules/requirements.txt new file mode 100644 index 0000000..8796418 --- /dev/null +++ b/modules/requirements.txt @@ -0,0 +1,26 @@ + +# Core Requirements +numpy +scipy +scikit-image +sknw +shapely==1.6.4 +opencv-python +pyyaml +setuptools +tensorboard +pyscreenshot +pybullet + +# Plotting & Data Handling +matplotlib +pandas +ipython +jupyter + +# Testing & formatting +pytest +pytest-timeout +pytest-html +flake8 +vulture diff --git a/modules/setup.cfg b/modules/setup.cfg new file mode 100644 index 0000000..df6b664 --- /dev/null +++ b/modules/setup.cfg @@ -0,0 +1,5 @@ + +[flake8] +ignore = W503,W504,E203 +exclude = */pybind11/*,*/scratch/*,*/build/* +max-line-length = 120 \ No newline at end of file diff --git a/modules/unitybridge/setup.py b/modules/unitybridge/setup.py new file mode 100644 index 0000000..9050cf2 --- /dev/null +++ b/modules/unitybridge/setup.py @@ -0,0 +1,11 @@ +from setuptools import setup, find_packages + + +setup(name='unitybridge', + version='1.0.0', + description='Package for TCP communication with Unity3D', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/unitybridge/tests/test_unitybridge.py b/modules/unitybridge/tests/test_unitybridge.py new file mode 100644 index 0000000..442eeea --- /dev/null +++ b/modules/unitybridge/tests/test_unitybridge.py @@ -0,0 +1,78 @@ +import numpy as np +import pytest +import unitybridge + + +@pytest.mark.timeout(5) +def test_unitybridge_loads_without_crashing(unity_path): + """The UnityBridge class can load the env without crashing or hanging.""" + with unitybridge.UnityBridge(unity_path) as _: + pass + + +@pytest.mark.timeout(15) +def test_unitybridge_get_image(unity_path, do_debug_plot): + """The unity_bridge can be used to generate images.""" + with unitybridge.UnityBridge(unity_path) as unity_bridge: + pano_image = unity_bridge.get_image( + "robot/pano_camera") + pano_depth_image = unity_bridge.get_image( + "robot/pano_depth_camera") + pano_segmentation_image = unity_bridge.get_image( + "robot/pano_segmentation_camera") + + if do_debug_plot: + import matplotlib.pyplot as plt + plt.subplot(131) + plt.imshow(pano_image) + plt.title("Pano Image") + + plt.subplot(132) + plt.imshow(pano_depth_image) + plt.title("Pano Depth Image") + + plt.subplot(133) + plt.imshow(pano_segmentation_image) + plt.title("Pano Segmentation Image") + + plt.show() + + assert pano_image.size > 0 + assert np.std(pano_image) > 0 + assert pano_depth_image.size > 0 + assert np.std(pano_depth_image) > 0 + assert pano_segmentation_image.size > 0 + assert np.std(pano_segmentation_image) > 0 + + +@pytest.mark.timeout(15) +def test_unitybridge_can_add_objects(unity_path, do_debug_plot): + """Rendered images should change after a few objects are added.""" + with unitybridge.UnityBridge(unity_path) as unity_bridge: + pano_image = unity_bridge.get_image( + "robot/pano_camera") + pano_depth_image = unity_bridge.get_image( + "robot/pano_depth_camera") + + for _ in range(10): + unity_bridge.create_cube() + + pano_image_cubes = unity_bridge.get_image( + "robot/pano_camera") + pano_depth_image_cubes = unity_bridge.get_image( + "robot/pano_depth_camera") + + if do_debug_plot: + import matplotlib.pyplot as plt + plt.subplot(121) + plt.imshow(pano_image_cubes) + plt.title("Pano Image") + + plt.subplot(122) + plt.imshow(pano_depth_image_cubes) + plt.title("Pano Depth Image") + + plt.show() + + assert np.std(pano_image - pano_image_cubes) > 0 + assert np.std(pano_depth_image - pano_depth_image_cubes) > 0 diff --git a/modules/unitybridge/unitybridge/__init__.py b/modules/unitybridge/unitybridge/__init__.py new file mode 100644 index 0000000..76bea32 --- /dev/null +++ b/modules/unitybridge/unitybridge/__init__.py @@ -0,0 +1 @@ +from .unity_bridge import UnityBridge # noqa: F401 diff --git a/modules/unitybridge/unitybridge/unity_bridge.py b/modules/unitybridge/unitybridge/unity_bridge.py new file mode 100644 index 0000000..6e951b1 --- /dev/null +++ b/modules/unitybridge/unitybridge/unity_bridge.py @@ -0,0 +1,194 @@ +"""Some functions useful for running Unity within Python.""" +import numpy as np +import random +import socket +import struct +import subprocess +import time + + +class TCPUnityParser(object): + """Helper class for listening/parsing messages from Unity. + + The various functions, titled 'parse_VAR', are all designed to easily + listen for and parse the data of interest. + """ + def __init__(self, unity_socket): + self.unity_socket = unity_socket + self.unity_socket.listen(4) + connection, _ = self.unity_socket.accept() + time.sleep(0.1) + self.connection = connection + + def close(self): + """Close all open sockets/connections.""" + self.connection.close() + self.unity_socket.close() + + def parse_filler(self, filler_len): + """Listen for a set number of bytes (no return value).""" + self.connection.recv(filler_len) + + def parse_struct(self, data_type): + """Parse a single value of a set data_type. + + See the documentation for the 'struct' module for a list of data types. + """ + + if data_type == 'i': + return struct.unpack('i', self.connection.recv(4))[0] + elif data_type == 'f': + return struct.unpack('f', self.connection.recv(4))[0] + elif data_type == 'q': + return struct.unpack('q', self.connection.recv(8))[0] + else: + raise ValueError("Unknown data_type '{}'".format(data_type)) + + def parse_string(self): + """Listen for a string (terminated in '\x00').""" + data_name = '' + stop_char = b'\x00'[0] + while True: + letter = self.connection.recv(1)[0] + if letter == stop_char: + break + data_name += chr(letter) + + return data_name + + def parse_image(self): + """Listens for Unity image data. + + Unity provides more data than we care to use, yet the data is + stored in 'data' (a dictionary) in case it is ever wanted. + """ + + self.parse_filler(4) + + data = dict() + data['type'] = self.parse_struct('i') + data['tick'] = self.parse_struct('q') + data['name'] = self.parse_string() + + data['im_fov'] = self.parse_struct('f') + data['im_clip'] = self.parse_struct('f') + data['im_height'] = self.parse_struct('i') + data['im_width'] = self.parse_struct('i') + + im_data = b'' + im_data_target_len = data['im_height'] * data['im_width'] * 3 + while im_data_target_len - len(im_data) > 0: + im_data += self.connection.recv(im_data_target_len - len(im_data)) + image = np.frombuffer(im_data, dtype=np.uint8) + image = np.reshape(image, [data['im_width'], data['im_height'], 3]) + image = np.flip(image, axis=0) + return image + + +class UnityBridge(object): + def __init__( + self, + unity_exe, + unity_args='-batchmode -screen-fullscreen 0 -logFile /data/unity_logs.txt', + tcp_ip='127.0.0.1', + talk_port=None, + listen_port=None, + is_debug=False, + sim_scale=1.0): + + self.do_buffer = False + self.messages = [] + self.tcp_ip = tcp_ip + if talk_port: + self.talk_port = talk_port + else: + s = socket.socket() + s.bind(("", 0)) + self.talk_port = int(s.getsockname()[1]) + + if listen_port: + self.listen_port = listen_port + else: + s = socket.socket() + s.bind(("", 0)) + self.listen_port = int(s.getsockname()[1]) + + if is_debug: + print(("Ports: py-listen={} py-talk={}".format(self.listen_port, + self.talk_port))) + + self.unity_exe = unity_exe + self.unity_args = unity_args + ' -talk-port {} -listen-port {}'.format( + self.listen_port, self.talk_port) + + self.is_debug = is_debug + self.sim_scale = sim_scale + + def start_unity(self): + """Start Unity as a background process. + + Before starting Unity, we open a tcp socket. When Unity opens, it + connects to that socket, which we listen to via 'unity_listener'. + Note that this code must be run in this order: (1) open socket, (2) + start Unity, (3) listen to socket (via TCPUnityParser). In any other + order Unity will not connect, or Python may hang. + """ + + # Launch unity as a background process + if not self.is_debug: + unity_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + unity_socket.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + unity_socket.bind((self.tcp_ip, self.listen_port)) + self.unity_subprocess = subprocess.Popen( + [self.unity_exe] + self.unity_args.split(" "), + stdout=subprocess.DEVNULL) + else: + unity_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + unity_socket.bind((self.tcp_ip, self.listen_port)) + print(unity_socket) + + self.unity_listener = TCPUnityParser(unity_socket) + + def send_message(self, message, pause=0.1): + if self.do_buffer: + self.messages.append(message) + else: + self.talker.send(message.encode()) + if pause > 0: + time.sleep(pause) + + def __enter__(self): + self.start_unity() + self.start_talker() + return self + + def __exit__(self, type, value, traceback): + self.do_buffer = False + self.send_message("shutdown shutdown", pause=1.0) + self.unity_listener.close() + self.talker.close() + # Wait for the unity process to finish + if not self.is_debug: + self.unity_subprocess.wait() + time.sleep(1.0) + + def start_talker(self): + self.talker = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.talker.connect((self.tcp_ip, self.talk_port)) + + def create_cube(self): + rx = random.random() * 10 + ry = random.random() * 10 + rz = random.random() * 10 + self.send_message("main_builder cube {} {} {}".format(rx, ry, rz), + pause=0.001) + + def create_object(self, command_name, pose, height): + self.send_message("main_builder {} {} {} {}".format( + command_name, + pose.x * self.sim_scale, + pose.y * self.sim_scale, height), pause=0.001) + + def get_image(self, camera_name, pause=-1): + self.send_message(camera_name + " render", pause) + return self.unity_listener.parse_image() diff --git a/modules/vertexnav/Makefile.mk b/modules/vertexnav/Makefile.mk new file mode 100644 index 0000000..2c0231e --- /dev/null +++ b/modules/vertexnav/Makefile.mk @@ -0,0 +1,96 @@ + + +# This target is to make an image by calling a script within 'example' +VERTEXNAV_UNITY_BASENAME ?= $(UNITY_BASENAME) +VERTEXNAV_CORE_ARGS = \ + --unity_path /unity/$(VERTEXNAV_UNITY_BASENAME).x86_64 \ + --xpassthrough $(XPASSTHROUGH) \ + --max_range 100 \ + --num_range 32 \ + --num_bearing 128 +vertexnav_dungeon_base_dir = $(DATA_BASE_DIR)/vertexnav/dungeon + +vertexnav-dungeon-data-gen-seeds = \ + $(shell for ii in $$(seq 1000 1249); do echo "$(vertexnav_dungeon_base_dir)/data/training_env_plots/training_env_$$ii.png"; done) \ + $(shell for ii in $$(seq 2000 2024); do echo "$(vertexnav_dungeon_base_dir)/data/training_env_plots/testing_env_$$ii.png"; done) + +$(vertexnav-dungeon-data-gen-seeds): seed = $(shell echo $@ | grep -Eo '[0-9]+' | tail -1) +$(vertexnav-dungeon-data-gen-seeds): traintest = $(shell echo $@ | grep -Eo '(training|testing)' | tail -1) +$(vertexnav-dungeon-data-gen-seeds): + @$(call arg_check_unity) + @$(call arg_check_data) + @mkdir -p $(vertexnav_dungeon_base_dir)/data/pickles/ + @mkdir -p $(vertexnav_dungeon_base_dir)/data/training_env_plots/ + @rm -f $(vertexnav_dungeon_base_dir)/data/dungeon_*_$(seed).csv + @echo "dungeon_$(traintest)" + @$(DOCKER_PYTHON) -m vertexnav.scripts.gen_vertex_training_data_sim \ + $(VERTEXNAV_CORE_ARGS) \ + --base_data_path /data/vertexnav/dungeon \ + --environment dungeon \ + --data_file_base_name dungeon_$(traintest) \ + --data_plot_name $(traintest)_env \ + --seed $(seed) + +vertexnav-dungeon-train-net = $(vertexnav_dungeon_base_dir)/training_logs/$(EXPERIMENT_NAME)/VertexNavGrid.pt +$(vertexnav-dungeon-train-net): $(vertexnav-dungeon-data-gen-seeds) + @mkdir -p $(vertexnav_dungeon_base_dir)/training_logs/$(EXPERIMENT_NAME)/ + @$(call arg_check_data) + @$(DOCKER_PYTHON) -m vertexnav.scripts.train_vertex_nav_net \ + --training_data_file /data/vertexnav/dungeon/data/*train*.csv \ + --test_data_file /data/vertexnav/dungeon/data/*test*.csv \ + --logdir /data/vertexnav/dungeon/training_logs/$(EXPERIMENT_NAME)/ \ + --mini_summary_frequency 100 --summary_frequency 1000 \ + --num_epochs 8 \ + --learning_rate 0.001 \ + +# Dungeon Environment Parameters +DUNGEON_EXTENSION_NAME ?= dungeon +DUNGEON_UNITY_BASENAME ?= $(UNITY_BASENAME) +DUNGEON_MAX_RANGE ?= 100 +DUNGEON_NUM_RANGE ?= 32 +DUNGEON_NUM_BEARING ?= 128 + +vertexnav-dungeon-eval-seeds = \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r1_merge_none.png"; done) \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r1_merge_multi.png"; done) \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r1_merge_single.png"; done) \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r3_merge_none.png"; done) \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r3_merge_multi.png"; done) \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r3_merge_single.png"; done) + +vertexnav-dungeon-eval-seeds = \ + $(shell for ii in $$(seq 10000 10099); do echo "$(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME)/dungeon_slam_s$${ii}_r3_merge_none.png"; done) \ + +$(vertexnav-dungeon-eval-seeds): seed = $(shell echo '$@' | grep -Eo '[0-9]+' | tail -2 | head -1) +$(vertexnav-dungeon-eval-seeds): num_robots = $(shell echo '$@' | grep -Eo '[0-9]+' | tail -1) +$(vertexnav-dungeon-eval-seeds): merge_type = $(shell echo $@ | grep -Eo 'merge_(none|single|multi)' | tail -1) +$(vertexnav-dungeon-eval-seeds): $(vertexnav-dungeon-train-net) + @echo "Random Seed: $(seed)" + @echo "Number of robots: $(num_robots)" + @mkdir -p $(vertexnav_dungeon_base_dir)/results/$(EXPERIMENT_NAME) + @- $(DOCKER_PYTHON) -m vertexnav.scripts.eval_simulated \ + --video_path /data/vertexnav/dungeon/results/$(EXPERIMENT_NAME)/dungeon_slam_s$(seed)_r$(num_robots)_$(merge_type).mp4 \ + --figure_path /data/vertexnav/dungeon/results/$(EXPERIMENT_NAME)/dungeon_slam_s$(seed)_r$(num_robots)_$(merge_type).png \ + --network_file /data/vertexnav/dungeon/training_logs/$(EXPERIMENT_NAME)/VertexNavGrid.pt \ + --unity_exe_path /unity/$(DUNGEON_UNITY_BASENAME).x86_64 \ + --environment dungeon \ + --seed $(seed) \ + --do_use_robot \ + --do_explore \ + --do_use_frontiers \ + --num_robots $(num_robots) \ + --max_range $(DUNGEON_MAX_RANGE) \ + --num_range $(DUNGEON_NUM_RANGE) \ + --num_bearing $(DUNGEON_NUM_BEARING) \ + --merge_type $(merge_type) \ + --sig_r 5.0 \ + --sig_th 0.125 \ + --nn_peak_thresh 0.5 + @sleep 10 + +# Convenience Targets +.PHONY: vertexnav-dungeon-generate-data vertexnav-dungeon-train vertexnav-dungeon-eval vertexnav-dungeon +vertexnav-dungeon-generate-data: $(vertexnav-dungeon-data-gen-seeds) +vertexnav-dungeon-train: $(vertexnav-dungeon-train-net) +vertexnav-dungeon-eval: $(vertexnav-dungeon-eval-seeds) +vertexnav-dungeon: vertexnav-dungeon-eval diff --git a/modules/vertexnav/README.org b/modules/vertexnav/README.org new file mode 100644 index 0000000..75e7cac --- /dev/null +++ b/modules/vertexnav/README.org @@ -0,0 +1,36 @@ +* VertexNav: Mapping by detecting vertices in polygonal maps + +Algorithmic code pertaining to monocular mapping, by detecting structural vertices in panoramic images and fusing them into a polygonal map. Results include experiments for both a single robot and a 3-robot, centrally coordinated team. This module reproduces core algorithm and results first presented in the following paper: + +Gregory J. Stein, Christopher Bradley, Victoria Preston, and Nicholas Roy. "Enabling Topological Planning with Monocular Vision." In: International Conference on Robotics and Automation (ICRA). 2020. [[https://arxiv.org/abs/2003.14368][paper]], [[https://youtu.be/UVZ3UcK6MhI][talk (10 min)]]. + +#+begin_src bibtex +@inproceedings{stein2020gapnav, + author = {Gregory J. Stein and Christopher Bradley and Victoria Preston + and Nicholas Roy}, + booktitle = {International Conference on Robotics and Automation (ICRA)}, + title = {Enabling Topological Planning with Monocular Vision}, + year = 2020, + keywords = {topological mapping, topological planning, frontiers, + multi-agent search, exploration, learning}, +} +#+end_src + +Readers are referred to the paper for algorithmic details. + +** Usage + +Note: =make build= (see top-level README) must be successfully run before running the following commands. + +The =Makefile.mk= provides multiple targets for reproducing results. +- =make vertexnav-dungeon= will generate results from our multi-room "Dungeon" environment for both a single robot and for a centrally-coordinated 3-robot team. + +Both targets are run in single-threaded mode by default, however both data generation and evaluation can be run on multiple seeds in parallel. As such, running =make vertexnav-dungeon -j3= will run three concurrent instances. As data generation has a smaller VRAM footprint than does evaluation, it is often possible to run more concurrent instances specifically for data generation: + +#+begin_src bash +make build +make vertexnav-dungeon-generate-data -j6 +make vertexnav-dungeon -j3 +#+end_src + +GNU Make keeps track of progress, so if (for whatever reason) the code is stopped during a run. Rerunning the above commands will resume where it left off, without the need to redo any of the completed data generation, training, or evaluation instances. diff --git a/modules/vertexnav/setup.py b/modules/vertexnav/setup.py new file mode 100644 index 0000000..6122c9b --- /dev/null +++ b/modules/vertexnav/setup.py @@ -0,0 +1,10 @@ +from setuptools import setup, find_packages + +setup(name='vertexnav', + version='1.0.0', + description='A simple example module', + license="MIT", + author='Gregory J. Stein', + author_email='gjstein@gmu.edu', + packages=find_packages(), + install_requires=['numpy', 'matplotlib']) diff --git a/modules/vertexnav/tests/test_mvmp.py b/modules/vertexnav/tests/test_mvmp.py new file mode 100644 index 0000000..a7894a3 --- /dev/null +++ b/modules/vertexnav/tests/test_mvmp.py @@ -0,0 +1,261 @@ +import math +import numpy as np +import pytest +import random +from shapely import geometry +import vertexnav + + +def _plot_pvg_data(ax, pvg, world, title): + ax.clear() + ax.set_title(title) + ax.set_aspect('equal') + ax.get_xaxis().set_ticks([]) + ax.get_yaxis().set_ticks([]) + + pose = pvg.r_poses[len(pvg.r_poses) - 1] + proposed_world = pvg.get_proposed_world() + + # Plot the clusters + vertex_remapping = vertexnav.prob_vertex_graph._get_vertex_remapping( + vertices=pvg.vertices, topology=pvg.topology) + vertex_id_dict = {v.id: v for v in pvg.vertices} + clusters = [ + vertexnav.prob_vertex_graph.Cluster(c, vertex_id_dict) + for c in pvg.topology + ] + for cluster in clusters: + if not cluster.is_active and cluster.num_dets > 2: + vert = vertex_remapping[cluster.vids[0]] + ax.plot(vert.position[0], + vert.position[1], + 'r.', + alpha=0.4, + markersize=vertexnav.plotting.SCATTERSIZE * 2) + + vertexnav.plotting.plot_world(ax, world, alpha=0.2) + + robot_ids = set(p.robot_id for p in pvg.r_poses) + for rid in robot_ids: + r_points = np.array([(p.x, p.y) for p in pvg.r_poses + if p.robot_id == rid]) + line, = ax.plot(r_points[:, 0], r_points[:, 1], alpha=0.75) + ax.plot(r_points[-1, 0], r_points[-1, 1], '.', color=line.get_color()) + ax.plot(r_points[-1, 0], r_points[-1, 1], 'x', color=line.get_color()) + + vertexnav.plotting.plot_proposed_world(ax, + proposed_world, + do_show_points=True, + do_plot_visibility=False, + robot_pose=pose) + + +def _add_new_observation(pvg, + world, + pose, + odom, + err=None, + association_window=-1): + pose = vertexnav.Pose(pose.x, pose.y, pose.yaw, pose.robot_id) + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(pose), + pose, + do_add_noise=False, + cov_rt=[[0.1**2, 0], [0, 0.1**2]]) + assert len(obs) < 4 + + if odom is None: + pvg.add_observation(obs, + r_pose=pose, + association_window=association_window) + else: + odom = vertexnav.Pose(odom.x, odom.y, odom.yaw, odom.robot_id) + if err is not None: + odom.x += err[0] + odom.y += err[1] + odom.yaw += err[2] + # We need to update the position of the detections to make this a + # fair test. + nposes = len(pvg.r_poses) + num_robot_ids = len(set(p.robot_id for p in pvg.r_poses)) + updated_pose = odom * pvg.r_poses[nposes - num_robot_ids] + for det in obs: + det.update_props(updated_pose) + + pvg.add_observation(obs, + odom=odom, + association_window=association_window) + + +@pytest.mark.skip("Test unreliable; fails more often than not.") +def test_mvmp_slam_orbiting_square(do_debug_plot): + # Overwrite this for now + random.seed(304) + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_perfect.DO_SLAM = False + pvg_error = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_error.DO_SLAM = False + pvg_slam = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_slam.DO_SLAM = True + pvg_slam.DO_SAMPLE_TOPOLOGY = True + + pvg_mvmp = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_mvmp.DO_SLAM = True + pvg_mvmp.DO_SAMPLE_TOPOLOGY = True + + # Set the noise models + pvg_slam.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_slam.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_slam.CLUSTERING_NOISE = np.array([0.005, 0.005]) + + # Set the noise models + pvg_mvmp.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_mvmp.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_mvmp.CLUSTERING_NOISE = np.array([0.005, 0.005]) + + association_window = 1 + + # Add a number of observations + n_poses_per_loop = 80 + n_loops = 4 + for ii in range(n_loops * n_poses_per_loop + 1): + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th) + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose, + p_old=pvg_perfect.r_poses[nposes - + 1]) + + # A very simple error model + err = [ + 0.01 * (random.random() - 0.5), 0.01 * (random.random() - 0.5), + 0.005 * random.random() + ] + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_error, + world=world, + pose=pose, + odom=odom, + err=err) + + print("PVG_SLAM") + _add_new_observation(pvg=pvg_slam, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=association_window) + + _add_new_observation(pvg=pvg_mvmp, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=association_window) + + p = pvg_error.r_poses[len(pvg_error.r_poses) - 1] + print((p.x, p.y, p.yaw, p.index)) + p = pvg_slam.r_poses[len(pvg_slam.r_poses) - 1] + print((p.x, p.y, p.yaw, p.index)) + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 4, 1) + ax2 = plt.subplot(1, 4, 2) + ax3 = plt.subplot(1, 4, 3) + ax4 = plt.subplot(1, 4, 4) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_error, world, "Noisy Odom") + _plot_pvg_data(ax3, pvg_slam, world, "Noisy Odom + SLAM") + _plot_pvg_data(ax4, pvg_mvmp, world, "Noisy Odom + SLAM + MVMP") + + plt.show() + + assert not (pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 1] + == pvg_error.r_poses[len(pvg_error.r_poses) - 1]) + + assert len(pvg_perfect.vertices) == 4 + assert len(pvg_error.vertices) > 4 + assert len(pvg_slam.vertices) > 4 + assert len(pvg_mvmp.vertices) > 4 + + _, state_perfect = pvg_perfect.sample_vertices(do_update_state=False) + _, state_error = pvg_error.sample_vertices(do_update_state=False) + + # Sample topologies without and *with* MVMP to compare results. + num_topology_samples = 40 + mvmp_merge_dist_threshold = 0.1 + _, state_slam = pvg_slam.sample_states(do_update_state=True, + num_topology_samples=num_topology_samples, do_multi_vertex_merge=False) + _, state_mvmp = pvg_mvmp.sample_states(do_update_state=True, + num_topology_samples=num_topology_samples, do_multi_vertex_merge=True, + mvmp_merge_dist_threshold=mvmp_merge_dist_threshold) + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 4, 1) + ax2 = plt.subplot(1, 4, 2) + ax3 = plt.subplot(1, 4, 3) + ax4 = plt.subplot(1, 4, 4) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_error, world, "Noisy Odom") + _plot_pvg_data(ax3, pvg_slam, world, "Noisy Odom + SLAM") + _plot_pvg_data(ax4, pvg_mvmp, world, "Noisy Odom + SLAM + MVMP") + + plt.show() + + proposed_world = pvg_mvmp.get_proposed_world() + print("== MVMP ==") + print(f"Number of vertices: {len(proposed_world.vertices)}") + print(f"Number of walls: {len(proposed_world.walls)}") + print(f"Length of topology: {len(pvg_mvmp.topology)}") + + print("== SLAM ==") + proposed_world = pvg_slam.get_proposed_world() + print(f"Number of vertices: {len(proposed_world.vertices)}") + print(f"Number of walls: {len(proposed_world.walls)}") + print(f"Length of topology: {len(pvg_slam.topology)}") + + assert state_perfect.log_prob > state_error.log_prob + assert state_slam.log_prob > state_error.log_prob + + # Confirm that the 'perfect' world is as expected + proposed_world = pvg_perfect.get_proposed_world() + assert len(proposed_world.vertices) == 4 + for v in proposed_world.vertices: + assert abs(v[0]) == pytest.approx(1.0, abs=1e-2) + assert abs(v[1]) == pytest.approx(1.0, abs=1e-2) + assert len(proposed_world.walls) == 4 + + # Confirm the 'MVMP' world should look quite similar. + proposed_world = pvg_mvmp.get_proposed_world() + assert len(proposed_world.vertices) == 4 + for v in proposed_world.vertices: + assert abs(v[0]) == pytest.approx(1.0, abs=5e-2) + assert abs(v[1]) == pytest.approx(1.0, abs=5e-2) + assert len(proposed_world.walls) == 4 diff --git a/modules/vertexnav/tests/test_navigation.py b/modules/vertexnav/tests/test_navigation.py new file mode 100644 index 0000000..466a46e --- /dev/null +++ b/modules/vertexnav/tests/test_navigation.py @@ -0,0 +1,341 @@ +import vertexnav +import pytest +import shapely + + +def test_get_inflated_vertices(): + + # Simple world, with only 1 line, we should expect 4 vertices + verts = [(0, 0), (1, 0), (1, 1)] + world = vertexnav.world.ProposedWorld(vertices=verts, + walls=[[(0, 0), (1, 0)]]) + + # Solitary vert + world = vertexnav.world.ProposedWorld(vertices=[(0, 0)], walls=[]) + inf_verts, _ = world.get_inflated_vertices(inflation_rad=0.1) + assert len(inf_verts) > 1 + + # One vert, single wall + world = vertexnav.world.ProposedWorld(vertices=[(0, 0)], + walls=[[(0, 0), (1, 0)]]) + inf_verts, _ = world.get_inflated_vertices(inflation_rad=0.1) + assert len(inf_verts) > 2 + + # Two verts, single wall + world = vertexnav.world.ProposedWorld(vertices=[(0, 0), (1, 0)], + walls=[[(0, 0), (1, 0)]]) + inf_verts, _ = world.get_inflated_vertices(inflation_rad=0.1) + assert len([v for v in inf_verts if v[0] < 0]) >= 2 + assert len([v for v in inf_verts if v[0] > 1]) >= 2 + assert len([v for v in inf_verts if v[1] < 0]) >= 2 + assert len([v for v in inf_verts if v[1] > 0]) >= 2 + + # Single vert with 3 walls connected to it + world = vertexnav.world.ProposedWorld(vertices=[(0, 0)], + walls=[[(0, 0), (1, 0)], + [(0, 0), (-1, 0)], + [(0, 0), (0, 1)]]) + inf_verts, _ = world.get_inflated_vertices(inflation_rad=0.1) + assert len(inf_verts) == 3 + assert len([v for v in inf_verts if v[0] > 0.01]) == 1 + assert len([v for v in inf_verts if v[0] < -0.01]) == 1 + assert len([v for v in inf_verts if v[1] < 0]) == 1 + assert len([v for v in inf_verts if v[1] > 0]) == 2 + + # 3 verts joined at a 4th + world = vertexnav.world.ProposedWorld(vertices=[(0, 0), (1, 0.4), + (-1, 0.4), (0, 1)], + walls=[[(0, 0), (1, 0.4)], + [(0, 0), (-1, 0.4)], + [(0, 0), (0, 1)]]) + inf_verts, _ = world.get_inflated_vertices(inflation_rad=0.1) + assert len(inf_verts) >= 9 + + +def test_get_inflated_verts_and_visibility_one_vert(): + """Confirm that the inflated vertices and visibility edges conform to our expectation.""" + + # One vert, single wall + world = vertexnav.world.ProposedWorld(vertices=[(0, 0)], + walls=[[(0, 0), (1, 0)]]) + + inf_verts, inf_obs = world.get_inflated_vertices(inflation_rad=0.01) + vis_edges = world.get_visibility_edges_from_verts(inf_verts, inf_obs) + + assert len(world.vertices) == 1 + assert len(inf_verts) > 1 + assert len(inf_obs) == 1 + assert len(vis_edges) == len(inf_verts) - 1 + + world_b = vertexnav.world.ProposedWorld(vertices=[(0, 0)], + walls=[[(0, 0), (1, 1)]]) + + inf_verts_b, inf_obs_b = world_b.get_inflated_vertices(inflation_rad=0.01) + vis_edges_b = world_b.get_visibility_edges_from_verts( + inf_verts_b, inf_obs_b) + + assert len(world.vertices) == 1 + assert len(inf_verts_b) > 1 + assert len(inf_obs_b) == 1 + assert len(vis_edges_b) == len(inf_verts_b) - 1 + assert not inf_verts == inf_verts_b + assert not vis_edges == vis_edges_b + + world_c = vertexnav.world.ProposedWorld(vertices=[(1, 0)], + walls=[[(0, 0), (1, 0)]]) + + inf_verts_c, inf_obs_c = world_c.get_inflated_vertices(inflation_rad=0.01) + vis_edges_c = world_c.get_visibility_edges_from_verts( + inf_verts_c, inf_obs_c) + + assert len(world.vertices) == 1 + assert len(inf_verts_c) > 1 + assert len(inf_obs_c) == 1 + assert len(vis_edges_c) == len(inf_verts_c) - 1 + assert not inf_verts == inf_verts_c + assert not vis_edges == vis_edges_c + + +def test_get_inflated_verts_and_visibility_two_verts(): + """Confirm that the inflated vertices and visibility edges conform to our expectation.""" + + # One vert, single wall + world = vertexnav.world.ProposedWorld(vertices=[(0, 0)], + walls=[[(0, 0), (1, 0)]]) + + inf_verts, inf_obs = world.get_inflated_vertices(inflation_rad=0.01) + vis_edges = world.get_visibility_edges_from_verts(inf_verts, inf_obs) + + assert len(world.vertices) == 1 + assert len(inf_verts) > 1 + assert len(inf_obs) == 1 + assert len(vis_edges) == len(inf_verts) - 1 + + # One vert, single wall + world_b = vertexnav.world.ProposedWorld(vertices=[(0, 0), (1, 0)], + walls=[[(0, 0), (1, 0)]]) + + inf_verts_b, inf_obs_b = world_b.get_inflated_vertices(inflation_rad=0.01) + vis_edges_b = world_b.get_visibility_edges_from_verts( + inf_verts_b, inf_obs_b) + + assert len(world.vertices) == 1 + assert len(inf_verts_b) > 2 + assert len(inf_obs_b) == 2 + + assert len(world_b.vertices) == 2 + assert len(inf_verts_b) == 2 * len(inf_verts) + assert len(inf_obs_b) == 2 + assert len(vis_edges_b) > 2 * len(vis_edges) + + +@pytest.mark.skip("Test too succeptable to numerical noise.") +def test_get_h_obs_missing_wall(): + """Confirm that the hypothesized observation does not contain points outside the + visibility region. Test disabled: Note that this functionality is still + generally expected to succedd in the wild. However, using two different + "proposed world" instances is much more challenging when computing the + hypothetical observations because the C++ code is more succeptable to + numerical noise.""" + underlying_world = vertexnav.world.ProposedWorld(vertices=[(0, 0), (0, 1), + (1, 1), (1, 0)], + walls=[[(0, 0), (1, 0)], + [(1, 0), (1, 1)], + [(1, 1), (0, 1)], + [(0, 1), (0, 0)]]) + missing_wall_world = vertexnav.world.ProposedWorld(vertices=[ + (0, 0), (0, 1), (1, 1), (1, 0)], walls=[[(1, 0), (1, 1)], + [(1, 1), (0, 1)], + [(0, 1), + (0, 0)]]) + r_pose = vertexnav.Pose(-0.5, -1.0) + + vertices = underlying_world.get_vertices_for_pose(r_pose) + observation = vertexnav.noisy.convert_world_obs_to_noisy_detection( + vertices, r_pose) + naive_h_vertices = missing_wall_world.get_vertices_for_pose(r_pose) + naive_h_observation = vertexnav.noisy.convert_world_obs_to_noisy_detection( + naive_h_vertices, r_pose) + h_observation = vertexnav.noisy.compute_hypothetical_observation( + missing_wall_world, r_pose, observation) + + assert len(underlying_world.vertices) == 4 + assert len(missing_wall_world.vertices) == 4 + assert len(observation) == 3 + assert len(naive_h_vertices) == 4 + assert len(h_observation) == 3 + + def assert_in_obs(val): + for obs in h_observation: + if obs.position == pytest.approx(val): + break + else: + raise ValueError( + "{} does not appear in h_observtation.".format(val)) + + assert_in_obs([0, 0]) + assert_in_obs([0, 1]) + assert_in_obs([1, 0]) + with pytest.raises(ValueError): + assert_in_obs([1, 1]) + + # Now confirm that the visibility polygons have the properties we expect + obs_poly = shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs( + r_pose, observation)) + h_obs_poly = shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs( + r_pose, h_observation)) + naive_h_obs_poly = shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs( + r_pose, naive_h_observation)) + + assert obs_poly.area >= h_obs_poly.area + assert not obs_poly.intersects(shapely.geometry.Point(0.5, 0.25)) + assert not h_obs_poly.intersects(shapely.geometry.Point(0.5, 0.25)) + assert naive_h_obs_poly.intersects(shapely.geometry.Point(0.5, 0.25)) + + +def test_get_h_obs_false_neg(): + """Confirm that the hypothesized observation does not contain points + outside the visibility region.""" + pytest.xfail("Test does not conform to new C++ API.") + + underlying_world = vertexnav.world.ProposedWorld(vertices=[(0.0, 0.0), + (0.0, 1.0), + (1.0, 1.0), + (1.0, 0.0)], + walls=[[(0.0, 0.0), + (1.0, 0.0)], + [(1.0, 0.0), + (1.0, 1.0)], + [(1.0, 1.0), + (0.0, 1.0)], + [(0.0, 1.0), + (0.0, 0.0)]]) + + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + for ii in range(10): + r_pose = vertexnav.Pose(-0.5, -1.0) + + vertices = underlying_world.get_vertices_for_pose(r_pose) + observation = vertexnav.noisy.convert_world_obs_to_noisy_detection( + vertices, + r_pose, + do_add_noise=False, + cov_rt=[[0.5, 0.0], [0.0, 0.5]]) + if ii == 0: + nvg.add_observation(observation, r_pose) + else: + nvg.add_observation(observation, odom=vertexnav.Pose(0, 0, 0)) + + pw = nvg.get_proposed_world_fast(nvg.topology) + vertices = pw.vertices + [(0.1, -0.1), (2.0, -0.1)] + pw_aug = vertexnav.world.ProposedWorld(vertices=vertices, + walls=[[(0.0, 0.0), (1.0, 0.0)], + [(1.0, 0.0), (1.0, 1.0)], + [(1.0, 1.0), (0.0, 1.0)], + [(0.0, 1.0), (0.0, 0.0)]]) + + h_observation_correct = vertexnav.noisy.compute_hypothetical_observation( + pw, r_pose, observation) + h_observation = vertexnav.noisy.compute_hypothetical_observation( + pw_aug, r_pose, observation) + + obs_poly = shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs(r_pose, + observation, + radius=10)) + h_obs_poly = shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs(r_pose, + h_observation, + radius=10)) + + assert len(underlying_world.vertices) == 4 + assert len(pw.vertices) == 3 + assert len(pw_aug.vertices) == 5 + assert len(observation) == 3 + # Only one of the two extra vertices is in the visible region + assert len(h_observation_correct) == 3 + assert len(h_observation) == 4 + + def assert_in_obs(val): + for obs in h_observation: + if obs.position == pytest.approx(val): + break + else: + raise ValueError( + "{} does not appear in h_observtation.".format(val)) + + assert_in_obs([0, 0]) + assert_in_obs([0, 1]) + assert_in_obs([1, 0]) + with pytest.raises(ValueError): + assert_in_obs([1, 1]) + with pytest.raises(ValueError): + assert_in_obs([-1, -1]) + + # Now confirm that the visibility polygons have the properties we expect + assert obs_poly.area >= h_obs_poly.area + + +def test_get_h_obs_mixed(): + """This regression test was written to identify a particularly odd scenario in +which additional free space was added that was outside the map despite all +vertices being correctly identified. When the hypothetical observation was +computed, if some points in theactual observation had been disabled, the results +may not be correct.""" + pytest.xfail("Test incomplete; known to fail.") + + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + + underlying_world = vertexnav.world.ProposedWorld(vertices=[(3, -3), + (3, 3)], + walls=[[(2, 0), (3, -3)], + [(2, 0), (3, 3)], + [(3, -3), (3, 3)]]) + incorrect_world = vertexnav.world.ProposedWorld(vertices=[(1, 0), (3, -3), + (3, 3)], + walls=[[(1, 0), (3, -3)], + [(1, 0), (3, 3)], + [(3, -3), (3, 3)]]) + r_pose = vertexnav.Pose(0.0, 0.0) + + vertices = incorrect_world.get_vertices_for_pose(r_pose) + observation = vertexnav.noisy.convert_world_obs_to_noisy_detection( + vertices, + r_pose, + do_add_noise=False, + cov_rt=[[2.0**2, 0], [0, 0.15**2]]) + nvg.add_observation(observation, r_pose) + h_observation = vertexnav.noisy.compute_hypothetical_observation( + underlying_world, r_pose, observation) + + assert (len(h_observation) == 3) + + +def test_clutter_avoid(): + inflation_rad = 1.0 + proposed_world = vertexnav.world.ProposedWorld(walls=[], vertices=[]) + visibility_graph = vertexnav.planning.VisibilityGraph(proposed_world, + inflation_rad=0.8 * + inflation_rad) + + start = vertexnav.Pose(0, 0) + goal = vertexnav.Pose(0, 10) + + _, cost = visibility_graph.get_shortest_path(start_point=(start.x, + start.y), + end_point=(goal.x, goal.y), + do_return_cost=True) + + assert cost == pytest.approx(10.0) + + path, cost = visibility_graph.get_shortest_path( + start_point=(start.x, start.y), + end_point=(goal.x, goal.y), + do_return_cost=True, + nearby_clutter=[vertexnav.Pose(0.0, 5.0)], + cl_inflation_rad=inflation_rad) + + assert cost > 10.0 diff --git a/modules/vertexnav/tests/test_noisy_navigation.py b/modules/vertexnav/tests/test_noisy_navigation.py new file mode 100644 index 0000000..8344b66 --- /dev/null +++ b/modules/vertexnav/tests/test_noisy_navigation.py @@ -0,0 +1,124 @@ +import vertexnav +import math +import numpy as np +import pytest +from shapely import geometry + + +def test_proposed_world_dist(): + world = vertexnav.world.ProposedWorld(vertices=[(0, 0), (1, 0.4), + (-1, 0.4), (0, 1)], + walls=[[(0, 0), (1, 0.4)], + [(0, 0), (-1, 0.4)], + [(0, 0), (0, 1)]]) + + Pose = vertexnav.Pose + assert world.get_dist(Pose(0, 0)) == pytest.approx(0) + assert world.get_dist(Pose(0, -1)) == pytest.approx(1) + + +def test_vis_graph_path_gen(): + world = vertexnav.world.ProposedWorld(vertices=[(0, -1), (0, 1)], + walls=[[(0, -1), (0, 1)]]) + vgraph = vertexnav.planning.VisibilityGraph(world) + + path = vgraph.get_shortest_path(start_point=(-1, 0), end_point=(1, 0)) + + def path_length(path): + return sum([ + math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + for p1, p2 in zip(path[:-1], path[1:]) + ]) + + assert path[0] == (-1, 0) + assert path[-1] == (1, 0) + assert path_length(path) >= 2 * math.sqrt(2) + assert path_length(path) < 2 * math.sqrt(2) + 0.1 + + +def test_vis_graph_path_gen_blocked(): + world = vertexnav.world.ProposedWorld(vertices=[(0, -2), (0, 1)], + walls=[[(0, -2), (0, 1)]]) + vgraph = vertexnav.planning.VisibilityGraph(world) + bf = vertexnav.planning.Frontier(geometry.LineString([(0, 1), (0, 5)])) + + path = vgraph.get_shortest_path(start_point=(-1, 0), + end_point=(1, 0), + blocked_frontiers=[bf]) + + def path_length(path): + return sum([ + math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + for p1, p2 in zip(path[:-1], path[1:]) + ]) + + assert path[0] == (-1, 0) + assert path[-1] == (1, 0) + assert path_length(path) >= 2 * math.sqrt(1.0**2 + 2.0**2) + assert path_length(path) < 2 * math.sqrt(1.0**2 + 2.0**2) + 0.1 + + +def test_vis_graph_robot_motion(): + # Generate a simple world + obstacles, boundary = vertexnav.environments.simulated.build_hallway_from_path( + path=([0, 0], [100, 0], [100, 100]), width=20) + world = vertexnav.world.World(obstacles=obstacles, boundary=boundary) + + inflation_rad = 4.0 + + Pose = vertexnav.Pose + + robot = vertexnav.robot.Turtlebot_Robot(Pose(0, 0, 0)) + goal = Pose(100, 100) + + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + prev_pose = None + for _ in range(200): + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(robot.pose), + robot.pose, + do_add_noise=True, + cov_rt=[[1, 0], [0, 0.5]]) + if prev_pose is None: + nvg.add_observation(obs, robot.pose) + else: + odom = vertexnav.Pose.get_odom(p_new=robot.pose, p_old=prev_pose) + nvg.add_observation(obs, odom=odom) + + prev_pose = robot.pose + proposed_world = nvg.get_proposed_world() + + visibility_graph = vertexnav.planning.VisibilityGraph( + proposed_world, inflation_rad=0.8 * inflation_rad) + shortest_path = visibility_graph.get_shortest_path( + start_point=(robot.pose.x, robot.pose.y), + end_point=(goal.x, goal.y)) + robot.move(goal, shortest_path, inflation_rad=inflation_rad) + + assert abs(robot.pose.x - 100) < 2 + assert abs(robot.pose.y - 100) < 2 + + +def test_h_value_computation(): + world = vertexnav.world.ProposedWorld(vertices=[(0, -2), (0, 1)], + walls=[[(0, -2), (0, 1)]]) + + segment1 = ((-1, 0), (2, 0)) + segment2 = ((2, 0), (-1, 0)) + segment3 = ((-1, 0), (0, 2)) + segment4 = ((0, 2), (2, 0)) + + h1 = vertexnav.planning.compute_h_value_for_segment( + segment1, world.vertices) + h2 = vertexnav.planning.compute_h_value_for_segment( + segment2, world.vertices) + h3 = vertexnav.planning.compute_h_value_for_segment( + segment3, world.vertices) + h4 = vertexnav.planning.compute_h_value_for_segment( + segment4, world.vertices) + print(h1) + print((h1 + h2)) + print((h3 + h4)) + print((h3 + h4 + h2)) + assert np.all(h1 + h2 == complex(0, 0)) + assert np.any(h3 + h4 + h2 != complex(0, 0)) diff --git a/modules/vertexnav/tests/test_noisy_vertex_nav.py b/modules/vertexnav/tests/test_noisy_vertex_nav.py new file mode 100644 index 0000000..b26e066 --- /dev/null +++ b/modules/vertexnav/tests/test_noisy_vertex_nav.py @@ -0,0 +1,240 @@ +import vertexnav +from vertexnav.world import World +import numpy as np +import pytest +import random + +from shapely import geometry + + +def get_world_square(is_inside=False): + # A square + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + if is_inside: + return World(obstacles=[], boundary=square_poly) + else: + return World(obstacles=[square_poly]) + + +def get_world_two_squares_vert(): + # A square + square_poly_1 = geometry.Polygon([(-1, 1), (-1, 2), (1, 2), (1, 1)]) + square_poly_2 = geometry.Polygon([(-1, -2), (-1, -1), (1, -1), (1, -2)]) + + return World(obstacles=[square_poly_1, square_poly_2]) + + +def get_world_two_squares_horz(): + # A square + square_poly_1 = geometry.Polygon([(-1, -1), (-1, 1), (-2, 1), (-2, -1)]) + square_poly_2 = geometry.Polygon([(1, -1), (1, 1), (2, 1), (2, -1)]) + + return World(obstacles=[square_poly_1, square_poly_2]) + + +def test_prob_of_wall(): + """Tests that the most likely map corresponds to the one with the walls in the correct places""" + pytest.xfail("Test not yet written.") + + world_sq = get_world_square() + world_vert = get_world_two_squares_vert() + world_horz = get_world_two_squares_horz() + worlds = [] + worlds.append(world_sq) + worlds.append(world_vert) + worlds.append(world_horz) + + +def test_square_map_building_no_noise(): + """Tests that we can build a simple square map by fusing multiple measurements + (without any false positive or negative detections).""" + world = get_world_square() + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + + counter = 0 + for ii in range(100): + robot_pose = vertexnav.Pose(x=0.001, y=0.001, yaw=0.0) + counter += 1 + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(robot_pose), + robot_pose, + do_add_noise=False, + cov_rt=[[0.5, 0], [0, 0.5]]) + if ii == 0: + nvg.add_observation(obs, robot_pose) + else: + nvg.add_observation(obs, odom=vertexnav.Pose(0, 0, 0)) + assert (len(obs) == 4) + + assert (len(nvg.vertices) == 4) + + # Confirm that the number of "active" walls is also 4 + wall_count = len([ + None for k, wall in nvg.walls.items() + if wall.is_active and not k[0] == k[1] + ]) + + assert (wall_count == 4) + + nvg.sample_vertices(num_samples=20, p_window=1000, inflation_rad=0.1) + proposed_world = nvg.get_proposed_world_fast(nvg.topology) + assert (len(nvg.vertices) == 4) + assert (len(proposed_world.vertices) == 4) + assert (nvg.compute_world_log_prob( + proposed_world, list(zip(nvg.r_poses, nvg.observations))) < 0) + + +def test_square_map_building_position_noise(): + """Tests that we can build a simple square map by fusing multiple measurements + (without any false positive or negative detections).""" + world = get_world_square(is_inside=True) + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + + for ii in range(10): + robot_pose = vertexnav.Pose(x=0.0, y=0.0, yaw=0.0) + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(robot_pose), + robot_pose, + do_add_noise=True, + cov_rt=[[0.5, 0], [0, 0.5]]) + if ii == 0: + nvg.add_observation(obs, robot_pose) + else: + nvg.add_observation(obs, odom=vertexnav.Pose(0, 0, 0)) + + assert (len(nvg.vertices) == 4) + + # Confirm that the number of "active" walls is also 4 + wall_count = len([ + None for k, wall in nvg.walls.items() + if wall.is_active and not k[0] == k[1] + ]) + + assert (wall_count == 4) + + +@pytest.mark.parametrize("fp_range", [(2.0), (0.5)]) +def test_square_map_building_sampling_false_positive(fp_range): + """Show that, even with a couple false-positive detections, + we can get the map that best corresponds to the real map.""" + + # Initializations + world = get_world_square(is_inside=True) + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + + # Construct the noisy graph with a handful of measurements + prev_pose = None + counter = 0 + for _ in range(25): + robot_pose = vertexnav.Pose(x=0.0, y=0.0, yaw=0.0) + counter += 1 + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(robot_pose), + robot_pose, + do_add_noise=True, + cov_rt=[[1, 0], [0, 0.5]]) + if prev_pose is not None: + odom = vertexnav.Pose.get_odom( + p_new=vertexnav.Pose(robot_pose.x, robot_pose.y, + robot_pose.yaw), + p_old=vertexnav.Pose(prev_pose.x, prev_pose.y, prev_pose.yaw)) + nvg.add_observation(obs, odom=odom) + else: + nvg.add_observation(obs, robot_pose) + prev_pose = robot_pose + + # Now add some systematically 'bad' measurements + for _ in range(5): + robot_pose = vertexnav.Pose(x=0.0, y=0.0, yaw=0.0) + counter += 1 + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(robot_pose), + robot_pose, + do_add_noise=True, + cov_rt=[[1, 0], [0, 0.5]]) + obs.append( + vertexnav.noisy.NoisyVertexDetection( + angle_rad=0.0, + range=fp_range, + detection_type=vertexnav.noisy.NoisyDetectionType( + [0.25, 0.25, 0.25, 0.25]), + cov_rt=np.array([[1, 0], [0, 0.5]]))) + obs = sorted(obs, key=lambda pvd: pvd.angle_rad) + odom = vertexnav.Pose.get_odom( + p_new=vertexnav.Pose(robot_pose.x, robot_pose.y, robot_pose.yaw), + p_old=vertexnav.Pose(prev_pose.x, prev_pose.y, prev_pose.yaw)) + nvg.add_observation(obs, odom=odom) + prev_pose = robot_pose + + # Now get the 'most likely' proposed world + random.seed(1234) + np.random.seed(1234) + old_proposed_world = nvg.get_proposed_world_fast(topology=nvg.topology) + old_prob = nvg.compute_world_log_prob( + old_proposed_world, list(zip(nvg.r_poses, nvg.observations))) + nvg.sample_vertices(num_samples=20, p_window=1000, inflation_rad=0.1) + proposed_world = nvg.get_proposed_world() + assert (len(nvg.vertices) == 5) + assert (len(proposed_world.vertices) == 4) + assert (len(proposed_world.walls) == 4) + proposed_world = nvg.get_proposed_world_fast(topology=nvg.topology) + new_prob = nvg.compute_world_log_prob( + proposed_world, list(zip(nvg.r_poses, nvg.observations))) + + assert new_prob < 0 + assert new_prob >= old_prob + + +def test_get_m_distance(): + pos_a = [0, 0] + pos_b = [2, 0] + pos_c = [4, 0] + pos_d = [0, 3] + + cov_1 = np.array([[4, 0], [0, 9]]) + inv_cov_1 = np.linalg.inv(cov_1) + + assert vertexnav.utils.calc.m_distance(pos_a, pos_b, + inv_noise=inv_cov_1) == 1.0 + assert vertexnav.utils.calc.m_distance(pos_a, pos_c, + inv_noise=inv_cov_1) == 2.0 + assert vertexnav.utils.calc.m_distance(pos_a, pos_d, + inv_noise=inv_cov_1) == 1.0 + + +@pytest.mark.parametrize("r_cov, theta, dist, r_theta", + [(4.0, 0.0, 1.0, 0.01), (4.0, 0.0, 2.0, 0.01), + (4.0, 1.0, 1.0, 0.01), (4.0, 1.0, 2.0, 0.01), + (2.0, 2.0, 2.0, 0.01)]) +def test_transform_local_to_world(r_cov, theta, dist, r_theta): + _, cov = vertexnav.utils.calc.transform_local_to_world( + det_theta=theta, + det_r=dist, + cov_rt=np.array([[r_cov, 0], [0, r_theta]]), + r_pose=vertexnav.Pose(0, 0)) + + # Confirm that the max eigenvalue of the transformed covariance matrix + # matches that of the original matrix. + vals, vecs = np.linalg.eigh(cov) + assert max(vals) == pytest.approx(r_cov) + assert min(vals) == pytest.approx(r_theta * dist * dist) + + +def test_detect_peaks(): + """Confirm the peaks are where we expect.""" + grid = np.zeros([100, 100]) * 1.0 + known_coords = np.array([ + [9, 14], + [9, 48], + [25, 14], + [99, 20], + ]) + + for c in known_coords: + grid[c[0], c[1]] = 1.0 + + peaks = vertexnav.utils.calc.detect_peaks(grid, peak_thresh=0.5) + + assert len(peaks) == len(known_coords) + for p in peaks: + assert p in known_coords diff --git a/modules/vertexnav/tests/test_vertexnav.py b/modules/vertexnav/tests/test_vertexnav.py new file mode 100644 index 0000000..177892e --- /dev/null +++ b/modules/vertexnav/tests/test_vertexnav.py @@ -0,0 +1,270 @@ +import math +import matplotlib.pyplot as plt +import pytest + +import vertexnav +from vertexnav.world import World +from vertexnav_accel import Pose + +import shapely +from shapely import geometry + + +def get_world_square(): + # A square + square_poly = geometry.Polygon([(1, 1), (1, 2), (2, 2), (2, 1)]) + return World(obstacles=[square_poly]) + + +def get_world_two_squares(): + # A square + square_poly_1 = geometry.Polygon([(1, 1), (1, 2), (2, 2), (2, 1)]) + square_poly_2 = geometry.Polygon([(3, 1.6), (3, 2.5), (4, 2.5), (4, 1.6)]) + + return World(obstacles=[square_poly_1, square_poly_2]) + + +def get_world_overlapping_shapes(): + # A square + square_poly_1 = geometry.Polygon([(1, 1), (1, 2), (2, 2), (2, 1)]) + square_poly_2 = geometry.Polygon([(1.25, 1.5), (3, 2.5), (4, 2.5), + (4, 1.5)]) + + return World(obstacles=[square_poly_1.union(square_poly_2)]) + + +def test_world_square_corner_detection(): + """Simple world with only a single square in it.""" + square_world = get_world_square() + + assert (len(square_world.get_all_vertices()) == 4) + + assert (len( + square_world.get_visible_vertices_for_pose( + robot_pose=Pose(x=0.0, y=0.0))) == 3) + + assert (len( + square_world.get_visible_vertices_for_pose( + robot_pose=Pose(x=1.5, y=0.0))) == 2) + + # If inside square, no vertices are expected to be visible (obstacle) + assert (len( + square_world.get_visible_vertices_for_pose( + robot_pose=Pose(x=1.5, y=1.5))) == 4) + + +def test_world_square_gap_detection(): + """Simple world with only a single square in it.""" + square_world = get_world_square() + + def count_gaps(vertices): + return sum([v[1] == 'l' or v[1] == 'r' for v in vertices]) + + side_vertices = square_world.get_vertices_for_pose( + robot_pose=Pose(x=0.0, y=0.0)) + assert (count_gaps(side_vertices) == 2) + assert (sum([v[1] == 'c' for v in side_vertices]) == 1) + assert (sum([v[1] == 'l' for v in side_vertices]) == 1) + assert (sum([v[1] == 'r' for v in side_vertices]) == 1) + + side_vertices = square_world.get_vertices_for_pose( + robot_pose=Pose(x=1.5, y=0.0)) + assert (count_gaps(side_vertices) == 2) + assert (sum([v[1] == 'l' for v in side_vertices]) == 1) + assert (sum([v[1] == 'r' for v in side_vertices]) == 1) + + inside_vertices = square_world.get_vertices_for_pose( + robot_pose=Pose(x=1.5, y=1.5)) + assert len(inside_vertices) == 4 + assert (sum([v[1] == 'c' for v in inside_vertices]) == 4) + + +def test_world_two_squares_corner_detection(): + """Simple world with only a single square in it.""" + square_world = get_world_two_squares() + + assert (len(square_world.get_all_vertices()) == 8) + + assert (len( + square_world.get_visible_vertices_for_pose( + robot_pose=Pose(x=0.0, y=0.0))) == 4) + + assert (len( + square_world.get_visible_vertices_for_pose( + robot_pose=Pose(x=1.5, y=0.0))) == 5) + + assert (len( + square_world.get_visible_vertices_for_pose( + robot_pose=Pose(x=1.5, y=1.5))) == 4) + + +def test_world_signed_distance(): + """Confirms that the signed distance function works as expected + for a simple square world.""" + + world = get_world_square() + + assert world.get_signed_dist(Pose(x=0, y=0)) == pytest.approx(math.sqrt(2)) + assert world.get_signed_dist(Pose(x=1, y=1)) == pytest.approx(0.0) + assert world.get_signed_dist(Pose(x=-10, y=1)) == pytest.approx(11.0) + assert world.get_signed_dist(Pose(x=1.5, y=1.5)) == pytest.approx(-0.5) + + +def test_proposed_world_get_visible(): + """Show that I can initialize a "ProposedWorld" with a set of walls.""" + + vertices = [(0, 0), (1, 0), (1, 1), (0, 1)] + walls = [((0, 0), (1, 0)), ((1, 0), (1, 1)), ((1, 1), (0, 1)), + ((0, 1), (0, 0))] + + proposed_world = vertexnav.world.ProposedWorld(vertices=vertices, + walls=walls) + + verts = proposed_world.get_vertices_for_pose(Pose(x=0.5, y=0.5)) + assert len(verts) == 4 + assert len([v for v in verts if v[1] == 'c']) == 4 + + verts = proposed_world.get_vertices_for_pose(Pose(x=-1.0, y=-1.0)) + num_c = len([v for v in verts if v[1] == 'c']) + num_l = len([v for v in verts if v[1] == 'l']) + num_r = len([v for v in verts if v[1] == 'r']) + assert len(verts) == 3 + assert num_l == 1 + assert num_r == 1 + assert num_c == 1 + + verts = proposed_world.get_vertices_for_pose(Pose(x=-0.5, y=0.5)) + num_l = len([v for v in verts if v[1] == 'l']) + num_r = len([v for v in verts if v[1] == 'r']) + assert len(verts) == 2 + assert num_l == 1 + assert num_r == 1 + + +def test_proposed_world_get_visible_max_range(): + """Show that I can initialize a "ProposedWorld" with a set of walls.""" + + vertices = [(0, 0), (1, 0), (1, 1), (0, 1)] + walls = [((0, 0), (1, 0)), ((1, 0), (1, 1)), ((1, 1), (0, 1)), + ((0, 1), (0, 0))] + + proposed_world = vertexnav.world.ProposedWorld(vertices=vertices, + walls=walls) + + verts = proposed_world.get_vertices_for_pose(Pose(x=0.5, y=0.5), + max_range=0.1) + assert len(verts) == 0 + + verts = proposed_world.get_vertices_for_pose(Pose(x=0.5, y=0.5), + max_range=1.0) + assert len(verts) == 4 + + # When the max range is limited, the vertex class should also change + verts = proposed_world.get_vertices_for_pose(Pose(x=-1.0, y=-1.0), + max_range=math.sqrt(2.5)) + assert len(verts) == 1 + assert len([v for v in verts if v[1] == 'p']) == 1 + + verts = proposed_world.get_vertices_for_pose(Pose(x=-1.0, y=-1.0), + max_range=math.sqrt(8)) + assert len(verts) == 3 + assert len([v for v in verts if v[1] == 'p']) == 0 + + +def test_hallway_world_clutter(): + """Confirm that clutter generation respects signed distance.""" + num_elements = 100 + min_signed_dist = -0.5 + max_signed_dist = 1.0 + world = vertexnav.environments.simulated.HallwayWorld( + num_clutter_elements=num_elements, + max_clutter_signed_distance=max_signed_dist, + min_clutter_signed_distance=min_signed_dist) + + assert len(world.clutter_element_poses) == num_elements + + for pose in world.clutter_element_poses: + signed_dist = world.get_signed_dist(pose) + assert signed_dist >= min_signed_dist + assert signed_dist <= max_signed_dist + + +def test_get_visibility_polygon_world(): + pytest.xfail("Plotting for debugging purposes") + + vertices = [(0, 0), (1, 0), (1, 1), (0, 1)] + walls = [((0, 0), (1, 0)), ((1, 0), (1, 1)), ((1, 1), (0, 1)), + ((0, 1), (0, 0))] + + vertices = [(0, 0), (3, 0), (3, 3), (0, 5), (2.5, 6), (1, 2), (2, 4), + (1, 4)] + + walls = [((0, 0), (3, 0)), ((3, 0), (3, 3)), ((0, 0), (0, 5)), + ((0, 5), (2.5, 6)), ((1, 2), (2, 4)), ((1, 2), (1, 4)), + ((1, 4), (2, 4))] + + proposed_world = vertexnav.world.ProposedWorld(vertices=vertices, + walls=walls) + + # from matplotlib.patches import Polygon + # from matplotlib.collections import PatchCollection + # import shapely + + # patches = [] + # colors = [] + + # pose = Pose(0.48, 1) + # color = [1, 0, 0] + # poly_points = vertexnav.noisy.get_visibility_polygon( + # pose, proposed_world, radius=10, do_cut_with_world=True) + # poly_a = shapely.geometry.Polygon(poly_points) + # plt.plot(pose.x, pose.y, 'o', color=color) + # vertexnav.plotting.plot_polygon(plt.gca(), poly_a, + # color=color, alpha=0.1) + # poly_points = vertexnav.noisy.get_visibility_polygon( + # pose, proposed_world, radius=-1, do_cut_with_world=True) + # poly_a = shapely.geometry.Polygon(poly_points) + # plt.plot(pose.x, pose.y, 'o', color=color) + # vertexnav.plotting.plot_polygon(plt.gca(), poly_a, + # color=color, alpha=0.1) + + # pose = Pose(1.2, 4.5) + # color = [0, 0, 1] + # poly_points = vertexnav.noisy.get_visibility_polygon( + # pose, proposed_world, radius=10, do_cut_with_world=True) + # poly_b = shapely.geometry.Polygon(poly_points) + # plt.plot(pose.x, pose.y, 'o', color=color) + # vertexnav.plotting.plot_polygon(plt.gca(), poly_b, + # color=color, alpha=0.1) + # poly_points = vertexnav.noisy.get_visibility_polygon( + # pose, proposed_world, radius=-1, do_cut_with_world=True) + # poly_b = shapely.geometry.Polygon(poly_points) + # plt.plot(pose.x, pose.y, 'o', color=color) + # vertexnav.plotting.plot_polygon(plt.gca(), poly_b, + # color=color, alpha=0.1) + + pose = Pose(5.45, 1.3) + color = [0, 1, 0] + poly_points = vertexnav.noisy.get_visibility_polygon(pose, + proposed_world, + radius=10, + is_conservative=True) + poly_b = shapely.geometry.Polygon(poly_points) + plt.plot(pose.x, pose.y, 'o', color=color) + vertexnav.plotting.plot_polygon(plt.gca(), poly_b, color=color, alpha=0.1) + poly_points = vertexnav.noisy.get_visibility_polygon(pose, + proposed_world, + radius=10, + is_conservative=False) + poly_b = shapely.geometry.Polygon(poly_points) + plt.plot(pose.x, pose.y, 'o', color=color) + vertexnav.plotting.plot_polygon(plt.gca(), poly_b, color=color, alpha=0.1) + + # poly = shapely.ops.cascaded_union([poly_a, poly_b]) + # vertexnav.plotting.plot_polygon(plt.gca(), poly, + # color=[0.0, 0.0, 0.0], alpha=0.2) + vertexnav.plotting.plot_proposed_world(plt.gca(), proposed_world) + + plt.show() + + assert False diff --git a/modules/vertexnav/tests/test_vertexnav_data.py b/modules/vertexnav/tests/test_vertexnav_data.py new file mode 100644 index 0000000..e3070d9 --- /dev/null +++ b/modules/vertexnav/tests/test_vertexnav_data.py @@ -0,0 +1,55 @@ +import environments +import vertexnav +import matplotlib.pyplot as plt +import numpy as np +import random +from shapely import geometry + + +def get_world_square(): + # A square + square_poly = geometry.Polygon([(1, 1), (1, 2), (2, 2), (2, 1)]) + return vertexnav.world.World(obstacles=[square_poly]) + + +def test_vertexnav_data_formatted_correctly(do_debug_plot, unity_path): + world = get_world_square() + world.breadcrumb_element_poses = [] + world.breadcrumb_type = None + world_building_unity_bridge = \ + environments.simulated.WorldBuildingUnityBridge + with world_building_unity_bridge(unity_path) as unity_bridge: + unity_bridge.make_world(world) + + for counter in range(10): + datum = vertexnav.learning.get_vertex_datum_for_pose( + vertexnav.Pose(0, 0, 2 * np.pi * random.random()), + world, + unity_bridge, + max_range=10, + num_range=32, + num_bearing=128, + min_range=0.2) + + print(counter) + + if do_debug_plot: + plt.subplot(311) + plt.imshow(datum['image']) + plt.subplot(312) + plt.imshow(datum['depth']) + plt.subplot(313) + plt.imshow(datum['is_vertex']) + plt.show() + + assert datum['image'].max() <= 1.0 + assert datum['image'].min() >= 0.0 + + # Pick a few rotations and confirm that the minimum depth corresponds to + # a vertex location. + min_depth_loc = np.argmin(datum['depth'][64, :]) + depth_cols = datum['depth'].shape[1] + corner_vertex_loc = np.argmax(np.max(datum['is_corner'], axis=0)) + vertex_cols = datum['is_corner'].shape[1] + diff = min_depth_loc / depth_cols - corner_vertex_loc / vertex_cols + assert abs(diff) < 0.05 or abs(abs(diff) - 1) < 0.05 diff --git a/modules/vertexnav/tests/test_vertexnav_environments.py b/modules/vertexnav/tests/test_vertexnav_environments.py new file mode 100644 index 0000000..f34e395 --- /dev/null +++ b/modules/vertexnav/tests/test_vertexnav_environments.py @@ -0,0 +1,39 @@ +import vertexnav +import matplotlib.pyplot as plt +import pytest + + +def test_vertexnav_can_generate_dungeon(do_debug_plot): + world = vertexnav.environments.dungeon.DungeonWorld(random_seed=13) + + if do_debug_plot: + vertexnav.plotting.plot_world(plt.gca(), world) + plt.show() + + +def test_vertexnav_dungeon_seed_control(do_debug_plot): + """Confirm that setting the seed controls the generation.""" + seed_a, seed_b, seed_c = 13, 10, 13 + world_a = vertexnav.environments.dungeon.DungeonWorld(random_seed=seed_a) + world_b = vertexnav.environments.dungeon.DungeonWorld(random_seed=seed_b) + world_c = vertexnav.environments.dungeon.DungeonWorld(random_seed=seed_c) + ksp_a = world_a.known_space_poly + ksp_b = world_b.known_space_poly + ksp_c = world_c.known_space_poly + + if do_debug_plot: + plt.subplot(131) + vertexnav.plotting.plot_world(plt.gca(), world_a) + plt.title(f"Seed: {seed_a}") + plt.subplot(132) + vertexnav.plotting.plot_world(plt.gca(), world_b) + plt.title(f"Seed: {seed_b}") + plt.subplot(133) + vertexnav.plotting.plot_world(plt.gca(), world_c) + plt.title(f"Seed: {seed_c}") + plt.show() + + assert not seed_a == seed_b + assert ksp_a.intersection(ksp_b).area / ksp_a.area < 1.0 + assert seed_a == seed_c + assert ksp_a.intersection(ksp_c).area / ksp_a.area == pytest.approx(1.0) diff --git a/modules/vertexnav/tests/test_vertexnav_slam.py b/modules/vertexnav/tests/test_vertexnav_slam.py new file mode 100644 index 0000000..8b55029 --- /dev/null +++ b/modules/vertexnav/tests/test_vertexnav_slam.py @@ -0,0 +1,1084 @@ +import numpy as np +import environments +import vertexnav +import math +import pytest +import os.path +import random +from shapely import geometry +import time + +# Obvously, replace this with your own Unity project. +UNITY_EXE = '/Users/gjstein/rrg_data/unity/unity_tcp_test.app/Contents/MacOS/unity_tcp_test' + + +def get_map_and_path_hall_snake(): + maze_poly = geometry.Polygon([(10, -10), (10, 20), (50, 20), (50, 50), + (70, 50), (70, 00), (130, 00), (130, 20), + (90, 20), (90, 70), (30, 70), (30, 40), + (-10, 40), (-10, -10)]) + path = [(40, 30), (40, 60), (80, 60), (80, 10), (120, 10)] + return vertexnav.world.World(obstacles=[maze_poly]), path + + +def follow_path_data_iterator(unity_bridge, world, path, steps=50, pause=None): + """Loop through data along a path.""" + stime = time.time() + unity_bridge.make_world(world) + print(f"Time to Make World: {time.time() - stime}") + pose_generator = (vertexnav.Pose( + ii * 1.0 * seg[1][0] / steps + (1 - ii * 1.0 / steps) * seg[0][0], + ii * 1.0 * seg[1][1] / steps + (1 - ii * 1.0 / steps) * seg[0][1]) + for seg in zip(path[:-1], path[1:]) # noqa: E126 + for ii in range(steps)) + + for pose in pose_generator: + # Get the images + if pause is not None: + unity_bridge.move_object_to_pose("robot", pose, pause) + pano_image = unity_bridge.get_image("robot/pano_camera", pause) + pano_depth_image = unity_bridge.get_image( + "robot/pano_depth_camera", pause) + else: + pano_image = unity_bridge.get_image("robot/pano_camera") + pano_depth_image = unity_bridge.get_image( + "robot/pano_depth_camera") + unity_bridge.move_object_to_pose("robot", pose) + + pano_image = pano_image[64:-64] * 1.0 / 255 + ranges = vertexnav.utils.convert.ranges_from_depth_image( + pano_depth_image) + + yield pose, pano_image, ranges + + +def _add_new_observation(pvg, + world, + pose, + odom, + err=None, + association_window=-1): + pose = vertexnav.Pose(pose.x, pose.y, pose.yaw, pose.robot_id) + obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(pose), + pose, + do_add_noise=False, + cov_rt=[[0.1**2, 0], [0, 0.1**2]]) + assert len(obs) < 4 + + if odom is None: + pvg.add_observation(obs, + r_pose=pose, + association_window=association_window) + else: + odom = vertexnav.Pose(odom.x, odom.y, odom.yaw, odom.robot_id) + if err is not None: + odom.x += err[0] + odom.y += err[1] + odom.yaw += err[2] + # We need to update the position of the detections to make this a + # fair test. + nposes = len(pvg.r_poses) + num_robot_ids = len(set(p.robot_id for p in pvg.r_poses)) + updated_pose = odom * pvg.r_poses[nposes - num_robot_ids] + for det in obs: + det.update_props(updated_pose) + + pvg.add_observation(obs, + odom=odom, + association_window=association_window) + + +def _add_new_observation_learned(pvg, + image, + eval_net, + args, + pose, + odom, + err=None): + pose = vertexnav.Pose(pose.x, pose.y, pose.yaw, pose.robot_id) + # Get the observation + obs = vertexnav.noisy.convert_net_grid_data_to_noisy_detection( + eval_net(image), + pose, + max_range=args.max_range, + num_range=args.num_range, + num_bearing=args.num_bearing, + sig_r=args.sig_r, + sig_th=args.sig_th, + nn_peak_thresh=args.nn_peak_thresh) + + assert len(obs) > 0 + + if odom is None: + pvg.add_observation(obs, r_pose=pose) + else: + odom = vertexnav.Pose(odom.x, odom.y, odom.yaw, odom.robot_id) + if err is not None: + odom.x += err[0] + odom.y += err[1] + odom.yaw += err[2] + # We need to update the position of the detections to make this a + # fair test. + nposes = len(pvg.r_poses) + updated_pose = odom * pvg.r_poses[nposes - 1] + for det in obs: + det.update_props(updated_pose) + + pvg.add_observation(obs, odom=odom) + + +def _plot_pvg_data(ax, pvg, world, title): + ax.clear() + ax.set_title(title) + ax.set_aspect('equal') + ax.get_xaxis().set_ticks([]) + ax.get_yaxis().set_ticks([]) + + pose = pvg.r_poses[len(pvg.r_poses) - 1] + proposed_world = pvg.get_proposed_world() + + # Plot the clusters + vertex_remapping = vertexnav.prob_vertex_graph._get_vertex_remapping( + vertices=pvg.vertices, topology=pvg.topology) + vertex_id_dict = {v.id: v for v in pvg.vertices} + clusters = [ + vertexnav.prob_vertex_graph.Cluster(c, vertex_id_dict) + for c in pvg.topology + ] + for cluster in clusters: + if not cluster.is_active and cluster.num_dets > 2: + vert = vertex_remapping[cluster.vids[0]] + ax.plot(vert.position[0], + vert.position[1], + 'r.', + alpha=0.4, + markersize=vertexnav.plotting.SCATTERSIZE * 2) + + vertexnav.plotting.plot_world(ax, world, alpha=0.2) + + robot_ids = set(p.robot_id for p in pvg.r_poses) + for rid in robot_ids: + r_points = np.array([(p.x, p.y) for p in pvg.r_poses + if p.robot_id == rid]) + line, = ax.plot(r_points[:, 0], r_points[:, 1], alpha=0.75) + ax.plot(r_points[-1, 0], r_points[-1, 1], '.', color=line.get_color()) + ax.plot(r_points[-1, 0], r_points[-1, 1], 'x', color=line.get_color()) + + vertexnav.plotting.plot_proposed_world(ax, + proposed_world, + do_show_points=True, + do_plot_visibility=False, + robot_pose=pose) + + +def test_slam_orbiting_square(do_debug_plot): + random.seed(304) + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_perfect.DO_SLAM = False + pvg_error = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_error.DO_SLAM = False + pvg_slam = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_slam.DO_SLAM = True + + # Set the noise models + pvg_slam.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_slam.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_slam.CLUSTERING_NOISE = np.array([0.005, 0.005]) + + # Add a number of observations + n_poses_per_loop = 80 + n_loops = 4 + for ii in range(n_loops * n_poses_per_loop + 1): + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th) + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose, + p_old=pvg_perfect.r_poses[nposes - + 1]) + + # A very simple error model + err = [ + 0.01 * (random.random() - 0.5), 0.01 * (random.random() - 0.5), + 0.005 * random.random() + ] + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_error, + world=world, + pose=pose, + odom=odom, + err=err) + + print("PVG_SLAM") + _add_new_observation(pvg=pvg_slam, + world=world, + pose=pose, + odom=odom, + err=err) + + p = pvg_error.r_poses[len(pvg_error.r_poses) - 1] + print((p.x, p.y, p.yaw, p.index)) + p = pvg_slam.r_poses[len(pvg_slam.r_poses) - 1] + print((p.x, p.y, p.yaw, p.index)) + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 3, 1) + ax2 = plt.subplot(1, 3, 2) + ax3 = plt.subplot(1, 3, 3) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_error, world, "Noisy Odom") + _plot_pvg_data(ax3, pvg_slam, world, "Noisy Odom + SLAM") + + plt.show() + + assert not (pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 1] + == pvg_error.r_poses[len(pvg_error.r_poses) - 1]) + + assert len(pvg_perfect.vertices) == 4 + assert len(pvg_error.vertices) > 4 + assert len(pvg_slam.vertices) == 4 + + _, state_perfect = pvg_perfect.sample_vertices(do_update_state=False) + _, state_error = pvg_error.sample_vertices(do_update_state=False) + _, state_slam = pvg_slam.sample_vertices(do_update_state=False) + + assert state_perfect.log_prob > state_error.log_prob + assert state_slam.log_prob > state_error.log_prob + + # Confirm that the 'perfect' world is as expected + proposed_world = pvg_perfect.get_proposed_world() + assert len(proposed_world.vertices) == 4 + for v in proposed_world.vertices: + assert abs(v[0]) == pytest.approx(1.0, abs=1e-2) + assert abs(v[1]) == pytest.approx(1.0, abs=1e-2) + assert len(proposed_world.walls) == 4 + + # Confirm the 'SLAM' world should look quite similar. + proposed_world = pvg_slam.get_proposed_world() + assert len(proposed_world.vertices) == 4 + for v in proposed_world.vertices: + assert abs(v[0]) == pytest.approx(1.0, abs=5e-2) + assert abs(v[1]) == pytest.approx(1.0, abs=5e-2) + assert len(proposed_world.walls) == 4 + + +def test_slam_pose_robot_id(): + pose = vertexnav.Pose(0, 0, 0, 1) + assert (pose.robot_id == 1) + + pose = vertexnav.Pose(0, 0, 0, 2) + assert (pose.robot_id == 2) + + +def test_slam_orbiting_square_multi_agent(do_debug_plot): + random.seed(304) + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_perfect.DO_SLAM = False + pvg_error = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_error.DO_SLAM = False + pvg_slam = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_slam.DO_SLAM = True + + # Set the noise models + pvg_slam.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_slam.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_slam.CLUSTERING_NOISE = np.array([0.005, 0.005]) + + # Add a number of observations + n_poses_per_loop = 80 + n_loops = 4 + for ii in range(n_loops * n_poses_per_loop + 1): + + # Robot 1 + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th, + robot_id=1) + pose1 = pose + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose1, + p_old=pvg_perfect.r_poses[nposes - + 2]) + + # A very simple error model + if ii == 0: + err = [0, 0, 0] + else: + err = [ + 0.01 * (random.random() - 0.5), 0.01 * (random.random() - 0.5), + 0.005 * random.random() + ] + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_error, + world=world, + pose=pose, + odom=odom, + err=err) + + _add_new_observation(pvg=pvg_slam, + world=world, + pose=pose, + odom=odom, + err=err) + + # Robot 2 + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + 2 * np.pi / 3 + pose = vertexnav.Pose(x=3.5 * math.cos(th), + y=3.5 * math.sin(th), + yaw=th, + robot_id=2) + pose2 = pose + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose2, + p_old=pvg_perfect.r_poses[nposes - + 2]) + + # A very simple error model + if ii == 0: + err = [0, 0, 0] + else: + err = [ + 0.01 * (random.random() - 0.5), 0.01 * (random.random() - 0.5), + 0.005 * random.random() + ] + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_error, + world=world, + pose=pose, + odom=odom, + err=err) + + _add_new_observation(pvg=pvg_slam, + world=world, + pose=pose, + odom=odom, + err=err) + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 3, 1) + ax2 = plt.subplot(1, 3, 2) + ax3 = plt.subplot(1, 3, 3) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_error, world, "Noisy Odom") + _plot_pvg_data(ax3, pvg_slam, world, "Noisy Odom + SLAM") + + plt.show() + + assert abs(pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 1].x - + pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 2].x) > 2.0 + assert abs(pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 1].y - + pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 2].y) > 2.0 + + assert not (pvg_perfect.r_poses[len(pvg_perfect.r_poses) - 1] + == pvg_error.r_poses[len(pvg_error.r_poses) - 1]) + + assert len(pvg_perfect.vertices) == 4 + assert len(pvg_error.vertices) > 4 + assert len(pvg_slam.vertices) == 4 + + _, state_perfect = pvg_perfect.sample_vertices(do_update_state=False) + _, state_error = pvg_error.sample_vertices(do_update_state=False) + _, state_slam = pvg_slam.sample_vertices(do_update_state=False) + + assert state_perfect.log_prob > state_error.log_prob + assert state_slam.log_prob > state_error.log_prob + + # Confirm that the 'perfect' world is as expected + proposed_world = pvg_perfect.get_proposed_world() + assert len(proposed_world.vertices) == 4 + for v in proposed_world.vertices: + assert abs(v[0]) == pytest.approx(1.0, abs=1e-2) + assert abs(v[1]) == pytest.approx(1.0, abs=1e-2) + assert len(proposed_world.walls) == 4 + + # Confirm the 'SLAM' world should look quite similar. + proposed_world = pvg_slam.get_proposed_world() + assert len(proposed_world.vertices) == 4 + for v in proposed_world.vertices: + assert abs(v[0]) == pytest.approx(1.0, abs=5e-2) + assert abs(v[1]) == pytest.approx(1.0, abs=5e-2) + assert len(proposed_world.walls) == 4 + + +def test_slam_vertex_disabling(do_debug_plot): + random.seed(304) + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_error = vertexnav.prob_vertex_graph.ProbVertexGraph() + + # Add a number of observations + n_poses_per_loop = 40 + n_loops = 6 + for ii in range(n_loops * n_poses_per_loop + 1): + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th) + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose, + p_old=pvg_perfect.r_poses[nposes - + 1]) + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_error, + world=world, + pose=pose, + odom=odom, + err=None) + + pvg_perfect.perform_slam_update() + pvg_error.perform_slam_update() + + # Confirm that the two roughly match + assert all([ + abs(pp.x - pe.x) < 1e-3 and abs(pp.y - pe.y) < 1e-3 + for pp, pe in zip(pvg_perfect.r_poses, pvg_error.r_poses) + ]) + + # Corrupt observations of one of the vertices + for obs, r_pose in zip(pvg_error.observations, pvg_error.r_poses): + for det in obs: + if det.position[0] > 0.5 and det.position[1] > 0.5: + det.range += 0.1 + det.update_props(r_pose) + + # Run SLAM on the erroneous system + pvg_error.perform_slam_update() + + # Confirm that some of the poses have shifted away + assert not all( + abs(pp.x - pe.x) < 1e-3 and abs(pp.y - pe.y) < 1e-3 + for pp, pe in zip(pvg_perfect.r_poses, pvg_error.r_poses)) + dist_err = sum( + math.sqrt((pp.x - pe.x)**2 + (pp.y - pe.y)**2) + for pp, pe in zip(pvg_perfect.r_poses, pvg_error.r_poses)) + + # Disabling the selected vertex should restore the system to its original + # state. I disable this vertex, rerun SLAM, and test. + for v in pvg_error.vertices: + if v.position[0] > 0.5 and v.position[1] > 0.5: + v.is_active = False + + pvg_error.perform_slam_update() + + dist_disabled = sum( + math.sqrt((pp.x - pe.x)**2 + (pp.y - pe.y)**2) + for pp, pe in zip(pvg_perfect.r_poses, pvg_error.r_poses)) + + assert dist_disabled < dist_err + + +def test_slam_vertex_clustering_manual(do_debug_plot): + random.seed(304) + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_no_top = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_no_top.DO_SLAM = False + pvg_with_top = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_with_top.DO_SLAM = False + + # Add a number of observations + n_poses_per_loop = 40 + n_loops = 0.75 + for ii in range(int(n_loops * n_poses_per_loop) + 1): + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th) + err = [0.0, 0.0, 0.005] + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose, + p_old=pvg_perfect.r_poses[nposes - + 1]) + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_no_top, + world=world, + pose=pose, + odom=odom, + err=err) + + _add_new_observation(pvg=pvg_with_top, + world=world, + pose=pose, + odom=odom, + err=err) + + # Check some properties + assert len(pvg_perfect.vertices) == 4 + assert len(pvg_no_top.vertices) == 5 + assert len(pvg_with_top.vertices) == 5 + + pvg_no_top.DO_SLAM = True + pvg_with_top.DO_SLAM = True + + # We should be sure the system is + # "settled" before changing it. + pvg_no_top.perform_slam_update() + + # Merge a couple of the vertices + clustered_verts = [] + topology = [] + for v in pvg_with_top.vertices: + if v.position[0] > 0.5 and v.position[1] < -0.5: + clustered_verts += [v.id] + else: + topology += [(v.id, )] + + topology += [tuple(clustered_verts)] + pvg_with_top.topology = topology + + # Rerun the SLAM system and observe the change + pvg_with_top.perform_slam_update() + + # The poses with the merge should be closer to perfect + dist_sq_no_top = 0 + dist_sq_with_top = 0 + for pp, pn, pm in zip(pvg_perfect.r_poses, pvg_no_top.r_poses, + pvg_with_top.r_poses): + dist_sq_no_top += (pp.x - pn.x)**2 + (pp.y - pn.y)**2 + dist_sq_with_top += (pp.x - pm.x)**2 + (pp.y - pm.y)**2 + + assert dist_sq_with_top < dist_sq_no_top + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 3, 1) + ax2 = plt.subplot(1, 3, 2) + ax3 = plt.subplot(1, 3, 3) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_no_top, world, "SLAM (no merging)") + _plot_pvg_data(ax3, pvg_with_top, world, "SLAM (with merging)") + + plt.show() + + # Compare the likelihoods of each map + _, state_perfect = pvg_perfect.sample_vertices(do_update_state=False) + _, state_no_top = pvg_no_top.sample_vertices(do_update_state=False) + _, state_with_top = pvg_with_top.sample_vertices(do_update_state=False) + + print((pvg_perfect.topology)) + print((pvg_with_top.topology)) + print((pvg_no_top.topology)) + assert state_perfect.log_prob > state_no_top.log_prob + assert state_with_top.log_prob > state_no_top.log_prob + + # Now merge all the vertices into a single cluster + # (to see if anything breaks) + topology = [tuple([v.id for v in pvg_with_top.vertices])] + pvg_with_top.topology = topology + pvg_with_top.perform_slam_update() + + +@pytest.mark.skip("Test too succeptable to numerical noise.") +def test_slam_vertex_clustering_full(do_debug_plot): + random.seed(304) + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_no_top = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_with_top = vertexnav.prob_vertex_graph.ProbVertexGraph() + + # Add a number of observations + n_poses_per_loop = 40 + n_loops = 2 + for ii in range(int(n_loops * n_poses_per_loop) + 1): + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th) + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose, + p_old=pvg_perfect.r_poses[nposes - + 1]) + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + + _add_new_observation(pvg=pvg_no_top, + world=world, + pose=pose, + odom=odom, + err=[0.0, 0.0, 0.01], + association_window=5) + + _add_new_observation(pvg=pvg_with_top, + world=world, + pose=pose, + odom=odom, + err=[0.0, 0.0, 0.01], + association_window=5) + + if ii % 5 == 0: + # Sample only vertices for the no-top one + pvg_no_top.sample_vertices(p_window=15, + num_samples=50, + do_update_state=True) + + # Sample topologies for the other + pvg_with_top.sample_states(num_topology_samples=20, + num_vertex_samples=50, + vertex_association_dist_threshold=2, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + do_update_state=True) + + # Add one final sample for each + pvg_no_top.sample_vertices(p_window=15, + num_samples=50, + do_update_state=True) + pvg_with_top.sample_states(num_topology_samples=40, + num_vertex_samples=50, + vertex_association_dist_threshold=2, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + do_update_state=True) + + # Test some basic properties + print((pvg_perfect.vertices)) + print(pvg_with_top.vertices) + print(pvg_no_top.vertices) + print(pvg_with_top.topology) + print(pvg_no_top.topology) + assert len(pvg_perfect.vertices) == 4 + assert len(pvg_with_top.vertices) > 4 + assert len(pvg_no_top.vertices) > 4 + + print((pvg_with_top.vertices)) + print((pvg_with_top.topology)) + assert len(pvg_with_top.topology) < 6 + assert len(pvg_no_top.topology) > 4 + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 3, 1) + ax2 = plt.subplot(1, 3, 2) + ax3 = plt.subplot(1, 3, 3) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_no_top, world, "SLAM (no merging)") + _plot_pvg_data(ax3, pvg_with_top, world, "SLAM (with merging)") + + plt.show() + + # Compare the likelihoods of each map + _, state_perfect = pvg_perfect.sample_vertices(do_update_state=False) + _, state_no_top = pvg_no_top.sample_vertices(do_update_state=False) + _, state_with_top = pvg_with_top.sample_vertices(do_update_state=False) + + assert state_perfect.log_prob > state_no_top.log_prob + assert state_with_top.log_prob > state_no_top.log_prob + + +@pytest.mark.skip("Test too succeptable to numerical noise.") +def test_slam_orbiting_square_multi_agent_windowed(do_debug_plot): + random.seed(304) + + # Parameters + bg_association = 10000 + sm_association = 5 + + # A square world + square_poly = geometry.Polygon([(-1, -1), (-1, 1), (1, 1), (1, -1)]) + world = vertexnav.world.World(obstacles=[square_poly]) + + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_perfect.DO_SLAM = False + pvg_bg_window = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_bg_window.DO_SLAM = True + pvg_bg_window_top = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_bg_window_top.DO_SLAM = True + pvg_sm_window = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_sm_window.DO_SLAM = True + pvg_sm_window_top = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_sm_window_top.DO_SLAM = True + + # Set the noise models + pvg_bg_window.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_bg_window.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_bg_window.CLUSTERING_NOISE = np.array([0.005, 0.005]) + pvg_bg_window_top.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_bg_window_top.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_bg_window_top.CLUSTERING_NOISE = np.array([0.005, 0.005]) + pvg_sm_window.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_sm_window.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_sm_window.CLUSTERING_NOISE = np.array([0.005, 0.005]) + pvg_sm_window_top.PRIOR_NOISE = np.array([0.3, 0.3, 0.1]) + pvg_sm_window_top.ODOMETRY_NOISE = np.array([0.02, 0.02, 0.5]) + pvg_sm_window_top.CLUSTERING_NOISE = np.array([0.005, 0.005]) + + # Add a number of observations + n_poses_per_loop = 80 + n_loops = 2 + for ii in range(n_loops * n_poses_per_loop + 1): + + # Robot 1 + th = 2 * math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=2.5 * math.cos(th), + y=2.5 * math.sin(th), + yaw=th, + robot_id=1) + pose1 = pose + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose1, + p_old=pvg_perfect.r_poses[nposes - + 2]) + + # A very simple error model + if ii == 0: + err = [0, 0, 0] + else: + err = [ + 0.01 * (random.random() - 0.5), 0.01 * (random.random() - 0.5), + 0.005 * random.random() + ] + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + _add_new_observation(pvg=pvg_bg_window, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=bg_association) + _add_new_observation(pvg=pvg_bg_window_top, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=bg_association) + _add_new_observation(pvg=pvg_sm_window, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=sm_association) + _add_new_observation(pvg=pvg_sm_window_top, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=sm_association) + + # Robot 2 + th = math.pi * ii / n_poses_per_loop + 0.0001 + pose = vertexnav.Pose(x=3.5 * math.cos(th), + y=3.5 * math.sin(th), + yaw=th, + robot_id=2) + pose2 = pose + + if ii == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom(p_new=pose2, + p_old=pvg_perfect.r_poses[nposes - + 2]) + + _add_new_observation(pvg=pvg_perfect, + world=world, + pose=pose, + odom=odom, + err=None) + _add_new_observation(pvg=pvg_bg_window, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=bg_association) + _add_new_observation(pvg=pvg_bg_window_top, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=bg_association) + _add_new_observation(pvg=pvg_sm_window, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=sm_association) + _add_new_observation(pvg=pvg_sm_window_top, + world=world, + pose=pose, + odom=odom, + err=err, + association_window=sm_association) + + # A very simple error model + if ii == 0: + err = [0, 0, 0] + else: + err = [ + 0.01 * (random.random() - 0.5), 0.01 * (random.random() - 0.5), + 0.005 * random.random() + ] + + if ii % 5 == 0: + # Sample topologies + pvg_bg_window_top.sample_states( + num_topology_samples=20, + num_vertex_samples=50, + vertex_association_dist_threshold=2, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + do_update_state=True) + pvg_sm_window_top.sample_states( + num_topology_samples=20, + num_vertex_samples=50, + vertex_association_dist_threshold=2, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + do_update_state=True) + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(3, 2, 1) + ax2 = plt.subplot(3, 2, 3) + ax3 = plt.subplot(3, 2, 4) + ax4 = plt.subplot(3, 2, 5) + ax5 = plt.subplot(3, 2, 6) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_bg_window, world, "Bg") + _plot_pvg_data(ax3, pvg_bg_window_top, world, "Bg + Top") + _plot_pvg_data(ax4, pvg_sm_window, world, "Sm") + _plot_pvg_data(ax5, pvg_sm_window_top, world, "Sm + Top") + + plt.show() + + # Sample one more time + pvg_bg_window_top.sample_states(num_topology_samples=100, + num_vertex_samples=50, + vertex_association_dist_threshold=2, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + do_update_state=True) + pvg_sm_window_top.sample_states(num_topology_samples=100, + num_vertex_samples=50, + vertex_association_dist_threshold=2, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + do_update_state=True) + + assert len(pvg_perfect.vertices) == 4 + assert len(pvg_bg_window.topology) == 8 + assert len(pvg_bg_window_top.topology) < 8 # ==4, but sensitive to noise + assert len(pvg_sm_window.topology) > 10 + assert len(pvg_sm_window_top.topology) < 8 # ==4, but sensitive to noise + + +@pytest.mark.skip(reason="requires CNN that does not exist yet.") +def test_slam_dungeon_rails_nav_unity(do_debug_plot, unity_path, + sim_dungeon_network_path): + random.seed(304) + + if unity_path is None: + pytest.xfail("Missing Unity dungeon environment path. " + "Set via '--unity-dungeon-path'.") + + if sim_dungeon_network_path is None: + pytest.xfail("Missing network .proto for sim hallway. " + "Set via '--sim-dungeon-network-path'.") + + # Set the parameters for learning + processing + args = lambda: None # noqa: E731 + args.max_range = 100 + args.num_range = 32 + args.num_bearing = 128 + args.sig_r = 5.0 + args.sig_th = 0.25 + args.nn_peak_thresh = 0.5 + + world, path = get_map_and_path_hall_snake() + world.breadcrumb_element_poses = [] + pvg_perfect = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_error = vertexnav.prob_vertex_graph.ProbVertexGraph() + pvg_error.DO_SLAM = False + pvg_slam = vertexnav.prob_vertex_graph.ProbVertexGraph() + + world_building_unity_bridge = \ + environments.simulated.WorldBuildingUnityBridge + with world_building_unity_bridge(unity_path) as unity_bridge: + + data_iterator = follow_path_data_iterator(unity_bridge, + world, + path, + steps=20) + unity_bridge.make_world(world) + + if not os.path.exists(sim_dungeon_network_path): + pytest.xfail( + f"Network file {sim_dungeon_network_path} does not exist.") + + eval_net = vertexnav.learning.load_pytorch_net_vertex( + sim_dungeon_network_path, 'cuda') + + for pose, image, ranges in data_iterator: + + if len(pvg_perfect.r_poses) == 0: + odom = None + else: + nposes = len(pvg_perfect.r_poses) + odom = vertexnav.Pose.get_odom( + p_new=pose, p_old=pvg_perfect.r_poses[nposes - 1]) + + # A very simple error model + err = [ + 0.05 * (random.random() - 0.5), 0.05 * (random.random() - 0.5), + 0.125 * (random.random() - 0.5) + ] + + _add_new_observation_learned(pvg=pvg_perfect, + image=image, + eval_net=eval_net, + args=args, + pose=pose, + odom=odom, + err=None) + + _add_new_observation_learned(pvg=pvg_error, + image=image, + eval_net=eval_net, + args=args, + pose=pose, + odom=odom, + err=err) + + _add_new_observation_learned(pvg=pvg_slam, + image=image, + eval_net=eval_net, + args=args, + pose=pose, + odom=odom, + err=err) + pvg_slam.perform_slam_update() + + if do_debug_plot: + import matplotlib.pyplot as plt + + plt.figure() + + ax1 = plt.subplot(1, 3, 1) + ax2 = plt.subplot(1, 3, 2) + ax3 = plt.subplot(1, 3, 3) + + _plot_pvg_data(ax1, pvg_perfect, world, "Perfect Odometry") + _plot_pvg_data(ax2, pvg_error, world, "Noisy Odom") + _plot_pvg_data(ax3, pvg_slam, world, "Noisy Odom + SLAM") + + plt.show() + + # The poses with the merge should be closer to perfect + for pp, pn, pm in zip(pvg_perfect.r_poses, pvg_error.r_poses, + pvg_slam.r_poses): + dist_sq_no_top = (pp.x - pn.x)**2 + (pp.y - pn.y)**2 + dist_sq_with_top = (pp.x - pm.x)**2 + (pp.y - pm.y)**2 + assert dist_sq_with_top - dist_sq_no_top <= 1e-2 diff --git a/modules/vertexnav/vertexnav/__init__.py b/modules/vertexnav/vertexnav/__init__.py new file mode 100644 index 0000000..e4eda80 --- /dev/null +++ b/modules/vertexnav/vertexnav/__init__.py @@ -0,0 +1,13 @@ +import vertexnav_accel # noqa: F401 +from vertexnav_accel import Pose # noqa: F401 +from . import planning # noqa: F401 +from . import plotting # noqa: F401 +from . import utils # noqa: F401 +from . import learning # noqa: F401 +from . import models # noqa: F401 +from . import robot # noqa: F401 +from . import world # noqa: F401 +from . import noisy # noqa: F401 +from . import vertex_graph # noqa: F401 +from . import prob_vertex_graph # noqa: F401 +from . import environments # noqa: F401 diff --git a/modules/vertexnav/vertexnav/environments/__init__.py b/modules/vertexnav/vertexnav/environments/__init__.py new file mode 100644 index 0000000..a94b519 --- /dev/null +++ b/modules/vertexnav/vertexnav/environments/__init__.py @@ -0,0 +1,3 @@ +from . import real # noqa: F401 +from . import dungeon # noqa: F401 +from . import simulated # noqa: F401 diff --git a/modules/vertexnav/vertexnav/environments/dungeon.py b/modules/vertexnav/vertexnav/environments/dungeon.py new file mode 100644 index 0000000..e8f0279 --- /dev/null +++ b/modules/vertexnav/vertexnav/environments/dungeon.py @@ -0,0 +1,398 @@ +import argparse +import environments.simulated +import vertexnav +import itertools +import math +import matplotlib.pyplot as plt +import numpy as np +import random +import shapely.geometry + + +class Dungeon(): + """Funtionality for building and returning shapely polygon of environment. + + Arguments: + rooms (Room obj): list of rooms to build environment from. + scale (int): width of hallways + inflate_ratio (float): how much to inflate obstacles + + Attributes: + scale (int): width of hallways + inflate_ratio (float): how much to inflate obstacles + grid (np.array): occupancy grid of environment (1 is free) + xc (int): x bound + yc (int): y bound + """ + def __init__(self, rooms, scale=10, inflate_ratio=0): + self.scale = scale + self.inflate_ratio = inflate_ratio + if self.inflate_ratio >= 1.0 / 2.0: + raise ValueError("Inflation ratio too large.") + + if _do_rooms_overlap(rooms): + raise ValueError + + xs = [x for room in rooms for x in room.xbounds] + xbounds = (min(xs) - 1, max(xs) + 1) + ys = [y for room in rooms for y in room.ybounds] + ybounds = (min(ys) - 1, max(ys) + 1) + + self.xc = np.arange(xbounds[0], xbounds[1] + 1) + self.yc = np.arange(ybounds[0], ybounds[1] + 1) + + self.grid = np.zeros((self.xc.size, self.yc.size)) + self.rooms = [] + for room in rooms: + self._add_room(room) + + config = random.choice([0, 1, 2, 3]) + + if config == 0: + # Cycle between three; final room connected at random to another + self._add_room_connection(self.rooms[0], self.rooms[1]) + self._add_room_connection(self.rooms[1], self.rooms[2]) + self._add_room_connection(self.rooms[2], self.rooms[0]) + self._add_room_connection(self.rooms[3], + random.choice(self.rooms[0:3])) + elif config == 1: + # Cycle between four + self._add_room_connection(self.rooms[0], self.rooms[1]) + self._add_room_connection(self.rooms[1], self.rooms[2]) + self._add_room_connection(self.rooms[2], self.rooms[3]) + self._add_room_connection(self.rooms[3], self.rooms[0]) + elif config == 2: + # No cycle + self._add_room_connection(self.rooms[0], self.rooms[1]) + self._add_room_connection(self.rooms[1], self.rooms[2]) + self._add_room_connection(self.rooms[2], self.rooms[3]) + elif config == 3: + # Two cycles connected by another line + self._add_room_connection(self.rooms[0], self.rooms[1]) + self._add_room_connection(self.rooms[0], self.rooms[1]) + self._add_room_connection(self.rooms[1], self.rooms[2]) + self._add_room_connection(self.rooms[2], self.rooms[3]) + self._add_room_connection(self.rooms[2], self.rooms[3]) + else: + raise ValueError("Configuration not possible") + + # Now check for runs of a certain length + from itertools import groupby + + def len_iter(items): + return sum(1 for _ in items) + + def consecutive_one(data): + v = [len_iter(run) for val, run in groupby(data) if val == 1] + if len(v): + return max(v) + else: + return 0 + + for row in self.grid: + if consecutive_one(row) > 11: + raise ValueError + for col in self.grid.T: + if consecutive_one(col) > 11: + raise ValueError + + # Prune impossible corners + if np.logical_and( + np.logical_and(self.grid[1:, :-1] == 0, self.grid[:-1, + 1:] == 0), + np.logical_and(self.grid[1:, 1:] == 1, + self.grid[:-1, :-1] == 1)).any(): + raise ValueError + if np.logical_and( + np.logical_and(self.grid[1:, :-1] == 1, self.grid[:-1, + 1:] == 1), + np.logical_and(self.grid[1:, 1:] == 0, + self.grid[:-1, :-1] == 0)).any(): + raise ValueError + + def compute_obstacles_and_boundary(self): + """Return the shapely polygons for the boundary and all obstacles""" + print("Computing obstacles") + print((self.inflate_ratio)) + + known_space_poly = shapely.geometry.Polygon() + + cx = 0.5 * (self.xc[0] + self.xc[-1]) + cy = 0.5 * (self.yc[0] + self.yc[-1]) + + if self.inflate_ratio > 0: + s = self.scale * 1.0 / (1 + self.inflate_ratio) + print(("Scale: {}".format(s))) + else: + s = 1 + + for index, val in np.ndenumerate(self.grid): + if val < 1: + continue + + y, x = index + y *= s + x *= s + y -= (0.5 + cy) * s + x -= (0.5 + cx) * s + poly = shapely.geometry.Polygon([(x, y), (x + s, y), + (x + s, y + s), (x, y + s)]) + known_space_poly = known_space_poly.union(poly) + + if self.inflate_ratio > 0: + known_space_poly = known_space_poly.buffer(s * self.inflate_ratio / + 2, + 0, + cap_style=3, + join_style=2) + + # Handle if the polygon has an interior; any interior 'rings' are + # converted to Polygons and returned as obstacles. This will only + # matter if do_enforce_hallway == False. + obstacles = [ + vertexnav.utils.calc.full_simplify_shapely_polygon( + shapely.geometry.Polygon(interior)) + for interior in list(known_space_poly.interiors) + ] + + # Simplify the polygon + boundary = vertexnav.utils.calc.full_simplify_shapely_polygon( + known_space_poly) + + return obstacles, boundary + + def _compute_poly_and_walls(self): + """Compute known space polygon and walls for the environment""" + + known_space_poly = shapely.geometry.Polygon() + + for index, val in np.ndenumerate(self.grid): + if val < 1: + continue + + s = self.scale + y, x = index + y *= s + x *= s + y -= 0.5 * s + x -= 0.5 * s + poly = shapely.geometry.Polygon([(x, y), (x + s, y), + (x + s, y + s), (x, y + s)]) + known_space_poly = known_space_poly.union(poly) + + walls = [] + for ls in known_space_poly.boundary: + print(ls) + for pa, pb in zip(ls.coords[1:], ls.coords[:-1]): + walls.append((pa, pb)) + + known_space_exterior = vertexnav.utils.calc.full_simplify_shapely_polygon( + known_space_poly) + interiors = [ + vertexnav.utils.calc.full_simplify_shapely_polygon( + shapely.geometry.Polygon(interior)) + for interior in list(known_space_poly.interiors) + ] + known_space_poly = known_space_exterior + for interior in interiors: + known_space_poly = known_space_poly.difference(interior) + + return known_space_poly, walls + + def _add_room(self, room): + """Adds a room and updates the grid""" + + is_room_x = np.logical_and(self.xc >= min(room.xbounds), + self.xc <= max(room.xbounds)) + is_room_y = np.logical_and(self.yc >= min(room.ybounds), + self.yc <= max(room.ybounds)) + self.grid[np.outer(is_room_x, is_room_y)] = 1 + self.rooms.append(room) + + def _add_room_connection(self, room_a, room_b): + """Connects rooms with hallways and updates the grid""" + if random.random() > 0.5: + start, end = room_a.get_random_point(), room_b.get_random_point() + else: + start, end = room_b.get_random_point(), room_a.get_random_point() + + start = [ + np.argwhere(start[0] == self.xc)[0], + np.argwhere(start[1] == self.yc)[0] + ] + end = [ + np.argwhere(end[0] == self.xc)[0], + np.argwhere(end[1] == self.yc)[0] + ] + + if abs(start[0] - end[0]) > 6 or abs(start[1] - end[1]) > 6: + raise ValueError + + # Draw first a vertical then a horizontal line + point = start + while not point[0] == end[0]: + point[0] = point[0] - int(math.copysign(1, point[0] - end[0])) + self.grid[point[0], point[1]] = 1 + while not point[1] == end[1]: + point[1] = point[1] - int(math.copysign(1, point[1] - end[1])) + self.grid[point[0], point[1]] = 1 + + +class Room(): + """Funtionality for defining polygon of rooms that make up environment. + + Arguments: + xbounds (tuple of ints): x bounds of a room + ybounds (tuple of ints): y bounds of a room + + Attributes: + xbounds (tuple of ints): x bounds of a room + ybounds (tuple of ints): y bounds of a room + poly (shapely polygon): polygon defining room + """ + def __init__(self, xbounds, ybounds): + self.xbounds = xbounds + self.ybounds = ybounds + self.poly = shapely.geometry.Polygon([(min(xbounds), min(ybounds)), + (max(xbounds), min(ybounds)), + (max(xbounds), max(ybounds)), + (min(xbounds), max(ybounds))]) + + def get_random_point(self): + "Returns uniformly sampled position from room" "" + return [ + random.randint(min(self.xbounds) + 1, + max(self.xbounds) - 1), + random.randint(min(self.ybounds) + 1, + max(self.ybounds) - 1) + ] + + +def _do_rooms_overlap(rooms): + """Return if rooms overlap in map generation""" + for r_pair in itertools.combinations(rooms, 2): + if r_pair[0].poly.buffer(2.05, 1).intersects(r_pair[1].poly): + return True + + return False + + +def _get_dungeon(scale=10, inflate_ratio=0): + """Returns sample map""" + while True: + rooms = [] + + for _ in range(4): + xc = random.randint(0, 14) + width = random.randint(2, 3) + yc = random.randint(0, 14) + height = random.randint(2, 3) + rooms.append(Room([xc, xc + width], [yc, yc + height])) + try: + return Dungeon(rooms, scale=scale, inflate_ratio=inflate_ratio) + except Exception as e: + if len(str(e)) > 2: + raise + pass + + +class DungeonWorld(vertexnav.world.World): + """Implementation of world class to build Dungeon World""" + def __init__(self, + hall_width=20, + inflate_ratio=0.3, + num_attempts=10000, + num_clutter_elements=40, + min_clutter_signed_distance=0.5, + max_clutter_signed_distance=1.5, + min_interlight_distance=30, + min_light_to_wall_distance=9, + random_seed=None): + + self.breadcrumb_type = None + + if random_seed is not None: + random.seed(random_seed) + np.random.seed(random_seed) + + # Construct a hallway + for _ in range(num_attempts): + dungeon_obj = _get_dungeon(scale=hall_width, + inflate_ratio=inflate_ratio) + + try: + obstacles, boundary = dungeon_obj.compute_obstacles_and_boundary( + ) + super(DungeonWorld, self).__init__(obstacles=obstacles, + boundary=boundary) + break + except Exception as e: + if len(str(e)) > 2: + print(e) + raise + pass + else: + raise RuntimeError("Failed to generate hallway map " + + f"in {num_attempts} attempts") + + # Add clutter (intersects walls) + self.clutter_element_poses = [] + while len(self.clutter_element_poses) < num_clutter_elements: + pose = self.get_random_pose( + min_signed_dist=min_clutter_signed_distance) + signed_dist = self.get_signed_dist(pose) + if signed_dist <= max_clutter_signed_distance \ + and signed_dist >= min_clutter_signed_distance: + self.clutter_element_poses.append(pose) + + counter = 0 + self.clutter_element_data = [] # XYZWHD + for p in self.clutter_element_poses: + if counter % 2: + self.clutter_element_data.append( + ['box', p.x, p.y, 0.0, 2.25, 2.25, 2.25]) + else: + self.clutter_element_data.append( + ['cylinder', p.x, p.y, 0.0, 1.0, 1.0, 2.25]) + counter += 1 + + self.breadcrumb_element_poses = [] + + self.light_poses = environments.simulated._generate_light_poses( + world=self, + min_interlight_distance=min_interlight_distance, + min_light_to_wall_distance=min_light_to_wall_distance) + + self.ceiling_poses = environments.simulated._generate_ceiling_poses( + self.boundary) + + +def show_test_map(): + """Plots sample map""" + ax = plt.gca() + grid = _get_dungeon(inflate_ratio=0.25) + img = ax.imshow(grid.grid) + img.set_cmap('binary') + poly, walls = grid._compute_poly_and_walls() + + vertexnav.plotting.plot_polygon(plt.gca(), poly, alpha=0.2) + + for w in walls: + plt.plot((w[0][0], w[1][0]), (w[0][1], w[1][1])) + plt.show() + + +def parse_args(): + """Define the command line arguments.""" + parser = argparse.ArgumentParser(description='Generate a random map.') + parser.add_argument('--seed', type=int, default=13) + args = parser.parse_args() + + return args + + +if __name__ == "__main__": + args = parse_args() + random.seed(args.seed) + np.random.seed(args.seed) + show_test_map() diff --git a/modules/vertexnav/vertexnav/environments/real.py b/modules/vertexnav/vertexnav/environments/real.py new file mode 100644 index 0000000..252723c --- /dev/null +++ b/modules/vertexnav/vertexnav/environments/real.py @@ -0,0 +1,857 @@ +from vertexnav.world import World +# from vertexnav.environments.simulated import DungeonBuildingUnityBridge +from environments.simulated import WorldBuildingUnityBridge +import math +from shapely import geometry + + +class SloanBuildingUnityBridge(WorldBuildingUnityBridge): + """Communication between Unity and DungeonWorld""" + def make_world(self, world, scale=1.0): + def dist(p1, p2): + return math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + + def move_object_to_pose(self, object_name, pose): + self.send_message("{} move {} {} {} {}".format(object_name, pose.y, + 0.33, pose.x, pose.yaw)) + + +def get_world_mit_sloan(inc=['w']): + """ + Defines the SLOAN environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + obs = [] + inter1 = [] + inter2 = [] + obstacle = [] + enclosure = [ + (-3.14407277107, 0.788364052773, 'w'), + (6.14413881302, 12.6185903549, 'w'), + (-12.0155696869, 26.52003479, 'w'), + (-12.4228839874, 25.9558563232, 'd'), + (-13.6241636276, 26.8344650269, 'd'), + (-13.347240448, 27.2506904602, 'w'), + (-14.1134939194, 27.8486385345, 'w'), + (-12.3362522125, 30.1839828491, 'w'), + (-11.0614967346, 31.8463897705, 'w'), + (-5.2670173645, 27.4334201813, 'w'), + (-6.63337087631, 25.5421028137, 'w'), + (2.09723901749, 18.812625885, 'w'), + (11.7331724167, 31.4063949585, 'w'), + (13.0758991241, 30.3736534119, 'd'), + (12.8482961655, 30.0300617218, 'w'), + (23.4888877869, 21.9004497528, 'w'), + (23.8377017975, 22.2859344482, 'd'), + (26.2551231384, 20.3886737823, 'w'), + (22.5347251892, 15.413731575, 'w'), + (21.3889122009, 16.2697792053, 'w'), + (15.6230278015, 8.66678333282, 'w'), + (20.6673297882, 4.94552898407, 'w'), + (22.8188037872, 7.56888961792, 'w'), + (24.8803653717, 6.02704238892, 'w'), + (21.1974391937, 1.21215391159, 'w'), + (18.9743843079, 2.91657972336, 'w'), + (18.5539512634, 2.3295249939, 'd'), + (18.9713439941, 1.98489522934, 'd'), + (18.6201305389, 1.5396156311, 'd'), + (18.1702041626, 1.84140849113, 'd'), + (13.2366666794, -4.69163894653, 'w'), + (13.6548461914, -5.03814697266, 'd'), + (12.7687597275, -6.21916770935, 'w'), + (13.8509063721, -7.02065372467, 'w'), + (11.8666172028, -9.66930198669, 'w'), + (7.02449989319, -5.96890592575, 'd'), + (7.4119644165, -5.45906877518, 'w'), + (3.67599725723, -2.68643403053, 'w'), + (2.8580198288, -3.76152467728, 'w'), + ] + + interior1 = [ + (1.78792965412, 2.13901901245, 'w'), + (8.49860858917, 10.8221216202, 'w'), + (17.8252353668, 3.77096366882, 'w'), + (11.1824111938, -4.97536230087, 'w'), + (5.94924497604, -1.02605688572, 'w'), + (7.122, 0.6171, 'w'), + (6.87442111969, 0.197876304388, 'i'), + (6.87442111969, 0.841532409191, 'i'), + (6.56519842148, 0.473038047552, 'i'), + (6.83265399933, 0.197876304388, 'i'), + (6.83265399933, 0.841532409191, 'i'), + (4.80285215378, 2.38317370415, 'w'), + (3.57057929039, 0.765040695667, 'w'), + ] + + interior2 = [ + (3.38511824608, 17.6859512329, 'w'), + (11.7208995819, 28.6295452118, 'w'), + (22.4496116638, 20.4469108582, 'w'), + (14.1521968842, 9.48162269592, 'w'), + ] + + # for el in enclosure: + # if el[2] in inc: + # obs.append((el[1], el[0])) + # + # world = World(obstacles=[], boundary=geometry.Polygon(obs)) + # return world + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + for el in interior1: + if el[2] in inc: + inter1.append((el[1], el[0])) + + for el in interior2: + if el[2] in inc: + inter2.append((el[1], el[0])) + + # obstacle += [geometry.Polygon(obs)] + obstacle += [geometry.Polygon(inter1)] + obstacle += [geometry.Polygon(inter2)] + + world = World(obstacles=obstacle, boundary=geometry.Polygon(obs)) + + return world + + +def get_world_mit_sloan_small(inc=['w']): + """ + Defines the SLOAN environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + obs = [] + inter1 = [] + inter2 = [] + obstacle = [] + enclosure = [ + (-3.14407277107, 0.788364052773, 'w'), + (6.14413881302, 12.6185903549, 'w'), + (0.66, 16.8, 'w'), + # (-12.0155696869, 26.52003479, 'w'), + # (-12.4228839874, 25.9558563232, 'd'), + # (-13.6241636276, 26.8344650269, 'd'), + # (-13.347240448, 27.2506904602, 'w'), + # (-14.1134939194, 27.8486385345, 'w'), + # (-12.3362522125, 30.1839828491, 'w'), + # (-11.0614967346, 31.8463897705, 'w'), + # (-5.2670173645, 27.4334201813, 'w'), + # (-6.63337087631, 25.5421028137, 'w'), + # (2.09723901749, 18.812625885, 'w'), + (11.7331724167, 31.4063949585, 'w'), + (13.0758991241, 30.3736534119, 'd'), + (12.8482961655, 30.0300617218, 'w'), + (23.4888877869, 21.9004497528, 'w'), + (23.8377017975, 22.2859344482, 'd'), + (26.2551231384, 20.3886737823, 'w'), + (22.5347251892, 15.413731575, 'w'), + (21.3889122009, 16.2697792053, 'w'), + (15.6230278015, 8.66678333282, 'w'), + (20.6673297882, 4.94552898407, 'w'), + # (22.8188037872, 7.56888961792, 'w'), + # (24.8803653717, 6.02704238892, 'w'), + # (21.1974391937, 1.21215391159, 'w'), + (18.9743843079, 2.91657972336, 'w'), + (18.5539512634, 2.3295249939, 'd'), + (18.9713439941, 1.98489522934, 'd'), + (18.6201305389, 1.5396156311, 'd'), + (18.1702041626, 1.84140849113, 'd'), + (13.2366666794, -4.69163894653, 'w'), + (13.6548461914, -5.03814697266, 'd'), + (12.7687597275, -6.21916770935, 'w'), + (13.8509063721, -7.02065372467, 'w'), + (11.8666172028, -9.66930198669, 'w'), + (7.02449989319, -5.96890592575, 'd'), + (7.4119644165, -5.45906877518, 'w'), + (3.67599725723, -2.68643403053, 'w'), + (2.8580198288, -3.76152467728, 'w'), + ] + + interior1 = [ + (1.78792965412, 2.13901901245, 'w'), + (8.49860858917, 10.8221216202, 'w'), + (17.8252353668, 3.77096366882, 'w'), + (11.1824111938, -4.97536230087, 'w'), + (5.94924497604, -1.02605688572, 'w'), + (7.122, 0.6171, 'w'), + (6.87442111969, 0.197876304388, 'i'), + (6.87442111969, 0.841532409191, 'i'), + (6.56519842148, 0.473038047552, 'i'), + (6.83265399933, 0.197876304388, 'i'), + (6.83265399933, 0.841532409191, 'i'), + (4.80285215378, 2.38317370415, 'w'), + (3.57057929039, 0.765040695667, 'w'), + ] + + interior2 = [ + (3.38511824608, 17.6859512329, 'w'), + (11.7208995819, 28.6295452118, 'w'), + (22.4496116638, 20.4469108582, 'w'), + (14.1521968842, 9.48162269592, 'w'), + ] + + # for el in enclosure: + # if el[2] in inc: + # obs.append((el[1], el[0])) + # + # world = World(obstacles=[], boundary=geometry.Polygon(obs)) + # return world + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + for el in interior1: + if el[2] in inc: + inter1.append((el[1], el[0])) + + for el in interior2: + if el[2] in inc: + inter2.append((el[1], el[0])) + + # obstacle += [geometry.Polygon(obs)] + obstacle += [geometry.Polygon(inter1)] + obstacle += [geometry.Polygon(inter2)] + + world = World(obstacles=obstacle, boundary=geometry.Polygon(obs)) + + return world + + +def get_world_mit_36_2(inc=['w', 'i', 'o']): + """ + Defines the second floor building 36 environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + inc = ['w', 'i'] + obs = [] + enclosure = [ + (38.7570610046, -3.12935352325, 'w'), + (38.4254875183, -6.02763223648, 'w'), + (35.9273605347, -5.732609272, 'w'), + (36.0338592529, -4.72073936462, 'w'), + (30.4610881805, -4.02793741226, 'w'), + (30.3002986908, -5.30161094666, 'w'), + (28.4203224182, -5.05502796173, 'w'), + (28.577747345, -3.81505322456, 'w'), + (24.2908153534, -3.2570939064, 'w'), + (23.1455860138, -12.6708564758, 'i'), + (23.5236606598, -12.7585678101, 'o'), + (23.3259391785, -14.8170433044, 'o'), + (22.8470745087, -14.7449150085, 'i'), + (22.7091636658, -15.7196521759, 'w'), + (21.0488395691, -15.5088796616, 'w'), + (21.0998191833, -14.5375595093, 'i'), + (20.5249958038, -14.4318656921, 'o'), + (20.7750339508, -12.362159729, 'o'), + (21.2153587341, -12.439291954, 'i'), + (22.4119281769, -3.02628231049, 'w'), + (18.1535205841, -2.48051929474, 'w'), + (17.9231758118, -3.72574901581, 'w'), + (16.0669116974, -3.49696040154, 'w'), + (16.2137260437, -2.24265217781, 'w'), + (11.9817743301, -1.71824479103, 'w'), + (11.8117218018, -2.97447133064, 'w'), + (9.92018318176, -2.73534393311, 'w'), + (10.0608558655, -1.48662948608, 'w'), + (5.7767457962, -0.944746792316, 'w'), + (5.62486600876, -2.19767570496, 'w'), + (3.73253750801, -1.96283602715, 'w'), + (3.8689892292, -0.713662087917, 'w'), + (-1.30833816528, -0.0575175732374, 'w'), + (-0.820710837841, 1.81734800339, 'w'), + (1.64509093761, 1.49642062187, 'i'), + (1.62319505215, 1.27957892418, 'o'), + (2.22265481949, 1.18973243237, 'o'), + (2.28501915932, 1.43376898766, 'i'), + (7.84277963638, 0.741574943066, 'i'), + (7.82410860062, 0.492920964956, 'o'), + (8.37747764587, 0.415470451117, 'o'), + (8.44029426575, 0.665226399899, 'i'), + (14.0294523239, -0.0646714270115, 'i'), + (14.0272254944, -0.291882008314, 'o'), + (14.5760030746, -0.328506231308, 'o'), + (14.6258554459, -0.112949237227, 'i'), + (20.1594562531, -0.820017635822, 'i'), + (20.1439762115, -1.0235145092, 'o'), + (20.7715759277, -1.12369084358, 'o'), + (20.8246517181, -0.90669375658, 'i'), + (26.3659000397, -1.60172569752, 'i'), + (26.3387889862, -1.82181167603, 'o'), + (26.9604492188, -1.90010118484, 'o'), + (26.9995651245, -1.66911172867, 'i'), + (32.5302772522, -2.36135649681, 'i'), + (32.496219635, -2.64454317093, 'o'), + (36.2797546387, -3.12007308006, 'o'), + (36.322265625, -2.83676743507, 'i'), + ] + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + world = World(obstacles=[], boundary=geometry.Polygon(obs)) + return world + + +def get_world_mit_36_4(inc=['w', 'i', 'o']): + """ + Defines the fourth floor building 36 environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + inc = ['w', 'i'] + obs = [] + enclosure = [ + (39.470615387, 2.17658805847, 'w'), + (39.5517578125, -0.778692960739, 'w'), + (37.1224822998, -0.792905807495, 'w'), + (37.1066856384, 0.216090083122, 'w'), + (31.4875926971, 0.163706541061, 'w'), + (31.4955043793, -1.09642136097, 'w'), + (29.6029090881, -1.11483800411, 'w'), + (29.5899162292, 0.133202314377, 'w'), + (25.2512607574, 0.0875393152237, 'w'), + (25.3790092468, -12.3033285141, 'w'), + (23.530456543, -12.2894716263, 'w'), + (22.7724628448, -12.3010883331, 'w'), + (22.7586727142, -10.8385105133, 'w'), + (23.4751091003, -10.83634758, 'w'), + (23.4275474548, -7.00789165497, 'w'), + (22.7338638306, -7.01555681229, 'w'), + (22.7105083466, -5.01922798157, 'w'), + (23.4016036987, -5.01984977722, 'w'), + (23.342918396, 0.0681455731392, 'w'), + (19.0065593719, -0.00826094299555, 'w'), + (19.0055923462, -1.26869416237, 'w'), + (17.1461353302, -1.27939558029, 'w'), + (17.1066074371, -0.0262905806303, 'w'), + (12.7384872437, -0.080764144659, 'w'), + (12.7348575592, -1.3459829092, 'w'), + (10.8751897812, -1.35382306576, 'w'), + (10.8389368057, -0.107532173395, 'w'), + (6.49898195267, -0.168952524662, 'w'), + (6.51066637039, -1.42084622383, 'w'), + (4.63645172119, -1.47652590275, 'w'), + (4.60488986969, -0.196030437946, 'w'), + (-1.45355057716, -0.261074662209, 'w'), + (-1.47934246063, 1.63643169403, 'w'), + (-1.07470369339, 1.62006211281, 'i'), + (-1.0499471426, 1.42805719376, 'o'), + (-0.398554444313, 1.40628743172, 'o'), + (-0.383432030678, 1.66659641266, 'i'), + (2.06509804726, 1.70228624344, 'i'), + (2.07631206512, 1.46379709244, 'o'), + (2.72291278839, 1.46340346336, 'o'), + (2.73739314079, 1.69070458412, 'i'), + (8.3018693924, 1.78669095039, 'i'), + (8.31966781616, 1.56134295464, 'o'), + (15.2177839279, 1.62270522118, 'o'), + (15.2278184891, 1.90178537369, 'i'), + (20.8298988342, 1.98004806042, 'i'), + (20.8382892609, 1.73651635647, 'o'), + (24.2886581421, 1.76902282238, 'o'), + (24.2821846008, 2.00581073761, 'i'), + (27.0716133118, 2.04999828339, 'i'), + (27.0848274231, 1.79932630062, 'o'), + (27.7151622772, 1.80324888229, 'o'), + (27.7255306244, 2.0597319603, 'i'), + (33.2807273865, 2.13156175613, 'i'), + (33.3048973083, 1.80056929588, 'o'), + (37.0950737, 1.8587243557, 'o'), + (37.1251792908, 2.14234638214, 'i'), + ] + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + world = World(obstacles=[], boundary=geometry.Polygon(obs)) + return world + + +def get_world_mit_rainbow(inc=['w', 'd', 'o']): + """ + Defines the building 6-c atrium environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + obs = [] + inter = [] + obstacle = [] + enclosure = [ + (-1.74510025978, -0.362198621035, 'w'), + (-0.175234735012, 3.58867192268, 'w'), + (2.46903991699, 2.55160903931, 'w'), + # (2.95548057556, 3.73032903671, 'w'), + (3.25592064857, 3.61595106125, 'w'), + (15.1639242172, 33.9498100281, 'w'), + (20.6315841675, 31.8032855988, 'w'), + (20.9885425568, 32.6318511963, 'w'), + (27.0885944366, 30.204252243, 'w'), + (26.1086349487, 27.5749340057, 'w'), + (29.0680809021, 26.376367569, 'w'), + (31.2907600403, 32.3501091003, 'w'), + (33.3107223511, 31.4998016357, 'w'), + (31.388130188, 26.7301578522, 'w'), + (36.0618476868, 24.8097076416, 'w'), + (36.7049064636, 26.3712940216, 'w'), + (42.2522735596, 24.2410507202, 'w'), + (28.0738716125, -11.9708051682, 'w'), + ] + + interior = [ + (8.61875629425, 1.74197411537, 'w'), + (19.1257266998, 28.7334136963, 'w'), + (35.3876571655, 22.2446556091, 'w'), + (24.7255630493, -4.51794481277, 'w'), + ] + + # for el in enclosure: + # if el[2] in inc: + # obs.append((el[1], el[0])) + # + # world = World(obstacles=[], boundary=geometry.Polygon(obs)) + # return world + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + for el in interior: + if el[2] in inc: + inter.append((el[1], el[0])) + + # obstacle += [geometry.Polygon(obs)] + obstacle += [geometry.Polygon(inter)] + + world = World(obstacles=obstacle, boundary=geometry.Polygon(obs)) + + return world + + +def get_world_mit_36_3(inc=['w', 'd', 'o']): + """ + Defines the third floor building 36 environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + obs = [] + enclosure = [ + (-1.28510594368, -0.950448155403, 'w'), + (-1.26561045647, 1.98215174675, 'w'), + (0.78294980526, 1.92930912971, 'w'), + (0.781651258469, 0.918382287025, 'w'), + (6.40367031097, 0.770433545113, 'w'), + (6.44467449188, 2.04712867737, 'w'), + (8.32676696777, 1.98643231392, 'w'), + (8.29667949677, 0.728792667389, 'w'), + (12.6598567963, 0.621804118156, 'w'), + (12.8215961456, 8.2595243454, 'w'), + (10.7018947601, 8.34455394745, 'w'), + (10.7585535049, 10.0590114594, 'w'), + (12.8739976883, 9.9890165329, 'w'), + (12.9294176102, 11.4235944748, 'w'), + (14.8173770905, 11.3829231262, 'w'), + (14.5473890305, 0.558336257935, 'w'), + (18.8813743591, 0.462022334337, 'w'), + (18.8974475861, 1.72398304939, 'w'), + (20.8024616241, 1.66811966896, 'w'), + (20.7876739502, 0.412778347731, 'w'), + (25.1160430908, 0.311468243599, 'w'), + (25.1928119659, 1.58532786369, 'w'), + (27.0265808105, 1.53227448463, 'w'), + (27.0221347809, 0.269255757332, 'w'), + (31.3815422058, 0.159548997879, 'w'), + (31.3768787384, 1.43545508385, 'w'), + (33.2887763977, 1.3646812439, 'w'), + (33.274105072, 0.113353967667, 'w'), + (38.4715766907, -0.00231754779816, 'w'), + # (38.4314880371, -1.68135285378, 'w'), + # (38.2056045532, -1.69291961193, 'w'), + (38.1883621216, -1.93129241467, 'w'), + (35.7454452515, -1.86713457108, 'w'), + # (35.7256622314, -1.63385355473, 'w'), + # (35.0763053894, -1.60776901245, 'w'), + (35.0536003113, -1.86640024185, 'w'), + (29.4700222015, -1.72219216824, 'w'), + # (29.4591026306, -1.45304965973, 'w'), + # (28.832321167, -1.45452356339, 'w'), + (28.8393287659, -1.72187423706, 'w'), + (23.2270851135, -1.55938816071, 'w'), + # (23.2298221588, -1.31273126602, 'w'), + # (22.601568222, -1.30073022842, 'w'), + (22.5778522491, -1.55320835114, 'w'), + (16.9946975708, -1.42228245735, 'w'), + # (16.9974918365, -1.15552663803, 'w'), + # (16.3734397888, -1.14367723465, 'w'), + (16.3343772888, -1.40885400772, 'w'), + (10.7635622025, -1.28230047226, 'w'), + # (10.7464923859, -1.01644444466, 'w'), + # (10.1138267517, -1.00723361969, 'w'), + (10.0916166306, -1.26735246181, 'w'), + (4.52453184128, -1.13372325897, 'w'), + # (4.52107810974, -0.809861898422, 'w'), + # (0.722912549973, -0.722848773003, 'w'), + (0.701989889145, -1.0292403698, 'w'), + ] + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + world = World(obstacles=[], boundary=geometry.Polygon(obs)) + return world + + +def get_world_mit_triangle(inc=['w', 'd', 'o']): + """ + Defines the building 26 environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + obs = [] + enclosure = [ + (2.87602329254, 1.66094315052, 'w'), + (3.02457976341, -0.277234375477, 'w'), + (1.1925547123, -0.48699092865, 'w'), + (2.6140422821, -1.16811239719, 'w'), + (2.7875521183, -0.817048668861, 'w'), + (3.9190826416, -1.30428636074, 'w'), + (3.74861049652, -1.73623657227, 'w'), + (4.70419788361, -2.18745160103, 'w'), + (4.06106233597, -3.63641834259, 'w'), + (-2.04141759872, -0.763803839684, 'w'), + (-3.59127926826, -0.889113783836, 'w'), + (-3.404631853, -1.09580254555, 'w'), + (-4.07717704773, -2.46486473083, 'w'), + (-6.80567789078, -1.16066837311, 'w'), + (-8.34850215912, -1.30688309669, 'w'), + (-8.14921569824, -1.46727395058, 'w'), + (-8.80341911316, -2.85632491112, 'w'), + (-11.5505390167, -1.55757308006, 'w'), + (-13.1011791229, -1.71716272831, 'w'), + (-12.890378952, -1.8913090229, 'w'), + (-13.5456161499, -3.25967502594, 'w'), + (-16.2983837128, -1.95905804634, 'w'), + (-17.8527164459, -2.10862636566, 'w'), + (-17.6496162415, -2.26252698898, 'w'), + (-18.3006019592, -3.65934681892, 'w'), + (-21.0536670685, -2.36308908463, 'w'), + (-22.5990886688, -2.47623682022, 'w'), + (-22.4007225037, -2.6397562027, 'w'), + (-23.0495223999, -4.01550722122, 'w'), + (-25.7878341675, -2.75738215446, 'w'), + (-27.306596756, -2.88873624802, 'w'), + (-27.1116600037, -3.06163406372, 'w'), + (-27.7712249756, -4.44324588776, 'w'), + (-30.4956283569, -3.15703606606, 'w'), + (-32.1033821106, -3.2613799572, 'w'), + (-31.888250351, -3.42187952995, 'w'), + (-32.5309448242, -4.85204267502, 'w'), + (-35.3453865051, -3.51110839844, 'w'), + (-38.3925132751, -3.78853678703, 'w'), + (-38.2125854492, -3.98152565956, 'w'), + (-38.8996696472, -5.35960865021, 'w'), + (-39.1587142944, -5.29189872742, 'w'), + (-39.3042259216, -5.56304454803, 'w'), + (-50.2030715942, -0.347498208284, 'w'), + (-50.201675415, 0.0393722653389, 'w'), + (-50.8027572632, 0.388799101114, 'w'), + (-50.345035553, 1.191442132, 'w'), + (-50.3433685303, 2.37946200371, 'w'), + (-41.3140182495, -2.06900119781, 'w'), + ] + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + # obstacle += [geometry.Polygon(obs)] + # obstacle += [geometry.Polygon(col)] + + world = World(obstacles=[], boundary=geometry.Polygon(obs)) + + return world + + +def get_world_mit_basement_2(inc=['w', 'd', 'o']): + """ + Defines the basement environment + + Input: List of vertex types to include in polygon + + Output: World object containing shapely polygons + """ + obs = [] + col = [] + obstacle = [] + column = [ + (3.29, -3.24, 'w'), + (2.76, -3.30, 'w'), + (2.66, -2.75, 'w'), + (3.23, -2.69, 'w'), + ] + enclosure = [ + (-4.63, -0.44, 'w'), + (2.55, 0.82, 'w'), + (2.16, 2.60, 'w'), + (2.36, 2.66, 'w'), + (2.21, 3.23, 'w'), + (2.06, 3.26, 'w'), + (1.92, 3.39, 'd'), + (1.56, 5.10, 'd'), + (1.12, 7.89, 'w'), + (1.44, 8.07, 'o'), + (1.08, 8.13, 'w'), + (0.61, 10.22, 'd'), + (0.45, 11.13, 'd'), + (0.01, 13.68, 'd'), + (-0.21, 14.54, 'd'), + (-0.69, 17.30, 'd'), + (-0.88, 18.18, 'd'), + (-2.11, 25.15, 'd'), + (-2.45, 26.95, 'd'), + (-2.65, 28.53, 'd'), + (-2.78, 29.45, 'd'), + (-2.94, 29.64, 'd'), + (-3.12, 30.73, 'd'), + (-3.66, 33.78, 'd'), + (-3.75, 34.50, 'd'), + (-3.93, 34.93, 'd'), + (-4.11, 35.78, 'd'), + (-6.39, 48.18, 'd'), + (-6.78, 50.00, 'd'), + (-7.43, 52.13, 'd'), + (-7.51, 53.87, 'd'), + (-7.55, 55.15, 'w'), + (-7.26, 55.34, 'd'), + (-5.72, 55.60, 'd'), + (-4.29, 55.70, 'w'), + (-4.25, 56.07, 'w'), + (-3.70, 56.23, 'd'), + (-1.73, 56.57, 'd'), + (-0.68, 56.75, 'w'), + (-0.65, 56.40, 'w'), + (7.87, 57.93, 'w'), + (7.88, 58.37, 'w'), + (10.13, 58.82, 'w'), + (10.27, 58.10, 'w'), + (12.11, 58.52, 'w'), + (12.05, 58.72, 'w'), + (16.02, 59.46, 'w'), + (16.00, 59.84, 'w'), + (16.88, 60.01, 'd'), + (18.87, 60.38, 'd'), + (19.58, 60.53, 'w'), + (19.60, 60.11, 'w'), + (29.62, 62.24, 'd'), + (31.47, 62.68, 'd'), + (32.21, 62.69, 'w'), + (32.21, 62.91, 'w'), + (34.63, 63.50, 'd'), + (35.46, 63.65, 'd'), + (38.37, 64.24, 'd'), + (39.26, 64.41, 'd'), + (40.17, 64.50, 'w'), + (40.53, 62.88, 'd'), + (40.68, 62.17, 'd'), + (40.68, 61.97, 'w'), + (37.88, 61.44, 'w'), + (37.81, 61.65, 'w'), + (35.99, 61.28, 'd'), + (34.47, 61.00, 'd'), + (33.68, 60.77, 'd'), + (32.79, 60.59, 'd'), + (21.63, 58.59, 'd'), + (20.58, 58.26, 'd'), + (18.75, 57.83, 'd'), + (17.69, 57.67, 'd'), + (17.20, 57.63, 'd'), + (16.46, 57.56, 'd'), + (9.30, 56.04, 'd'), + (8.39, 55.88, 'd'), + (7.82, 55.81, 'd'), + (5.85, 55.42, 'd'), + (4.60, 55.16, 'd'), + (3.59, 55.02, 'd'), + (-1.79, 54.02, 'd'), + (-2.71, 53.88, 'd'), + (-4.72, 53.56, 'w'), + (-4.79, 53.32, 'd'), + (-4.45, 51.79, 'd'), + (-4.39, 51.57, 'd'), + (-4.21, 50.42, 'd'), + (-2.73, 43.05, 'd'), + (-2.36, 41.20, 'd'), + (-2.15, 40.15, 'd'), + (-1.86, 38.33, 'd'), + (0.21, 27.59, 'd'), + (0.39, 26.55, 'd'), + (1.27, 21.71, 'd'), + (1.45, 20.68, 'd'), + (2.03, 17.63, 'd'), + (2.20, 16.76, 'd'), + (2.55, 14.71, 'd'), + (2.73, 13.71, 'd'), + (3.47, 9.77, 'd'), + (3.65, 8.72, 'd'), + (3.57, 8.57, 'w'), + (3.37, 8.47, 'o'), + (3.55, 8.36, 'w'), + (3.69, 7.77, 'w'), + (10.17, 9.07, 'd'), + (10.84, 9.22, 'd'), + (11.15, 9.26, 'w'), + (11.41, 7.69, 'o'), + (9.84, 7.42, 'o'), + (9.86, 7.13, 'o'), + (8.93, 6.92, 'w'), + (4.24, 6.03, 'w'), + (4.67, 3.71, 'w'), + (4.32, 3.67, 'w'), + (4.39, 3.06, 'w'), + (4.51, 3.06, 'w'), + (4.74, 2.60, 'd'), + (4.92, 1.66, 'd'), + (5.02, 0.51, 'w'), + (9.30, 1.29, 'o'), + (9.72, -0.94, 'o'), + (9.05, -1.10, 'w'), + (9.06, -1.45, 'w'), + (6.17, -2.01, 'w'), + (6.52, -4.03, 'w'), + (6.45, -4.05, 'w'), + (6.50, -4.50, 'w'), + (9.94, -3.77, 'w'), + (9.95, -3.89, 'w'), + (10.83, -3.71, 'd'), + (11.92, -3.51, 'd'), + (17.56, -2.29, 'd'), + (18.44, -2.14, 'd'), + (19.26, -1.97, 'd'), + (20.21, -1.78, 'd'), + (23.86, -1.13, 'd'), + (25.34, -0.83, 'd'), + (28.09, -0.28, 'd'), + (29.82, 0.07, 'd'), + (40.00, 2.07, 'd'), + (41.81, 2.44, 'd'), + (43.03, 2.60, 'w'), + (43.09, 2.40, 'd'), + (43.48, 0.52, 'd'), + (43.46, 0.25, 'w'), + (41.95, -0.13, 'd'), + (41, 30, -0.27, 'd'), + (26.30, -3.27, 'd'), + (24.50, -3.59, 'd'), + (18.94, -4.73, 'd'), + (18.08, -4.88, 'd'), + (17.58, -4.85, 'd'), + (16.04, -5.18, 'd'), + (13.85, -5.57, 'd'), + (12.02, -5.92, 'd'), + (11.52, -6.03, 'd'), + (10.79, -6.16, 'd'), + (6.10, -7.13, 'o'), + (6.33, -7.17, 'w'), + (7.67, -14.21, 'w'), + (7.38, -14.38, 'o'), + (7.69, -14.44, 'w'), + (8.52, -18.04, 'o'), + (8.71, -18.86, 'o'), + (9.73, -24.79, 'd'), + (9.92, -25.76, 'd'), + (9.93, -26.30, 'd'), + (10.06, -26.98, 'd'), + (10.34, -28.52, 'd'), + (10.71, -30.30, 'd'), + (11.00, -31.65, 'd'), + (11.23, -32.71, 'd'), + (11.32, -33.14, 'd'), + (11.54, -34.20, 'd'), + (12.55, -39.46, 'd'), + (12.70, -40.55, 'd'), + (12.74, -40.92, 'd'), + (13.12, -42.85, 'd'), + (13.79, -45.40, 'd'), + (14.12, -47.14, 'd'), + (14.67, -49.95, 'd'), + (15.81, -56.33, 'w'), + (15.51, -56.51, 'd'), + (13.60, -56.78, 'd'), + (13.43, -56.84, 'w'), + (13.22, -56.27, 'd'), + (12.84, -54.38, 'd'), + (12.35, -51.86, 'd'), + (12.22, -50.81, 'd'), + (11.39, -46.87, 'd'), + (11.25, -45, 97, 'd'), + (11.16, -45.49, 'd'), + (11.00, -44.68, 'd'), + (10.79, -43.64, 'd'), + (10.43, -41.92, 'd'), + (8.21, -30.72, 'd'), + (7.87, -29.00, 'd'), + (6.16, -19.54, 'd'), + (5.96, -18.50, 'd'), + (5.30, -14.92, 'w'), + (5.40, -14.82, 'o'), + (5.24, -14.70, 'w'), + (5.15, -14.35, 'd'), + (4.95, -13.30, 'd'), + (4.31, -10.33, 'd'), + (4.15, -9.33, 'd'), + (4.12, -8.83, 'd'), + (3.97, -7.82, 'd'), + (3.96, -7.57, 'w'), + (4.25, -7.48, 'o'), + (4.07, -7.34, 'w'), + (3.70, -5.18, 'w'), + (3.32, -5.20, 'd'), + (2.34, -5.38, 'd'), + (2.20, -5.38, 'w'), + (1.58, -2.13, 'w'), + (1.33, -2.18, 'd'), + (-2.84, -2.99, 'd'), + (-3.03, -3.02, 'w'), + (-2.90, -4.01, 'w'), + (-3.93, -4.25, 'w'), + (-4.18, -3.08, 'd'), + (-4.57, -1.09, 'd'), + ] + + for el in enclosure: + if el[2] in inc: + obs.append((el[1], el[0])) + + for el in column: + if el[2] in inc: + col.append((el[1], el[0])) + + # obstacle += [geometry.Polygon(obs)] + obstacle += [geometry.Polygon(col)] + + world = World(obstacles=obstacle, boundary=geometry.Polygon(obs)) + + return world diff --git a/modules/vertexnav/vertexnav/environments/simulated.py b/modules/vertexnav/vertexnav/environments/simulated.py new file mode 100644 index 0000000..913e02b --- /dev/null +++ b/modules/vertexnav/vertexnav/environments/simulated.py @@ -0,0 +1,623 @@ +import math +import numpy as np +import random +import shapely +import shapely.prepared +from shapely import geometry + +import vertexnav +from vertexnav.world import World +from unitybridge import UnityBridge + + +class WorldBuildingUnityBridge(UnityBridge): + """Connection between World object and unity""" + def make_world(self, world): + """Build world in unity""" + for obstacle in world.obstacles: + xs, ys = obstacle.exterior.xy + + def chunks(lst, n): + """Yield successive n-sized chunks from lst.""" + n = max(1, n) + for i in range(0, len(lst), n): + if i == 0: + yield lst[i:i + n] + else: + yield lst[i - 1:i + n] + + for lls in chunks(list(zip(xs, ys)), 10): + coords = "" + for x, y in lls: + coords += " {} {}".format(y, x) + message = "main_builder poly" + coords + print(message) + self.send_message(message) + + self._add_clutter(world) + + def _add_clutter(self, world): + """Add clutter to unity sim""" + for pose in world.clutter_element_poses: + self.create_object(command_name='clutter', + pose=pose, + height=random.random() * 6.0 - 4.0) + + def regenerate_clutter(self, world): + # Clear old clutter + self.send_message("main_builder reset_clutter") + # Make new clutter and publish + world.regenerate_clutter() + self._add_clutter(world) + + def move_object_to_pose(self, object_name, pose): + self.send_message("{} move {} {} {} {}".format(object_name, pose.y, + 1.5, pose.x, pose.yaw)) + + +def get_hallway_segment(start_point, end_point, width=20): + """Gets a hallway segment that extends from a start point to an end + point (each a 2-element python list or numpy array) with a specified + width. The return type is a shapely Polygon.""" + sp = np.array(start_point) + ep = np.array(end_point) + s_to_e = ep - sp + s_to_e = s_to_e / np.linalg.norm(s_to_e) * width * 0.5 + s_to_e_perp = np.array([s_to_e[1], -s_to_e[0]]) + + return geometry.Polygon([ + sp - s_to_e - s_to_e_perp, sp - s_to_e + s_to_e_perp, + ep + s_to_e + s_to_e_perp, ep + s_to_e - s_to_e_perp + ]) + + +def build_hallway_from_path(path, width=20, do_enforce_hallway=True): + """Creates a simple 'hallway' map by connecting segments that follow a + provided path. Note that this path does *not* need to be the one that + the robot ultimately follows. The 'width' parameter controls the width + of the hallway (and the size of the 'end caps' on each segment). + + The 'do_enforce_hallway' flag ensures that the hallway never intersects + itself; if set to false, the hallway will be built regardless of the + properties of the input path.""" + + # First collect the individual segments + segments = [] + for sp, ep in zip(path[:-1], path[1:]): + segment = get_hallway_segment(sp, ep, width=width) + segments.append(segment) + + # Loop through segments and ensure that each segment only collides + # with its immediate proceeding neighbor. + poly = None + for s_old, s_new in zip(segments[:-1], segments[1:]): + if poly is None: + poly = s_old + elif do_enforce_hallway and poly.distance(s_new) < 0.0001: + raise ValueError("Hallway intersects itself.") + poly = poly.union(s_old) + # Add the final segment + poly = poly.union(segments[-1]) + + # Handle if the polygon has an interior; any interior 'rings' are + # converted to Polygons and returned as obstacles. This will only + # matter if do_enforce_hallway == False. + obstacles = [ + vertexnav.utils.calc.full_simplify_shapely_polygon( + geometry.Polygon(interior)) for interior in list(poly.interiors) + ] + + # Simplify the polygon + boundary = vertexnav.utils.calc.full_simplify_shapely_polygon(poly) + + return obstacles, boundary + + +def gen_hallway_path(num_segments, hall_width): + """Generate a random path (for a hallway).""" + unit_direction = np.array([1.0, 0.0]) + path = np.array([[0.0, 0.0]]) + for seg_ind in range(num_segments): + seg_length = random.uniform(2 * hall_width, 5 * hall_width) + path = np.append(path, [path[-1] + seg_length * unit_direction], + axis=0) + + # Randomly rotate the direction + if random.random() > 0.5: + unit_direction = np.array([unit_direction[1], unit_direction[0]]) + else: + unit_direction = np.array([unit_direction[1], -unit_direction[0]]) + + return path + + +class HallwayWorld(World): + """Constructs a simulated hallway world.""" + def __init__(self, + hall_width=20, + num_segments=6, + num_attempts=10000, + num_clutter_elements=0, + min_clutter_signed_distance=0.0, + max_clutter_signed_distance=1.0, + do_enforce_hallway=True): + # Construct a hallway + for _ in range(num_attempts): + path = gen_hallway_path(num_segments, hall_width) + + try: + obstacles, boundary = build_hallway_from_path( + path, + width=hall_width, + do_enforce_hallway=do_enforce_hallway) + self.path = path + super(HallwayWorld, self).__init__(obstacles=obstacles, + boundary=boundary) + break + except ValueError: + pass + + else: + raise RuntimeError("Failed to generate hallway map " + + "in {} attempts".format(num_attempts)) + + # Add clutter (intersects walls) + self.clutter_element_poses = [] + while len(self.clutter_element_poses) < num_clutter_elements: + pose = self.get_random_pose( + min_signed_dist=min_clutter_signed_distance) + signed_dist = self.get_signed_dist(pose) + if signed_dist <= max_clutter_signed_distance \ + and signed_dist >= min_clutter_signed_distance: + self.clutter_element_poses.append(pose) + + +class OutdoorWorld(World): + """Constructs a simulated outdoor world with buildings and trees""" + def __init__(self, + hall_width=20, + inflate_ratio=0, + num_attempts=10000, + num_clutter_elements=30, + min_signed_distance=25.0, + max_signed_distance=40.0, + min_clutter_signed_distance=15.0, + max_clutter_signed_distance=40.0, + num_buildings=8): + + self.num_clutter_elements = num_clutter_elements + self.min_signed_distance = min_signed_distance + self.max_signed_distance = max_signed_distance + self.min_clutter_signed_distance = min_clutter_signed_distance + self.max_clutter_signed_distance = max_clutter_signed_distance + self.clutter_element_data = None + + obs_command = [] + obstacles = [] + + def is_new_obs_acceptable(all_obstacles, new_obs): + if len(all_obstacles) == 0: + return True, random.random() + min_signed_distance + + dists = [obs.distance(new_obs) for obs in all_obstacles] + current_closest = min(dists) + tot_dist = sum(sorted(dists)[0:3]) + + if (current_closest > min_signed_distance + and current_closest < max_signed_distance): + return True, 0 * current_closest + tot_dist / len(dists[0:3]) + else: + return False, None + + def get_random_building(): + bld_name = random.choice(["A1", "E1", "E5"]) + # rot_deg = random.choice([0, 90, 180, 270]) + rot_deg = random.random() * 360.0 + pot_obs_cmd = [ + bld_name, 300 * random.random() - 150, + 300 * random.random() - 20, 2.0 + 1.5 * random.random(), + 2.0 + 1.5 * random.random(), rot_deg + ] + if bld_name == "A1": + pot_obs_cmd[3] *= 0.5 + pot_obs_cmd[4] *= 0.5 + pot_obs = _get_bld_A1(*pot_obs_cmd[1:]) + elif bld_name == "E1": + pot_obs = _get_bld_E1(*pot_obs_cmd[1:]) + elif bld_name == "E5": + pot_obs_cmd[3] *= 1.5 + pot_obs_cmd[4] *= 1.5 + pot_obs = _get_bld_E5(*pot_obs_cmd[1:]) + else: + raise ValueError( + "Building type '{}' not allowed.".format(bld_name)) + + return pot_obs_cmd, pot_obs + + while len(obs_command) < num_buildings: + blds = [get_random_building() for _ in range(1000)] + dists = [is_new_obs_acceptable(obstacles, b[1]) for b in blds] + accepted = [(b[0], b[1], d[1]) for b, d in zip(blds, dists) + if d[0]] + + if len(accepted) == 0: + continue + + pot_obs_cmd, pot_obs, _ = min(accepted, key=lambda a: a[2]) + + print((pot_obs, obs_command)) + if is_new_obs_acceptable(obstacles, pot_obs): + obs_command.append(pot_obs_cmd) + obstacles.append(pot_obs) + + minx = 1e8 + maxx = -1e8 + miny = 1e8 + maxy = -1e8 + for obs in obstacles: + x1, y1, x2, y2 = obs.bounds + minx = min(minx, x1, x2) + maxx = max(maxx, x1, x2) + miny = min(miny, y1, y2) + maxy = max(maxy, y1, y2) + + self._map_bounds = ((minx, maxx), (miny, maxy)) + + self.obs_command = obs_command + super(OutdoorWorld, self).__init__(obstacles=obstacles) + + # Overwrite default values for area + self.boundary_poly = shapely.geometry.Polygon([(minx, miny), + (maxx, miny), + (maxx, maxy), + (minx, maxy)]) + self.known_space_poly = self.boundary_poly + for obs in obstacles: + self.known_space_poly = self.known_space_poly.difference(obs) + self.area = self.known_space_poly.area + + # Generate the clutter + self.regenerate_clutter() + + def get_nearby_clutter(self, robot_pose, dist_threshold): + def pose_dist(pa, pb): + return math.sqrt((pa.x - pb.x)**2 + (pa.y - pb.y)**2) + + return [ + p for p in self.clutter_element_poses + if pose_dist(p, robot_pose) <= dist_threshold + ] + + def regenerate_clutter(self): + # Add clutter + self.clutter_element_poses = [] + while len(self.clutter_element_poses) < self.num_clutter_elements: + pose = self.get_random_pose( + min_signed_dist=self.min_clutter_signed_distance, + max_signed_dist=self.max_clutter_signed_distance) + signed_dist = self.get_signed_dist(pose) + if signed_dist <= self.max_clutter_signed_distance \ + and signed_dist >= self.min_clutter_signed_distance: + self.clutter_element_poses.append(pose) + + @property + def map_bounds(self): + return self._map_bounds + + def compute_iou(self, known_space_poly): + """For the outdoor world, the IoU is computed differently.""" + try: + known_space_poly = known_space_poly.buffer(0.1, + resolution=0, + cap_style=3, + join_style=2) + interior_ksp = shapely.geometry.Polygon() + if isinstance(known_space_poly, shapely.geometry.Polygon): + for poly in list(known_space_poly.interiors): + interior_ksp = interior_ksp.union(geometry.Polygon(poly)) + + interior_ksp = interior_ksp.buffer(0.1, + resolution=0, + cap_style=3, + join_style=2) + + intersection = self.obs_poly.intersection(interior_ksp).area + union = self.obs_poly.union(interior_ksp).area + return intersection / union + except: # noqa + print("IoU failed!") + return 0.00001 + + +class OutdoorBuildingUnityBridge(WorldBuildingUnityBridge): + """Unity Bridge for outdoor world""" + def make_world(self, world, scale=10.0): + for cmd in world.obs_command: + message = 'main_builder bld {} {} {} {} {} {}'.format(*cmd) + self.send_message(message) + + self._add_clutter(world) + + def _add_clutter(self, world): + for pose in world.clutter_element_poses: + self.create_object(command_name=random.choice(['tree', + 'tree_alt']), + pose=pose, + height=0.0) + + def move_object_to_pose(self, object_name, pose): + self.send_message("{} move {} {} {} {}".format(object_name, pose.y, + 2.5, pose.x, pose.yaw)) + + +class OccupancyGridWorld(World): + """Use occupancy grid to improve planning efficiency""" + def __init__(self, + grid, + map_data, + num_breadcrumb_elements=500, + min_breadcrumb_signed_distance=4.0): + self.grid = (1.0 - grid.T) # Differences in occupancy value + self.map_data = map_data + self.resolution = map_data['resolution'] + print(f"OGW resolution: {map_data['resolution']}") + + obstacles, boundary = vertexnav.utils.calc.obstacles_and_boundary_from_occupancy_grid( + self.grid, self.resolution) + + self.x = (np.arange(0, self.grid.shape[0]) + 0.0) * self.resolution + self.y = (np.arange(0, self.grid.shape[1]) + 0.0) * self.resolution + + super(OccupancyGridWorld, self).__init__(obstacles=obstacles, + boundary=boundary) + + # Add clutter (intersects walls) + self.breadcrumb_element_poses = [] + while len(self.breadcrumb_element_poses) < num_breadcrumb_elements: + pose = self.get_random_pose( + min_signed_dist=min_breadcrumb_signed_distance, + semantic_label='goal_path') + signed_dist = self.get_signed_dist(pose) + if signed_dist >= min_breadcrumb_signed_distance: + self.breadcrumb_element_poses.append(pose) + + def get_random_pose(self, + xbounds=None, + ybounds=None, + min_signed_dist=0, + num_attempts=10000, + semantic_label=None): + """Get a random pose in the world, respecting the signed distance + to all the obstacles. + + Each "bound" is a N-element list structured such that: + + > xmin = min(xbounds) + > xmax = max(xbounds) + + "num_attempts" is the number of trials before an error is raised. + + """ + + for _ in range(num_attempts): + pose = super(OccupancyGridWorld, + self).get_random_pose(xbounds, ybounds, + min_signed_dist, num_attempts) + if semantic_label is None: + return pose + + # FIXME: Unsure quite why this flip is necessary... + pose_cell_x = np.argmin(np.abs(self.y - pose.x)) + pose_cell_y = np.argmin(np.abs(self.x - pose.y)) + + grid_label_ind = self.map_data['semantic_grid'][pose_cell_x, + pose_cell_y] + if grid_label_ind == self.map_data['semantic_labels'][ + semantic_label]: + return pose + else: + raise ValueError("Could not find random point within bounds") + + def get_grid_from_poly(self, known_space_poly, proposed_world=None): + known_space_poly = known_space_poly.buffer(self.resolution / 2) + mask = -1 * np.ones(self.grid.shape) + + for ii in range(mask.shape[0]): + for jj in range(mask.shape[1]): + p = shapely.geometry.Point(self.y[jj], self.x[ii]) + if known_space_poly.contains(p): + mask[ii, jj] = 1 + + out_grid = -1.0 * np.ones(mask.shape) + # out_grid[mask == 1] = self.grid[mask == 1] + # out_grid[np.logical_and(mask == 1, self.grid == 1)] = 0.0 + # out_grid[np.logical_and(mask == 1, self.grid == 0)] = 1.0 + out_grid[mask == 1] = 0.0 + + if proposed_world is not None: + for v in proposed_world.vertices: + cell_y = np.argmin(np.abs(self.y - v[0])) + cell_x = np.argmin(np.abs(self.x - v[1])) + out_grid[cell_x, cell_y] = 1.0 + + for w in proposed_world.walls: + ys = np.linspace(w[0][0], w[1][0], 100) + xs = np.linspace(w[0][1], w[1][1], 100) + + for x, y in zip(xs, ys): + cell_x = np.argmin(np.abs(self.x - x)) + cell_y = np.argmin(np.abs(self.y - y)) + out_grid[cell_x, cell_y] = 1.0 + + return out_grid.T + + +def get_poly_from_base_points(func): + def transform_points(tx, tz, sx, sy, rot_deg): + points = func() + st = math.sin(math.radians(-rot_deg)) + ct = math.cos(math.radians(-rot_deg)) + + scaled_points = [(sy * p[0], sx * p[1]) for p in points] + + rotated_points = [(ct * p[0] + st * p[1], -st * p[0] + ct * p[1]) + for p in scaled_points] + + return geometry.Polygon([(tz + rp[0], tx + rp[1]) + for rp in rotated_points]) + + return transform_points + + +@get_poly_from_base_points +def _get_bld_E1(): + return [ + (-10.5, 10.5), + (3.5, 10.5), + (3.5, 3.5), + (10.5, 3.5), + (10.5, -10.5), + (-10.5, -10.5), + ] + + +@get_poly_from_base_points +def _get_bld_E5(): + return [ + (7.0, -3.5), + (7.0, 3.5), + (-7.0, 3.5), + (-7.0, -3.5), + ] + + +@get_poly_from_base_points +def _get_bld_A1(): + return [ + (-14.1, 14.1), + (14.1, 14.1), + (14.1, -14.1), + (-14.1, -14.1), + ] + return [ + (-14.3, 14.3), + (14.3, 14.3), + (14.3, -14.3), + (-14.3, -14.3), + ] + + +def get_world_guardian_center(): + """Guardian Center for UNITY""" + # A square + # bld1 = geometry.Polygon([]) + + bld = [] + # Regions numbered in "reading order": across rows starting at top + + # Region 1 + bld += [ + geometry.Polygon([ + (63.44, -52.08), + (75.94, -64.54), + (73.1, -67.32), + (79.35, -73.49), + (73.79, -79.23), + (73.39, -79.01), + (66.16, -86.11), + (59.17, -79.22), + (66.34, -72.06), + (54.97, -60.49), + ]) + ] + bld += [_get_bld_E1(tx=-48.9, tz=84.1, sx=0.5952, sy=1.1291, rot_deg=45)] + + # Region 2 + bld += [_get_bld_E1(tx=-9.3, tz=105.3, sx=1.1618, sy=0.6061, rot_deg=45)] + bld += [_get_bld_A1(tx=21.4, tz=123.1, sx=0.337, sy=1.19, rot_deg=45)] + bld += [ + geometry.Polygon([(147.55, 21.09), (164.28, 4.46), (146.53, -13.4), + (145.84, -12.71), (129.28, -29.27), (119.48, -19.47), + (136.06, -2.89), (129.78, 3.39)]) + ] + + # Region 3 + bld += [_get_bld_E1(tx=7.6, tz=-1.8, sx=0.5524, sy=1.2164, rot_deg=90.0)] + bld += [_get_bld_E5(tx=-27.43, tz=38.77, sx=1.714, sy=1.718, rot_deg=45)] + bld += [_get_bld_E1(tx=-37.1, tz=15.3, sx=1.2067, sy=0.5881, rot_deg=45)] + bld += [_get_bld_E1(tx=-5.9, tz=48, sx=1.1453, sy=0.6232, rot_deg=45)] + bld += [_get_bld_E5(tx=30.7, tz=19.9, sx=3.2857, sy=0.8638, rot_deg=90)] + + # Region 4 + bld += [ + geometry.Polygon([ + (73.23, 11.27), + (55.23, 29.27), + (63.03, 37.07), + (80.23, 19.87), + (92.35, 31.99), + (94.73, 29.61), + (102.14, 37.02), + (106.8, 32.36), + (84.59, 10.15), + (78.39, 16.35), + ]) + ] + + # Region 5 + bld += [_get_bld_E1(tx=63.22, tz=5.13, sx=1.0717, sy=0.6243, rot_deg=90)] + bld += [_get_bld_E1(tx=72.15, tz=25.87, sx=0.5714, sy=1.239, rot_deg=90)] + bld += [_get_bld_E1(tx=99.92, tz=27.49, sx=0.6333, sy=1.1067, rot_deg=90)] + bld += [_get_bld_E1(tx=108.9, tz=5.64, sx=1.16, sy=0.5971, rot_deg=90)] + + # Region 6 + bld += [_get_bld_E5(tx=66.3, tz=75.6, sx=1.644, sy=1.660, rot_deg=-90)] + bld += [_get_bld_A1(tx=98.3, tz=70.1, sx=0.8596, sy=1.2158, rot_deg=90)] + bld += [_get_bld_E1(tx=75.4, tz=99, sx=0.619, sy=1.147, rot_deg=90)] + bld += [_get_bld_E1(tx=99.7, tz=99, sx=0.619, sy=1.147, rot_deg=90)] + + # Region 7 + bld += [_get_bld_E5(tx=85, tz=128.5, sx=1.573, sy=1.7157, rot_deg=90)] + bld += [_get_bld_A1(tx=108, tz=145.7, sx=0.8596, sy=0.4924, rot_deg=90)] + + # Region 8 + bld += [_get_bld_A1(tx=141, tz=19, sx=0.8772, sy=0.4737, rot_deg=90)] + bld += [_get_bld_A1(tx=163, tz=29, sx=0.4211, sy=0.9480, rot_deg=90)] + bld += [_get_bld_A1(tx=184, tz=18, sx=1.2193, sy=0.4386, rot_deg=90)] + + # Region 9 + bld += [_get_bld_E5(tx=149, tz=59, sx=1.145, sy=2.5, rot_deg=90)] + bld += [_get_bld_A1(tx=182, tz=56, sx=0.5614, sy=0.7368, rot_deg=90)] + bld += [_get_bld_A1(tx=137, tz=85, sx=1.0351, sy=0.3864, rot_deg=90)] + bld += [_get_bld_E1(tx=184, tz=91, sx=1.1667, sy=0.5952, rot_deg=90)] + + # Region 10 + bld += [_get_bld_E1(tx=137, tz=134, sx=1.1669, sy=0.5971, rot_deg=90)] + bld += [_get_bld_A1(tx=161, tz=131, sx=1.2357, sy=0.35087, rot_deg=0)] + bld += [_get_bld_E1(tx=185, tz=134, sx=1.1669, sy=0.5971, rot_deg=90)] + + return World(obstacles=bld) + + +def get_world_mit_north_court(): + """MIT north court environment""" + bld = [] + + bld.append( + geometry.Polygon([ + (-57.25, 82.95), + (-67.5, 170.7), + (-97.2, 100.3), + (-80.8, 96.7), + (-87, 81.2), + (-92.5, 82.9), + (-144.5, -38.3), + (-128.6, -44.7), + (-105, 12.2), + (-101.7, 11.2), + (-75.3, 76), + (-83.8, 79.6), + (-78.2, 91.6), + ])) + + return World(obstacles=bld) diff --git a/modules/vertexnav/vertexnav/learning.py b/modules/vertexnav/vertexnav/learning.py new file mode 100644 index 0000000..de037df --- /dev/null +++ b/modules/vertexnav/vertexnav/learning.py @@ -0,0 +1,67 @@ +import numpy as np +import vertexnav + + +def get_vertex_datum_for_pose(pose, + world, + unity_bridge, + max_range, + num_range, + num_bearing, + min_range=None, + pano_image=None): + """Get all relevant data for a single pose.""" + if unity_bridge is not None: + unity_bridge.move_object_to_pose("robot", pose) + pano_image = unity_bridge.get_image("robot/pano_camera") + pano_image = vertexnav.utils.convert.image_aligned_to_robot( + pano_image, pose) / 255 + pishape = pano_image.shape + + # Reshape the image if necessary and error handling + if 2 * pishape[0] == pishape[1]: + pano_image = pano_image[pishape[0] // 4:3 * pishape[0] // 4] + elif not 4 * pishape[0] == pishape[1]: + raise ValueError(f"Image aspect ratio unsupported (shape {pishape})") + + pano_depth_image = unity_bridge.get_image("robot/pano_depth_camera") + pano_depth_image = vertexnav.utils.convert.depths_from_depth_image( + pano_depth_image) + sh = pano_depth_image.shape + minimum_range = min(pano_depth_image[sh[0] // 2]) + if min_range is not None and minimum_range < min_range: + print("FAILED: within minimum range.") + return None + + pano_depth_image = pano_depth_image[sh[0] // 4:3 * sh[0] // 4] + pano_depth_image = vertexnav.utils.convert.image_aligned_to_robot( + pano_depth_image, pose) + + perfect_gap_obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(pose, max_range=max_range), + pose, + do_add_noise=False) + + vertex_data = vertexnav.utils.convert.get_vertex_grid_data_from_obs( + observation=perfect_gap_obs, + size=pano_image.shape[1], + pose=pose, + max_range=max_range, + num_range=num_range, + num_bearing=num_bearing) + + return { + 'pose_x': pose.x, + 'pose_y': pose.y, + 'pose_yaw_rad': pose.yaw, + 'image': pano_image, + 'depth': pano_depth_image.astype(np.float32), + 'image_size': pano_image.shape[:2], + 'output_size': vertex_data['is_vertex'].shape, + 'is_vertex': vertex_data['is_vertex'], + 'is_left_gap': vertex_data['is_left_gap'], + 'is_right_gap': vertex_data['is_right_gap'], + 'is_corner': vertex_data['is_corner'], + 'is_point_vertex': vertex_data['is_point_vertex'], + 'is_in_view': vertex_data['is_in_view'], + } diff --git a/modules/vertexnav/vertexnav/models.py b/modules/vertexnav/vertexnav/models.py new file mode 100644 index 0000000..b13141d --- /dev/null +++ b/modules/vertexnav/vertexnav/models.py @@ -0,0 +1,230 @@ +import numpy as np +import torch +import torch.nn as nn +import torch.nn.functional as F + +from learning.logging import tensorboard_plot_decorator + + +class EncoderNBlocks(nn.Module): + def __init__(self, in_channels, out_channels, num_layers): + super(EncoderNBlocks, self).__init__() + nin = in_channels + nout = out_channels + modules = [] + + # First layer + modules.append(nn.Conv2d(nin, nout, kernel_size=3, stride=1, + padding=1)) + modules.append(nn.BatchNorm2d(nout)) + modules.append(nn.LeakyReLU(0.1, inplace=True)) + + # Add remaining layers + for ii in range(1, num_layers): + modules.append( + nn.Conv2d(nout, nout, kernel_size=3, stride=1, padding=1)) + modules.append(nn.BatchNorm2d(nout)) + modules.append(nn.LeakyReLU(0.1, inplace=True)) + + modules.append(nn.MaxPool2d(kernel_size=2, stride=2)) + + self.cnn_layers = nn.Sequential(*modules) + + def forward(self, x): + return self.cnn_layers(x) + + +class DecoderNBlocks(nn.Module): + def __init__(self, in_channels, out_channels, num_layers): + super(DecoderNBlocks, self).__init__() + nin = in_channels + nout = out_channels + modules = [] + + # Define the per-layer strides + strides = [1] * num_layers + strides[-1] = 2 + + # First layer + modules.append(nn.Conv2d(nin, nout, kernel_size=3, stride=1, + padding=1)) + modules.append(nn.BatchNorm2d(nout)) + modules.append(nn.LeakyReLU(0.1, inplace=True)) + + # Add remaining layers + for ii in range(1, num_layers): + if strides[ii] > 1: + modules.append( + nn.ConvTranspose2d(nout, + nout, + kernel_size=3, + stride=strides[ii], + output_padding=1)) + else: + modules.append( + nn.ConvTranspose2d(nout, + nout, + kernel_size=3, + stride=strides[ii])) + modules.append(nn.BatchNorm2d(nout)) + modules.append(nn.LeakyReLU(0.1, inplace=True)) + + self.cnn_layers = nn.Sequential(*modules) + + def forward(self, x): + return self.cnn_layers(x)[:, :, 1:-1, 1:-1] + + +class VertexNavGrid(nn.Module): + name = "VertexNavGrid" + ROLL_VARIABLES = [ + 'image', 'is_vertex', 'is_right_gap', 'is_corner', 'is_left_gap', + 'is_point_vertex' + ] + + def __init__(self, args=None): + super(VertexNavGrid, self).__init__() + self._args = args + + # Initialize the blocks + self.enc_1 = EncoderNBlocks(3, 64, num_layers=2) + self.enc_2 = EncoderNBlocks(64, 64, num_layers=2) + self.enc_3 = EncoderNBlocks(64, 128, num_layers=2) + self.enc_4 = EncoderNBlocks(128, 128, num_layers=2) + self.enc_5 = EncoderNBlocks(128, 256, num_layers=2) + + self.dec_1 = DecoderNBlocks(256, 128, num_layers=2) + self.dec_2 = DecoderNBlocks(128, 64, num_layers=2) + self.dec_3 = DecoderNBlocks(64, 64, num_layers=2) + self.conv_out = nn.Conv2d(64, 5, kernel_size=1) + self.goal_bn = nn.BatchNorm2d(2) + + def forward(self, data, device): + image = data['image'].to(device) + x = image + + # Encoding layers + x = self.enc_1(x) + x = self.enc_2(x) + x = self.enc_3(x) + x = self.enc_4(x) + x = self.enc_5(x) + + # Decoding layers + x = self.dec_1(x) + x = self.dec_2(x) + x = self.dec_3(x) + + # Output layer + x = self.conv_out(x) + + return x + + def loss(self, nn_out, data, device='cpu', writer=None, index=None): + def masked_reduce_mean(data, mask): + mask = (mask > 0.5).float() + mask_sum = torch.sum(mask) + data_sum = torch.sum(data * mask) + return data_sum / (mask_sum + 1) + + rpw = self._args.relative_positive_weight + + # Compute the contribution from is_vertex + is_vertex_logits = nn_out[:, 0, :, :] + is_vertex_label = data['is_vertex'].to(device) + is_vertex_xentropy = rpw * is_vertex_label * -F.logsigmoid(is_vertex_logits) + \ + (1 - is_vertex_label) * -F.logsigmoid(-is_vertex_logits) + is_vertex_xentropy = torch.mean(is_vertex_xentropy) + + # Separate outputs. + is_label_logits = nn_out[:, 1:, :, :] + is_right_gap = data['is_right_gap'].to(device) + is_corner = data['is_corner'].to(device) + is_left_gap = data['is_left_gap'].to(device) + is_point_vertex = data['is_point_vertex'].to(device) + is_label_label = torch.stack( + [is_right_gap, is_corner, is_left_gap, is_point_vertex], axis=1) + is_label_logsoftmax = torch.nn.LogSoftmax(dim=1)(is_label_logits) + is_label_xentropy = -torch.sum(is_label_logsoftmax * is_label_label, + dim=1) + is_label_xentropy = masked_reduce_mean(is_label_xentropy, + is_vertex_label) + + loss = self._args.vertex_pred_weight * is_vertex_xentropy + is_label_xentropy + + # Logging + if writer is not None: + writer.add_scalar("Loss/is_vertex_xentropy", + is_vertex_xentropy.item(), index) + writer.add_scalar("Loss/total_loss", loss.item(), index) + + return loss + + @tensorboard_plot_decorator + def plot_images(self, fig, image, out, data): + image = np.transpose(image, (1, 2, 0)) + + is_vertex_pred = torch.sigmoid(out[0, :, :]).cpu().numpy() + is_vertex_label = data['is_vertex'][0] + + is_label_pred = torch.softmax(out[1:, :, :], dim=0).cpu().numpy() + is_label_pred = np.transpose(is_label_pred, axes=[1, 2, 0]) + + is_right_gap = data['is_right_gap'][0] * 1.0 + is_corner = data['is_corner'][0] * 1.0 + is_left_gap = data['is_left_gap'][0] * 1.0 + is_point_vertex = data['is_point_vertex'][0] * 1.0 + is_label_label = torch.stack( + [is_right_gap, is_corner, is_left_gap, is_point_vertex], + axis=2).numpy() + + is_label_label[:, :, 0][is_vertex_label < 0.5] = float('NaN') + is_label_label[:, :, 1][is_vertex_label < 0.5] = float('NaN') + is_label_label[:, :, 2][is_vertex_label < 0.5] = float('NaN') + + axs = fig.subplots(3, 2) + axs[0, 0].imshow(image, interpolation='none') + axs[1, 0].imshow(is_vertex_label, + interpolation='none', + vmin=0.0, + vmax=1.0) + axs[2, 0].imshow(is_vertex_pred, + interpolation='none', + vmin=0.0, + vmax=1.0) + + axs[0, 1].imshow(image, interpolation='none') + axs[1, 1].imshow(is_label_label[:, :, :3], interpolation='none') + axs[2, 1].imshow(is_label_pred[:, :, :3], interpolation='none') + + @classmethod + def get_net_eval_fn(_, network_file, device, do_return_model=False): + model = VertexNavGrid() + model.load_state_dict(torch.load(network_file, + map_location=torch.device('cpu')), + strict=False) + model.eval() + model.to(device) + + def vertex_net(image): + with torch.no_grad(): + image = np.transpose(image, (2, 0, 1)) + out = model( + { + 'image': + torch.tensor(np.expand_dims(image, axis=0)).float(), + }, + device=device) + + out[0, 0] = torch.sigmoid(out[0, 0]) + out[0, 1:] = torch.softmax(out[0, 1:], dim=0) + out = out.detach().cpu().numpy() + return { + 'is_vertex': out[0, 0], + 'vertex_label': np.transpose(out[0, 1:], axes=(1, 2, 0)) + } + + if do_return_model: + return vertex_net, model + else: + return vertex_net diff --git a/modules/vertexnav/vertexnav/noisy.py b/modules/vertexnav/vertexnav/noisy.py new file mode 100644 index 0000000..ba1fe2a --- /dev/null +++ b/modules/vertexnav/vertexnav/noisy.py @@ -0,0 +1,267 @@ +import math +import numpy as np + +import vertexnav +import vertexnav_accel +import shapely +""" +- Some terminology: +- Vertex is a landmark; a point that defines part of a polygonal boundary +- Detection refers to a single measurement of a landmark +- Observation refers to a set of detections from a single viewpoint; an + observation should be ordered by the image-space 'angle' of the detections. +""" + +NoisyDetectionType = vertexnav_accel.NoisyDetectionType +NoisyVertexDetection = vertexnav_accel.NoisyVertexDetection +HallucinatedVertexDetection = vertexnav_accel.HallucinatedVertexDetection +NoisyVertex = vertexnav_accel.NoisyVertex +NoisyWall = vertexnav_accel.NoisyWall + + +def compute_conservative_space_from_obs(r_pose, + observation, + radius=1000, + vertex_remapping=None): + """Returns a list of points corresponding to the known space polygon +(conservative estimate) from an observation.""" + + if not observation or len(observation) == 1: + return [] + + if isinstance(observation[0], HallucinatedVertexDetection): + # Remapping the vertices is not necessary (and will fail) for + # HallucinatedVertexDetection objects. + def get_position(det): + return det.position + elif isinstance(observation[0], NoisyVertexDetection): + if vertex_remapping is None: + + def get_position(det): + return det.associated_vertex.position + else: + + def get_position(det): + return vertex_remapping[det.associated_vertex.id].position + else: + raise NotImplementedError() + + positions = [get_position(det) for det in observation] + dat = [(p, math.atan2(p[1] - r_pose.y, p[0] - r_pose.x)) + for p in positions] + + dat = sorted(dat, key=lambda d: d[1]) + + shift_dat = dat[1:] + dat[:1] + + poly_points = [] + for (_, high_angle), (pos_R, low_angle) in zip(shift_dat, dat): + if high_angle < low_angle: + high_angle += 2 * math.pi + + poly_points.append(pos_R) + if high_angle - low_angle >= math.pi: + poly_points.append((r_pose.x, r_pose.y)) + + poly_points.append(poly_points[0]) + return poly_points + + +class HypotheticalObservation(list): + def __hash__(self): + raise NotImplementedError() + + +def compute_hypothetical_observation(world, + r_pose, + observation, + radius=1000, + vertex_remapping=None): + """Compute the hypothesized observation given a proposed world, a robot pose, and the actual observation at that point. + +The hypothesized observation should not introduce any new visibility +connections, so the actual observation is used to prune points that were not +observed in the space.""" + # Compute the polygon formed by the observation + poly_points = vertexnav_accel.compute_conservative_space_observed( + r_pose, observation, vertex_remapping) + + if isinstance(world, vertexnav_accel.ProposedWorldCore): + h_vertex_data = world.get_vertices_for_pose(r_pose, poly_points) + else: + h_vertex_data = world.get_vertices_for_pose( + r_pose, do_compute_detection_type=False, bound_points=poly_points) + if not h_vertex_data: + return HypotheticalObservation([]) + + positions = np.array(h_vertex_data) + ds = positions - [r_pose.x, r_pose.y] + angles = np.arctan2(ds[:, 1], ds[:, 0]) + + h_obs = [ + HallucinatedVertexDetection(angle_rad=angle_rad, position=position) + for (position, angle_rad) in zip( + positions, + angles, + ) + ] + h_obs = sorted(h_obs, key=lambda d: d.angle_rad) + + return HypotheticalObservation(h_obs) + + +def get_angle_rad(position, obs_pose): + return math.atan2(position[1] - obs_pose.y, position[0] - obs_pose.x) + + +def get_range(position, obs_pose): + return math.sqrt((position[1] - obs_pose.y)**2 + + (position[0] - obs_pose.x)**2) + + +def prob_of_wall(label1, label2): + # return (1 - label1.prob_left_gap) * (1 - label2.prob_right_gap) + return (1 - 0.5 * (label1.prob_left_gap + label2.prob_right_gap)) + + +def convert_world_obs_to_noisy_detection(world_obs, + pose, + do_add_noise=False, + cov_rt=None): + """Helper function. Convert the output of 'world.get_vertices_for_pose into + the form necessary for working with NoisyVertexGraph (NoisyVertexDetection). + FIXME(gjstein): need to add covariance. + """ + def get_angle_rad(position, obs_pose): + return math.atan2(position[1] - obs_pose.y, + position[0] - obs_pose.x) - obs_pose.yaw + + if do_add_noise: + if cov_rt is None: + raise ValueError("cov_rt must be set when do_add_noise is True") + + noise = np.random.normal(scale=0.01, size=[2]) + else: + noise = np.zeros([2]) + + if cov_rt is None: + obs = [ + HallucinatedVertexDetection( + angle_rad=get_angle_rad(position + noise, pose), + range=get_range(position + noise, pose), + r_pose=pose) for position, detection_label in world_obs + ] + for det, (_, detection_label) in zip(obs, world_obs): + det.detection_type = vertexnav.noisy.NoisyDetectionType( + detection_label) + else: + obs = [ + NoisyVertexDetection( + angle_rad=get_angle_rad(position + noise, pose), + range=get_range(position + noise, pose), + detection_type=NoisyDetectionType(detection_label), + cov_rt=cov_rt) for position, detection_label in world_obs + ] + + return sorted(obs, key=lambda pvd: pvd.angle_rad) + + +def get_visibility_polygon(pose, world, radius=100, is_conservative=True): + """Helper function. Returns the points on the boundary of the visibility + polygon for a given pose. Conservative flag should be kept true. + """ + vertices = world.get_vertices_for_pose(pose) + observation = convert_world_obs_to_noisy_detection(vertices, pose) + + if not vertices: + return [(radius * math.cos(th) + pose.x, + radius * math.sin(th) + pose.y) + for th in np.linspace(0, 2 * math.pi, num=6)] + + shifted_observation = observation[1:] + observation[:1] + + new_walls = [] + for det in observation: + th = det.angle_rad + new_walls.append((det.position, (radius * math.cos(th) + pose.x, + radius * math.sin(th) + pose.y))) + + poly_points = [] + for det_L, det_R in zip(shifted_observation, observation): + + # Get angles for sweep + low_angle, high_angle = det_R.angle_rad, det_L.angle_rad + if high_angle < low_angle: + high_angle += 2 * math.pi + + is_wall = prob_of_wall(det_R.detection_type, + det_L.detection_type) > 0.5 + + does_go_around = False + if high_angle - low_angle >= math.pi: + # observation goes around robot + does_go_around = True + + if is_wall or (is_conservative and not does_go_around): + poly_points.append(det_R.position) + poly_points.append(det_L.position) + else: + for th in np.linspace(low_angle, high_angle, num=3): + poly_points.append((radius * math.cos(th) + pose.x, + radius * math.sin(th) + pose.y)) + + poly_points.append(poly_points[0]) + + if is_conservative: + return poly_points + + point = shapely.geometry.Point(pose.x, pose.y) + polygon = shapely.geometry.Polygon(poly_points) + + def get_angle_rad(position, obs_pose): + return math.atan2(position[1] - obs_pose.y, position[0] - obs_pose.x) + + for wall in world.walls: + angles = (get_angle_rad(wall[0], pose), get_angle_rad(wall[1], pose)) + + ws = shapely.geometry.LineString( + ((2 * radius * math.cos(angles[0]) + pose.x, + 2 * radius * math.sin(angles[0]) + pose.y), wall[0], wall[1], + (2 * radius * math.cos(angles[1]) + pose.x, + 2 * radius * math.sin(angles[1]) + pose.y))) + try: + result = shapely.ops.split(polygon, ws) + except: # noqa + result = [polygon] + for poly in result: + if poly.contains(point): + polygon = poly + + poly_points = list(zip(*polygon.boundary.xy)) + + return poly_points + + +def convert_net_grid_data_to_noisy_detection(net_data, pose, max_range, + num_range, num_bearing, sig_r, + sig_th, nn_peak_thresh): + """Helper function. Convert the output of 'world.get_vertices_for_pose into + the form necessary for working with NoisyVertexGraph (NoisyVertexDetection). + """ + # Lookup vectors + vec_range, vec_bearing = vertexnav.utils.calc.range_bearing_vecs( + max_range, num_range, num_bearing) + out_coords = vertexnav.utils.calc.detect_peaks(net_data['is_vertex'], + is_circular_boundary=True, + peak_thresh=nn_peak_thresh) + + obs = [ + NoisyVertexDetection(angle_rad=vec_bearing[ith], + range=vec_range[ir], + detection_type=NoisyDetectionType( + list(net_data['vertex_label'][ir, ith])), + cov_rt=[[sig_r**2, 0], [0, sig_th**2]]) + for (ir, ith) in out_coords + ] + + return sorted(obs, key=lambda pvd: pvd.angle_rad) diff --git a/modules/vertexnav/vertexnav/planning.py b/modules/vertexnav/vertexnav/planning.py new file mode 100644 index 0000000..416368c --- /dev/null +++ b/modules/vertexnav/vertexnav/planning.py @@ -0,0 +1,517 @@ +import math +import cmath +import numpy as np +import random +import scipy +import shapely + + +class Frontier(): + """ Defines a single frontier between vertices in polygon + + Attributes: + linestring: line connecting vertices + centroid (tuple): position of centroid of linestring + """ + def __init__(self, linestring): + self.linestring = linestring + if isinstance(self.linestring, shapely.geometry.GeometryCollection): + self.centroid = shapely.geometry.Point(10000, 10000) + else: + self.centroid = self.linestring.centroid + + def __hash__(self): + return hash(str(self.linestring)) + + +def get_boundary_vertices_from_poly(known_poly, world, inflation_rad): + """Generates a list of vertices on the boundary of the known poly.""" + boundary = known_poly.boundary + + vpoints = [ + shapely.geometry.Point(vert[0], vert[1]) for vert in world.vertices + ] + boundary_verts = [ + vert for (vert, vpoint) in zip(world.vertices, vpoints) + if boundary.intersects( + vpoint.buffer( + inflation_rad / 10, resolution=8, cap_style=3, join_style=2)) + ] + + return boundary_verts + + +def compute_h_value_for_segment(segment, vertices): + """Generates the 'h_value' (homotopy) for a segment of a path""" + z1 = segment[0] + z2 = segment[1] + h = np.zeros(len(vertices), dtype=np.complex_) + for ii, vertex in enumerate(vertices): + ks = list(range(-2, 3)) + c1 = complex(z1[0] - vertex[0], z1[1] - vertex[1]) + c2 = complex(z2[0] - vertex[0], z2[1] - vertex[1]) + argdiff = cmath.phase(c1) - cmath.phase(c2) + arglist = [argdiff + 2 * k * math.pi for k in ks] + absargmin = np.argmin([abs(arg) for arg in arglist]) + absmin = arglist[absargmin] + h[ii] = complex(math.log(abs(c1)) - math.log(abs(c2)), absmin) + return h + + +def compute_frontiers_from_poly(known_poly, world, inflation_rad): + """Generates a list of frontiers from a known poly and a proposed world.""" + try: + boundary = known_poly.boundary + except: # noqa + return [] + + # Compute the boundary where walls do not exist: + for obs in world.obstacles: + boundary = boundary.difference( + obs.buffer(inflation_rad / 10, + resolution=8, + cap_style=3, + join_style=2)) + + for vert in world.vertices: + vpoint = shapely.geometry.Point(vert[0], vert[1]) + boundary = boundary.difference( + vpoint.buffer(inflation_rad / 10, + resolution=8, + cap_style=3, + join_style=2)) + + if isinstance(boundary, shapely.geometry.MultiLineString): + frontiers = [Frontier(ls) for ls in boundary] + else: + frontiers = [Frontier(boundary)] + + def man_dist_from_point(f, point): + f_cent = f.centroid + return abs(f_cent.x - point[0]) + abs(f_cent.y - point[1]) + + frontiers = sorted(frontiers, + key=lambda f: man_dist_from_point(f, [-3170, 1280])) + + return frontiers + + +def compute_path_length(path): + """Return length of a path""" + return sum([ + math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + for p1, p2 in zip(path[:-1], path[1:]) + ]) + + +def multiagent_select_frontiers_greedy(robots, + frontiers, + visibility_graph, + do_explore, + known_space_poly, + goal=None, + penalty=10000, + nearby_clutter_fn=None, + cl_inflation_rad=None): + """Helper function for planning with multiple agents. + + Computes the cost of planning through each frontier, either to a goal or to + explore, for each agent and uses the Hungarian Matching Algorithm to select + the frontiers that minimize net cost. If fewer frontiers than agents exist, + extra agents will still navigate to their nearest frontier. + """ + + if not do_explore and goal is None: + raise ValueError('If not exploring, goal must be provided') + elif do_explore and known_space_poly is None: + raise ValueError('If exploring, known_space_poly must be provided') + + if not frontiers: + return [] + + # Compute the costs + all_paths_dict = dict() + + def get_path_cost(robot, blocked_frontiers, do_get_clutter=False): + if nearby_clutter_fn and do_get_clutter: + nearby_clutter = nearby_clutter_fn(robot) + else: + nearby_clutter = None + + # Compute cost + if do_explore: + path, cost = visibility_graph.get_shortest_path( + start_point=(robot.pose.x, robot.pose.y), + known_space_poly=known_space_poly, + blocked_frontiers=blocked_frontiers, + do_return_cost=True, + nearby_clutter=nearby_clutter, + cl_inflation_rad=cl_inflation_rad) + else: + path, cost = visibility_graph.get_shortest_path( + start_point=(robot.pose.x, robot.pose.y), + end_point=(goal.x, goal.y), + blocked_frontiers=blocked_frontiers, + do_return_cost=True, + nearby_clutter=nearby_clutter, + cl_inflation_rad=cl_inflation_rad) + + return path, cost + + def get_frontier_for_plan(plan): + plan_ls = shapely.geometry.LineString(plan) + for f in frontiers: + if f.linestring.intersects(plan_ls): + return f + + # First get the costs for all the robot plans + rf_data = dict() + included_frontiers = set() + prev_len = 0 + while len(included_frontiers) < min(len(robots), len(frontiers)): + tmp_frontiers = set() + print((len(robots), len(frontiers), len(included_frontiers))) + for rind, robot in enumerate(robots): + path, cost = get_path_cost(robot, included_frontiers) + local_frontier = get_frontier_for_plan(path) + rf_data[(rind, hash(local_frontier))] = (path, cost) + tmp_frontiers.add(local_frontier) + + included_frontiers.update(tmp_frontiers) + if prev_len == len(included_frontiers): + break + else: + prev_len = len(included_frontiers) + + # Now run the matching algorithm on the result + included_frontiers = list(included_frontiers) + mul = int(math.ceil(1.0 * len(robots) / len(included_frontiers))) + nf = len(included_frontiers) + cost_mat = 10000 * penalty * np.ones([len(robots), mul * nf]) + for rind, robot in enumerate(robots): + for find, frontier in enumerate(included_frontiers): + key = (rind, hash(frontier)) + if key in list(rf_data.keys()): + path, cost = rf_data[key] + + all_paths_dict[(rind, find)] = path + + for ii in range(mul): + cost_mat[rind, find + ii * nf] = cost + ii * penalty + + print(cost_mat) + + finds, rinds = scipy.optimize.linear_sum_assignment(cost_mat.T) + + def get_remaining_frontiers(selected_frontier): + if selected_frontier is None: + return [] + else: + return set(frontiers).difference({selected_frontier}) + + return [ + (included_frontiers[fi % nf], + get_path_cost(robots[ri], + get_remaining_frontiers(included_frontiers[fi % nf]), + do_get_clutter=True)[0], robots[ri]) + for ri, fi in zip(rinds, finds) + ] + + +def multiagent_select_frontiers(robots, + frontiers, + visibility_graph, + do_explore, + known_space_poly, + goal=None, + penalty=10000, + nearby_clutter_fn=None, + cl_inflation_rad=None): + """Helper function for planning with multiple agents. + + Computes the cost of planning through each frontier, either to a goal or to + explore, for each agent and uses the Hungarian Matching Algorithm to select + the frontiers that minimize net cost. If fewer frontiers than agents exist, + extra agents will still navigate to their nearest frontier. + """ + + if not do_explore and goal is None: + raise ValueError('If not exploring, goal must be provided') + elif do_explore and known_space_poly is None: + raise ValueError('If exploring, known_space_poly must be provided') + + if not frontiers: + return [] + + # Compute the costs + mul = int(math.ceil(1.0 * len(robots) / len(frontiers))) + nf = len(frontiers) + cost_mat = np.zeros([len(robots), mul * nf]) + all_paths_dict = dict() + + def get_path_cost(robot, frontier, do_get_clutter=False): + if nearby_clutter_fn and do_get_clutter: + nearby_clutter = nearby_clutter_fn(robot) + else: + nearby_clutter = None + + # Compute cost + if do_explore: + path, cost = visibility_graph.get_shortest_path( + start_point=(robot.pose.x, robot.pose.y), + known_space_poly=known_space_poly, + blocked_frontiers=set(frontiers).difference({frontier}), + do_return_cost=True, + nearby_clutter=nearby_clutter, + cl_inflation_rad=cl_inflation_rad) + else: + path, cost = visibility_graph.get_shortest_path( + start_point=(robot.pose.x, robot.pose.y), + end_point=(goal.x, goal.y), + blocked_frontiers=set(frontiers).difference({frontier}), + do_return_cost=True, + nearby_clutter=nearby_clutter, + cl_inflation_rad=cl_inflation_rad) + + return path, cost + + for rind, robot in enumerate(robots): + for find, frontier in enumerate(frontiers): + path, cost = get_path_cost(robot, frontier) + + all_paths_dict[(rind, find)] = path + + for ii in range(mul): + cost_mat[rind, find + ii * nf] = cost + ii * penalty + + finds, rinds = scipy.optimize.linear_sum_assignment(cost_mat.T) + + return [(frontiers[fi % nf], + get_path_cost(robots[ri], frontiers[fi], + do_get_clutter=True)[0], robots[ri]) + for ri, fi in zip(rinds, finds)] + + # return [(frontiers[fi % nf], all_paths_dict[(ri, fi % nf)], robots[ri]) + # for ri, fi in zip(rinds, finds)] + + +class VisibilityGraph(object): + """Defines the visibility graph for a proposed world + + Arguments: + proposed_world (World object): World defining vertices and walls + inflation_rad (float): How much to inflate obstacles for v-graph + """ + def __init__(self, proposed_world, inflation_rad=0.01): + self._world = proposed_world + self._vertices, self._inflation_obstacles = \ + self._world.get_inflated_vertices(inflation_rad) + self.inflation_rad = inflation_rad + + def get_shortest_path(self, + start_point, + end_point=None, + known_space_poly=None, + blocked_frontiers={}, + do_return_cost=False, + nearby_clutter=None, + cl_inflation_rad=None): + """Return shortest path between two points through visibility graph. If + end point is not specified, sample one at random. Optionally return the + cost of the optimal path. + """ + + cl_inflated_verts = [] + cl_inflated_obstacles = [] + if nearby_clutter: + for cl in nearby_clutter: + print((" CLUTTER: {}".format(cl))) + num_angles = 6 + poly_verts = [] + for th in np.linspace(0, + 2 * math.pi, + num=num_angles, + endpoint=False): + cl_inflated_verts.append( + (cl.x + cl_inflation_rad * math.cos(th), + cl.y + cl_inflation_rad * math.sin(th))) + poly_verts.append( + (cl.x + 0.95 * cl_inflation_rad * math.cos(th), + cl.y + 0.95 * cl_inflation_rad * math.sin(th))) + + cl_inflated_obstacles.append( + shapely.geometry.Polygon(poly_verts)) + + mdist = 100000000.0 + # known_space_poly = known_space_poly.buffer( + # self.inflation_rad/10) + + if end_point is not None: + verts = self._vertices + cl_inflated_verts + [ + start_point, end_point + ] + start_ind = len(verts) - 2 + end_inds = [len(verts) - 1] + elif known_space_poly is not None: + + extra_verts = [] + if isinstance(known_space_poly, shapely.geometry.Polygon): + + def get_random_point(polygon): + """Helper function: returns random point in polygon""" + minx, miny, maxx, maxy = polygon.bounds + for _ in range(1000): + point = shapely.geometry.Point( + random.uniform(minx, maxx), + random.uniform(miny, maxy)) + if polygon.contains(point): + return point + + return None + + for poly in list(known_space_poly.interiors): + point = get_random_point(shapely.geometry.Polygon(poly)) + point = shapely.geometry.Polygon(poly).centroid + if point: + extra_verts.append((point.x, point.y)) + + verts = self._vertices + cl_inflated_verts + extra_verts + [ + start_point + ] + start_ind = len(verts) - 1 + end_inds = [] + if not len(verts): + if do_return_cost: + return ([start_point, start_point], mdist) + else: + return [start_point, start_point] + + for ind, v in enumerate(verts): + if v in cl_inflated_verts: + continue + + vp = shapely.geometry.Point(v) + try: + does_contain = known_space_poly.contains(vp) + except: # noqa + does_contain = False + + if not does_contain and ind is not start_ind: + for bf in blocked_frontiers: + if bf and bf.linestring.buffer( + self.inflation_rad / 10).contains(vp): + break + else: + end_inds.append(ind) + + if not len(end_inds): + if do_return_cost: + return ([start_point, start_point], mdist) + else: + return [start_point, start_point] + else: + raise ValueError("Either 'end_point' or 'known_space_poly' " + + "must be provided to 'get_shortest_path'.") + + def get_neighbors(ind): + """Helper: return neighbors in visibility graph""" + possible_edges = [(ind, ii) for ii in range(len(verts)) + if not ii == ind] + return [ + e[1] for e in possible_edges if self._world.is_covisible( + verts[e[0]], verts[e[1]], self._inflation_obstacles) + ] + + def does_intersect_block(p1, p2): + """Helper: returns 1 if path passes through blocked frontier""" + ls = shapely.geometry.LineString((p1, p2)) + for bf in blocked_frontiers: + if bf and ls.intersects(bf.linestring): + return 1.0 + + for bcl in cl_inflated_obstacles: + if ls.intersects(bcl): + return 1.0 + + return 0.0 + + start_neighbors = get_neighbors(start_ind) + + def get_neighbor_dists(ind, neighbors): + def dist(p1, p2): + return math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + + def get_explore_cost(inda, indb): + o_ind = None + if inda in start_neighbors and indb == start_ind: + o_ind = inda + elif indb in start_neighbors and inda == start_ind: + o_ind = indb + + if o_ind is None: + return 0.0 + + if o_ind in end_inds: # and start_ind not in end_inds: + + d = dist(verts[o_ind], verts[start_ind]) + s = 0.999 - 0.00 * max(1 - 0.5 * d / self.inflation_rad, 0) + return 0.0 - s * d + else: + return 0.0 + + return [ + (ni, + dist(verts[ind], verts[ni]) + 0 * get_explore_cost(ind, ni) + + 100000 * does_intersect_block(verts[ind], verts[ni])) + for ni in neighbors + ] + + # Initializations + is_visited = np.zeros(len(verts)) + upstream_node = -1 * np.ones(len(verts), dtype=int) + node_dists = np.ones(len(verts)) * mdist + + # Dijkstra's algorithm + current_ind = start_ind + node_dists[current_ind] = 0 + stored_neighbors = {} + + while current_ind not in end_inds: + is_visited[current_ind] = 1 + current_dist = node_dists[current_ind] + neighbors = get_neighbors(current_ind) + stored_neighbors[current_ind] = neighbors + ndists = get_neighbor_dists(current_ind, neighbors) + + # Update neighbors + for ni, dist in ndists: + new_dist = current_dist + dist + if new_dist < node_dists[ni]: + node_dists[ni] = new_dist + upstream_node[ni] = current_ind + + # Pick new node + current_ind = np.argmin(node_dists * (1 - is_visited) + 2 * mdist * + (is_visited)) + + # Get shortest path from graph + path_inds = [current_ind] + if node_dists[current_ind] >= mdist: + print("Greater than mdist") + if do_return_cost: + return ([start_point, start_point], mdist) + else: + return [start_point, start_point] + + while node_dists[path_inds[-1]] > 0.0001: + new_ind = int(upstream_node[path_inds[-1]]) + path_inds.append(new_ind) + + if len(path_inds) == 1: + path_inds.append(start_ind) + + if do_return_cost: + return ([verts[ii] + for ii in path_inds[::-1]], node_dists[path_inds[0]]) + else: + return [verts[ii] for ii in path_inds[::-1]] diff --git a/modules/vertexnav/vertexnav/plotting.py b/modules/vertexnav/vertexnav/plotting.py new file mode 100644 index 0000000..d1e096e --- /dev/null +++ b/modules/vertexnav/vertexnav/plotting.py @@ -0,0 +1,171 @@ +# import matplotlib +# matplotlib.use('Qt5Agg') # noqa: E702 +import matplotlib +from matplotlib.patches import Ellipse +import math +import numpy as np +import shapely +import vertexnav + +LINEWIDTH = 1.5 +SCATTERSIZE = 4.0 +""" +A bunch of functions to facilitate plotting results +""" + + +def plot_proposed_world(ax, + world, + do_show_points=False, + do_plot_visibility=False, + robot_pose=None): + for obstacle in world.obstacles: + x, y = obstacle.xy + ax.plot(x, y, 'k', linewidth=LINEWIDTH) + + if do_show_points and len(world.vertices): + points = np.array(world.vertices) + if points.size > 0: + ax.plot(points[:, 0], points[:, 1], 'k.', markersize=SCATTERSIZE) + + if do_plot_visibility: + # FIXME(gjstein): don't hard-code inflation radius + inf_verts = world.get_inflated_vertices(inflation_rad=4) + if robot_pose is not None: + inf_verts.append((robot_pose.x, robot_pose.y)) + vis_edges = world.get_visibility_edges_from_verts(inf_verts) + for line in vis_edges: + ax.plot([line[0][0], line[1][0]], [line[0][1], line[1][1]], + 'b', + alpha=0.2) + + +def plot_world(ax, world, do_show_points=False, alpha=1.0): + for obstacle in world.obstacles: + x, y = obstacle.exterior.xy + if do_show_points: + ax.plot(x, y, 'ko-', linewidth=LINEWIDTH, alpha=alpha) + else: + ax.plot(x, y, 'k', linewidth=LINEWIDTH, alpha=alpha) + + if isinstance(world, vertexnav.environments.dungeon.DungeonWorld): + counter = 0 + for p in world.clutter_element_poses: + if counter % 2 == 1: + # Make a box + th = np.linspace(0.25 * math.pi, 2.25 * math.pi, 5) + points = np.array([3 * np.cos(th) + p.x, 3 * np.sin(th) + p.y]) + else: + # Make a pipe + th = np.linspace(0.0, 2 * math.pi, 33) + points = np.array([1 * np.cos(th) + p.x, 1 * np.sin(th) + p.y]) + ax.plot(points[0], + points[1], + color='yellow', + linewidth=LINEWIDTH, + alpha=min(alpha + 0.2, 0.8)) + counter += 1 + elif isinstance(world, vertexnav.environments.simulated.OutdoorWorld): + counter = 0 + for p in world.clutter_element_poses: + # Make a tree + th = np.linspace(0.0, 2 * math.pi, 33) + points = np.array([1 * np.cos(th) + p.x, 1 * np.sin(th) + p.y]) + ax.plot(points[0], + points[1], + color='orange', + linewidth=LINEWIDTH, + alpha=alpha + 0.2) + counter += 1 + + +def plot_noisy_wall(ax, wall): + lvp = wall.left_vertex.position + rvp = wall.right_vertex.position + prob = wall.prob_exists + ax.plot([lvp[0], rvp[0]], [lvp[1], rvp[1]], + color=[1 - prob, prob, 0], + alpha=0.5 * prob + 0.1) + + +def eigsorted(cov): + vals, vecs = np.linalg.eigh(cov) + order = vals.argsort()[::-1] + return vals[order], vecs[:, order] + + +def plot_corners_position_overhead(ax, obs, plt_format='mo', do_plt_cov=True): + for gap in obs: + ax.plot(gap.position[0], gap.position[1], plt_format, mfc='none') + if do_plt_cov and gap.cov is not None: + nstd = 1 + cov = gap.cov + vals, vecs = eigsorted(cov) + theta = np.degrees(np.arctan2(*vecs[:, 0][::-1])) + w, h = 2 * nstd * np.sqrt(vals) + ell = Ellipse(xy=(gap.position[0], gap.position[1]), + width=w, + height=h, + angle=theta, + color='black') + ell.set_facecolor('b') + ell.set_edgecolor(None) + ell.set_alpha(0.2) + ax.add_artist(ell) + + +def plot_shapely_linestring(ax, ls, color=[0.25, 0.25, 1.0], alpha=1.0): + if isinstance(ls, shapely.geometry.MultiLineString): + [plot_shapely_linestring(ax, line, color, alpha) for line in ls] + return + + x, y = ls.xy + ax.plot(x, y, color=color, alpha=alpha, linewidth=0.2) + + +def plot_polygon(ax, poly, color=[0.0, 0.0, 1.0], alpha=1.0): + # Plotting code from: https://sgillies.net/2010/04/06/painting-punctured-polygons-with-matplotlib.html + + if isinstance(poly, shapely.geometry.MultiPolygon): + [plot_polygon(ax, p, color, alpha) for p in poly] + return + + def ring_coding(ob): + # The codes will be all "LINETO" commands, except for "MOVETO"s at the + # beginning of each subpath + n = len(ob.coords) + codes = np.ones(n, dtype=matplotlib.path.Path.code_type) \ + * matplotlib.path.Path.LINETO + codes[0] = matplotlib.path.Path.MOVETO + return codes + + def pathify(polygon): + # Convert coordinates to path vertices. Objects produced by Shapely's + # analytic methods have the proper coordinate order, no need to sort. + vertices = np.concatenate([np.asarray(polygon.exterior)] + + [np.asarray(r) for r in polygon.interiors]) + codes = np.concatenate([ring_coding(polygon.exterior)] + + [ring_coding(r) for r in polygon.interiors]) + return matplotlib.path.Path(vertices, codes) + + try: + path = pathify(poly) + patch = matplotlib.patches.PathPatch(path, + facecolor=color, + linewidth=0, + alpha=alpha) + ax.add_patch(patch) + except: # noqa + pass + + +def plot_linestring(ax, linestring, **kwargs): + + if isinstance(linestring, shapely.geometry.GeometryCollection): + return + if isinstance(linestring, shapely.geometry.MultiLineString): + [plot_linestring(ax, ls, **kwargs) for ls in linestring] + return + + x, y = linestring.xy + ax.plot(x, y, **kwargs) diff --git a/modules/vertexnav/vertexnav/prob_vertex_graph.py b/modules/vertexnav/vertexnav/prob_vertex_graph.py new file mode 100644 index 0000000..01efcc7 --- /dev/null +++ b/modules/vertexnav/vertexnav/prob_vertex_graph.py @@ -0,0 +1,698 @@ +import itertools +import math +import numpy as np +import random +import shapely + +import vertexnav +import vertexnav_accel + +from .noisy import NoisyVertex + +PRIOR_NOISE = np.array([0.01, 0.01, 0.01]) +ODOMETRY_NOISE = np.array([.05, 0.05, 0.05]) +CLUSTERING_NOISE = np.array([0.01, 0.01]) + + +def _get_vertex_remapping(vertices, topology): + # FIXME: does not actually work with clusters + vertex_id_dict = {v.id: v for v in vertices} + vertex_remapping = dict() + + for cluster in topology: + # FIXME: not doing anything smart for now + if False and len(cluster) == 1: + vertex_remapping[cluster[0]] = vertex_id_dict[cluster[0]] + else: + # Create new noisy vertex for clusters of more than a single + # vertex.The new NoisyVertex has a mean and covariance that + # depends on those of its parts + sum_cov_inv = 0 + sum_weighted_means = 0 + for cid in cluster: + vert = vertex_id_dict[cid] + cov_inv = np.linalg.inv(vert.cov) + sum_cov_inv += cov_inv + pos_T = [[vert.position[0]], [vert.position[1]]] + sum_weighted_means += np.matmul(cov_inv, pos_T) + + cov = np.linalg.inv(sum_cov_inv) + mean = np.matmul(cov, sum_weighted_means).tolist() + + cluster_vert = NoisyVertex( + [mean[0][0], mean[1][0]], cov) + + for cid in cluster: + vertex_remapping[cid] = cluster_vert + + return vertex_remapping + + +class Cluster(object): + class_counter = 0 + + def __init__(self, vids, vertex_id_dict): + self.vids = vids + self._is_active = any(vertex_id_dict[vid].is_active for vid in vids) + self._is_locked = all(vertex_id_dict[vid].is_locked for vid in vids) + self.vertices = [ + v for k, v in list(vertex_id_dict.items()) if k in vids + ] + self.last_updated = max(v.last_updated for v in self.vertices) + self.num_dets = sum(v.num_detections for v in self.vertices) + + self.id = Cluster.class_counter + Cluster.class_counter += 1 + + @property + def is_active(self): + return self._is_active + + @property + def is_locked(self): + return self._is_locked + + def set_is_active(self, new_is_active): + # Set state of the component vertices. Changing the state of a vertex + # automatically unlocks it. + for v in self.vertices: + old_v_is_active = v.is_active + if new_is_active is not old_v_is_active: + v.is_active = new_is_active + v.is_locked = False + + # Set the internal property + self._is_active = new_is_active + + def lock(self): + self._is_locked = True + for v in self.vertices: + v.is_locked = True + + +SamplingState = vertexnav_accel.SamplingState + + +class ProbVertexGraph(vertexnav_accel.ProbVertexGraph): + def __init__(self): + super(ProbVertexGraph, self).__init__() + + self.PRIOR_NOISE = PRIOR_NOISE + self.ODOMETRY_NOISE = ODOMETRY_NOISE + self.CLUSTERING_NOISE = CLUSTERING_NOISE + self.DO_MULTI_VERTEX_MERGE = False + + def add_observation(self, + observation, + r_pose=None, + odom=None, + association_window=-1): + """ + Add a new observation to the graph. First associate each detection + with a single vertex. Ensure these matches are one to one. Any + unmatched detections create new vertices. Update the graphs various + lists and dictionaries in the process. Then pick the most likely map + given this observation, and add the walls to the list of all walls. + + Arguments: + self -- NoisyVertexGraph + observation -- list of NoisyVertexDetections + r_pose -- pose of the robot + """ + if r_pose is not None: + robot_id = r_pose.robot_id + elif odom is not None: + robot_id = odom.robot_id + else: + raise ValueError("One of 'r_pose' or 'odom' required.") + + num_poses_for_id = sum(1 for p in self.r_poses + if p.robot_id == robot_id) + + if num_poses_for_id == 0: + if r_pose is None: + raise ValueError("Should provide an initial pose.") + super(ProbVertexGraph, + self).add_observation_pose(observation, r_pose, + association_window) + else: + if r_pose is not None: + raise ValueError("Cannot provide a pose after initial pose.") + super(ProbVertexGraph, + self).add_observation_odom(observation, odom, + association_window) + + # Run a SLAM update + self.perform_slam_update() + + def get_proposed_world(self, r_poses=[], topology=None): + """Get proposed world from robot poses""" + if topology is None: + topology = self.topology + + topology = set(tuple(c) for c in topology) + + active_verts = [ + v for v in self.vertices if v.num_detections > 2 and v.is_active + ] + active_verts = sorted(active_verts, + key=lambda v: v.last_updated, + reverse=True) + + # Clusters with any active vertices are active + active_vert_ids = set((v.id for v in active_verts)) + active_clusters = set( + cluster for cluster in topology + if len(active_vert_ids.intersection(set(cluster)))) + + # Build the temporary wall dictionary + vertex_remapping = vertexnav_accel.get_vertex_remapping( + self.vertices, topology) + wall_dict = vertexnav_accel.get_remapped_wall_dict( + self.walls, active_clusters, vertex_remapping) + + try: + r_traj = shapely.geometry.LineString([(p.x, p.y) for p in r_poses]) + + def does_intersect_robot_trajectory(wall): + ws = shapely.geometry.LineString( + [wall.left_vertex.position, wall.right_vertex.position]) + return ws.intersects(r_traj) + except ValueError as e: + print(e) + + def does_intersect_robot_trajectory(wall): + return False + + # Remap the clusters (for wall computation) + remapped_clusters = [ + vertex_remapping[cluster[0]].id for cluster in active_clusters + ] + potential_walls = [ + wv for wk, wv in list(wall_dict.items()) + if wv.is_active and not wk[0] == wk[1] + and wk[0] in remapped_clusters and wk[1] in remapped_clusters + and not does_intersect_robot_trajectory(wv) + ] + + cluster_verts = [vertex_remapping[c[0]] for c in active_clusters] + vertex_positions = [(vertex.position[0], vertex.position[1]) + for vertex in cluster_verts] + wall_positions = [(wall.left_vertex.position, + wall.right_vertex.position) + for wall in potential_walls] + + return vertexnav.world.ProposedWorld(vertices=vertex_positions, + walls=wall_positions, + topology=topology, + vertex_remapping=vertex_remapping) + + def get_known_poly(self, proposed_world, max_range=1000, topology=None): + """Return known space polygon""" + observations = self.observations + r_poses = self.r_poses + vertex_remapping = proposed_world.vertex_remapping + + h_obss = [ + vertexnav_accel.VectorHalDet( + vertexnav.noisy.compute_hypothetical_observation( + proposed_world, + r_pose, + observation, + vertex_remapping=vertex_remapping)) + for r_pose, observation in zip(r_poses, observations) + ] + h_polys = [ + shapely.geometry.Polygon( + vertexnav_accel.compute_conservative_space_hallucinated( + r_pose, h_obs)).buffer( + 1e-2, resolution=0, cap_style=3, join_style=2) + if len(h_obs) > 2 else shapely.geometry.Polygon() + for r_pose, h_obs in zip(r_poses, h_obss) + ] + + o_polys = [ + shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs( + r_pose, obs, max_range, + vertex_remapping=vertex_remapping)).buffer(1e-2, + resolution=0, + cap_style=3, + join_style=2) + for r_pose, obs in zip(r_poses, observations) + ] + + poly = shapely.geometry.Polygon() + for h_poly, o_poly in zip(h_polys, o_polys): + poly = vertexnav.vertex_graph.safely_add_poly( + poly, h_poly.intersection(o_poly)) + + return poly.buffer(-0.9e-2, 0, cap_style=3, join_style=2) + + def sample_vertices(self, + p_window=15, + num_samples=30, + inflation_rad=4.0, + topology=None, + do_update_state=True, + active_vert_ids=None, + do_use_all_poses=False): + """Consider turning on/off different vertices to sample map space""" + if not topology: + topology = self.topology + + active_clusters = self._get_active_clusters( + p_window=p_window, + inflation_rad=inflation_rad, + topology=topology, + active_vert_ids=active_vert_ids) + cluster_vert_ids = set( + itertools.chain.from_iterable( + [list(c.vids) for c in active_clusters])) + + # Decide which pose, observation pairs are needed for prob computation. + def does_observe_active_cluster(observation): + for det in observation: + if det.associated_vertex.id in cluster_vert_ids: + return True + return False + + if do_use_all_poses: + pose_obs_pairs = None + else: + pose_obs_pairs = [ + pair for pair in zip(self.r_poses, self.observations) + if does_observe_active_cluster(pair[1]) + ] + + already_sampled = [] + + # Store the "initial" state (needed for comparison) + self.perform_slam_update() + initial_proposed_world = self.get_proposed_world_fast( + topology=self.topology) + if do_use_all_poses: + initial_proposed_world_log_prob = self.compute_world_log_prob_full( + initial_proposed_world) + else: + initial_proposed_world_log_prob = self.compute_world_log_prob( + initial_proposed_world, pose_obs_pairs) + + initial_sampling_state = self.get_state( + initial_proposed_world_log_prob) + + # Set the initial updated state. + # (if the topology is unchanged, this has no impact) + self.topology = topology + self.perform_slam_update() + proposed_world = self.get_proposed_world_fast(topology=topology) + if do_use_all_poses: + proposed_world_log_prob = self.compute_world_log_prob_full( + proposed_world) + else: + proposed_world_log_prob = self.compute_world_log_prob( + proposed_world, pose_obs_pairs) + + best_sampling_state = self.get_state(proposed_world_log_prob) + + if len(active_clusters) == 0: + return initial_sampling_state, best_sampling_state + + # FIXME: sort the clusters + counter = 0 + v_iter_counter = 0 + while counter < num_samples and len(already_sampled) < len( + active_clusters): # noqa: E501 + # Pick a vertex and optionally toggle it + toggle_cluster = active_clusters[v_iter_counter % + len(active_clusters)] + # toggle_cluster = random.choice(active_clusters) + if toggle_cluster.id in already_sampled: + v_iter_counter += 1 + continue + elif toggle_cluster.is_locked: + v_iter_counter += 1 + already_sampled.append(toggle_cluster.id) + continue + + toggle_cluster.set_is_active(not toggle_cluster.is_active) + + # Compute the new proposed world and compare + new_proposed_world = self.get_proposed_world_fast( + topology=topology) + if do_use_all_poses: + new_proposed_world_log_prob = self.compute_world_log_prob_full( + new_proposed_world) + else: + new_proposed_world_log_prob = self.compute_world_log_prob( + new_proposed_world, pose_obs_pairs) + + if new_proposed_world_log_prob > best_sampling_state.log_prob: + best_sampling_state = self.get_state( + new_proposed_world_log_prob) + + # Print the debug output + print( + ("#{:2d} | Init:{:8.3f} | Best:{:8.3f} | Prop:{:8.3f} ({:2d})" + .format(counter, initial_proposed_world_log_prob, + proposed_world_log_prob, new_proposed_world_log_prob, + len(active_clusters)))) + + # MCMC test + delta_log_prob = new_proposed_world_log_prob \ + - proposed_world_log_prob + + if delta_log_prob > math.log(random.random() * 1.00 + 0.00): + proposed_world = new_proposed_world + proposed_world_log_prob = new_proposed_world_log_prob + print(" Switching") + already_sampled = [] + v_iter_counter = 0 + else: + # Switch the cluster back + toggle_cluster.set_is_active(not toggle_cluster.is_active) + # if delta_log_prob < -100: + # print(" Locking cluster: ") + # toggle_cluster.lock() + + already_sampled.append(toggle_cluster.id) + + v_iter_counter += 1 + counter += 1 + + # Now either restore the PVG to its original state or use the maximum + # likelihood state. + if do_update_state: + self.set_state(best_sampling_state) + else: + self.set_state(initial_sampling_state) + + return initial_sampling_state, best_sampling_state + + def sample_states(self, + num_topology_samples=3, + num_vertex_samples=30, + vertex_association_dist_threshold=10, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + vertex_visibility_inflation_rad=4.0, + mvmp_merge_dist_threshold=0.5, + do_update_state=True): + """Primary sampling functionality. Samples over topologies (if + DO_SAMPLE_TOPOLOGY is True) and over vertices.""" + if self.DO_SAMPLE_TOPOLOGY: + if self.DO_MULTI_VERTEX_MERGE: + print("Sampling topologies (with multi vertex merge)") + else: + print("Sampling topologies (with single vertex merge)") + + return self.sample_topologies( + num_samples=num_topology_samples, + association_dist_threshold=vertex_association_dist_threshold, + vertex_association_time_window=vertex_association_time_window, + vertex_sampling_time_window=vertex_sampling_time_window, + num_vertex_samples=num_vertex_samples, + inflation_rad=vertex_visibility_inflation_rad, + do_update_state=do_update_state, + mvmp_merge_dist_threshold=mvmp_merge_dist_threshold, + do_multi_vertex_merge=self.DO_MULTI_VERTEX_MERGE) + else: + print("Sampling vertices only (with no vertex merge)") + return self.sample_vertices( + p_window=vertex_sampling_time_window, + num_samples=num_vertex_samples, + inflation_rad=vertex_visibility_inflation_rad, + do_update_state=do_update_state) + + def sample_topologies(self, + num_samples=3, + association_dist_threshold=10, + vertex_association_time_window=15, + vertex_sampling_time_window=15, + num_vertex_samples=30, + inflation_rad=4.0, + mvmp_merge_dist_threshold=0.5, + do_update_state=True, + do_multi_vertex_merge=False): + + # First sample vertices with the current topology + initial_state, best_state = self.sample_vertices( + p_window=vertex_sampling_time_window, + num_samples=num_vertex_samples, + inflation_rad=inflation_rad, + do_update_state=True) + + # Helper variables + vertex_id_dict = {v.id: v for v in self.vertices} + active_clusters = self._get_active_clusters( + p_window=vertex_association_time_window, + inflation_rad=inflation_rad, + topology=self.topology) + active_vert_ids = set( + itertools.chain.from_iterable( + [list(c.vids) for c in active_clusters])) + + successful_samples = 0 + did_sample = [] + + for ii in range(2000): + # Generate new topology from the current topology + new_topology, _, move_type = vertexnav.utils.topology.draw_sample( + self.topology) + + # Compute which vertices changed via the topology update + old_t = frozenset([frozenset(c) for c in self.topology]) + new_t = frozenset([frozenset(c) for c in new_topology]) + updated_vert_ids = list( + itertools.chain.from_iterable(old_t - new_t)) + if len(updated_vert_ids) == 0: + continue + + # Decide if the new topology is valid + # If any of the vertices in the updated_vert_ids are stale, reject. + if len(set(updated_vert_ids) - active_vert_ids): + continue + + # At least one vertex should be within p_window + # if vertex_association_time_window is not None \ + # and vertex_association_time_window < len(self.r_poses): + # last_updated_thresh = self.r_poses[ + # len(self.r_poses) - vertex_association_time_window].index + # if not any( + # vertex_id_dict[vid].last_updated >= last_updated_thresh + # for vid in updated_vert_ids): + # continue + + # # If any of the vertices have basically no detections + # if any(vertex_id_dict[vid].num_detections <= 10 + # for vid in updated_vert_ids): + # continue + + # During a merge, if any of the vertices + if move_type == 1: # merge + + def eucl_dist_sq(vida, vidb): + va = vertex_id_dict[vida] + vb = vertex_id_dict[vidb] + return ((va.position[0] - vb.position[0])**2 + + (va.position[1] - vb.position[1])**2) + + association_dist_thresh_sq = association_dist_threshold**2 + + if any( + eucl_dist_sq(vid_a, vid_b) > association_dist_thresh_sq + for vid_a, vid_b in itertools.permutations( + updated_vert_ids, 2)): + continue + + # Check if we've tried this one already or if it's disallowed + top_diff = (set(tuple(sorted(c)) for c in (old_t - new_t)), + set(tuple(sorted(c)) for c in (new_t - old_t))) + # diff = (old_t, new_t) + if top_diff in self.disallowed_topology_operations: + continue + elif top_diff in did_sample: + continue + else: + did_sample += [top_diff] + + # Count the number of times a sample was allowed to be tested. + successful_samples += 1 + + # Sample with the new topology + initial_trial_state, trial_state = self.sample_vertices( + topology=new_topology, + do_update_state=False, + p_window=vertex_sampling_time_window, + num_samples=num_vertex_samples, + inflation_rad=inflation_rad, + active_vert_ids=updated_vert_ids, + do_use_all_poses=True) + + # If we already did a single vertex merge, and MVMP is in use, then + # we attempt to merge again + if move_type == 1 and do_multi_vertex_merge: + # Compute new topolology corresponding to a multi-vertex merge + mvmp_topology = [] + + # *Temporarily* set the PVG state to trial state + # NOTE: must be _reset_ after evaluation + self.set_state(trial_state) + + # TODO(kevin): Manually do topological surgery + vertex_id_dict = {v.id: v for v in self.vertices} + + mvmp_topology = [] + merged_set = set() + + # Propose new merges + for ci in self.topology: + vidi = ci[0] + cij = list(ci) + if tuple(ci) in merged_set: + continue + merged_set.add(tuple(ci)) + for cj in self.topology: + if tuple(cj) in merged_set: + continue + vidj = cj[0] + + def eucl_dist_sq(vida, vidb): + va = vertex_id_dict[vida] + vb = vertex_id_dict[vidb] + return ((va.position[0] - vb.position[0])**2 + + (va.position[1] - vb.position[1])**2) + + if eucl_dist_sq(vidi, vidj) < mvmp_merge_dist_threshold**2: + cij += list(cj) + merged_set.add(tuple(cj)) + + mvmp_topology.append(cij) + + assert(len(sum(mvmp_topology, [])) == len(sum(self.topology, []))) + + # Reconstruct clusters + # cluster_map += [c for c in self.topology if c not in merged_set] + + # Ensure each vertex id _does not_ appear more than once + # TODO(kevin): assert ??? + + # for v in self.vertices: + # if v.position[0] > -0.2 and v.position[1] < 0.2: + # origin_verts += [v] + # else: + # topology += [(v.id, )] + + # Compute which vertices changed via the topology update + old_t = frozenset([frozenset(c) for c in self.topology]) + new_t = frozenset([frozenset(c) for c in mvmp_topology]) + updated_vert_ids = list( + itertools.chain.from_iterable(old_t - new_t)) + + # Sample with the MVMP topology + _, mvmp_trial_state = self.sample_vertices( + topology=mvmp_topology, + do_update_state=False, + p_window=vertex_sampling_time_window, + num_samples=num_vertex_samples, + inflation_rad=inflation_rad, + active_vert_ids=updated_vert_ids, + do_use_all_poses=True) + + if mvmp_trial_state.log_prob > trial_state.log_prob: + trial_state = mvmp_trial_state + + # Reset PVG state to current best after evaluating MVMP + self.set_state(best_state) + + # MCMC criteria + d_prob_trial = trial_state.log_prob - initial_trial_state.log_prob + # Is this correct? + # d_prob_trial = trial_state.log_prob - best_state.log_prob + if d_prob_trial > math.log(random.random() * 1.00 + 0.00): + print( + "Switching: \n" + + " New State Prob: {}\n".format(trial_state.log_prob) + + " Initial State Prob: {}\n".format( + initial_trial_state.log_prob) + + " Old Best State Prob: {}\n".format(best_state.log_prob)) + did_sample = [] + self.set_state(trial_state) + best_state = trial_state + else: + print("Not Switching: \n" + + " (rejected) Trial State Prob: {}\n".format( + trial_state.log_prob) + + " Initial State Prob: {}\n".format( + initial_trial_state.log_prob) + + " Best State Prob: {}\n".format(best_state.log_prob)) + + if successful_samples > num_samples: + break + + return initial_state, best_state + + def _get_active_clusters(self, + p_window, + inflation_rad, + topology, + active_vert_ids=None): + """Helper function to compute which clusters may be flipped + during sampling.""" + + if active_vert_ids is None: + observations = self.observations[-p_window:] + r_poses = self.r_poses[-p_window:] + polys = [ + shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs( + r_pose, obs)).buffer(inflation_rad, + resolution=0, + cap_style=3, + join_style=2) + for r_pose, obs in zip(r_poses, observations) + ] + + def is_inside_polys(position): + for poly in polys: + if poly.contains(shapely.geometry.Point(position)): + return True + return False + + # Compute which vertices may be toggled + seen_verts = { + v + for v in self.vertices if is_inside_polys(v.position) + } + recent_verts = { + det.associated_vertex + for obs in observations for det in obs + } + verts = [ + v for v in seen_verts.union(recent_verts) + if v.num_detections > 2 and not v.is_locked + ] + vert_ids = [v.id for v in verts] + vert_ids = set(vert_ids) + else: + vert_ids = set(active_vert_ids) + + # Compute which clusters may be toggled + vertex_id_dict = {v.id: v for v in self.vertices} + clusters = [Cluster(c, vertex_id_dict) for c in topology] + active_clusters = [ + c for c in clusters if not vert_ids.isdisjoint(c.vids) + ] + active_clusters = sorted(active_clusters, + key=lambda c: c.last_updated, + reverse=True) + + # No elements should be in the vert_ids that are not part of a cluster. + cluster_vert_ids = set( + itertools.chain.from_iterable( + [list(c.vids) for c in active_clusters])) + assert len(vert_ids.difference(cluster_vert_ids)) == 0 + + active_clusters.sort(reverse=True, key=lambda c: c.last_updated) + + return active_clusters diff --git a/modules/vertexnav/vertexnav/robot.py b/modules/vertexnav/vertexnav/robot.py new file mode 100644 index 0000000..25ecda7 --- /dev/null +++ b/modules/vertexnav/vertexnav/robot.py @@ -0,0 +1,276 @@ +""" +Includes definitions for various 'Robot' classes which are useful for +storing the agent's state and getting the agent's available actions during +navigation. The primary robot class is the "Turtlebot_Robot", which defines +a basic set of motion primitives relevant to differential drive robots. +""" + +from vertexnav_accel import Pose +import copy +import math +import numpy as np +from . import utils + + +class Motion_Primitive(): + def __init__(self, poses, cost, map_data=None): + self.poses = poses + self.cost = cost + self.map_data = map_data + + def transform(self, pose): + """Transform the motion primitive by a given pose. + This is equivalent to 'right multiplying' the pose/transform. + The resulting primitive should be such that the output poses + are the input poses applied to the pose. + """ + new_poses = [p * pose for p in self.poses] + return Motion_Primitive(poses=new_poses, cost=self.cost) + + +class Robot: + """Base robot class. + All robots must define the 'move' function, which defines how they can + move through space. The Robot class is also useful for defining how an + embodied agent travels through space and for storing a history of poses. + """ + def __init__(self, pose): + self.pose = copy.copy(pose) + self.all_poses = [copy.copy(self.pose)] + self.does_use_motion_primitives = 0 + self.net_motion = 0 + + def move(self, plan, distance=1.0): + + # Start at 1 so that the "rounded current robot pose" is not used + ii = 1 + remaining_dist = distance + while remaining_dist > 0 and ii < plan.shape[1]: + subgoal = plan[:, ii] + dx = subgoal[0] - self.pose.x + dy = subgoal[1] - self.pose.y + step_dist = math.sqrt(dx * dx + dy * dy) + if step_dist < remaining_dist: + remaining_dist -= step_dist + self.pose.x = subgoal[0] + self.pose.y = subgoal[1] + self.net_motion += step_dist + ii += 1 + else: + self.pose.x += remaining_dist * dx / step_dist + self.pose.y += remaining_dist * dy / step_dist + self.net_motion += remaining_dist + self.all_poses += [copy.copy(self.pose)] + return + + def max_travel_distance(self, num_recent_poses): + """Returns the farthest distance between two poses out of the last N poses""" + max_dist = 0.0 + if len(self.all_poses) < num_recent_poses: + return 1e10 + for pose_a in self.all_poses[-num_recent_poses:]: + for pose_b in self.all_poses[-num_recent_poses:]: + max_dist = max(max_dist, + Pose.cartesian_distance(pose_a, pose_b)) + return max_dist + + @property + def pose_m(self): + if self.map_data is None: + return self.pose + + return Pose(x=self.pose.x * self.map_data['resolution'] + + self.map_data['x_offset'], + y=self.pose.y * self.map_data['resolution'] + + self.map_data['y_offset'], + yaw=self.pose.yaw) + + +class Motion_Primitive_Robot(Robot): + """A simple robot that moves using motion primitives. + This is the base class for robots that use motion primitives to move. + As such, the 'get_motion_primitives' function must be defined and the + move class has been updated to include the selected primitive for motion. + """ + def __init__(self, + pose, + num_primitives=32, + primitive_length=2.8, + map_data=None, + unity_bridge=None): + self.pose = copy.copy(pose) + self.all_poses = [copy.copy(self.pose)] + self.net_motion = 0 + self.does_use_motion_primitives = 1 + self.num_primitives = num_primitives + self.primitive_length = primitive_length + self.map_data = map_data + self.unity_bridge = unity_bridge + self.has_moved = False + self.still_count = 0 + + def _get_local_points(self, range_thresh): + def _transform_rays(rays, sensor_pose): + """Transform (rotate and offset) a laser scan according to pose.""" + origin = np.array([[sensor_pose.x], [sensor_pose.y]]) + rotation_mat = np.array( + [[math.cos(sensor_pose.yaw), -math.sin(sensor_pose.yaw)], + [math.sin(sensor_pose.yaw), + math.cos(sensor_pose.yaw)]]) + + return np.matmul(rotation_mat, rays) + origin + + # Get the depth image & raw ranges + if self.unity_bridge is None: + return None + + self.unity_bridge.move_object_to_pose("robot", self.pose) + pano_depth_image = self.unity_bridge.get_image( + "robot/pano_depth_camera") + pano_depth_image = utils.convert.depths_from_depth_image( + pano_depth_image) / self.unity_bridge.sim_scale + + # Get the close points in the local frame + ranges = pano_depth_image[pano_depth_image.shape[0] // 2] + is_close = ranges <= range_thresh + if is_close.any(): + directions, _ = utils.calc.directions_vec(ranges.size) + close_points = (ranges * directions)[:, is_close] + + # Transform to global frame and return + no_yaw_pose = self.pose + no_yaw_pose.yaw = 0 + return _transform_rays(close_points, self.pose) + else: + return None + + def get_motion_primitives(self): + """Returns the motion primitives available to the robot at the current + time (can be a function of robot state).""" + # Create motion primitives + return [ + Motion_Primitive(poses=[ + Pose(x=self.primitive_length * + math.cos(2 * math.pi * i / self.num_primitives), + y=self.primitive_length * + math.sin(2 * math.pi * i / self.num_primitives), + yaw=0) * self.pose + ], cost=self.primitive_length) + for i in range(self.num_primitives) + ] + + def move(self, goal, path, inflation_rad): + def dist(p1, p2): + return math.sqrt((p1[0] - p2[0])**2 + (p1[1] - p2[1])**2) + + is_still = False + if dist(path[-1], (self.pose.x, self.pose.y)) < 0.001: + print("is still") + is_still = True + else: + self.has_moved = True + + if is_still and not self.has_moved: + return + + primitives = self.get_motion_primitives() + + # Get distances + max_range = 6.0 * inflation_rad + 2 * self.primitive_length + obs_points = self._get_local_points(range_thresh=max_range) + + def get_obs_dist(primitive): + if obs_points is None: + return 100000 + else: + pose = primitive.poses[-1] + dists = np.linalg.norm(obs_points - [[pose.x], [pose.y]], + axis=0) + assert 2 * dists.size == obs_points.size + return min(dists) + + # Cost = distance + WEIGHT * linear + # costs = [ + # dist((prim.poses[-1].x, prim.poses[-1].y), path[1]) + 100.0 * max( + # inflation_rad - proposed_world.get_dist(prim.poses[-1]), 0) + # for prim in primitives + # ] + costs = [ + dist((prim.poses[-1].x, prim.poses[-1].y), path[1]) + # - 0.8*dist((prim.poses[-1].x, prim.poses[-1].y), path[-1]) + + 10000.0 * max(1.0 - get_obs_dist(prim) / inflation_rad, 0) + + prim.cost * max(8.0 - + (get_obs_dist(prim) / inflation_rad - 1)**2, 0) / + 6.0 # Soft cost + + prim.cost for prim in primitives + ] + + if is_still: + costs = [ + self.primitive_length * + max(12.0 - (get_obs_dist(prim) / inflation_rad - 1.0), 0) / + 3.0 # Soft cost + + prim.cost for prim in primitives + ] + self.still_count += 1 + else: + self.still_count = max(0, self.still_count - 2) + + # if len(path) > 1: + # second_costs = [ + # dist((prim.poses[-1].x, prim.poses[-1].y), path[2]) + # + 100.0 * max(inflation_rad - get_obs_dist(prim), 0) + # + 0.5 * max(2 * inflation_rad - get_obs_dist(prim), 0) # Soft cost + # for prim in primitives] + # costs = [min(c, sc) for c, sc in zip(costs, second_costs)] + + ind = costs.index(min(costs)) + primitive = primitives[ind] + self.net_motion += primitive.cost + self.pose = Pose(primitive.poses[-1].x, primitive.poses[-1].y, + primitive.poses[-1].yaw) + for pose in primitive.poses: + p = Pose(pose.x, pose.y, pose.yaw) + self.all_poses.append(p) + + +class Turtlebot_Robot(Motion_Primitive_Robot): + """A simple 'turtlebot' robot class.""" + def __init__(self, + pose, + num_primitives=20, + max_yaw=math.pi / 2, + primitive_length=1.0, + map_data=None, + unity_bridge=None): + self.pose = Pose(pose.x, pose.y, pose.yaw) + self.all_poses = [self.pose] + self.net_motion = 0 + self.does_use_motion_primitives = 1 + self.num_primitives = num_primitives + self.max_yaw = max_yaw + self.primitive_length = primitive_length + self.map_data = map_data + self.unity_bridge = unity_bridge + self.still_count = 0 + self.has_moved = False + + def get_motion_primitives(self): + """Returns the motion primitives available to the robot at the current + time (can be a function of robot state).""" + r0 = self.primitive_length + N = self.num_primitives + angles = [(i * 1.0 / N - 1) * self.max_yaw / 2 + for i in range(2 * N + 1)] + primitive_list = [ + Motion_Primitive(poses=[ + Pose(x=r0 * math.cos(angle) * (math.cos(angle)), + y=r0 * math.sin(angle) * (math.cos(angle)), + yaw=2 * angle) * self.pose + ], cost=r0) for angle in angles + ] + primitive_list += [ + Motion_Primitive(poses=[Pose(x=0, y=0, yaw=math.pi) * self.pose], + cost=2 * r0) + ] + return primitive_list diff --git a/modules/vertexnav/vertexnav/scripts/__init__.py b/modules/vertexnav/vertexnav/scripts/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/modules/vertexnav/vertexnav/scripts/eval_simulated.py b/modules/vertexnav/vertexnav/scripts/eval_simulated.py new file mode 100644 index 0000000..9005aaa --- /dev/null +++ b/modules/vertexnav/vertexnav/scripts/eval_simulated.py @@ -0,0 +1,737 @@ +"""Generate figures for the simulated hallway environments""" +import argparse +import matplotlib.animation as animation +import matplotlib.pyplot as plt +import environments +import vertexnav_accel +import vertexnav +import math +import numpy as np +import os +import random +import time as time +import torch +import shapely + + +def set_up_video_gen(video_path, figure_only=False): + """Helper function. Returns axes and writer.""" + fig = plt.figure(figsize=(4, 8)) + fig.subplots_adjust(left=0, + bottom=0, + right=1, + top=0.9, + wspace=None, + hspace=None) + + # For video + ax1 = plt.subplot2grid((5, 1), (0, 0), colspan=1, rowspan=2) + ax2 = plt.subplot2grid((5, 1), (2, 0), colspan=1, rowspan=3) + + ax1.autoscale(enable=True, axis='x', tight=True) + ax2.set_aspect('equal') + ax2.autoscale(enable=True, axis='x', tight=True) + + if figure_only: + return ax1, ax2 + else: + writer = animation.FFMpegWriter(15) + writer.setup(fig, os.path.join(video_path), 500) + return (ax1, ax2), writer + + +def get_environment(args): + if args.environment == 'dungeon': + inflation_rad = 6.0 + world = vertexnav.environments.dungeon.DungeonWorld( + hall_width=20, inflate_ratio=0.30, random_seed=args.current_seed, + + ) + builder = environments.simulated.WorldBuildingUnityBridge + path = [world.get_random_pose(min_signed_dist=inflation_rad)] + elif args.environment == 'outdoor': + # inflation_rad = 6.0 + # world = vertexnav.environments.simulated.OutdoorWorld( + # num_buildings=5, + # num_clutter_elements=15, + # min_clutter_signed_distance=20.0) + # builder = vertexnav.environments.simulated.OutdoorBuildingUnityBridge + # path = [world.get_random_pose(min_signed_dist=inflation_rad, + # max_signed_dist=2*inflation_rad)] + raise NotImplementedError() + elif args.environment == 'guidedmaze': + # from lsp.utils.mapgen import generate_map_and_poses + # args.base_resolution = args.grid_resolution + # args.inflation_radius_m = 2.5 * args.grid_resolution + # args.map_type = 'maze' + # args.current_seed = args.seed + # args.map_maze_path_width = 10 + # args.map_maze_cell_dims = [7, 7] + # args.map_maze_wide_path_width = 14 + # args.map_maze_all_wide = True + # grid, map_data, pose, goal = generate_map_and_poses(args) + # inflation_rad = args.base_resolution * 4.0 + # world = vertexnav.environments.simulated.OccupancyGridWorld(grid, map_data) + # builder = vertexnav.environments.simulated.DungeonBuildingUnityBridge + # path = [vertexnav.Pose(pose.x, pose.y)] + raise NotImplementedError() + else: + raise ValueError("Environment '{}' unrecognized.".format( + args.environment)) + + return world, builder, inflation_rad, path + + +def get_data_iterator(unity_bridge, + world, + path, + segment_steps=50, + smooth_factor=1.0 / 3, + robots=None, + do_return_time=False): + path_iterator = vertexnav.utils.data.follow_path_iterator( + path, segment_steps, smooth_factor) + + prev_poses = None + + while True: + iter_start_time = time.time() + if robots is not None: + poses = [robot.pose for robot in robots] + else: + poses = [next(path_iterator)] + + if prev_poses is None: + odoms = [None for robot in robots] + else: + odoms = [ + vertexnav.Pose.get_odom(p_new=pn, p_old=po) + for pn, po in zip(poses, prev_poses) + ] + + prev_poses = [ + vertexnav.Pose(p.x, p.y, p.yaw, p.robot_id) for p in poses + ] + + # Get the images + def get_image(p): + unity_bridge.move_object_to_pose("robot", p) + pano_image = unity_bridge.get_image("robot/pano_camera") + pano_image = vertexnav.utils.convert.image_aligned_to_robot( + image=pano_image, r_pose=p) + return pano_image[64:-64] * 1.0 / 255 + + pano_images = [get_image(p) for p in poses] + + if do_return_time: + yield poses, odoms, pano_images, time.time() - iter_start_time + else: + yield poses, pano_images + + +def write_video_frame(axs, + writer, + counter, + pose, + pano_images, + net_data, + obs, + nvg, + perfect_nvg, + plot_data, + args, + figure_only=False): + ax1, ax3 = axs + + do_plot_frontier_paths = True + do_plot_vis_polys = False + + s = pano_images[0].shape + buf = np.ones([8, s[1], 3]) + + composite_image = pano_images[0] + + for im in pano_images[1:]: + composite_image = np.concatenate((composite_image, buf, im), axis=0) + + ax1.clear() + ax1.axis('off') + ax1.imshow(composite_image) + ax1.set_xlim(0, composite_image.shape[1]) + ax1.set_ylim(composite_image.shape[0], 0) + + ax3.clear() + ax3.set_facecolor([0.8, 0.8, 0.8]) + ax3.get_xaxis().set_ticks([]) + ax3.get_yaxis().set_ticks([]) + + proposed_world = nvg.get_proposed_world() + known_space_poly = plot_data['known_space_poly'] + + vertexnav.plotting.plot_polygon(ax3, + known_space_poly, + color=[1.0, 1.0, 1.0], + alpha=1.0) + + # Plot the clusters + vertex_remapping = vertexnav_accel.get_vertex_remapping( + nvg.vertices, set(tuple(c) for c in nvg.topology)) + vertex_id_dict = {v.id: v for v in nvg.vertices} + clusters = [ + vertexnav.prob_vertex_graph.Cluster(c, vertex_id_dict) + for c in nvg.topology + ] + for cluster in clusters: + if not cluster.is_active and cluster.num_dets > 2: + vert = vertex_remapping[cluster.vids[0]] + ax3.plot(vert.position[0], + vert.position[1], + 'r.', + alpha=0.4, + markersize=vertexnav.plotting.SCATTERSIZE * 2) + + vertexnav.plotting.plot_world(ax3, plot_data['world'], alpha=0.2) + + if do_plot_frontier_paths: + plot_data['frontier_paths'] = sorted(plot_data['frontier_paths'], + key=lambda d: id(d[2])) + + for ii in range(args.num_robots): + perfect_points = np.array([ + (p.x, p.y, p.yaw, p.index) + for p in perfect_nvg.r_poses[ii::args.num_robots] + ]) + ax3.plot(perfect_points[:, 0], + perfect_points[:, 1], + '--k', + alpha=0.5) + + for ii, (f, path, f_robot) in enumerate(plot_data['frontier_paths']): + points = vertexnav.utils.calc.smooth_path(path) + line, = ax3.plot(points[:, 0], + points[:, 1], + alpha=0.5, + linewidth=1.5) + if f is not None: + vertexnav.plotting.plot_linestring(ax3, + f.linestring, + color=line.get_color(), + alpha=1.0, + linewidth=1.0, + linestyle='--') + r_points = np.array([ + (p.x, p.y, p.yaw, p.index) + for p in nvg.r_poses[ii::args.num_robots] + ]) + ax3.plot(r_points[:, 0], + r_points[:, 1], + color=line.get_color(), + alpha=0.75) + + ax3.plot(f_robot.pose.x, + f_robot.pose.y, + '.', + color=line.get_color()) + ax3.plot(f_robot.pose.x, + f_robot.pose.y, + 'x', + color=line.get_color()) + + vertexnav.plotting.plot_proposed_world(ax3, + proposed_world, + do_show_points=True, + do_plot_visibility=False, + robot_pose=pose) + + if do_plot_vis_polys: + poly_points = vertexnav.noisy.compute_conservative_space_from_obs( + nvg.r_poses[-1], nvg.observations[-1], radius=args.max_range) + obs_space = shapely.geometry.Polygon(poly_points) + vertexnav.plotting.plot_polygon(ax3, + obs_space, + color=[1.0, 0.0, 0.0], + alpha=0.4) + + h_obs = vertexnav.noisy.compute_hypothetical_observation( + proposed_world, + nvg.r_poses[-1], + nvg.observations[-1], + radius=args.max_range) + poly_points = vertexnav.noisy.compute_conservative_space_from_obs( + nvg.r_poses[-1], h_obs, radius=args.max_range) + obs_space = shapely.geometry.Polygon(poly_points) + vertexnav.plotting.plot_polygon(ax3, + obs_space, + color=[0.0, 0.0, 1.0], + alpha=0.3) + + xbounds, ybounds = plot_data['world'].map_bounds + ax3.set_xlim(xbounds[0] - 15, xbounds[1] + 15) + ax3.set_ylim(ybounds[1] + 15, ybounds[0] - 15) + + if not figure_only: + writer.grab_frame() + + +def travel_and_make_plot(args): + """Integration test running the robot through a simple environment, + adding new vertext detections, and performing inference to determine + the most likely map""" + + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + print(f"Neural Net Compute Device: {device}") + # eval_net = vertexnav.learning.load_pytorch_net_vertex( + # args.network_file, device) + eval_net = vertexnav.models.VertexNavGrid.get_net_eval_fn( + network_file=args.network_file, device=device) + + save_dir = os.path.dirname(args.figure_path) + log_text_file_name = os.path.join(save_dir, "data_log.txt") + logs = { + "r_poses": [], + "net_time": [], + "perfect_coverage": [], + "noisy_coverage": [], + "final_map": None + } + + def get_range(position, obs_pose): + return math.sqrt((position[1] - obs_pose.y)**2 + + (position[0] - obs_pose.x)**2) + + if args.video_path is not None: + axs, writer = set_up_video_gen(args.video_path) + + world, builder, inflation_rad, path = get_environment(args) + plogs = [] + + start_pose = path[0] + start_time = time.time() + with builder(args.unity_exe_path, sim_scale=0.15) as unity_bridge: + if args.do_use_robot: + if args.environment == 'outdoor': + robots = [ + vertexnav.robot.Turtlebot_Robot(start_pose, + primitive_length=2.0 * 1.8, + unity_bridge=unity_bridge) + for _ in range(args.num_robots) + ] + else: + robots = [ + vertexnav.robot.Turtlebot_Robot(start_pose, + primitive_length=1.8, + unity_bridge=unity_bridge) + for _ in range(args.num_robots) + ] + goals = [ + world.get_random_pose(min_signed_dist=inflation_rad) + for _ in range(100) + ] + goal = max(goals, + key=lambda g: (g.x - start_pose.x)**2 + + (g.y - start_pose.y)**2) + else: + robots = None + + if args.do_explore: + goal = vertexnav.Pose(x=10000, y=10000) + + # Set up environment and data loop + unity_bridge.make_world(world) + data_iterator = get_data_iterator(unity_bridge, + world, + path, + robots=robots, + do_return_time=True) + + # nvg = vertexnav.vertex_graph.NoisyVertexGraph() + nvg = vertexnav.prob_vertex_graph.ProbVertexGraph() + nvg.DO_SLAM = True + nvg.DO_SAMPLE_TOPOLOGY = args.do_merge_vertices + nvg.DO_MULTI_VERTEX_MERGE = args.do_multi_vertex_merge + perfect_nvg = vertexnav.vertex_graph.PerfectVertexGraph() + + counter = 0 + t_counter = 0 + net_time = 0 + + for poses, odoms, pano_images, get_data_time in data_iterator: + t_counter += 1 + counter += len(poses) + + print(("=" * 80)) + print(("Pose: {} | Counter: {}".format(poses[0], t_counter))) + print(("dtime(image data): {}".format(get_data_time))) + + for pose in poses: + perfect_obs_time = time.time() + perfect_obs = vertexnav.noisy.convert_world_obs_to_noisy_detection( + world.get_vertices_for_pose(pose, + max_range=args.max_range), + pose, + do_add_noise=False, + cov_rt=[[2.0**2, 0], [0, 0.15**2]]) + perfect_nvg.add_observation(perfect_obs, pose) + print(("dtime(perfect obs): {}".format(time.time() - + perfect_obs_time))) + + if not args.do_use_perfect_obs: + neural_net_time = time.time() + net_data = [eval_net(pano_image) for pano_image in pano_images] + + obss = [ + vertexnav.noisy.convert_net_grid_data_to_noisy_detection( + nd, + pose, + max_range=args.max_range, + num_range=args.num_range, + num_bearing=args.num_bearing, + sig_r=args.sig_r, + sig_th=args.sig_th, + nn_peak_thresh=args.nn_peak_thresh) + for pose, nd in zip(poses, net_data) + ] + + print(("dtime(neural net time): {}".format(time.time() - + neural_net_time))) + + add_obs_time = time.time() + for robot_id, (obs, odom, + pose) in enumerate(zip(obss, odoms, poses)): + if odom is None: + pose.robot_id = robot_id + nvg.add_observation(obs, r_pose=pose) + else: + odom.robot_id = robot_id + odom = vertexnav.Pose(x=odom.x, + y=odom.y, + yaw=odom.yaw + 0.1 * + (random.random() - 0.5), + robot_id=odom.robot_id) + # yaw=odom.yaw + 0.01) + print(("odom", odom)) + nvg.add_observation(obs, odom=odom) + + print(("dtime(add observation): {}".format(time.time() - + add_obs_time))) + + if t_counter % 5 == 0: + stime = time.time() + nvg.sample_states( + vertex_association_time_window=15 * args.num_robots, + vertex_sampling_time_window=15 * args.num_robots, + num_topology_samples=20, + num_vertex_samples=50, + vertex_association_dist_threshold=20, + do_update_state=True) + dtime = time.time() - stime + net_time += dtime + print(("Sampling: ", dtime, net_time)) + else: + net_data = None + obs = perfect_obs + nvg = perfect_nvg + + # Planning + proposed_world_time = time.time() + # FIXME(gjstein): get_proposed_world should take robot.all_poses + proposed_world = nvg.get_proposed_world() + print(("dtime(proposed world): {}".format(time.time() - + proposed_world_time))) + + vis_graph_time = time.time() + visibility_graph = vertexnav.planning.VisibilityGraph( + proposed_world, inflation_rad=0.8 * inflation_rad) + print(("dtime(compute vis graph): {}".format(time.time() - + vis_graph_time))) + + known_poly_time = time.time() + known_space_poly = nvg.get_known_poly(proposed_world, + args.max_range) + print(("dtime(compute known poly): {}".format(time.time() - + known_poly_time))) + + perfect_known_space_poly = perfect_nvg.get_known_poly( + perfect_nvg.get_proposed_world(), args.max_range) + + coverage_perfect_iou = world.compute_iou(perfect_known_space_poly) + print(("Coverage (Perfect): {}".format(coverage_perfect_iou))) + coverage_noisy_iou = world.compute_iou(known_space_poly) + print(("Coverage (Noisy): {}".format(coverage_noisy_iou))) + + compute_path_time = time.time() + + uninflated_ksp = known_space_poly + if args.environment == 'outdoor': + known_space_poly = known_space_poly.buffer(inflation_rad / 8) + if args.do_use_frontiers: + frontiers = vertexnav.planning.compute_frontiers_from_poly( + uninflated_ksp, proposed_world, inflation_rad) + frontier_paths = vertexnav.planning.multiagent_select_frontiers_greedy( + robots, + frontiers, + visibility_graph, + do_explore=args.do_explore, + known_space_poly=known_space_poly, + goal=goal, + nearby_clutter_fn=lambda rob: world.get_nearby_clutter( + rob.pose, 3 * inflation_rad), + cl_inflation_rad=1.4 * inflation_rad) + else: + nearby_clutter = world.get_nearby_clutter( + robots[0].pose, 3 * inflation_rad) + if args.do_explore: + path, cost = visibility_graph.get_shortest_path( + start_point=(robots[0].pose.x, robots[0].pose.y), + known_space_poly=known_space_poly, + do_return_cost=True, + nearby_clutter=nearby_clutter, + cl_inflation_rad=1.4 * inflation_rad) + else: + path, cost = visibility_graph.get_shortest_path( + start_point=(robots[0].pose.x, robots[0].pose.y), + end_point=(goal.x, goal.y), + do_return_cost=True, + nearby_clutter=nearby_clutter, + cl_inflation_rad=inflation_rad) + + frontier_paths = [(None, path, robots[0])] + + known_space_poly = uninflated_ksp + + print( + ("dtime(compute compute path): {}".format(time.time() - + compute_path_time))) + + # Plotting + plotting_time = time.time() + plot_data = { + 'known_space_poly': known_space_poly, + 'world': world, + 'frontier_paths': frontier_paths, + } + plogs.append({ + 'world_boundary': + world.boundary, + 'proposed_world_walls': + proposed_world.walls, + 'proposed_world_verts': + proposed_world.vertices, + 'inactive_verts': [ + v.position for v in nvg.vertices + if not v.is_active and v.num_detections > 2 + ], + 'known_poly': + known_space_poly, + # 'clutter_data': world.clutter_element_data, + 'poses': [(p.x, p.y) for p in robots[0].all_poses], + 'perfect_poses': [(p.x, p.y) for p in perfect_nvg.r_poses] + }) + + if counter > args.num_robots * args.max_steps: + break + + if args.video_path is not None: + try: + data = sorted(zip(pano_images, robots), + key=lambda d: id(d[1])) + s_pano_images = [environments.utils.convert.image_aligned_from_robot_to_global(im, ro.pose) + for im, ro in data] + + write_video_frame(axs, + writer, + t_counter, + poses[0], + s_pano_images, + net_data, + obs=obs, + nvg=nvg, + perfect_nvg=perfect_nvg, + plot_data=plot_data, + args=args) + except: # noqa + raise ValueError + + print(("dtime(compute plotting): {}".format(time.time() - + plotting_time))) + + # Store logs + rp = robots[0].pose + logs["r_poses"].append( + vertexnav.Pose(rp.x, rp.y, rp.yaw, rp.robot_id)) + logs["perfect_coverage"].append(coverage_perfect_iou) + logs["noisy_coverage"].append(coverage_noisy_iou) + + # Robot motion + if args.do_use_robot: + robot_motion_time = time.time() + + try: + for f, path, robot in frontier_paths: + robot.move(goal, path, inflation_rad=inflation_rad) + + except ValueError: + pass + + print(("dtime(robot motion): {}".format(time.time() - + robot_motion_time))) + + goal_dist = min([ + math.sqrt((robot.pose.x - goal.x)**2 + + (robot.pose.y - goal.y)**2) for robot in robots + ]) + all_still = all([r.still_count > 10 for r in robots]) + if all_still or goal_dist < 2: + logs["net_time"].append(time.time() - start_time) + print(("Total time: {}".format(time.time() - start_time))) + print("Finishing up.") + break + + logs["net_time"].append(time.time() - start_time) + print(("Total time: {}".format(time.time() - start_time))) + + # Compute and print the final map likelihood + nvg.perform_slam_update() + pose_obs_pairs = list(zip(nvg.r_poses, nvg.observations)) + final_proposed_world = nvg.get_proposed_world_fast( + topology=nvg.topology) + final_proposed_world_log_prob = nvg.compute_world_log_prob( + final_proposed_world, pose_obs_pairs) + print( + ("Final Log Prob: {:8.3f}".format(final_proposed_world_log_prob))) + + # Finish up the video + writer.finish() + + # Generate a plot + axs = set_up_video_gen(video_path=None, figure_only=True) + write_video_frame(axs, + None, + t_counter, + poses[0], + s_pano_images, + net_data, + obs=obs, + nvg=nvg, + perfect_nvg=perfect_nvg, + plot_data=plot_data, + args=args, + figure_only=True) + plt.savefig(args.figure_path, dpi=300) + + with open(log_text_file_name, "a+") as log_file: + if args.do_use_perfect_obs: + s_planner = "perfect" + else: + s_planner = " noisy" + + if args.do_explore: + s_planner += " exp" + else: + s_planner += " nav" + + if args.do_merge_vertices: + if args.do_multi_vertex_merge: + s_planner += " Mvmp" + else: + s_planner += " Svmp" + else: + s_planner += " NOmp" + + log_file.write( + "{:10d} {} {:8d} {:12.6f} {:8.6f} {:8.6f} {} {}\n".format( + args.seed, + s_planner, + len(logs["net_time"]), + max(logs["net_time"]), + max(logs["perfect_coverage"][-10:]), + max(logs["noisy_coverage"][-10:]), + args.environment, + args.num_robots, + )) + + +def parse_args(): + """Define the command line arguments.""" + parser = argparse.ArgumentParser( + description='Generate video showing neural net results ' + + 'in simulated hallway environment.') + parser.add_argument('--environment', type=str) + parser.add_argument('--unity_exe_path', type=str) + parser.add_argument('--network_file', type=str) + parser.add_argument('--video_path', type=str, default=None) + parser.add_argument('--figure_path', type=str, default=None) + parser.add_argument('--save_frames', type=int, nargs='+', default=None) + parser.add_argument('--seed', type=int, default=13) + parser.add_argument('--do_use_perfect_obs', action='store_true') + parser.add_argument('--do_explore', action='store_true') + parser.add_argument('--do_use_frontiers', action='store_true') + parser.add_argument('--num_robots', + type=int, + default=1, + help='Number of robots.') + parser.add_argument('--grid_resolution', type=float, default=1.0) + parser.add_argument('--merge_type', type=str, required=True) + + # Grid variables + parser.add_argument('--max_range', + type=int, + default=120, + help='Max range for range in output grid.') + parser.add_argument('--num_range', + type=int, + default=32, + help='Number of range cells in output grid.') + parser.add_argument('--num_bearing', + type=int, + default=128, + help='Number of bearing cells in output grid.') + + parser.add_argument('--sig_r', type=float, default=10.0) + parser.add_argument('--sig_th', type=float, default=0.25) + parser.add_argument('--nn_peak_thresh', type=float, required=True) + + parser.add_argument('--xbounds', + nargs='+', + type=int, + default=[-50, 220], + help='Boundary in "x".') + parser.add_argument('--ybounds', + nargs='+', + type=int, + default=[-100, 250], + help='Boundary in "y".') + parser.add_argument('--max_steps', type=int, default=400) + + # Robot variables + parser.add_argument('--do_use_robot', action='store_true') + + args = parser.parse_args() + + if not args.do_use_perfect_obs and args.network_file is None: + raise ValueError( + "Network file required when perfect detections not used.") + + if 'none' not in args.merge_type: + args.do_merge_vertices = True + else: + args.do_merge_vertices = False + if 'multi' in args.merge_type: + args.do_multi_vertex_merge = True + else: + args.do_multi_vertex_merge = False + + if args.do_use_robot: + if args.num_robots < 1: + raise ValueError("There must be at least one robot.") + if not args.num_robots == 1 and not args.do_use_frontiers: + raise ValueError("Frontiers must be used for multiple robots.") + + return args + + +if __name__ == "__main__": + args = parse_args() + args.current_seed = args.seed + travel_and_make_plot(args) diff --git a/modules/vertexnav/vertexnav/scripts/gen_vertex_training_data_sim.py b/modules/vertexnav/vertexnav/scripts/gen_vertex_training_data_sim.py new file mode 100644 index 0000000..4ef061f --- /dev/null +++ b/modules/vertexnav/vertexnav/scripts/gen_vertex_training_data_sim.py @@ -0,0 +1,131 @@ +import argparse +import environments +import vertexnav +import learning +import matplotlib.pyplot as plt +import numpy as np +import os + + +def data_gen_loop_dungeon(args, seed): + """Loop through poses and write data to file.""" + WorldBuildingUnityBridge = environments.simulated.WorldBuildingUnityBridge + + with WorldBuildingUnityBridge(args.unity_path, sim_scale=0.15) as unity_bridge: + print(f"Generating new world (seed: {seed})") + world = vertexnav.environments.dungeon.DungeonWorld(hall_width=20, + inflate_ratio=0.30) + unity_bridge.make_world(world) + for counter in range(args.poses_per_world): + pose = world.get_random_pose(min_signed_dist=2.0) + datum = vertexnav.learning.get_vertex_datum_for_pose( + pose, + world, + unity_bridge, + min_range=2.0, + max_range=args.max_range, + num_range=args.num_range, + num_bearing=args.num_bearing) + + if datum is None: + continue + + if args.do_visualize_data: + print("Visualizing Data") + visualize_datum(datum) + plt.show() + + # Write datum to file + write_datum_to_pickle(args, counter, datum) + counter += 1 + print(f"Saved pose: {args.seed}.{counter}") + + # Write a final file that indicates training is done + plt.figure(figsize=(6, 6)) + vertexnav.plotting.plot_world(plt.gca(), world) + plt.title(f'Seed: {args.seed}') + plt.savefig(os.path.join(args.base_data_path, 'data', + 'training_env_plots', + f'{args.data_plot_name}_{args.seed}.png'), + dpi=150) + + +def write_datum_to_pickle(args, counter, datum): + save_dir = os.path.join(args.base_data_path, 'data') + data_filename = os.path.join('pickles', f'dat_{args.seed}_{counter}.pgz') + learning.data.write_compressed_pickle( + os.path.join(save_dir, data_filename), datum) + + csv_filename = f'{args.data_file_base_name}_{args.seed}.csv' + with open(os.path.join(save_dir, csv_filename), 'a') as f: + f.write(f'{data_filename}\n') + + +def visualize_datum(datum): + """Visualize data.""" + fig = plt.figure(figsize=(12, 12)) + (ax1, ax2, ax3) = fig.subplots(3, 1) + ax2.set_aspect('equal') + + ax1.clear() + for circle in np.argwhere(datum['is_left_gap']): + ax1.plot(circle[1] * 512 / 128, 128 / 2, '.', color='c') + for circle in np.argwhere(datum['is_corner']): + ax1.plot(circle[1] * 512 / 128, 128 / 2, '.', color='m') + for circle in np.argwhere(datum['is_right_gap']): + ax1.plot(circle[1] * 512 / 128, 128 / 2, '.', color='y') + for circle in np.argwhere(datum['is_point_vertex']): + ax1.plot(circle[1] * 512 / 128, 128 / 2, '.', color='w') + ax1.imshow(datum['image']) + + ax2.clear() + ax2.imshow(datum['depth']) + + ax3.clear() + vert_data = np.zeros(list(datum['is_vertex'].shape) + [3]) + vert_data[datum['is_vertex'] > 0.5] = 1.0 + vert_data[:, :, 0][datum['is_left_gap'] > 0.5] = 0 + vert_data[:, :, 1][datum['is_corner'] > 0.5] = 0 + vert_data[:, :, 2][datum['is_right_gap'] > 0.5] = 0 + ax3.imshow(vert_data) + + plt.show() + + +def get_parser(): + """Define the command line arguments.""" + parser = argparse.ArgumentParser(description='Generate vertext data.') + parser.add_argument('--xpassthrough', type=str, default='false') + parser.add_argument('--poses_per_world', default=250, type=int) + parser.add_argument('--environment', type=str, default='dungeon') + parser.add_argument('--unity_path', type=str) + parser.add_argument('--base_data_path', type=str, default='/data/') + parser.add_argument('--data_file_base_name', type=str, required=True) + parser.add_argument('--data_plot_name', type=str, required=True) + parser.add_argument('--seed', type=int) + parser.add_argument('--max_range', + type=int, + help='Max range for range in output grid.') + parser.add_argument('--num_range', + type=int, + help='Number of range cells in output grid.') + parser.add_argument('--num_bearing', + type=int, + help='Number of bearing cells in output grid.') + return parser + + +if __name__ == "__main__": + args = get_parser().parse_args() + args.do_visualize_data = args.xpassthrough == 'true' + data_gen_loop_dungeon(args, args.seed) + + # for seed in range(args.seed_range[0], args.seed_range[1]): + # print("Seed: {}".format(seed)) + # random.seed(seed, version=1) + # np.random.seed(seed) + # args.current_seed = seed + + # if args.environment.lower() == 'dungeon': + # else: + # raise ValueError("Environment '{}' not recognized.".format(args.environment)) diff --git a/modules/vertexnav/vertexnav/scripts/train_vertex_nav_net.py b/modules/vertexnav/vertexnav/scripts/train_vertex_nav_net.py new file mode 100644 index 0000000..bc4be8b --- /dev/null +++ b/modules/vertexnav/vertexnav/scripts/train_vertex_nav_net.py @@ -0,0 +1,171 @@ +import learning +import vertexnav +import argparse + +import os +import numpy as np +import torch +from torch.utils.tensorboard import SummaryWriter + + +def _get_preprocess_vertex_data_fn(args, roll_variables=None): + def preprocess_vertex_data(datum): + datum['image'] = np.transpose(datum['image'], + (2, 0, 1)).astype(np.float32) + + if roll_variables is not None: + rval = np.random.rand() + for var in roll_variables: + sh = datum[var].shape + datum[var] = np.roll(datum[var], + shift=int(round(rval * sh[-1])), + axis=len(sh) - 1) + + return datum + + return preprocess_vertex_data + + +def main(args): + use_cuda = torch.cuda.is_available() + device = torch.device("cuda" if use_cuda else "cpu") + model = vertexnav.models.VertexNavGrid(args).to(device) + print(f"Training Device: {device}") + + # Create the datasets and loaders + preprocess_function = _get_preprocess_vertex_data_fn( + args, model.ROLL_VARIABLES) + train_dataset = learning.data.CSVPickleDataset(args.training_data_file, + preprocess_function) + test_dataset = learning.data.CSVPickleDataset(args.test_data_file, + preprocess_function) + train_loader = torch.utils.data.DataLoader(train_dataset, + batch_size=args.batch_size, + shuffle=True, + num_workers=8) + test_loader = torch.utils.data.DataLoader(test_dataset, + batch_size=args.batch_size, + shuffle=True, + num_workers=4) + test_loader_iter = iter(test_loader) + + # Set up logging + train_writer = SummaryWriter(log_dir=os.path.join(args.logdir, "train")) + test_writer = SummaryWriter(log_dir=os.path.join(args.logdir, "test")) + + # Define the optimizer + learning_rate = args.learning_rate + optimizer = torch.optim.Adam(model.parameters(), lr=learning_rate) + + tot_index = 0 + for epoch in range(args.num_epochs): + for index, batch in enumerate(train_loader): + out = model(batch, device) + loss = model.loss(out, + batch, + device=device, + writer=train_writer, + index=tot_index) + + if index % 100 == 0: + with torch.no_grad(): + try: + tbatch = next(test_loader_iter) + except StopIteration: + test_loader_iter = iter(test_loader) + tbatch = next(test_loader_iter) + + tim = tbatch['image'] + tout = model(tbatch, device) + tloss = model.loss(tout, + tbatch, + device=device, + writer=test_writer, + index=tot_index) + next(iter(test_loader)) + + print( + f"Test Loss({epoch}.{index}, {tot_index}): {tloss.item()}" + ) + model.plot_images(test_writer, + 'image', + tot_index, + image=tim[0].detach(), + out=tout[0].detach().cpu(), + data=tbatch) + + # Perform update + optimizer.zero_grad() + loss.backward() + optimizer.step() + tot_index += 1 + + # Now save the trained model to file + torch.save(model.state_dict(), os.path.join(args.logdir, + f"{model.name}.pt")) + + +def get_parser(): + # Add new arguments + parser = argparse.ArgumentParser( + description="Train GapNav/LSP net with PyTorch.", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument('--training_data_file', + default=['tmp.tfrecords'], + nargs='+', + help='TFRecord containing the training data', + type=str) + parser.add_argument('--test_data_file', + default=[], + nargs='+', + help='TFRecord containing the test data', + type=str) + + # Logging + parser.add_argument('--logdir', + help='Directory in which to store log files', + required=True, + type=str) + parser.add_argument( + '--mini_summary_frequency', + default=100, + help='Frequency (in steps) mini summary printed to the terminal', + type=int) + parser.add_argument('--summary_frequency', + default=1000, + help='Frequency (in steps) summary is logged to file', + type=int) + + # Training + parser.add_argument('--num_epochs', + default=20, + help='Number of epochs to run training', + type=int) + parser.add_argument('--roll_variables', default=None, nargs='+') + parser.add_argument('--learning_rate', + default=0.005, + help='Initial learning rate', + type=float) + parser.add_argument('--batch_size', + default=8, + help='Number of data per training iteration batch', + type=int) + # parser.add_argument('--image_size', default=[128, 512], nargs='+', type=int) + parser.add_argument('--output_num_bearing', default=128, type=int) + parser.add_argument('--output_num_range', default=32, type=int) + parser.add_argument('--relative_positive_weight', + default=8.0, + help='Initial learning rate', + type=float) + parser.add_argument('--vertex_pred_weight', + default=500.0, + help='Initial learning rate', + type=float) + + return parser + + +if __name__ == '__main__': + # Parse the command line args and set device + args = get_parser().parse_args() + main(args) diff --git a/modules/vertexnav/vertexnav/utils/__init__.py b/modules/vertexnav/vertexnav/utils/__init__.py new file mode 100644 index 0000000..5450dc7 --- /dev/null +++ b/modules/vertexnav/vertexnav/utils/__init__.py @@ -0,0 +1,4 @@ +from . import calc # noqa: F401 +from . import convert # noqa: F401 +from . import data # noqa: F401 +from . import topology # noqa: F401 diff --git a/modules/vertexnav/vertexnav/utils/calc.py b/modules/vertexnav/vertexnav/utils/calc.py new file mode 100644 index 0000000..52f25d6 --- /dev/null +++ b/modules/vertexnav/vertexnav/utils/calc.py @@ -0,0 +1,198 @@ +import itertools +import math +import numpy as np +from skimage import measure +import shapely +import shapely.ops + +import vertexnav +"""Helper functions for doing calculations used in many files""" + +# Define some helper indices +yind = 0 +heightind = 1 +xind = 2 +yawind = 3 + + +def data_to_world_pose(d): + x = d[xind] + y = d[yind] + yaw = d[yawind] * math.pi / 180.0 + pose = vertexnav.Pose(x, y, yaw) + return pose + + +def eucl_dist(pos1, pos2): + return math.sqrt(eucl_dist_sq(pos1, pos2)) + + +def eucl_dist_sq(pos1, pos2): + return (pos1[1] - pos2[1])**2 + (pos1[0] - pos2[0])**2 + + +def directions_vec(num_im_cols): + """Returns an array of 'direction vectors' for a panoramic image + from Unity""" + + angles_rad = np.linspace(-math.pi, math.pi, num_im_cols + 1)[:-1] + directions = np.vstack((np.cos(angles_rad), np.sin(angles_rad))) + return (directions, angles_rad) + + +def range_bearing_vecs(max_range, num_range, num_bearing): + vec_range = np.linspace(start=0.0, stop=max_range, num=num_range + 1) + vec_range = vec_range[1:] + _, vec_bearing = directions_vec(num_bearing) + + return vec_range, vec_bearing + + +def detect_peaks(image, is_circular_boundary=False, peak_thresh=None): + + if is_circular_boundary: + ncols = image.shape[1] + image = np.concatenate((image, image), axis=1) + assert image.shape[1] == ncols * 2 + + labels = measure.label(image >= (peak_thresh - 0.1)) + + peaks = [] + for ii in range(1, labels.max().max() + 1): + tmp = np.zeros(image.shape) + mask = (labels == ii) + tmp[mask] = image[mask] + ind = np.unravel_index(np.argmax(tmp, axis=None), tmp.shape) + if tmp[ind] > peak_thresh: + peaks.append(ind) + + if is_circular_boundary: + return np.array([(coord[0], coord[1] % ncols) for coord in peaks + if coord[1] >= ncols / 2 and coord[1] < 3 * ncols / 2 + ]) + + return peaks + + +# State estimation and distance measures +def m_distance(pos_1, pos_2, inv_noise): + dpos = np.array([[pos_1[0] - pos_2[0]], [pos_1[1] - pos_2[1]]]) + M_dist = math.sqrt(np.matmul(dpos.T, np.matmul(inv_noise, dpos))) + return M_dist + + +def transform_local_to_world(det_theta, det_r, cov_rt, r_pose): + world_theta = det_theta + r_pose.yaw + cov_r = cov_rt[0, 0] + r_sq_cov_theta = (det_r**2) * cov_rt[1, 1] + sin_th = math.sin(world_theta) + cos_th = math.cos(world_theta) + sin_th_sq = sin_th**2 + cos_th_sq = cos_th**2 + Q11 = r_sq_cov_theta * sin_th_sq + cov_r * cos_th_sq + Q22 = r_sq_cov_theta * cos_th_sq + cov_r * sin_th_sq + Q12 = (cov_r - r_sq_cov_theta) * cos_th * sin_th + position = [r_pose.x + det_r * cos_th, r_pose.y + det_r * sin_th] + return position, np.array([[Q11, Q12], [Q12, Q22]]) + + +def smooth_path(path, segment_steps=50, smooth_factor=1.0 / 3): + steps = segment_steps + points = [ + (ii * 1.0 * seg[1][0] / steps + (1 - ii * 1.0 / steps) * seg[0][0], + ii * 1.0 * seg[1][1] / steps + (1 - ii * 1.0 / steps) * seg[0][1]) + for seg in zip(path[:-1], path[1:]) for ii in range(steps) + ] + points = np.array(points) + + # Smooth the points + sw = int(steps * smooth_factor) + if sw > 0: + avg_kernel = np.ones(sw) / sw + points[:, 0] = np.convolve( + np.pad(points[:, 0], (sw // 2, sw - sw // 2 - 1), 'edge'), + avg_kernel, 'valid') + points[:, 1] = np.convolve( + np.pad(points[:, 1], (sw // 2, sw - sw // 2 - 1), 'edge'), + avg_kernel, 'valid') + + return points + + +def full_simplify_shapely_polygon(poly): + """This function simplifies a polygon, removing any colinear points. + Though Shapely has this functionality built-in, it won't remove the + "start point" of the polygon, even if it's colinear.""" + + if isinstance(poly, shapely.geometry.MultiPolygon) or isinstance( + poly, shapely.geometry.GeometryCollection): + return shapely.geometry.MultiPolygon( + [full_simplify_shapely_polygon(p) for p in poly]) + + poly = poly.simplify(0.001, preserve_topology=True) + # The final point is removed, since shapely will auto-close polygon + points = np.array(poly.exterior.coords) + if (points[-1] == points[0]).all(): + points = points[:-1] + + def is_colinear(p1, p2, p3, tol=1e-6): + """Checks if the area formed by a triangle made of the three points + is less than a tolerance value.""" + return abs(p1[0] * (p2[1] - p3[1]) + p2[0] * (p3[1] - p1[1]) + p3[0] * + (p1[1] - p2[1])) < tol + + if is_colinear(points[0], points[1], points[-1]): + poly = shapely.geometry.Polygon(points[1:]) + + return poly + + +def obstacles_and_boundary_from_occupancy_grid(grid, resolution): + print("Computing obstacles") + print(resolution) + + known_space_poly = shapely.geometry.Polygon() + + polys = [] + for index, val in np.ndenumerate(grid): + if val < 0.5: + continue + + y, x = index + y *= resolution + x *= resolution + y -= 0.5 * resolution + x -= 0.5 * resolution + r = resolution + polys.append( + shapely.geometry.Polygon([(x, y), (x + r, y), (x + r, y + r), + (x, y + r) + ]).buffer(0.001 * resolution, 0)) + + known_space_poly = shapely.ops.cascaded_union(polys) + + def get_obstacles(poly): + if isinstance(poly, shapely.geometry.MultiPolygon): + return list( + itertools.chain.from_iterable([get_obstacles(p) + for p in poly])) + + obstacles = [ + full_simplify_shapely_polygon(shapely.geometry.Polygon(interior)) + for interior in list(poly.interiors) + ] + + # Simplify the polygon + boundary = full_simplify_shapely_polygon(poly) + + obstacles.append(boundary) + + return obstacles + + obs = get_obstacles(known_space_poly) + obs.sort(key=lambda x: x.area, reverse=True) + return obs[1:], obs[0] + + # # Old versions + # return get_obstacles(known_space_poly), None + # return [], get_obstacles(known_space_poly)[0] diff --git a/modules/vertexnav/vertexnav/utils/convert.py b/modules/vertexnav/vertexnav/utils/convert.py new file mode 100644 index 0000000..e9d2053 --- /dev/null +++ b/modules/vertexnav/vertexnav/utils/convert.py @@ -0,0 +1,131 @@ +import math +import numpy as np +import shapely + +import vertexnav +"""Functions devoted to converting between (mostly) the various data types +introduced in the vertexnav package.""" + + +def ranges_from_depth_image(depth, max_range=200.0): + """Convert depth image into ranges.""" + dshape = depth.shape + dslice = depth[dshape[0] // 2, :, :] + ranges = (1.0 * dslice[:, 0] + dslice[:, 1] / 256.0 + + dslice[:, 2] / 256.0 / 256.0) / 256.0 * max_range + return ranges.astype(np.float32) + + +def depths_from_depth_image(depth_image): + return (1.0 * depth_image[:, :, 0] + depth_image[:, :, 1] / 256.0 + + depth_image[:, :, 2] / 256.0 / 256.0) / 256.0 * 200.0 + + +def image_aligned_to_robot(image, r_pose): + """Permutes an image from axis-aligned to robot frame.""" + cols = image.shape[1] + roll_amount = int(round(-cols * r_pose.yaw / (2 * math.pi))) + return np.roll(image, shift=roll_amount, axis=1) + + +def image_aligned_to_subgoal(image, r_pose, subgoal): + """Permutes an image from axis-aligned to subgoal-pointing frame. + The subgoal should appear at the center of the image.""" + cols = image.shape[1] + sp = subgoal.get_centroid() + yaw = np.arctan2(sp[1] - r_pose.y, sp[0] - r_pose.x) - r_pose.yaw + roll_amount = int(round(-cols * yaw / (2 * math.pi))) + return np.roll(image, shift=roll_amount, axis=1) + + +def get_corner_vector_from_obs(observation, size, pose, dtype='gap'): + """Get the flattened vector of gaps. The size of the vector typically + corresponds to the number of columns in the corresponding image.""" + is_gap_vector = np.zeros([size], dtype=int) + gap_dist = np.zeros([size], dtype=int) + directions, angles_rad = vertexnav.utils.calc.directions_vec(size) + point = np.array([pose.x, pose.y]) + + if not dtype == 'gap' and not dtype == 'convex': + raise ValueError('Corner type "{}" unsupported.'.format(dtype)) + + def dist(a, b): + d = b - a + return math.sqrt(d[0]**2 + d[1]**2) + + for corner in observation: + ind = np.argmax(np.cos(angles_rad - corner.angle_rad)) + is_gap_vector[ind] = 1 + gap_dist[ind] = dist(corner.position, point) + + return is_gap_vector, gap_dist + + +def get_vertex_grid_data_from_obs(observation, size, pose, max_range, + num_range, num_bearing): + """Get the flattened vector of gaps. The size of the vector typically + corresponds to the number of columns in the corresponding image. + + 'observation' is assumed to be a vector of PerfectVertexDetection objects + and ordered according to their 'angle_rad'. + """ + + # Initialize some vectors + is_vertex_vector = np.zeros([num_range, num_bearing], dtype=int) + is_left_gap_vector = np.zeros([num_range, num_bearing], dtype=int) + is_right_gap_vector = np.zeros([num_range, num_bearing], dtype=int) + is_corner_vector = np.zeros([num_range, num_bearing], dtype=int) + is_point_vertex_vector = np.zeros([num_range, num_bearing], dtype=int) + is_in_view = np.zeros([num_range, num_bearing], dtype=int) + + # Lookup vectors + vec_range, vec_bearing = vertexnav.utils.calc.range_bearing_vecs( + max_range, num_range, num_bearing) + + point = np.array([pose.x, pose.y]) + + def dist(a, b): + d = b - a + return math.sqrt(d[0]**2 + d[1]**2) + + for vertex in observation: + # For all gap types, add the detection to the 'is_vertex' vector and + # compute distance. + vertex_range = dist(vertex.position, point) + ind_bearing = np.argmax(np.cos(vec_bearing - vertex.angle_rad)) + ind_range = np.argmin(abs(vec_range - vertex_range)) + + is_vertex_vector[ind_range, ind_bearing] = 1 + + label = vertex.detection_type.label + is_right_gap_vector[ind_range, ind_bearing] = label[0] + is_corner_vector[ind_range, ind_bearing] = label[1] + is_left_gap_vector[ind_range, ind_bearing] = label[2] + is_point_vertex_vector[ind_range, ind_bearing] = label[3] + + # Also generate the observed region: + dr = vec_range[1] - vec_range[0] + vis_poly = shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs(pose, + observation, + radius=max_range)) + vis_poly = vis_poly.buffer(1.5 * dr) + for ir, vr in np.ndenumerate(vec_range): + for ib, vb in np.ndenumerate(vec_bearing): + x = vr * math.cos(vb) + pose.x + y = vr * math.sin(vb) + pose.y + if vis_poly.contains(shapely.geometry.Point(x, y)): + is_in_view[ir, ib] = 1 + + # assert((is_vertex_vector == ( + # is_left_gap_vector + is_right_gap_vector + + # is_corner_vector + is_point_vertex_vector)).all()) + + return { + 'is_vertex': is_vertex_vector, + 'is_left_gap': is_left_gap_vector, + 'is_right_gap': is_right_gap_vector, + 'is_corner': is_corner_vector, + 'is_point_vertex': is_point_vertex_vector, + 'is_in_view': is_in_view, + } diff --git a/modules/vertexnav/vertexnav/utils/data.py b/modules/vertexnav/vertexnav/utils/data.py new file mode 100644 index 0000000..5a397e5 --- /dev/null +++ b/modules/vertexnav/vertexnav/utils/data.py @@ -0,0 +1,15 @@ +import vertexnav + + +def follow_path_iterator(path, segment_steps=50, smooth_factor=1.0 / 3): + """Loop through a pose and return a smoothed path (of Poses).""" + # First get the smoothed path + points = vertexnav.utils.calc.smooth_path(path, + segment_steps=segment_steps, + smooth_factor=smooth_factor) + + # Convert to poses + poses = [vertexnav.Pose(point[0], point[1]) for point in points] + + for pose in poses: + yield pose diff --git a/modules/vertexnav/vertexnav/utils/topology.py b/modules/vertexnav/vertexnav/utils/topology.py new file mode 100644 index 0000000..7f273d2 --- /dev/null +++ b/modules/vertexnav/vertexnav/utils/topology.py @@ -0,0 +1,124 @@ +#!/usr/env/python +''' +An implementation of an adjusted inference algorithm in: +Inference in the Space of Topological Maps: An MCMC-based Approach +https://smartech.gatech.edu/bitstream/handle/1853/38451/Ranganathan04iros.pdf +Maintainer: vpreston-at-{whoi, mit}-dot-edu +''' + +import itertools +import numpy as np +import random + + +def draw_sample(topo): + '''Given a starting topology, draw a proposal topology and return the proposal ratio. + Done by randonly choosing a merge or split move among the partitions in the topology. + Algorithm 2. + Input: + - T (list of tuples) topology + Output: + - prop (list of tuples) update topology + - prop_ratio (float) proposal ratio + - move_type (int 1 or 2) integer flag for move type proposed + ''' + T = [[ii for ii in c] for c in topo] + if np.random.uniform(0, 1, 1) <= 0.5: + # Perform a merge move, move_type flag == 1 + move_type = 1 + + if len(T) == 1: # if there is only one set, cannot merge + prop = T + prop_ratio = 1. + else: + # find the total number of mergeable pairs of sets, Nm + Nm = len(list(itertools.combinations( + T, 2))) # simply enumerate all possible pairs + + # select P and Q, the sets to merge + Pid = random.randrange(len(T)) # select a set at random + P = T[Pid] + T.pop(Pid) + + Qid = random.randrange(len(T)) # select another set at random + Q = T[Qid] + T.pop(Qid) + + # make the merge proposal + merge = [] + for elem in P: + merge.append(elem) + for elem in Q: + merge.append(elem) + + T.append(tuple(merge)) + + # Find the total number of splits in proposal topology, Ns + Ns = 0. + for elem in T: + if len(elem) > 1: + Ns += 1. + + # calculate the proposal ratio + prop = T + prop_ratio = Nm * 1. / (Ns * stirling(len(merge), 2)) + else: + # Perform a split move, move_type flag == 2 + move_type = 2 + + # find the total number of splits Ns + Ns = 0. + for elem in T: + if len(elem) > 1: + Ns += 1. + + # select R and get P and Q + options = [] + for i, r in enumerate(T): + if len(r) <= 1: + pass + else: + options.append(i) + + if Ns < 1: + # there are only singleton sets, propose the same topo + prop = T + prop_ratio = 1. + else: + # there are at least options + Rid = options[random.randrange( + 0, + len(options))] # choose a random index from the valid options + R = T[Rid] + T.pop(Rid) + splitid = random.randrange(len(R)) + P = R[:splitid] + Q = R[splitid:] + if len(P) > 0: + T.append(tuple(P)) + if len(Q) > 0: + T.append(tuple(Q)) + + # find the total number of sets in proposal topology, Nm + if len(T) > 1: + Nm = len(list(itertools.combinations(T, 2))) + prop_ratio = 1. / Nm * Ns * stirling(len(R), 2) + else: + Nm = 1. + prop_ratio = 0.0 # 1./Nm * Ns * stirling(len(R), 2) + prop = T + + return prop, prop_ratio, move_type + + +def stirling(n, m): + '''Recursive function that returns the Stirling number of the first + kind.''' + row = [1] + [0 for _ in range(m)] + for i in range(1, n + 1): + new = [0] + for j in range(1, m + 1): + sling = (i - 1) * row[j] + row[j - 1] + new.append(sling) + row = new + return row[m] diff --git a/modules/vertexnav/vertexnav/vertex_graph.py b/modules/vertexnav/vertexnav/vertex_graph.py new file mode 100644 index 0000000..563386b --- /dev/null +++ b/modules/vertexnav/vertexnav/vertex_graph.py @@ -0,0 +1,269 @@ +import math +import numpy as np +import scipy +import shapely + +import vertexnav +from .noisy import NoisyVertex, NoisyWall + + +def safely_add_poly(poly, adding_poly): + """Combine two shapely (or other type) polygons""" + try: + new_poly = poly.union(adding_poly) + if isinstance(new_poly, shapely.geometry.GeometryCollection): + + new_new_poly = poly + for geom in new_poly: + if isinstance(geom, shapely.geometry.Polygon): + new_new_poly = new_new_poly.union(geom) + else: + new_new_poly = new_new_poly.union( + geom.buffer(1e-2, + resolution=0, + cap_style=3, + join_style=2)) + + if isinstance(new_new_poly, shapely.geometry.Polygon): + new_poly = new_new_poly + else: + return poly + if new_poly.is_valid and new_poly.area >= 0.9999 * poly.area: + return new_poly.simplify(1.5e-2, preserve_topology=False) + else: + return poly + + except Exception as e: + print("Failure") + print((str(e))) + return poly + + +class PerfectVertexGraph(object): + """ + PerfectVertexGraph represents the underlying map of vertices and wall edges. + Same as Noisy version, but with (obviously) no noise in observations + """ + def __init__(self): + self.vertices = [] + self.walls = {} # Dict: {(vert_L.id, vert_R.id) : NoisyWall} + self.r_poses = [] + self.observations = [] + self.world = None + + self.false_positive_rate = 0.0 + self.false_negative_rate = 0.0 + + self._last_proposed_world = None + self._known_space_last_updated = -1 + self._known_space_poly = shapely.geometry.Polygon([]) + + def add_wall_detection(self, + vert_det_L, + vert_det_R, + num_false_positives=0): + """Updates walls to include sensor observations. This function + requires that the 'inverse_associations' has already been taken + care of.""" + + # Check that the inverse association has not yet been done + assert not isinstance(vert_det_L, NoisyVertex) + assert not isinstance(vert_det_R, NoisyVertex) + + # If the angle spread is too high, reject this wall proposal + dtheta = (vert_det_L.angle_rad - vert_det_R.angle_rad) % (2 * math.pi) + if dtheta >= math.pi: + return + + vert_L = vert_det_L.associated_vertex + vert_R = vert_det_R.associated_vertex + + key = tuple(sorted([vert_L.id, vert_R.id])) + if key not in self.walls: + self.walls[key] = NoisyWall(vert_L, vert_R) + + fp_factor = self.false_positive_rate**num_false_positives + self.walls[key].add_detection(vert_det_L, + vert_det_R, + false_positive_factor=fp_factor) + + def add_observation(self, observation, r_pose): + """ + Add a new observation to the graph. First associate each detection + with a single vertex. Ensure these matches are one to one. Any + unmatched detections create new vertices. Update the graphs various + lists and dictionaries in the process. Then pick the most likely map + given this observation, and add the walls to the list of all walls. + + Arguments: + self -- NoisyVertexGraph + observation -- list of NoisyVertexDetections + r_pose -- pose of the robot + """ + for det in observation: + det.update_props(r_pose) + + self.r_poses.append(r_pose) + self.observations.append(observation) + self.associate_detections(observation, r_pose) + + # Add the wall detections + shift = 0 + shifted_observation = observation + while shift < len(observation): + shifted_observation = shifted_observation[ + 1:] + shifted_observation[:1] + shift += 1 + for det_L, det_R in zip(shifted_observation, observation): + self.add_wall_detection(det_L, + det_R, + num_false_positives=shift - 1) + + def associate_detections(self, observation, r_pose): + """Use an optimal assignment to compute the vertex association. + Priority is given to the active vertices""" + + # Updating the vertices invalidates the vertex positions memo + self.vertex_positions_memo = None + + # First assignment + all_verts = self.vertices + all_detections = observation + if len(all_detections) == 0: + return + + # Orer: detections, vertices (+ unassociations) + cost_mat = 1.0 * np.ones( + (len(all_detections), len(all_verts) + len(all_detections))) + for dind, det in enumerate(all_detections): + det_inv_cov = np.linalg.inv(det.cov) + for vind, vert in enumerate(all_verts): + cost_mat[dind, vind] = vertexnav.utils.calc.m_distance( + vert.position, det.position, inv_noise=det_inv_cov) + if not vert.is_active: + cost_mat[dind, vind] += 0.8 + + dinds, vinds = scipy.optimize.linear_sum_assignment(cost_mat) + + unassociated_detections = [] + for dind, vind in zip(dinds, vinds): + # Check to see if it's unassociated + if vind >= len(all_verts): + unassociated_detections.append(all_detections[dind]) + else: + vert = all_verts[vind] + det = all_detections[dind] + vert.add_detection(det.position, det.cov, r_pose) + det.add_association(vert) + if len(unassociated_detections) == 0: + return + + unassociated_verts = [ + v for ii, v in enumerate(all_verts) if ii not in vinds + ] + + # Orer: detections, vertices (+ unassociations) + cost_mat = 1.0 * np.ones( + (len(unassociated_detections), + len(unassociated_verts) + len(unassociated_detections))) + for dind, det in enumerate(unassociated_detections): + det_inv_cov = np.linalg.inv(det.cov) + for vind, vert in enumerate(unassociated_verts): + cost_mat[dind, vind] = vertexnav.utils.calc.m_distance( + vert.position, det.position, inv_noise=det_inv_cov) + + dinds, vinds = scipy.optimize.linear_sum_assignment(cost_mat) + + for dind, vind in zip(dinds, vinds): + # Check to see if it's unassociated + det = unassociated_detections[dind] + if vind >= len(unassociated_verts): + # Create a new vertex + new_vert = NoisyVertex(det.position, det.cov) + det.add_association(new_vert) + self.vertices.append(new_vert) + else: + # Add association + vert = unassociated_verts[vind] + vert.add_detection(det.position, det.cov, r_pose) + det.add_association(vert) + + def get_proposed_world(self, r_poses=[], num_detections_lower_limit=1): + print("Limiting active verts") + active_verts = [ + v for v in self.vertices + if v.num_detections > num_detections_lower_limit + ] + + try: + r_traj = shapely.geometry.LineString([(p.x, p.y) for p in r_poses]) + + def does_intersect_robot_trajectory(wall): + ws = shapely.geometry.LineString( + [wall.left_vertex.position, wall.right_vertex.position]) + return ws.intersects(r_traj) + except ValueError as e: + print(e) + + def does_intersect_robot_trajectory(wall): + return False + + potential_walls = [ + w for w in list(self.walls.values()) + if w.prob_exists > 0.01 and not does_intersect_robot_trajectory(w) + ] + potential_walls = sorted( + potential_walls, + key=lambda w: max(w.left_vertex.last_updated, w.right_vertex. + last_updated), + reverse=True) + + vertex_positions = [(vertex.position[0], vertex.position[1]) + for vertex in active_verts] + wall_positions = [(wall.left_vertex.position, + wall.right_vertex.position) + for wall in potential_walls] + + proposed_world = vertexnav.world.ProposedWorld( + vertices=vertex_positions, walls=wall_positions) + + old_proposed_world = self._last_proposed_world + if old_proposed_world is not None: + if len(vertex_positions) == len(old_proposed_world.vertices) \ + and len(wall_positions) == len(old_proposed_world.walls): + return self._last_proposed_world + else: + # Old obstacles still exist, so keep the memos from + # covisibility queries that returned False + proposed_world.covis_memo = { + k: v + for k, v in old_proposed_world.covis_memo.items() if not v + } + + self._last_proposed_world = proposed_world + return proposed_world + + def get_known_poly(self, proposed_world, max_range=1000): + pose_obs = [(r_pose, obs) + for r_pose, obs in zip(self.r_poses, self.observations) + if r_pose.index > self._known_space_last_updated] + + polys = [ + shapely.geometry.Polygon( + vertexnav.noisy.compute_conservative_space_from_obs( + r_pose, obs, max_range)).buffer(1e-2, + resolution=0, + cap_style=3, + join_style=2) + for r_pose, obs in pose_obs + ] + + for poly in polys: + self._known_space_poly = safely_add_poly(self._known_space_poly, + poly) + + self._known_space_last_updated = self.r_poses[-1].index + return self._known_space_poly.buffer(-1e-2, + 1, + cap_style=3, + join_style=2) diff --git a/modules/vertexnav/vertexnav/world.py b/modules/vertexnav/vertexnav/world.py new file mode 100644 index 0000000..5bb873d --- /dev/null +++ b/modules/vertexnav/vertexnav/world.py @@ -0,0 +1,643 @@ +import itertools +import math +import numpy as np +import random +from vertexnav_accel import Pose +import shapely +import shapely.prepared +from shapely import geometry, strtree +import vertexnav_accel as gaccel + + +class WorldBase(object): + """Abstract class, defines some of the attributes and functions of World""" + def __init__(self): + raise NotImplementedError("WorldBase is an abstract class.") + + def get_all_vertices(self): + """Get all vertices in the map.""" + raise NotImplementedError("abstract method of the WorldBase class.") + + def is_vertex_visible(self, robot_position, corner, inflate_ratio=0.0001): + """Given a robot position, returns the vertices within line of sight""" + if not hasattr(self, strtree): + self.strtree = strtree.STRtree(self.obstacles) + + ir = inflate_ratio + mr = 1 - inflate_ratio + pair = np.array([robot_position, corner]) + pair = [mr * pair[0] + ir * pair[1], ir * pair[0] + mr * pair[1]] + line = geometry.LineString(pair) + + for obs in self.strtree.query(line): + if self.boundary is not None and obs == self.boundary: + if not obs.contains(line): + return False + elif line.intersects(obs): + return False + + return True + + def does_wall_exist(self, pos_a, pos_b): + """Returns true if wall exists between two points""" + ws = shapely.geometry.LineString([pos_a, pos_b]) + for obs in self.obstacles: + if isinstance(obs, shapely.geometry.Polygon): + if obs.boundary.buffer(1e-3, 1).contains(ws): + return True + elif obs.buffer(1e-3, 1).contains(ws): + return True + return False + + def get_nearby_clutter(self, robot_pose, dist_threshold): + return [] + + def get_visible_vertices_for_pose(self, + robot_pose, + filter_fn=None, + bound_points=None): + """Return gap observation""" + if self.fast_world is not None: + if bound_points is not None: + return self.fast_world.getVisPolyBounded( + robot_pose.x, robot_pose.y, bound_points[1:]) + else: + verts = self.fast_world.getVisPoly(robot_pose.x, robot_pose.y) + if filter_fn is None: + return verts + else: + return [v for v in verts if filter_fn((v[0], v[1]))] + + if filter_fn is None: + filter_fn = lambda x: True # noqa: E731 + + robot_position = (robot_pose.x, robot_pose.y) + visible_corners = [ + vertex for vertex in self.get_all_vertices() + if filter_fn((vertex[0], vertex[1])) + and self.is_vertex_visible(robot_position, vertex) + ] + return visible_corners + + def get_vertex_detection_type_for_vertex_noisy(self, robot_pose, vertex): + raise NotImplementedError + + def get_vertices_for_pose(self, + robot_pose, + noisy=False, + do_compute_detection_type=True, + filter_fn=None, + bound_points=None, + max_range=None): + """Returns Corner objects""" + + # Get visible corners + visible_vertices = self.get_visible_vertices_for_pose( + robot_pose, filter_fn, bound_points) + if max_range is not None: + visible_vertices = [ + v for v in visible_vertices + if math.sqrt((v[0] - robot_pose.x)**2 + + (v[1] - robot_pose.y)**2) < max_range + ] + + if not do_compute_detection_type: + return visible_vertices + + def get_angle_rad(pose, position): + return math.atan2(position[1] - pose.y, position[0] - pose.x) + + visible_vertices = sorted(visible_vertices, + key=lambda v: get_angle_rad(robot_pose, v), + reverse=True) + + def get_delta_angle_rad_ordered(pose, det_L, det_R): + """Get the difference in angle between detections from + the perspective of a robot pose""" + low_angle = get_angle_rad(pose, det_R) + high_angle = get_angle_rad(pose, det_L) + + if high_angle < low_angle: + high_angle += 2 * math.pi + + return high_angle - low_angle + + verts = visible_vertices + sverts = visible_vertices[1:] + visible_vertices[:1] + ssverts = visible_vertices[2:] + visible_vertices[:2] + vert_pairs = [] + for det_R, det, det_L in zip(ssverts, sverts, verts): + if get_delta_angle_rad_ordered(robot_pose, det_L, det) < math.pi \ + and self.does_wall_exist(det_L, det): + is_left_wall = True + else: + is_left_wall = False + + if get_delta_angle_rad_ordered(robot_pose, det, det_R) < math.pi \ + and self.does_wall_exist(det, det_R): + is_right_wall = True + else: + is_right_wall = False + + if is_left_wall and is_right_wall: + det_char = 'c' + elif not is_left_wall and is_right_wall: + det_char = 'l' + elif is_left_wall and not is_right_wall: + det_char = 'r' + elif not is_left_wall and not is_right_wall: + det_char = 'p' + else: + raise ValueError("should not be able to get here.") + + vert_pairs.append((det, det_char)) + + return vert_pairs + + def get_visibility_edges(self, inflate_ratio=0.0001): + """Return edges of visibility graph""" + + # Loop though all pairs of vertices + vs = self.get_all_vertices() + + def is_points_near(pA, pB): + return (abs(pA[1] - pB[1]) < 1e-8 and abs(pA[0] - pB[0]) < 1e-8) + + ir = inflate_ratio + mr = 1 - inflate_ratio + + visibility_lines = [] + + for pair in itertools.combinations(vs, 2): + pair = np.array(pair) + mid = 0.5 * pair[0] + 0.5 * pair[1] + if self.get_signed_dist(Pose(mid[0], mid[1])) < 0: + continue + pair = [mr * pair[0] + ir * pair[1], ir * pair[0] + mr * pair[1]] + line = geometry.LineString(pair) + for obs in self.obstacles: + intersection = self._compute_intersection(line, obs) + if isinstance(intersection, geometry.GeometryCollection): + pass + elif isinstance(intersection, geometry.Point): + break + elif isinstance(intersection, geometry.MultiPoint): + break + elif isinstance(intersection, geometry.LineString): + break + else: + raise ValueError("Unknown type for 'intersection'") + else: + visibility_lines.append(pair) + + return visibility_lines + + +class World(WorldBase): + """Stores the shapely polygons that define the world + + Attributes: + obstacles: list of shapely polygons + boudary: shapely polygon which defines the outer obstacle of world + clutter_element_poses: positions of clutter + known_space_poly: shapely polygon representing known, free space + area: area of known space polygon + """ + def __init__(self, obstacles, boundary=None): + self.obstacles = obstacles + self.boundary = boundary + self._internal_obstacles = list(obstacles) + self.clutter_element_poses = [] + if self.boundary is not None: + self.obstacles.append(boundary) + self.known_space_poly = boundary + for obs in self._internal_obstacles: + self.known_space_poly = self.known_space_poly.difference(obs) + self.area = self.known_space_poly.area + else: + # FIXME(gjstein): should compute with some bounds + self.obs_poly = shapely.geometry.Polygon() + for obs in self._internal_obstacles: + self.obs_poly = self.obs_poly.union(obs) + self.known_space_poly = shapely.geometry.Polygon() + self.area = 1 + + # Initialize the "fast_world" + segs = [] + segs += [[-500.1, -500.2, -500.3, 500.4]] + segs += [[-500.3, 500.4, 500.5, 500.6]] + segs += [[500.5, 500.6, 500.7, -500.8]] + segs += [[500.7, -500.8, -500.1, -500.2]] + + def add_coords(boundary, segs): + print(boundary) + for p0, p1 in zip(boundary.coords, boundary.coords[1:]): + segs += [[p0[0], p0[1], p1[0], p1[1]]] + + for obs in self.obstacles: + boundary = obs.boundary + if isinstance(boundary, geometry.MultiLineString): + for line in boundary: + add_coords(line, segs) + else: + add_coords(boundary, segs) + + self.fast_world = gaccel.FastWorld(segs, self.get_all_vertices()) + + def compute_iou(self, known_space_poly): + """Return intersection over union of kown space between + estimate and ground truth""" + try: + intersection = self.known_space_poly.intersection( + known_space_poly).area + union = self.known_space_poly.union(known_space_poly).area + return intersection / union + except: # noqa + print("IoU failed!") + return 0.0 + + @property + def map_bounds(self): + """Get the x and y limits of the underlying map. + + Returns: + xbounds: 2-element tuple [min(x), max(x)] + ybounds: 2-element tuple [min(y), max(y)] + """ + + if self.boundary is not None: + xs, ys = self.boundary.exterior.xy + xmin = min(xs) + xmax = max(xs) + ymin = min(ys) + ymax = max(ys) + else: + # FIXME(gjstein): should not be hard coded + return (-100, 200), (-100, 200) + + return (xmin, xmax), (ymin, ymax) + + def get_vertex_detection_type_for_vertex(self, robot_pose, vertex): + """For a given robot pose, return the vertex type from + the robot's perspective""" + robot_position = (robot_pose.x, robot_pose.y) + angle_rad = math.atan2(vertex[1] - robot_pose.y, + vertex[0] - robot_pose.x) + # Add another two lines to the left and right of the corner point and + # compute intersections. + s_off = 0.0001 + s_vec = (-math.sin(angle_rad), math.cos(angle_rad)) + l_off = 0.01 + l_vec = (math.cos(angle_rad), math.sin(angle_rad)) + dc_l = (vertex[0] + s_off * s_vec[0] + l_off * l_vec[0], + vertex[1] + s_off * s_vec[1] + l_off * l_vec[1]) + dc_r = (vertex[0] - s_off * s_vec[0] + l_off * l_vec[0], + vertex[1] - s_off * s_vec[1] + l_off * l_vec[1]) + + point = geometry.Point(vertex) + vobs = [ + obs for obs in self.strtree.query(point) + if not isinstance(self._compute_intersection(point, obs), + geometry.GeometryCollection) + ] + + if len(vobs) == 0: + return 'p' + + def intersect_dist(rp, dc): + line = geometry.LineString([rp, dc]) + for obs in vobs: + intr = self._compute_intersection(line, obs) + if isinstance(intr, geometry.Point): + dx = intr.x - rp[0] + dy = intr.y - rp[1] + return dx * dx + dy * dy + elif isinstance(intr, geometry.MultiPoint): + return min([(p.x - rp[0])**2 + (p.y - rp[1])**2 + for p in intr]) + return None + + l_int_dist = intersect_dist(robot_position, dc_l) + r_int_dist = intersect_dist(robot_position, dc_r) + dx = robot_position[0] - vertex[0] + dy = robot_position[1] - vertex[1] + c_dist = dx * dx + dy * dy + + if l_int_dist is not None and r_int_dist is not None: + if l_int_dist + r_int_dist > 2 * c_dist: + corner_type = 'c' + else: + corner_type = 'i' + # FIXME(gjstein): should I add a "flat" corner definition? + elif l_int_dist is None and r_int_dist is None: + raise ValueError("Point gaps unsupported.") + elif l_int_dist is None: + corner_type = 'l' + elif r_int_dist is None: + corner_type = 'r' + else: + raise ValueError("Point gaps unsupported.") + + return corner_type + + def _compute_intersection(self, line, obs): + """Computes an intersection between a line and a shapely geometry object. + The 'intersection' function behaves differently for different classes in + shapely, and this function is designed to abstract that away.""" + return line.intersection(obs.boundary) + + def get_signed_dist(self, pose): + """Get the signed distance to obstacles from a point.""" + # Loop through objects, get closest point and return distance + point = geometry.Point([pose.x, pose.y]) + distance = 1e10 + for obstacle in self._internal_obstacles: + if obstacle.contains(point): + obs_dist = -obstacle.exterior.distance(point) + else: + obs_dist = obstacle.distance(point) + + distance = min(distance, obs_dist) + + if self.boundary is not None: + # Ensure that the point is also inside the boundary + if self.boundary.contains(point): + boundary_dist = self.boundary.exterior.distance(point) + else: + boundary_dist = -self.boundary.distance(point) + distance = min(distance, boundary_dist) + + return distance + + def get_random_pose(self, + xbounds=None, + ybounds=None, + min_signed_dist=0, + max_signed_dist=10000, + num_attempts=10000): + """Get a random pose in the world, respecting the signed distance + to all the obstacles. + + Each "bound" is a N-element list structured such that: + + > xmin = min(xbounds) + > xmax = max(xbounds) + + "num_attempts" is the number of trials before an error is raised. + """ + + try: + xbounds, ybounds = self._map_bounds + except AttributeError: + pass + + if xbounds is None or ybounds is None: + if self.boundary is None: + raise ValueError("If world.boundary is None, bounds " + + "must be provided.") + else: + xbounds, ybounds = self.boundary.exterior.xy + + xmin = min(xbounds) + xmax = max(xbounds) + ymin = min(ybounds) + ymax = max(ybounds) + + counter = 0 + while counter < num_attempts: + pose = Pose(random.uniform(xmin, xmax), random.uniform(ymin, ymax)) + obs_signed_distance = self.get_signed_dist(pose) + if obs_signed_distance >= min_signed_dist and obs_signed_distance <= max_signed_dist: + return pose + else: + counter += 1 + else: + raise ValueError("Could not find random point within bounds") + + def get_all_vertices(self): + """Loop through all polys and get corners""" + + corner_lists = [ + list(obs.exterior.coords)[:-1] for obs in self.obstacles + ] + # Combine the nested lists into a single list of corners + return sum(corner_lists, []) + + +class ProposedWorld(WorldBase): + """Stores the vertices and walls that define a proposed world + + Attributes: + boundary: boundary of world + vertices: Noisy Vertex objects + obstacles: Lines representing walls between vertices + walls: wall objects between vertices + covis_memo: dictionary for covisibility between vertices + obs_memo: dictionary for observations + neighbor_points: dictionary for neighbor vertices + """ + def __init__(self, + vertices, + walls, + topology=None, + vertex_remapping=None, + wall_dict=None): + self.boundary = None + self.vertices = vertices + self.obstacles = [geometry.LineString(wall) for wall in walls] + self.walls = walls + self.topology = topology + self.vertex_remapping = vertex_remapping + self.wall_dict = wall_dict + + segs = [[w[0][0], w[0][1], w[1][0], w[1][1]] for w in walls] + segs += [[-500.1, -500.2, -500.3, 500.4]] + segs += [[-500.3, 500.4, 500.5, 500.6]] + segs += [[500.5, 500.6, 500.7, -500.8]] + segs += [[500.7, -500.8, -500.1, -500.2]] + + self.fast_world = gaccel.FastWorld(segs, + [[v[0], v[1]] for v in vertices]) + + self.covis_memo = {} + self.obs_memo = {} + self.neighbor_points = {} + + def get_vertex_detection_type_for_vertex(self, robot_pose, vertex): + robot_position = (robot_pose.x, robot_pose.y) + + # Add another two lines to the left and right of the corner point and + # compute intersections. + + def is_points_near(pA, pB): + return (abs(pA[1] - pB[1]) < 1e-6 and abs(pA[0] - pB[0]) < 1e-6) + + try: + ps = self.neighbor_points[vertex] + except: # noqa + ps = np.array([ + obs.coords[1] for obs in self.obstacles + if is_points_near(obs.coords[0], vertex) + ] + [ + obs.coords[0] for obs in self.obstacles + if is_points_near(obs.coords[1], vertex) + ]) + + self.neighbor_points[vertex] = ps + + if len(ps) == 0: + return 'p' + + rvec = [vertex[0] - robot_position[0], vertex[1] - robot_position[1]] + vecs = np.array([[p[0] - vertex[0], p[1] - vertex[1]] for p in ps]) + angles = np.arctan2(rvec[0] * vecs[:, 1] - rvec[1] * vecs[:, 0], + rvec[0] * vecs[:, 0] + rvec[1] * vecs[:, 1]) + + left_walls = [a for a in angles if a > 0] + if len(left_walls) == 0: + return 'l' + + right_walls = [a for a in angles if a < 0] + if len(right_walls) == 0: + return 'r' + + if max(left_walls) - min(right_walls) < math.pi: + return 'c' + else: + return 'i' + + def _compute_intersection(self, line, obs): + """Computes an intersection between a line and a shapely geometry object. + The 'intersection' function behaves differently for different classes in + shapely, and this function is designed to abstract that away.""" + return line.intersection(obs) + + def get_dist(self, pose): + """Get the signed distance to obstacles from a point.""" + # Loop through objects, get closest point and return distance + point = geometry.Point([pose.x, pose.y]) + try: + return min( + [obstacle.distance(point) for obstacle in self.obstacles]) + except ValueError: + return float('inf') + + def get_all_vertices(self): + """Loop through all polys and get corners""" + return self.vertices + + def get_inflated_vertices(self, inflation_rad=0.001): + """Get inflated vertices for computing visibility graph for + navigation. + + This procedure generates new 'vertices' for every point along.""" + inflated_verts = [] + inflated_obstacles = [] + + def is_points_near(pA, pB): + return (abs(pA[1] - pB[1]) < 1e-8 and abs(pA[0] - pB[0]) < 1e-8) + + def add_vert_and_poly(vert, low_angle, high_angle, num_angles): + poly_verts = [] + if abs(low_angle - high_angle % (2 * math.pi)) < 0.01: + is_endpoint = False + else: + is_endpoint = True + for th in np.linspace(low_angle, + high_angle, + num=num_angles, + endpoint=is_endpoint): + inflated_verts.append((vert[0] + inflation_rad * math.cos(th), + vert[1] + inflation_rad * math.sin(th))) + poly_verts.append( + (vert[0] + 0.95 * inflation_rad * math.cos(th), + vert[1] + 0.95 * inflation_rad * math.sin(th))) + + inflated_obstacles.append(geometry.Polygon(poly_verts)) + + for vert in self.vertices: + # Get all enabled walls for this vertex + walls = [ + wall for wall in self.walls if is_points_near(wall[0], vert) + or is_points_near(wall[1], vert) + ] + if len(walls) == 0: + add_vert_and_poly(vert, 0.0, 2 * math.pi, num_angles=6) + continue + + # Compute wall angles_rad + angles_rad = [] + for wall in walls: + if is_points_near(wall[0], vert): + nvert = wall[1] + else: + nvert = wall[0] + angles_rad.append( + math.atan2(nvert[1] - vert[1], nvert[0] - vert[0]) % + (2 * math.pi)) + + if len(walls) == 1: + add_vert_and_poly(vert, + low_angle=angles_rad[0] + 0.01 * math.pi, + high_angle=angles_rad[0] + 1.99 * math.pi, + num_angles=7) + continue + + angles_rad = sorted(angles_rad) + poly_verts = [] + for angles in zip(angles_rad, angles_rad[1:] + angles_rad[:1]): + th = 0.5 * (angles[0] + angles[1]) + if angles[0] > angles[1]: + # Handle the 'loop around' condition + th += math.pi + inflated_verts.append((vert[0] + inflation_rad * math.cos(th), + vert[1] + inflation_rad * math.sin(th))) + poly_verts.append( + (vert[0] + 0.95 * inflation_rad * math.cos(th), + vert[1] + 0.95 * inflation_rad * math.sin(th))) + + if len(poly_verts) > 3: + inflated_obstacles.append(geometry.Polygon(poly_verts)) + else: + inflated_obstacles.append( + geometry.LineString(poly_verts).buffer(1e-6)) + + return inflated_verts, inflated_obstacles + + def is_covisible(self, vert1, vert2, inflated_obstacles=[]): + """Returns Bool if two vertices can see one another (respecting the + underlying geometry and inflated obstacles).""" + + key = (tuple(vert1), tuple(vert2), len(inflated_obstacles)) + if key in self.covis_memo: + return self.covis_memo[key] + + rkey = (tuple(vert2), tuple(vert1), len(inflated_obstacles)) + + pair = np.array([vert1, vert2]) + line = geometry.LineString(pair) + + obs_key = len(self.obstacles) + len(inflated_obstacles) + + if obs_key not in list(self.obs_memo.keys()): + obs_tree = strtree.STRtree(self.obstacles + inflated_obstacles) + self.obs_memo[obs_key] = obs_tree + else: + obs_tree = self.obs_memo[obs_key] + + for obs in obs_tree.query(line): + if line.intersects(obs): + self.covis_memo[key] = False + self.covis_memo[rkey] = False + return False + + self.covis_memo[key] = True + self.covis_memo[rkey] = True + return True + + def get_visibility_edges_from_verts(self, verts, inflated_obstacles=[]): + # Loop though all pairs of vertices + return [ + pair for pair in itertools.combinations(verts, 2) + if self.is_covisible(pair[0], pair[1], inflated_obstacles) + ] diff --git a/modules/vertexnav_accel/CMakeLists.txt b/modules/vertexnav_accel/CMakeLists.txt new file mode 100644 index 0000000..b409895 --- /dev/null +++ b/modules/vertexnav_accel/CMakeLists.txt @@ -0,0 +1,54 @@ +cmake_minimum_required(VERSION 2.8.12) +project(vertexnav_accel) + +set(CMAKE_CXX_STANDARD 14) +set(CMAKE_BUILD_TYPE "Release") + +# Download pybind11 +find_package(Git QUIET) +if(GIT_FOUND AND NOT EXISTS "${PROJECT_SOURCE_DIR}/pybind11") +# Update submodules as needed + option(GIT_CLONE "Clone during build" ON) + if(GIT_CLONE) + message(STATUS "Clone update") + execute_process(COMMAND ${GIT_EXECUTABLE} clone --branch v2.2.0 https://github.com/pybind/pybind11.git + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR} + RESULT_VARIABLE GIT_CLONE_RESULT) + if(NOT GIT_CLONE_RESULT EQUAL "0") + message(FATAL_ERROR "git clone failed with ${GIT_CLONE_RESULT}.") + endif() + endif() +endif() + +# Why do I need this? pybind11? +link_directories(/usr/local/lib) + +# Locate the CGAL package +find_package(CGAL REQUIRED COMPONENTS Core) +include_directories(${CGAL_INCLUDE_DIRS}) + +# Use GTSAM +find_package(GTSAM REQUIRED) +include_directories(${GTSAM_INCLUDE_DIR}) +include_directories(/gtsam/gtsam/3rdparty/Eigen) +include_directories(/home/gjstein/research/external/gtsam/gtsam/3rdparty/Eigen) + +# Make the library that pybind will link against +include_directories(src) + +# Build the CGAL library +add_library(cgal_ex_lib STATIC src/cgal_ex.cpp) +set_target_properties(cgal_ex_lib PROPERTIES POSITION_INDEPENDENT_CODE TRUE) +target_link_libraries(cgal_ex_lib PRIVATE CGAL::CGAL) + +# Build separate library for vertexnav_accel +add_library(vertexnav_accel_noisy STATIC src/pose.cpp src/noisy.cpp src/Hungarian/Hungarian.cpp src/vertex_graph.cpp) +set_target_properties(vertexnav_accel_noisy PROPERTIES POSITION_INDEPENDENT_CODE TRUE) +target_link_libraries(vertexnav_accel_noisy gtsam) + + +# Build the python library +add_subdirectory(pybind11) + +pybind11_add_module(vertexnav_accel NO_EXTRAS src/main.cpp) +target_link_libraries(vertexnav_accel PRIVATE cgal_ex_lib vertexnav_accel_noisy) diff --git a/modules/vertexnav_accel/README.org b/modules/vertexnav_accel/README.org new file mode 100644 index 0000000..a24664e --- /dev/null +++ b/modules/vertexnav_accel/README.org @@ -0,0 +1,3 @@ +* VertexNav: Mapping by detecting vertices in polygonal maps (C++ additions) + +C++ code called by the =vertexnav= module. See the [[../vertexnav][VertexNav module]] for a full README. diff --git a/modules/vertexnav_accel/setup.cfg b/modules/vertexnav_accel/setup.cfg new file mode 100644 index 0000000..9af7e6f --- /dev/null +++ b/modules/vertexnav_accel/setup.cfg @@ -0,0 +1,2 @@ +[aliases] +test=pytest \ No newline at end of file diff --git a/modules/vertexnav_accel/setup.py b/modules/vertexnav_accel/setup.py new file mode 100644 index 0000000..8d2135a --- /dev/null +++ b/modules/vertexnav_accel/setup.py @@ -0,0 +1,85 @@ +import os +import re +import sys +import platform +import subprocess + +from setuptools import setup, Extension +from setuptools.command.build_ext import build_ext +from distutils.version import LooseVersion + + +class CMakeExtension(Extension): + def __init__(self, name, sourcedir=''): + Extension.__init__(self, name, sources=[]) + self.sourcedir = os.path.abspath(sourcedir) + + +class CMakeBuild(build_ext): + def run(self): + try: + out = subprocess.check_output(['cmake', '--version']) + except OSError: + raise RuntimeError( + "CMake must be installed to build the following extensions: " + + ", ".join(e.name for e in self.extensions)) + + if platform.system() == "Windows": + cmake_version = LooseVersion( + re.search(r'version\s*([\d.]+)', out.decode()).group(1)) + if cmake_version < '3.1.0': + raise RuntimeError("CMake >= 3.1.0 is required on Windows") + + for ext in self.extensions: + self.build_extension(ext) + + def build_extension(self, ext): + extdir = os.path.abspath( + os.path.dirname(self.get_ext_fullpath(ext.name))) + # cmake_args = ['-DCMAKE_PREFIX_PATH=/Users/gjstein/research/external/install/lib/cmake', + cmake_args = [ + '-DCMAKE_PREFIX_PATH=/home/gjstein/research/external/gtsam/install/lib/cmake', + '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY=' + extdir, + '-DPYTHON_EXECUTABLE=' + sys.executable + ] + + cfg = 'Debug' if self.debug else 'Release' + build_args = ['--config', cfg] + + if platform.system() == "Windows": + cmake_args += [ + '-DCMAKE_LIBRARY_OUTPUT_DIRECTORY_{}={}'.format( + cfg.upper(), extdir) + ] + if sys.maxsize > 2**32: + cmake_args += ['-A', 'x64'] + build_args += ['--', '/m'] + else: + cmake_args += ['-DCMAKE_BUILD_TYPE=' + cfg] + build_args += ['--', '-j8'] + + env = os.environ.copy() + env['CXXFLAGS'] = '{} -DVERSION_INFO=\\"{}\\"'.format( + env.get('CXXFLAGS', ''), self.distribution.get_version()) + if not os.path.exists(self.build_temp): + os.makedirs(self.build_temp) + subprocess.check_call(['cmake', ext.sourcedir] + cmake_args, + cwd=self.build_temp, + env=env) + subprocess.check_call(['cmake', '--build', '.'] + build_args, + cwd=self.build_temp) + + +setup( + name='vertexnav_accel', + version='0.1.0', + author='Greg Stein', + author_email='gjstein@mit.edu', + description='Speeding up the vertexnav project.', + long_description='', + ext_modules=[CMakeExtension('vertexnav_accel')], + cmdclass=dict(build_ext=CMakeBuild), + zip_safe=False, + setup_requires=['pytest-runner'], + tests_require=['pytest'], +) diff --git a/modules/vertexnav_accel/src/Hungarian/Hungarian.cpp b/modules/vertexnav_accel/src/Hungarian/Hungarian.cpp new file mode 100755 index 0000000..deb4f71 --- /dev/null +++ b/modules/vertexnav_accel/src/Hungarian/Hungarian.cpp @@ -0,0 +1,395 @@ +/////////////////////////////////////////////////////////////////////////////// +// Hungarian.cpp: Implementation file for Class HungarianAlgorithm. +// +// This is a C++ wrapper with slight modification of a hungarian algorithm implementation by Markus Buehren. +// The original implementation is a few mex-functions for use in MATLAB, found here: +// http://www.mathworks.com/matlabcentral/fileexchange/6543-functions-for-the-rectangular-assignment-problem +// +// Both this code and the orignal code are published under the BSD license. +// by Cong Ma, 2016 +// + +#include +#include // for DBL_MAX +#include // for fabs() +#include "Hungarian.h" + + +HungarianAlgorithm::HungarianAlgorithm(){} +HungarianAlgorithm::~HungarianAlgorithm(){} + + +//********************************************************// +// A single function wrapper for solving assignment problem. +//********************************************************// +double HungarianAlgorithm::Solve(vector >& DistMatrix, vector& Assignment) +{ + unsigned int nRows = DistMatrix.size(); + unsigned int nCols = DistMatrix[0].size(); + + double *distMatrixIn = new double[nRows * nCols]; + int *assignment = new int[nRows]; + double cost = 0.0; + + // Fill in the distMatrixIn. Mind the index is "i + nRows * j". + // Here the cost matrix of size MxN is defined as a double precision array of N*M elements. + // In the solving functions matrices are seen to be saved MATLAB-internally in row-order. + // (i.e. the matrix [1 2; 3 4] will be stored as a vector [1 3 2 4], NOT [1 2 3 4]). + for (unsigned int i = 0; i < nRows; i++) + for (unsigned int j = 0; j < nCols; j++) + distMatrixIn[i + nRows * j] = DistMatrix[i][j]; + + // call solving function + assignmentoptimal(assignment, &cost, distMatrixIn, nRows, nCols); + + Assignment.clear(); + for (unsigned int r = 0; r < nRows; r++) + Assignment.push_back(assignment[r]); + + delete[] distMatrixIn; + delete[] assignment; + return cost; +} + + +//********************************************************// +// Solve optimal solution for assignment problem using Munkres algorithm, also known as Hungarian Algorithm. +//********************************************************// +void HungarianAlgorithm::assignmentoptimal(int *assignment, double *cost, double *distMatrixIn, int nOfRows, int nOfColumns) +{ + double *distMatrix, *distMatrixTemp, *distMatrixEnd, *columnEnd, value, minValue; + bool *coveredColumns, *coveredRows, *starMatrix, *newStarMatrix, *primeMatrix; + int nOfElements, minDim, row, col; + + /* initialization */ + *cost = 0; + for (row = 0; row nOfColumns) */ + { + minDim = nOfColumns; + + for (col = 0; col= 0) + *cost += distMatrix[row + nOfRows*col]; + } +} + +/********************************************************/ +void HungarianAlgorithm::step2a(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim) +{ + bool *starMatrixTemp, *columnEnd; + int col; + + /* cover every column containing a starred zero */ + for (col = 0; col +#include + +using namespace std; + + +class HungarianAlgorithm +{ +public: + HungarianAlgorithm(); + ~HungarianAlgorithm(); + double Solve(vector >& DistMatrix, vector& Assignment); + +private: + void assignmentoptimal(int *assignment, double *cost, double *distMatrix, int nOfRows, int nOfColumns); + void buildassignmentvector(int *assignment, bool *starMatrix, int nOfRows, int nOfColumns); + void computeassignmentcost(int *assignment, double *cost, double *distMatrix, int nOfRows); + void step2a(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); + void step2b(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); + void step3(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); + void step4(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim, int row, int col); + void step5(int *assignment, double *distMatrix, bool *starMatrix, bool *newStarMatrix, bool *primeMatrix, bool *coveredColumns, bool *coveredRows, int nOfRows, int nOfColumns, int minDim); +}; + + +#endif \ No newline at end of file diff --git a/modules/vertexnav_accel/src/Hungarian/LICENSE b/modules/vertexnav_accel/src/Hungarian/LICENSE new file mode 100755 index 0000000..e453fb2 --- /dev/null +++ b/modules/vertexnav_accel/src/Hungarian/LICENSE @@ -0,0 +1,23 @@ +Copyright (c) 2016, mcximing +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/modules/vertexnav_accel/src/Hungarian/README.txt b/modules/vertexnav_accel/src/Hungarian/README.txt new file mode 100755 index 0000000..d58e635 --- /dev/null +++ b/modules/vertexnav_accel/src/Hungarian/README.txt @@ -0,0 +1,7 @@ + +Hungarian algorithm, also known as Munkres algorithm or Kuhn-Munkres algorithm, is a method for solving the assignment problem, for example assigning workers to jobs, which goal is to compute the optimal assignment that minimizes the total cost, and the like. + +This is a C++ wrapper with slight modification of a hungarian algorithm implementation by Markus Buehren. +The original code is a few mex-functions for use in MATLAB, found here: +http://www.mathworks.com/matlabcentral/fileexchange/6543-functions-for-the-rectangular-assignment-problem + diff --git a/modules/vertexnav_accel/src/Hungarian/license.txt b/modules/vertexnav_accel/src/Hungarian/license.txt new file mode 100755 index 0000000..cc78cfe --- /dev/null +++ b/modules/vertexnav_accel/src/Hungarian/license.txt @@ -0,0 +1,24 @@ +Copyright (c) 2014, Markus Buehren +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in + the documentation and/or other materials provided with the distribution + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/modules/vertexnav_accel/src/Hungarian/makefile b/modules/vertexnav_accel/src/Hungarian/makefile new file mode 100755 index 0000000..21e198c --- /dev/null +++ b/modules/vertexnav_accel/src/Hungarian/makefile @@ -0,0 +1,15 @@ +CC = g++ +CFLAGS = -std=c++11 + +test: main.o hung.o + $(CC) -o test main.o hung.o + +hung.o: Hungarian.cpp Hungarian.h + $(CC) -c Hungarian.cpp -o hung.o + +main.o: testMain.cpp Hungarian.h + $(CC) $(CFLAGS) -c testMain.cpp -o main.o + +clean: + -rm main.o hung.o + diff --git a/modules/vertexnav_accel/src/Hungarian/testMain.cpp b/modules/vertexnav_accel/src/Hungarian/testMain.cpp new file mode 100755 index 0000000..139e134 --- /dev/null +++ b/modules/vertexnav_accel/src/Hungarian/testMain.cpp @@ -0,0 +1,24 @@ +#include +#include "Hungarian.h" + + +int main(void) +{ + // please use "-std=c++11" for this initialization of vector. + vector< vector > costMatrix = { { 10, 19, 8, 15, 0 }, + { 10, 18, 7, 17, 0 }, + { 13, 16, 9, 14, 0 }, + { 12, 19, 8, 18, 0 } }; + + HungarianAlgorithm HungAlgo; + vector assignment; + + double cost = HungAlgo.Solve(costMatrix, assignment); + + for (unsigned int x = 0; x < costMatrix.size(); x++) + std::cout << x << "," << assignment[x] << "\t"; + + std::cout << "\ncost: " << cost << std::endl; + + return 0; +} diff --git a/modules/vertexnav_accel/src/cgal_ex.cpp b/modules/vertexnav_accel/src/cgal_ex.cpp new file mode 100644 index 0000000..67d6352 --- /dev/null +++ b/modules/vertexnav_accel/src/cgal_ex.cpp @@ -0,0 +1,231 @@ +#include +#include +#include +#include +#include + +#include +#include + +typedef Arrangement_2::Edge_const_iterator Edge_const_iterator; + +typedef CGAL::Exact_predicates_exact_constructions_kernel Kernel; +typedef Kernel::Point_2 Point_2; +typedef CGAL::Exact_predicates_inexact_constructions_kernel Kernel_In; + typedef Kernel_In::Point_2 Point_2_In; + +VVD filter_by_poly_points_alt(VVD poly_points, VVD unfiltered_points) { + int polyCorners = poly_points.size(); + int i, j = polyCorners - 1; + + std::vector constant; + std::vector multiple; + + for (i=0; i < polyCorners; ++i) { + if (poly_points[j][1] == poly_points[i][1]) { + constant.push_back(poly_points[i][0]); + multiple.push_back(0); + } else { + constant.push_back( + poly_points[i][0] + - (poly_points[i][1]*poly_points[j][0])/(poly_points[j][1]-poly_points[i][1]) + + (poly_points[i][1]*poly_points[i][0])/(poly_points[j][1]-poly_points[i][1])); + multiple.push_back( + (poly_points[j][0]-poly_points[i][0])/(poly_points[j][1]-poly_points[i][1])); + } + j = i; + } + + VVD out_points; + for (auto point : unfiltered_points) { + j = polyCorners - 1; + bool oddNodes = false; + + for (i=0; i < polyCorners; ++i) { + if ((poly_points[i][1] < point[1] && poly_points[j][1] >= point[1] + || poly_points[j][1]< point[1] && poly_points[i][1] >= point[1])) { + oddNodes^=(point[1]*multiple[i]+constant[i] < point[0]); } + j = i; + } + + if (oddNodes) { + out_points.push_back(point); + } + } + + return out_points; +} + +VVD filter_by_poly_points_inf(VVD poly_points, VVD unfiltered_points, + double x, double y) { + VVD poly_points_inf; + for (auto point : poly_points) { + poly_points_inf.push_back({ + point[0] + (point[0] - x)/2048, + point[1] + (point[1] - y)/2048, + }); + } + return filter_by_poly_points_alt(poly_points_inf, unfiltered_points); +} + +// void precalc_values() { + +// int i, j = polyCorners-1 ; + +// for(i=0; i=y +// || polyY[j]< y && polyY[i]>=y)) { +// oddNodes^=(y*multiple[i]+constant[i] segments; + for (int i=0; i < f_seg.size(); ++i) { + segments.push_back(Segment_2( + Point_2(f_seg[i][0], f_seg[i][1]), + Point_2(f_seg[i][2], f_seg[i][3]))); + } + + // insert geometry into the arrangement + CGAL::insert(env, segments.begin(), segments.end()); + tev = std::make_shared(env); +} + +bool check_inside(const Point_2_In &pt, + const Point_2_In *pgn_begin, + const Point_2_In *pgn_end, + const Kernel_In &traits) { + switch (CGAL::bounded_side_2(pgn_begin, pgn_end, pt, traits)) { + case CGAL::ON_BOUNDED_SIDE: + return true; + break; + case CGAL::ON_BOUNDARY: + return true; + break; + case CGAL::ON_UNBOUNDED_SIDE: + return false; + break; + } +} + +bool compare(const Point2 &a, const Point2 &b) { + return (fabs(a.x - b.x) < 0.00001) && (fabs(a.y - b.y) < 0.00001); +} + +VEV filter_by_poly_points(const std::vector &filter_points, + const VEV &unfiltered_vertices) { + VEV filtered_vertices; + + for (auto vert : unfiltered_vertices) { + if (check_inside(Point_2_In(vert[0], vert[1]), + filter_points.data(), + filter_points.data()+filter_points.size(), + Kernel_In())) { + filtered_vertices.push_back(vert); + } + } + + return filtered_vertices; +} + +VEV FastWorld::getVisPoly(double qx, double qy) const { + // find the face of the query point + // (usually you may know that by other means) + Point_2 q(qx, qy); + Arrangement_2::Face_const_handle * face; + CGAL::Arr_naive_point_location pl(env); + CGAL::Arr_point_location_result::Type obj = pl.locate(q); + // The query point locates in the interior of a face + face = boost::get (&obj); + + Arrangement_2 regular_output; + // RSPV regular_visibility(env); + tev->compute_visibility(q, *face, regular_output); + + std::vector vis_seg; + + for (Edge_const_iterator eit = regular_output.edges_begin(); eit != regular_output.edges_end(); ++eit) { + auto ps = eit->source()->point(); + auto pt = eit->target()->point(); + vis_seg.push_back(Seg( + CGAL::to_double(ps.x()), + CGAL::to_double(ps.y()), + CGAL::to_double(pt.x()), + CGAL::to_double(pt.y()))); + } + + std::sort( + vis_seg.begin(), + vis_seg.end(), + [&](const Seg &sa, const Seg &sb) { + double tha = atan2(sa.cy - qy, sa.cx - qx); + double thb = atan2(sb.cy - qy, sb.cx - qx); + return tha > thb; + }); + + auto near = [](const double a, const double b) { + return fabs(a - b) < 0.001; + }; + + // Orient the segments + for (int i=0; i < vis_seg.size()-1; ++i) { + Seg *sa = &(vis_seg[i+0]); + Seg *sb = &(vis_seg[i+1]); + + if (near(sa->x2, sb->x1) && near(sa->y2, sb->y1)) { + // pass; + } else if (near(sa->x2, sb->x2) && near(sa->y2, sb->y2)) { + sb->swap(); + } else if (near(sa->x1, sb->x1) && near(sa->y1, sb->y1)) { + sa->swap(); + } else if (near(sa->x1, sb->x2) && near(sa->y1, sb->y2)) { + sa->swap(); + sb->swap(); + } else { + std::cout << "Something's amiss\n"; + } + } + + std::vector vis_points; + for (auto seg : vis_seg) { + vis_points.push_back(Point_2_In(seg.x1, seg.y1)); + } + + return filter_by_poly_points(vis_points, vertices); + + // VVD vis_points_alt; + // for (auto seg : vis_seg) { + // vis_points_alt.push_back({seg.x1, seg.y1}); + // } + + // return filter_by_poly_points_inf(vis_points_alt, vertices, qx, qy); +} + +VEV FastWorld::getVisPolyBounded(double qx, double qy, + const VEV &poly_bound) const { + VEV out_vertices = getVisPoly(qx, qy); + + // Now filter by the polygon + std::vector filter_points; + for (auto vert : poly_bound) { + filter_points.push_back(Point_2_In(vert[0], vert[1])); + } + + return filter_by_poly_points(filter_points, out_vertices); +} diff --git a/modules/vertexnav_accel/src/cgal_ex.hpp b/modules/vertexnav_accel/src/cgal_ex.hpp new file mode 100644 index 0000000..2a32aea --- /dev/null +++ b/modules/vertexnav_accel/src/cgal_ex.hpp @@ -0,0 +1,72 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Define the used kernel and arrangement +typedef CGAL::Exact_predicates_exact_constructions_kernel Kernel; +typedef Kernel::Point_2 Point_2; +typedef Kernel::Segment_2 Segment_2; +typedef CGAL::Arr_segment_traits_2 Traits_2; +typedef CGAL::Arrangement_2 Arrangement_2; +typedef Arrangement_2::Halfedge_const_handle Halfedge_const_handle; +typedef Arrangement_2::Face_handle Face_handle; + +// Define the used visibility class +typedef CGAL::Triangular_expansion_visibility_2 TEV; + +struct Point2 { + double x, y; + Point2(double xl, double yl) { + x = xl; + y = yl; + } + + bool operator == (Point2 const &b) { + return (x == b.x) && (y == b.y); + } +}; + + +struct Seg { + double x1, y1, x2, y2, cx, cy; + Seg(const double &xl1, const double &yl1, + const double &xl2, const double &yl2) : + x1(xl1), y1(yl1), x2(xl2), y2(yl2), + cx((x1+x2)/2), cy((y1+y2)/2) { + } + + void swap() { + double tmp_x = x1; + double tmp_y = y1; + x1 = x2; + y1 = y2; + x2 = tmp_x; + y2 = tmp_y; + } + +}; + +struct FastWorld { + Arrangement_2 env; + std::shared_ptr tev; + VEV vertices; + + FastWorld() : vertices() {}; + FastWorld(const VVD &f_seg, const VEV &f_vert); + FastWorld(const std::vector &f_seg, + const std::vector &f_vert); + VEV getVisPoly(double x, double y) const; + VEV getVisPolyBounded(double x, double y, const VEV &poly_bound) const; + // ~FastWorld() { + // delete tev; + // } +}; diff --git a/modules/vertexnav_accel/src/main.cpp b/modules/vertexnav_accel/src/main.cpp new file mode 100644 index 0000000..1f60b7c --- /dev/null +++ b/modules/vertexnav_accel/src/main.cpp @@ -0,0 +1,219 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +// #include +#include + + +typedef std::map VertIdMap; +PYBIND11_MAKE_OPAQUE(MapPairWall); +// PYBIND11_MAKE_OPAQUE(VertIdMap); +// PYBIND11_MAKE_OPAQUE(std::vector); +// PYBIND11_MAKE_OPAQUE(std::vector>); +PYBIND11_MAKE_OPAQUE(std::vector>); +PYBIND11_MAKE_OPAQUE(std::vector); +PYBIND11_MAKE_OPAQUE(std::vector>); +PYBIND11_MAKE_OPAQUE(std::vector); +PYBIND11_MAKE_OPAQUE(std::vector); + + +namespace py = pybind11; + + +PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr); +PYBIND11_MODULE(vertexnav_accel, m) { + m.doc() = R"pbdoc( + Pybind11 plugin for accelerated GapNav + ----------------------- + + .. currentmodule:: vertexnav_accel + + .. autosummary:: + :toctree: _generate + + )pbdoc"; + + py::class_(m, "FastWorld") + .def(py::init()) + .def("getVisPoly", &FastWorld::getVisPoly) + .def("getVisPolyBounded", &FastWorld::getVisPolyBounded); + + py::class_(m, "Seg") + .def(py::init()); + + py::class_(m, "Point2") + .def(py::init()); + + py::class_>(m, "Pose") + .def(py::init(), + py::arg("x"), py::arg("y"), py::arg("yaw") = 0, py::arg("robot_id") = 0) + .def_readwrite("x", &Pose::x) + .def_readwrite("y", &Pose::y) + .def_readwrite("yaw", &Pose::yaw) + .def_readwrite("index", &Pose::index) + .def_readwrite("robot_id", &Pose::robot_id) + .def("__rmul__", &Pose::rmul) + .def("__mul__", &Pose::mul) + .def_static("get_odom", &Pose::get_odom, + py::arg("p_new"), py::arg("p_old")); + + py::class_>(m, "NoisyDetectionType") + .def(py::init()) + .def(py::init()) + .def_readonly("prob_left_gap", &NoisyDetectionType::prob_left_gap) + .def_readonly("prob_right_gap", &NoisyDetectionType::prob_right_gap) + .def_readonly("label", &NoisyDetectionType::label) + .def("__eq__", &NoisyDetectionType::eq); + + py::class_>(m, "NoisyVertex") + .def(py::init()) + .def(py::init()) + .def_property_readonly("position", &NoisyVertex::get_position, + py::return_value_policy::copy) + .def_property_readonly("cov", &NoisyVertex::get_cov, + py::return_value_policy::copy) + .def("set_position", &NoisyVertex::set_position) + .def("set_cov", &NoisyVertex::set_cov) + .def_readonly("id", &NoisyVertex::id) + .def_readonly("num_detections", &NoisyVertex::num_detections) + .def_readonly("last_updated", &NoisyVertex::last_updated) + .def_readwrite("is_active", &NoisyVertex::is_active) + .def_readwrite("is_locked", &NoisyVertex::is_locked) + .def("add_detection", &NoisyVertex::add_detection) + .def("__eq__", &NoisyVertex::eq) + .def("__hash__", &NoisyVertex::hash); + + py::class_>(m, "HallucinatedVertexDetection") + .def(py::init(), + py::arg("angle_rad"), py::arg("position")) + .def(py::init(), + py::arg("angle_rad"), py::arg("range"), py::arg("r_pose")) + .def_readonly("angle_rad", &HallucinatedVertexDetection::angle_rad) + .def_readonly("position", &HallucinatedVertexDetection::position) + .def_readonly("id", &HallucinatedVertexDetection::id) + .def_property("detection_type", + &HallucinatedVertexDetection::get_detection_type, + &HallucinatedVertexDetection::set_detection_type) + .def("__eq__", &HallucinatedVertexDetection::eq) + .def("__hash__", &HallucinatedVertexDetection::hash); + + py::class_>(m, "NoisyVertexDetection") + .def(py::init &, const Eigen::Matrix2d &>(), + py::arg("angle_rad"), + py::arg("range"), + py::arg("detection_type"), + py::arg("cov_rt")) + .def_readonly("position", &NoisyVertexDetection::position, + py::return_value_policy::copy) + .def_readonly("cov", &NoisyVertexDetection::cov, + py::return_value_policy::copy) + .def_readonly("cov_rt", &NoisyVertexDetection::cov_rt) + .def_readonly("angle_rad", &NoisyVertexDetection::angle_rad) + .def_readwrite("range", &NoisyVertexDetection::range) + .def_readwrite("associated_vertex", &NoisyVertexDetection::associated_vertex_ptr) + .def_property_readonly("detection_type", + &NoisyVertexDetection::get_detection_type) + .def("add_association", &NoisyVertexDetection::add_association) + .def("update_props", &NoisyVertexDetection::update_props); + + py::class_>(m, "NoisyWall") + .def(py::init< + const std::shared_ptr &, + const std::shared_ptr &>(), + py::arg("left_vertex"), py::arg("right_vertex")) + .def_readwrite("is_active", &NoisyWall::is_active) + .def_readwrite("prob_list", &NoisyWall::prob_list) + .def_readonly("left_vertex", &NoisyWall::left_vertex_ptr) + .def_readonly("right_vertex", &NoisyWall::right_vertex_ptr) + .def_property_readonly("prob_exists", &NoisyWall::prob_exists) + .def("_update", &NoisyWall::update) + .def("__eq__", &NoisyWall::eq) + .def("add_detection", &NoisyWall::add_detection, + py::arg("left_detection"), py::arg("right_detection"), + py::arg("false_positive_factor")); + + py::bind_map(m, "MapPairWall"); + // py::bind_map(m, "VertIdMap"); + // py::bind_vector>(m, "VectorInt"); + py::bind_vector>>(m, "VectorPose"); + // py::bind_vector>>(m, "VectorVectorInt"); + py::bind_vector>>(m, "VectorVertices"); + py::bind_vector>>(m, "VectorHalDet"); + py::bind_vector>(m, "VectorRealObservation"); + py::bind_vector>(m, "VectorTopologyOperation"); + + py::class_>(m, "ProposedWorldCore") + .def_readonly("vertices", &ProposedWorldCore::vertices) + .def_property_readonly("topology", &ProposedWorldCore::get_topology_py) + .def_readonly("vertex_remapping", &ProposedWorldCore::vertex_remapping) + .def_readonly("remapped_wall_dict", &ProposedWorldCore::remapped_wall_dict) + .def("get_vertices_for_pose", &ProposedWorldCore::get_vertices_for_pose); + + + py::class_>(m, "NoisyVertexInfo"); + + py::class_>(m, "SamplingState") + .def(py::init, + const std::vector> &, + float, const std::vector> &>(), + py::arg("vertices"), py::arg("topology"), py::arg("log_prob"), py::arg("poses")) + .def_readonly("log_prob", &SamplingState::log_prob) + .def_property_readonly("topology", &SamplingState::get_topology_py); + + + py::class_(m, "ProbVertexGraph") + .def(py::init<>()) + .def_readwrite("vertices", &ProbVertexGraph::vertices) + //.def_readwrite("topology", &ProbVertexGraph::topology) + .def_property("topology", + &ProbVertexGraph::get_topology_py, + &ProbVertexGraph::set_topology_py) + .def_readwrite("walls", &ProbVertexGraph::walls) + .def_readwrite("r_poses", &ProbVertexGraph::poses) + .def_readwrite("odoms", &ProbVertexGraph::odoms) + .def_readwrite("observations", &ProbVertexGraph::observations) + .def_readwrite("false_positive_rate", &ProbVertexGraph::false_positive_rate) + .def_readwrite("false_negative_rate", &ProbVertexGraph::false_negative_rate) + .def_readwrite("disallowed_topology_operations", &ProbVertexGraph::disallowed_topology_operations) + .def_readwrite("TOPOLOGY_LOCK_LOG_THRESH", &ProbVertexGraph::TOPOLOGY_LOCK_LOG_THRESH) + .def_readwrite("DO_SLAM", &ProbVertexGraph::DO_SLAM) + .def_readwrite("DO_SAMPLE_TOPOLOGY", &ProbVertexGraph::DO_SAMPLE_TOPOLOGY) + .def_readwrite("PRIOR_NOISE", &ProbVertexGraph::PRIOR_NOISE) + .def_readwrite("ODOMETRY_NOISE", &ProbVertexGraph::ODOMETRY_NOISE) + .def_readwrite("CLUSTERING_NOISE", &ProbVertexGraph::CLUSTERING_NOISE) + .def("get_state", &ProbVertexGraph::get_state) + .def("set_state", &ProbVertexGraph::set_state) + .def("add_observation_pose", &ProbVertexGraph::add_observation_pose) + .def("add_observation_odom", &ProbVertexGraph::add_observation_odom) + .def("_associate_detections", &ProbVertexGraph::associate_detections, py::arg("observation"), py::arg("r_pose"), py::arg("association_window") = -1) + .def("compute_world_log_prob", &ProbVertexGraph::compute_world_log_prob) + .def("compute_world_log_prob_full", &ProbVertexGraph::compute_world_log_prob_full) + .def("perform_slam_update", &ProbVertexGraph::perform_slam_update) + .def("get_proposed_world_fast", &ProbVertexGraph::get_proposed_world_py, py::arg("topology")); + + m.def("eval_mat_mul", &eval_mat_mul); + m.def("get_vertex_remapping", &get_vertex_remapping); + m.def("get_remapped_wall_dict", &get_remapped_wall_dict); + m.def("compute_conservative_space_hallucinated", + &compute_conservative_space_hallucinated); + m.def("compute_conservative_space_observed", + &compute_conservative_space_observed); + m.def("compute_hypothetical_observation", + &compute_hypothetical_observation); + +#ifdef VERSION_INFO + m.attr("__version__") = VERSION_INFO; +#else + m.attr("__version__") = "dev"; +#endif +} diff --git a/modules/vertexnav_accel/src/noisy.cpp b/modules/vertexnav_accel/src/noisy.cpp new file mode 100644 index 0000000..b690758 --- /dev/null +++ b/modules/vertexnav_accel/src/noisy.cpp @@ -0,0 +1,290 @@ +#include + +#include +#include +#include + + +NoisyVertex::NoisyVertex(const Eigen::Vector2d &n_position, + const Eigen::Matrix2d &n_cov): + last_updated(-1), num_detections(0), + is_active(true), is_locked(false), + position(n_position), cov(n_cov) { + id = class_id++; +} + + +NoisyVertex::NoisyVertex(const Eigen::Vector2d &n_position, + const Eigen::Matrix2d &n_cov, + const Pose &n_pose): + last_updated(n_pose.index), num_detections(1), + is_active(true), is_locked(false), + position(n_position), cov(n_cov) { + id = class_id++; +} + +void NoisyVertex::add_detection(const Eigen::Vector2d &n_position, + const Eigen::Matrix2d &n_cov, + const Pose &n_pose) { + // Compute Kalman gain (K) + Eigen::Matrix2d K = cov *(cov + n_cov).inverse(); + + // Perform the Kalman update + position << position + K * (n_position - position); + cov << (Eigen::Matrix2d::Identity() - K) * cov; + + // Some additional parameter updates. + num_detections += 1; + last_updated = n_pose.index; +} + +int NoisyVertex::class_id = 0; + + +NoisyVertexDetection::NoisyVertexDetection( + double n_angle_rad, double n_range, + const std::shared_ptr &n_detection_type_ptr, + const Eigen::Matrix2d &n_cov_rt): + angle_rad(n_angle_rad), + range(n_range), + cov_rt(n_cov_rt) { + detection_type_ptr = n_detection_type_ptr; +} + +const std::shared_ptr &NoisyVertexDetection::get_associated_vertex() const { + if (associated_vertex_ptr) { + return associated_vertex_ptr; + } else { + throw "ValueError: This detection does not have an associated vertex"; + } +} + +void NoisyVertexDetection::update_props(const Pose &pose) { + double world_theta = angle_rad + pose.yaw; + double cov_r = cov_rt(0, 0); + double r_sq_cov_theta = range * range * cov_rt(1, 1); + double sin_th = sin(world_theta); + double cos_th = cos(world_theta); + double sin_th_sq = sin_th * sin_th; + double cos_th_sq = cos_th * cos_th; + double Q11 = r_sq_cov_theta * sin_th_sq + cov_r * cos_th_sq; + double Q22 = r_sq_cov_theta * cos_th_sq + cov_r * sin_th_sq; + double Q12 = (cov_r - r_sq_cov_theta) * cos_th * sin_th; + + position << pose.x + range * cos_th, pose.y + range * sin_th; + cov << Q11, Q12, Q12, Q22; +} + + +// HallucinatedVertexDetection +int HallucinatedVertexDetection::class_id = 0; +void null_deleter(NoisyDetectionType *) {} +NoisyDetectionType HallucinatedVertexDetection::default_detection_type = NoisyDetectionType(); +std::shared_ptr HallucinatedVertexDetection::default_detection_type_ptr = std::shared_ptr(&HallucinatedVertexDetection::default_detection_type, &null_deleter); + +HallucinatedVertexDetection::HallucinatedVertexDetection( + double n_angle_rad, double n_range, const Pose &pose) : + angle_rad(n_angle_rad) { + id = ++class_id; + + Eigen::Vector2d tmp_position; + tmp_position << pose.x + n_range * cos(n_angle_rad), + pose.y + n_range * sin(n_angle_rad); + position = tmp_position; +} + +HallucinatedVertexDetection::HallucinatedVertexDetection( + double n_angle_rad, const Eigen::Vector2d &n_position) : + angle_rad(n_angle_rad), + position(n_position) { + id = ++class_id; +} + +const std::shared_ptr& HallucinatedVertexDetection::get_detection_type() const { + if (detection_type_ptr) { + return detection_type_ptr; + } else { + return default_detection_type_ptr; + } +} + + + +// NoisyWall + + +Eigen::Vector2d eval_mat_mul(Eigen::Matrix2d in_mat, Eigen::Vector2d in_vec) { + return in_mat * in_vec; +} + +double prob_of_wall( + const std::shared_ptr &label1, + const std::shared_ptr &label2) { + return (1 - 0.5 * (label1->prob_left_gap + label2->prob_right_gap)); +} + + +const std::map get_vertex_id_mapping( + const std::vector &vertices) { + std::map vertex_id_mapping; + for (auto &vert : vertices) { + vertex_id_mapping.insert(std::make_pair(vert->id, vert)); + } + return vertex_id_mapping; +} + + +const std::map get_vertex_remapping( + const std::vector &vertices, + const std::set> &topology) { + std::map vertex_id_mapping = + get_vertex_id_mapping(vertices); + std::map vertex_remapping; + + for (const auto &cluster : topology) { + if (cluster.size() == 1) { + vertex_remapping.insert(std::make_pair( + cluster[0], vertex_id_mapping[cluster[0]])); + } else { + Eigen::Matrix2d sum_cov_inv = Eigen::Matrix2d::Zero(); + Eigen::Vector2d sum_weighted_means = Eigen::Vector2d::Zero(); + for (const auto &vid : cluster) { + auto vert = vertex_id_mapping[vid]; + auto cov_inv = (vert->get_cov()).inverse(); + sum_cov_inv += cov_inv; + sum_weighted_means += cov_inv * vert->get_position(); + } + + auto cov = sum_cov_inv.inverse(); + NoisyVertexPtr cluster_vert = std::make_shared( + cov * sum_weighted_means, cov); + + for (const auto &vid : cluster) { + vertex_remapping.insert(std::make_pair(vid, cluster_vert)); + } + } + } + + return vertex_remapping; +} + +std::pair get_wall_dict_key(int id_a, int id_b) { + if (id_a < id_b) { + return std::pair(id_a, id_b); + } else { + return std::pair(id_b, id_a); + } +} + +const MapPairWall get_remapped_wall_dict( + const MapPairWall &walls, + const std::set> &topology, + const std::map &vertex_remapping) { + // Get list of unmapped vert ids + std::set unremapped_verts; + for (const auto &cluster : topology) { + if (cluster.size() == 1) { + unremapped_verts.insert(cluster[0]); + } + } + + MapPairWall walls_remapped; + for (auto pair_wall : walls) { + auto va = vertex_remapping.find(pair_wall.first.first)->second; + auto vb = vertex_remapping.find(pair_wall.first.second)->second; + auto remapped_key = get_wall_dict_key(va->id, vb->id); + + // If neither vertex is remapped, use the existing wall. + if (unremapped_verts.find(va->id) != unremapped_verts.end() && + unremapped_verts.find(vb->id) != unremapped_verts.end()) { + walls_remapped.insert(std::make_pair(remapped_key, pair_wall.second)); + continue; + } + + const auto &it = walls_remapped.find(remapped_key); + std::shared_ptr remapped_wall; + if (it != walls_remapped.end()) { + // Get the wall from the map + remapped_wall = it->second; + } else { + // Create a new wall and add it to the list + remapped_wall = std::make_shared(va, vb); + walls_remapped.insert(std::make_pair( + remapped_key, remapped_wall)); + } + remapped_wall->add_prob_list(pair_wall.second->prob_list); + } + + return walls_remapped; +} + +std::vector compute_poly_points_from_angle_pos_dat( + const std::vector &angle_pos_dat, + const std::shared_ptr &pose) { + std::vector poly_points; + int num_dats = angle_pos_dat.size(); + for (int rind = 0; rind < num_dats; ++rind) { + // Some helper variables + int lind = (rind + 1) % num_dats; + double low_angle = angle_pos_dat[rind].first; + double high_angle = angle_pos_dat[lind].first; + + // Add the current point + poly_points.push_back(angle_pos_dat[rind].second); + + // If necessary, add the robot pose + if (high_angle < low_angle) { + high_angle += 2 * M_PI; + } + if ((high_angle - low_angle) >= M_PI) { + Eigen::Vector2d pose_position; + pose_position << pose->x, pose->y; + poly_points.push_back(pose_position); + } + } + + // By convention, the final point is a duplicate of the first + if (num_dats > 0) { + poly_points.push_back(angle_pos_dat[0].second); + } + + return poly_points; +} + +std::vector compute_conservative_space_hallucinated( + const std::shared_ptr &pose, + const std::vector> &observation) { + std::vector angle_pos_dat; + for (auto& h_det : observation) { + angle_pos_dat.push_back(std::make_pair( + h_det->angle_rad, h_det->position)); + } + + std::sort(angle_pos_dat.begin(), angle_pos_dat.end(), + [](const AnglePos &a, const AnglePos &b) -> bool { + return a.first < b.first;}); + + return compute_poly_points_from_angle_pos_dat(angle_pos_dat, pose); +} + + +std::vector compute_conservative_space_observed( + const std::shared_ptr &pose, + const std::vector> &observation, + const std::map &vertex_remapping) { + std::vector angle_pos_dat; + for (auto& det : observation) { + Eigen::Vector2d position = vertex_remapping.find( + det->associated_vertex_ptr->id)->second->get_position(); + float angle_rad = atan2(position[1] - pose->y, + position[0] - pose->x); + angle_pos_dat.push_back(std::make_pair( + angle_rad, position)); + } + + std::sort(angle_pos_dat.begin(), angle_pos_dat.end(), + [](const AnglePos &a, const AnglePos &b) -> bool { + return a.first < b.first; }); + + return compute_poly_points_from_angle_pos_dat(angle_pos_dat, pose); +} diff --git a/modules/vertexnav_accel/src/noisy.hpp b/modules/vertexnav_accel/src/noisy.hpp new file mode 100644 index 0000000..5a8acc1 --- /dev/null +++ b/modules/vertexnav_accel/src/noisy.hpp @@ -0,0 +1,260 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#pragma once + +/* + Devoted to defining a number of the "noisy" classes: NoisyDetectionType, NoisyVertexDetection, HallucinatedVertexDetection, and NoisyVertex + +*/ + + +struct NoisyDetectionType { + Eigen::Vector4d label; + double prob_left_gap; + double prob_right_gap; + + NoisyDetectionType(): prob_left_gap(0.5), + prob_right_gap(0.5) { + label << 0.25, 0.25, 0.25, 0.25; + }; + + NoisyDetectionType(const char &label_in) : + prob_left_gap(0.0), prob_right_gap(0.0) { + Eigen::Vector4d tmp_label; + switch (label_in) { + case 'r': + tmp_label << 1.0, 0.0, 0.0, 0.0; + prob_right_gap = 1.0; + break; + case 'c': + tmp_label << 0.0, 1.0, 0.0, 0.0; + break; + case 'l': + tmp_label << 0.0, 0.0, 1.0, 0.0; + prob_left_gap = 1.0; + break; + case 'p': + tmp_label << 0.0, 0.0, 0.0, 1.0; + prob_left_gap = 1.0; + prob_right_gap = 1.0; + break; + default: + throw "Value Error: char not allowed in constructor."; + } + label << tmp_label; + } + + NoisyDetectionType(const Eigen::Vector4d &label_in) { + label << label_in; + prob_left_gap = label_in(2) + label_in(3); + prob_right_gap = label_in(0) + label_in(3); + } + + bool eq(const NoisyDetectionType &oth) const { + return label == oth.label; + } +}; + + +class NoisyVertex { + public: + NoisyVertex(const Eigen::Vector2d &n_position, + const Eigen::Matrix2d &n_cov); + NoisyVertex(const Eigen::Vector2d &n_position, + const Eigen::Matrix2d &n_cov, + const Pose &n_pose); + + void set_cov(const Eigen::Matrix2d &n_cov) { + cov = n_cov; + } + const Eigen::Matrix2d &get_cov() const { + return cov; + } + + void set_position(const Eigen::Vector2d &n_position) { + position = n_position; + } + const Eigen::Vector2d &get_position() const { + return position; + } + + int last_updated; + int num_detections; + int id; + + bool is_active; + bool is_locked; + + void add_detection(const Eigen::Vector2d &n_position, + const Eigen::Matrix2d &n_cov, + const Pose &n_pose); + + int hash() const { return id; } + bool eq(const NoisyVertex &oth) const { return id == oth.id; } + + protected: + static int class_id; + + private: + Eigen::Vector2d position; + Eigen::Matrix2d cov; +}; + +typedef std::shared_ptr NoisyVertexPtr; + + +class NoisyVertexDetection { +public: + double angle_rad; + double range; + Eigen::Vector2d position; + Eigen::Matrix2d cov; + Eigen::Matrix2d cov_rt; + std::shared_ptr detection_type_ptr; + std::shared_ptr associated_vertex_ptr; + + NoisyVertexDetection(double n_angle_rad, double n_range, + const std::shared_ptr &n_detection_type, + const Eigen::Matrix2d &n_cov_rt); + + const std::shared_ptr &get_associated_vertex() const; + const std::shared_ptr &get_detection_type() const { + return detection_type_ptr; + } + + void add_association(const std::shared_ptr &new_associated_vertex) { + associated_vertex_ptr = new_associated_vertex; + } + + void update_props(const Pose &pose); + +}; + +class HallucinatedVertexDetection { + public: + double angle_rad; + Eigen::Vector2d position; + int id; + + HallucinatedVertexDetection(double n_angle_rad, + const Eigen::Vector2d &n_position); + + HallucinatedVertexDetection(double n_angle_rad, double n_range, + const Pose &pose); + + const std::shared_ptr& get_detection_type() const; + + void set_detection_type(const std::shared_ptr &n_detection_type_ptr) { + detection_type_ptr = n_detection_type_ptr; + } + + int hash() const { return id; } + bool eq(HallucinatedVertexDetection oth) const { return id == oth.id; } + + protected: + static int class_id; + static NoisyDetectionType default_detection_type; + static std::shared_ptr default_detection_type_ptr; + std::shared_ptr detection_type_ptr; +}; + +double prob_of_wall( + const std::shared_ptr &label1, + const std::shared_ptr &label2); + + +struct NoisyWall { + std::vector prob_list; + std::shared_ptr left_vertex_ptr; + std::shared_ptr right_vertex_ptr; + bool is_active; + + NoisyWall(const std::shared_ptr &n_left_vertex_ptr, + const std::shared_ptr &n_right_vertex_ptr): + prob_list(), is_active(false) { + left_vertex_ptr = n_left_vertex_ptr; + right_vertex_ptr = n_right_vertex_ptr; + } + + void add_detection( + const std::shared_ptr &left_detection, + const std::shared_ptr &right_detection, + double false_positive_factor) { + prob_list.push_back(false_positive_factor * prob_of_wall( + right_detection->get_detection_type(), + left_detection->get_detection_type())); + update(); + } + + void add_prob_list(const std::vector &oth_prob_list) { + prob_list.insert( + prob_list.end(), + oth_prob_list.begin(), + oth_prob_list.end()); + update(); + } + + int num_observations() const { + return static_cast(prob_list.size()); + } + + double prob_exists() const { + double tot = 0; + for (auto& p : prob_list) { + tot += p; + } + return tot / (prob_list.size() + 1.0); + } + + void update() { is_active = (prob_exists() > 0.5); } + + bool eq(const NoisyWall &oth) const { + return (left_vertex_ptr->id == oth.left_vertex_ptr->id && + right_vertex_ptr->id == oth.right_vertex_ptr->id); + } + +}; + +typedef std::map, std::shared_ptr> MapPairWall; + +typedef std::pair AnglePos; + +Eigen::Vector2d eval_mat_mul(Eigen::Matrix2d in_mat, Eigen::Vector2d in_vec); + +const std::map get_vertex_id_mapping( + const std::vector &vertices); + +const std::map get_vertex_remapping( + const std::vector &vertices, + const std::set> &topology); + +std::pair get_wall_dict_key(int id_a, int id_b); + +const MapPairWall get_remapped_wall_dict( + const MapPairWall &walls, + const std::set> &topology, + const std::map &vertex_remapping); + +std::vector compute_poly_points_from_angle_pos_dat( + const std::vector &angle_pos_dat, + const std::shared_ptr &pose); + +std::vector compute_conservative_space_hallucinated( + const std::shared_ptr &pose, + const std::vector> &observation); + +std::vector compute_conservative_space_observed( + const std::shared_ptr &pose, + const std::vector> &observation, + const std::map &vertex_remapping); diff --git a/modules/vertexnav_accel/src/pose.cpp b/modules/vertexnav_accel/src/pose.cpp new file mode 100644 index 0000000..f5f17cf --- /dev/null +++ b/modules/vertexnav_accel/src/pose.cpp @@ -0,0 +1,25 @@ +#include +#include + +int Pose::class_id = 0; + +Pose Pose::rmul(const Pose &oth) const { + double sin_yaw = sin(yaw); + double cos_yaw = cos(yaw); + double xn = x + cos_yaw * oth.x - sin_yaw * oth.y; + double yn = y + sin_yaw * oth.x + cos_yaw * oth.y; + double yawn = fmod(yaw + oth.yaw, 2 * M_PI); + return Pose(xn, yn, yawn, robot_id); +} + +Pose Pose::get_odom(const Pose &p_new, const Pose &p_old) { + assert(p_new.robot_id == p_old.robot_id); + double dyaw = p_new.yaw - p_old.yaw; + double dx = p_new.x - p_old.x; + double dy = p_new.y - p_old.y; + double sin_yaw = sin(p_old.yaw); + double cos_yaw = cos(p_old.yaw); + double x_odom = cos_yaw * dx + sin_yaw * dy; + double y_odom = -sin_yaw * dx + cos_yaw * dy; + return Pose(x_odom, y_odom, dyaw, p_old.robot_id); +} diff --git a/modules/vertexnav_accel/src/pose.hpp b/modules/vertexnav_accel/src/pose.hpp new file mode 100644 index 0000000..f0bc83a --- /dev/null +++ b/modules/vertexnav_accel/src/pose.hpp @@ -0,0 +1,32 @@ +#include + +#pragma once + +// Defines the Pose class +static int pose_count; + +struct Pose { + protected: + static int class_id; + public: + int index; + int robot_id; + double x, y, yaw; + + Pose(double xi, double yi, double yawi, int n_robot_id): x(xi), y(yi), yaw(yawi), robot_id(n_robot_id) { + index = ++class_id; + } + + Pose mul(const Pose &oth) const { + return oth.rmul(*this); + } + + Pose rmul(const Pose &oth) const; + + static Pose get_odom(const Pose &p_new, const Pose &p_old); + + Pose operator* (const Pose &oth) const { + return mul(oth); + } + +}; diff --git a/modules/vertexnav_accel/src/types.hpp b/modules/vertexnav_accel/src/types.hpp new file mode 100644 index 0000000..cae2427 --- /dev/null +++ b/modules/vertexnav_accel/src/types.hpp @@ -0,0 +1,11 @@ + +#pragma once + +#include +#include + +typedef std::vector> VVD; +typedef std::vector VEV; +typedef std::vector> VES; +// typedef std::pair EigenSeg; +typedef std::vector VD; diff --git a/modules/vertexnav_accel/src/vertex_graph.cpp b/modules/vertexnav_accel/src/vertex_graph.cpp new file mode 100644 index 0000000..4e7343e --- /dev/null +++ b/modules/vertexnav_accel/src/vertex_graph.cpp @@ -0,0 +1,383 @@ +#include "vertex_graph.hpp" + +#include +#include +#include +#include +#include + +// GTSAM +#include +#include +#include +#include +#include +#include +#include +#include +#include + +double dipow(double base, int exp) { + double result = 1; + for (;;) { + if (exp & 1) + result *= base; + exp >>= 1; + if (!exp) + break; + base *= base; + } + + return result; +} + +bool does_cluster_overlap(const std::vector &cluster, + const std::set &vert_ids) { + for (const int &vid : cluster) { + auto it = vert_ids.find(vid); + if (it != vert_ids.end()) { + return true; + } + } + return false; +} + +void ProbVertexGraph::perform_slam_update() { + if (!DO_SLAM) { return; } + + gtsam::NonlinearFactorGraph graph; + gtsam::Values initials; + + gtsam::noiseModel::Diagonal::shared_ptr prior_noise = + gtsam::noiseModel::Diagonal::Sigmas(PRIOR_NOISE); + gtsam::noiseModel::Diagonal::shared_ptr odometry_noise = + gtsam::noiseModel::Diagonal::Sigmas(ODOMETRY_NOISE); + gtsam::noiseModel::Diagonal::shared_ptr clustering_noise = + gtsam::noiseModel::Diagonal::Sigmas(CLUSTERING_NOISE); + + // Get all the robot ids + std::set robot_ids; + for (const auto &pose : poses) { + robot_ids.insert(pose->robot_id); + } + + // Each robot_id forms a chain of poses + for (int rid : robot_ids) { + // Get all poses for a particular ID + std::vector> rid_poses; + for (const auto &pose : poses) { + if (pose->robot_id == rid) { + rid_poses.push_back(pose); + } + } + + // Get all odoms for a particular ID + std::vector> rid_odoms; + for (const auto &odom : odoms) { + if (odom->robot_id == rid) { + rid_odoms.push_back(odom); + } + } + + // Add the factor for the initial pose + const auto &initial_pose = rid_poses[0]; + gtsam::Symbol initial_pose_symbol = gtsam::Symbol('p', initial_pose->index); + graph.add(gtsam::PriorFactor( + initial_pose_symbol, gtsam::Pose2( + initial_pose->x, initial_pose->y, initial_pose->yaw), + prior_noise)); + initials.insert(initial_pose_symbol, gtsam::Pose2( + initial_pose->x, initial_pose->y, initial_pose->yaw)); + + // Add the odometry + int num_poses = rid_poses.size(); + for (int ii = 1; ii < num_poses; ii++) { + // Get the new symbol and add to the dictionary + const auto &pose = rid_poses[ii]; + gtsam::Symbol old_pose_symbol = gtsam::Symbol( + 'p', rid_poses[ii-1]->index); + gtsam::Symbol new_pose_symbol = gtsam::Symbol( + 'p', pose->index); + + // Add the odometry estimate + const auto &odom = rid_odoms[ii-1]; + graph.add(gtsam::BetweenFactor( + old_pose_symbol, new_pose_symbol, + gtsam::Pose2(odom->x, odom->y, odom->yaw), + odometry_noise)); + + // Add the initial estimate of pose + initials.insert( + new_pose_symbol, gtsam::Pose2(pose->x, pose->y, pose->yaw)); + } + } + + // Add the observation factors + int num_poses = poses.size(); + for (int ii = 0; ii < num_poses; ii++) { + const auto &pose = poses[ii]; + auto pose_symbol = gtsam::Symbol('p', pose->index); + + const auto &observation = observations[ii]; + for (const auto &det : observation) { + auto vert = det->associated_vertex_ptr; + auto vert_symbol = gtsam::Symbol('v', vert->id); + + Eigen::Vector2d det_cov_noise; + det_cov_noise << sqrt(det->cov_rt(1, 1)), sqrt(det->cov_rt(0, 0)); + if (!vert->is_active) { + det_cov_noise *= 10; + } + auto measurement_noise = gtsam::noiseModel::Diagonal::Sigmas( + det_cov_noise); + graph.add(gtsam::BearingRangeFactor( + pose_symbol, vert_symbol, + gtsam::Rot2(det->angle_rad), det->range, + measurement_noise)); + } + } + + // Add the clustering constraints + for (const auto &cluster : topology) { + int num_cluster_elements = cluster.size(); + if (num_cluster_elements == 1) { + continue; + } + + for (int ii = 0; ii < num_cluster_elements - 1; ii++) { + auto vert_symbol_a = gtsam::Symbol('v', cluster[ii]); + for (int jj = ii + 1; jj < num_cluster_elements; jj++) { + auto vert_symbol_b = gtsam::Symbol('v', cluster[jj]); + + graph.add(gtsam::BetweenFactor( + vert_symbol_a, vert_symbol_b, + gtsam::Point2(0.0, 0.0), + clustering_noise)); + } + } + } + + // Add the initial estimates for the vertex positions + for (const auto &vert : vertices) { + initials.insert(gtsam::Symbol('v', vert->id), + gtsam::Point2(vert->get_position())); + } + + // Optimize + const gtsam::LevenbergMarquardtParams params; + gtsam::LevenbergMarquardtOptimizer optimizer(graph, initials, params); + gtsam::Values result = optimizer.optimize(); + + // Set the vertex positions + for (const auto &vert : vertices) { + const auto &v_pos = result.at( + gtsam::Symbol('v', vert->id)); + Eigen::Vector2d eigen_vert_position; + eigen_vert_position << v_pos.x(), v_pos.y(); + vert->set_position(eigen_vert_position); + } + + // Set the poses and update the observations + for (int ii = 0; ii < num_poses; ii++) { + auto pose = poses[ii]; + const auto &pose_dat = result.at( + gtsam::Symbol('p', pose->index)); + pose->x = pose_dat.x(); + pose->y = pose_dat.y(); + pose->yaw = pose_dat.theta(); + + const auto &observation = observations[ii]; + for (const auto &det : observation) { + det->update_props(*pose); + } + } +} + +std::vector> compute_hypothetical_observation( + const std::shared_ptr &world, + const std::shared_ptr &pose, + const std::vector> &observation) { + auto poly_points = compute_conservative_space_observed( + pose, observation, world->vertex_remapping); + auto h_vertex_positions = world->get_vertices_for_pose( + pose, poly_points); + + std::vector> h_observation; + for (const Eigen::Vector2d &position : h_vertex_positions) { + double angle_rad = atan2(position(1) - pose->y, + position(0) - pose->x); + h_observation.push_back(std::make_shared( + angle_rad, position)); + } + std::sort(h_observation.begin(), h_observation.end(), + [] (const std::shared_ptr h_det_a, + const std::shared_ptr h_det_b) -> bool { + return h_det_a->angle_rad < h_det_b->angle_rad; + }); + + return h_observation; +} + +typedef std::pair PosKey; +typedef std::shared_ptr HVDptr; + +inline PosKey get_position_key(const Eigen::Vector2d &position) { + return std::make_pair(static_cast(position(0) * 1000000), + static_cast(position(1) * 1000000)); +} + +double compute_observation_log_likelihood( + const std::shared_ptr &world, + const std::shared_ptr &pose, + const std::vector> observation, + const std::map vertex_positions_memo, + double log_fp_rate, double log_fn_rate) { + double log_prob = 0.0; + int match_count = 0; + int fp_count = 0; + + std::vector h_observation + = compute_hypothetical_observation(world, pose, observation); + + std::map h_det_match_count_map; // h_det->id => num_matches + std::map h_det_dist_prob_map; // h_det->id => dist_prob + std::map h_det_vert_map; // h_det->id => parent vertex + std::map h_det_map; + + for (const auto &h_det : h_observation) { + PosKey h_pos_key = get_position_key(h_det->position); + h_det_map[h_pos_key] = h_det; + h_det_match_count_map[h_det->id] = 0; + h_det_vert_map[h_det->id] = vertex_positions_memo.find(h_pos_key)->second; + } + + for (const auto &r_det : observation) { + PosKey r_pos_key = get_position_key(world->vertex_remapping[ + r_det->associated_vertex_ptr->id]->get_position()); + + const auto &it = h_det_map.find(r_pos_key); + if (it != h_det_map.end()) { + // h_det found + auto h_det = it->second; + Eigen::Vector2d dx = r_det->position - h_det->position; + double dist_prob = -(r_det->cov.inverse() * dx).dot(dx); + + int count = h_det_match_count_map[h_det->id]++; + if (count > 0) { + // We've already seen this h_det + // Add a false positive, avg the det types, get max dist prob + fp_count++; + Eigen::Vector4d o_det_type, n_det_type; + o_det_type << h_det->get_detection_type()->label; + n_det_type << r_det->get_detection_type()->label; + h_det->set_detection_type(std::make_shared( + (count * o_det_type + n_det_type) / (1.0 + count))); + h_det_dist_prob_map[h_det->id] = max( + h_det_dist_prob_map[h_det->id], dist_prob); + } else { + // First time we're seeing this h_det + h_det->set_detection_type(r_det->get_detection_type()); + h_det_dist_prob_map[h_det->id] = dist_prob; + match_count++; + } + } else { + // h_det not found (incrememnt num false positives) + fp_count++; + } + } // end for (r_det) + + // Update the probability using the matches/misses + log_prob += (h_observation.size() - match_count) * log_fn_rate; + log_prob += (fp_count) * log_fp_rate; + + // Add the distance likelihoods + for (const auto &it : h_det_dist_prob_map) { + log_prob += max(log_fp_rate, it.second); + } + + // Wall likelihood computation + double wall_prob = 1.0; + int num_h_dets = h_observation.size(); + for (int rind = 0; rind < num_h_dets; ++rind) { + // Some helper variables + int lind = (rind + 1) % num_h_dets; + auto det_L = h_observation[lind]; + auto vert_L = h_det_vert_map[det_L->id]; + auto det_R = h_observation[rind]; + auto vert_R = h_det_vert_map[det_R->id]; + double high_angle = det_L->angle_rad; + double low_angle = det_R->angle_rad; + + if (high_angle < low_angle) { + high_angle += 2 * M_PI; + } + if (high_angle - low_angle >= M_PI) { + continue; + } + + double wall_exists_prob = 0.0; + auto wall_key = get_wall_dict_key(vert_L->id, vert_R->id); + const auto &it = world->remapped_wall_dict.find(wall_key); + if (it != world->remapped_wall_dict.end()) { + // wall found + wall_exists_prob = it->second->is_active; + } + + double obs_wall_prob = prob_of_wall( + det_R->get_detection_type(), det_L->get_detection_type()); + + wall_prob *= max(1 - abs(obs_wall_prob - wall_exists_prob), 0.25); + } // end for (walls) + + log_prob += log(wall_prob); + + return log_prob; +} + + +double ProbVertexGraph::compute_world_log_prob( + const std::shared_ptr &world, + const std::vector &pose_obs_pairs) const { + std::map vertex_positions_memo; + for (const auto &it : world->vertex_remapping) { + vertex_positions_memo.insert(std::make_pair( + get_position_key(it.second->get_position()), it.second)); + } + + double log_fp_rate = log(false_positive_rate); + double log_fn_rate = log(false_negative_rate); + + double prob = 2 * world->vertices.size() * log(false_positive_rate); + for (const auto &pose_obs_pair : pose_obs_pairs) { + prob += compute_observation_log_likelihood( + world, pose_obs_pair.first, pose_obs_pair.second, + vertex_positions_memo, + log_fp_rate, log_fn_rate); + } + + return prob; +} + + +double ProbVertexGraph::compute_world_log_prob_full( + const std::shared_ptr &world) const { + std::map vertex_positions_memo; + for (const auto &it : world->vertex_remapping) { + vertex_positions_memo.insert(std::make_pair( + get_position_key(it.second->get_position()), it.second)); + } + + double log_fp_rate = log(false_positive_rate); + double log_fn_rate = log(false_negative_rate); + + double prob = 2 * world->vertices.size() * log(false_positive_rate); + int num_poses = poses.size(); + for (int ii = 0; ii < num_poses; ii++) { + prob += compute_observation_log_likelihood( + world, poses[ii], observations[ii], + vertex_positions_memo, + log_fp_rate, log_fn_rate); + } + + return prob; +} diff --git a/modules/vertexnav_accel/src/vertex_graph.hpp b/modules/vertexnav_accel/src/vertex_graph.hpp new file mode 100644 index 0000000..18a6049 --- /dev/null +++ b/modules/vertexnav_accel/src/vertex_graph.hpp @@ -0,0 +1,435 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +typedef std::vector> RealObservation; +typedef std::pair>, std::set>> TopologyOperation; +typedef std::pair, RealObservation> PoseObsPair; + +double dipow(double base, int exp); + +bool does_cluster_overlap(const std::vector &cluster, + const std::set &vert_ids); + +struct NoisyVertexInfo { + bool is_active; + bool is_locked; + Eigen::Vector2d position; + + NoisyVertexInfo(const NoisyVertexPtr &vert) : + is_active(vert->is_active), + is_locked(vert->is_locked), + position(vert->get_position()) {} +}; + +struct SamplingState { + std::set> topology; + double log_prob; + std::map> vertex_info_map; + std::map> pose_info_map; + + SamplingState(const std::vector &vertices, + const std::vector> &n_topology, + double n_log_prob, + const std::vector> &poses) : + log_prob(n_log_prob) { + for (const auto &cluster : n_topology) { + topology.insert(cluster); + } + for (const auto &vert : vertices) { + vertex_info_map[vert->id] = + std::make_shared(vert); + } + for (const auto &pose : poses) { + pose_info_map[pose->index] = std::array( + {pose->x, pose->y, pose->yaw}); + } + } + + SamplingState(const std::vector &vertices, + const std::set> &n_topology, + double n_log_prob, + const std::vector> &poses) : + topology(n_topology), log_prob(n_log_prob) { + for (const auto &vert : vertices) { + vertex_info_map[vert->id] = + std::make_shared(vert); + } + for (const auto &pose : poses) { + pose_info_map[pose->index] = std::array( + {pose->x, pose->y, pose->yaw}); + } + } + + std::vector> get_topology_py() const { + std::vector> top_out(topology.begin(), topology.end()); + return top_out; + } +}; + + +class ProposedWorldCore : public FastWorld { + public: + std::set> topology; + std::map vertex_remapping; + MapPairWall remapped_wall_dict; + + ProposedWorldCore(const std::vector> &segs, + const std::vector &verts, + const std::set> &n_topology, + const std::map &n_vertex_remapping, + const MapPairWall &n_remapped_wall_dict) : + topology(n_topology), + vertex_remapping(n_vertex_remapping), + remapped_wall_dict(n_remapped_wall_dict) { + + for (const auto &vert : verts) { + vertices.push_back(vert->get_position()); + } + + std::vector segments; + for (const auto &seg : segs) { + segments.push_back(Segment_2( + Point_2(seg.first->get_position()(0), seg.first->get_position()(1)), + Point_2(seg.second->get_position()(0), seg.second->get_position()(1)))); + } + + // Needed so that the ray casting will never go "out of bounds" + segments.push_back(Segment_2( + Point_2(-500.1, -500.2), Point_2(-500.3, 500.4))); + segments.push_back(Segment_2( + Point_2(-500.3, 500.4), Point_2(500.5, 500.6))); + segments.push_back(Segment_2( + Point_2(500.5, 500.6), Point_2(500.7, -500.8))); + segments.push_back(Segment_2( + Point_2(500.7, -500.8), Point_2(-500.1, -500.2))); + + // insert geometry into the arrangement + CGAL::insert(env, segments.begin(), segments.end()); + tev = std::make_shared(env); + } + + std::vector> get_topology_py() const { + std::vector> top_out(topology.begin(), topology.end()); + return top_out; + } + + VEV get_vertices_for_pose(const std::shared_ptr &pose, + const VEV &poly_bound) const { + return getVisPolyBounded(pose->x, pose->y, poly_bound); + } + +}; + + +std::vector> compute_hypothetical_observation( + const std::shared_ptr &world, + const std::shared_ptr &pose, + const std::vector> &observation); + + +class ProbVertexGraph { + public: + std::vector> vertices; + std::set> topology; + MapPairWall walls; + + std::vector> poses; + std::vector> odoms; + std::vector observations; + + double false_positive_rate = 0.200; + double false_negative_rate = 0.200; + + std::vector disallowed_topology_operations; + double TOPOLOGY_LOCK_LOG_THRESH = 1000; + + bool DO_SLAM = true; + bool DO_SAMPLE_TOPOLOGY = true; + + Eigen::Vector3d PRIOR_NOISE; + Eigen::Vector3d ODOMETRY_NOISE; + Eigen::Vector2d CLUSTERING_NOISE; + + ProbVertexGraph() {} + + std::vector> get_topology_py() const { + std::vector> top_out(topology.begin(), topology.end()); + return top_out; + } + + void set_topology_py(const std::vector> &top_in) { + topology.clear(); + for (auto &it : top_in) { + topology.insert(it); + } + } + + void add_observation_pose(RealObservation n_observation, + std::shared_ptr n_pose, + int association_window = -1) { + for (const auto &det: n_observation) { + det->update_props(*n_pose); + } + + associate_detections(n_observation, n_pose, + association_window); + + poses.push_back(n_pose); + observations.push_back(n_observation); + + // Add the wall observations + int num_dets = n_observation.size(); + for (int rind = 0; rind < num_dets; ++rind) { + auto det_R = n_observation[rind]; + for (int shift = 1; shift < num_dets; ++shift) { + int lind = (rind + shift) % num_dets; + auto det_L = n_observation[lind]; + add_wall_detection(det_L, det_R, shift-1); + } + } + } + + void add_observation_odom(RealObservation n_observation, + std::shared_ptr n_odom, + int association_window = -1) { + // Compute odometry via the previous pose to match robot_id's + int pose_rid_int = -1; + for (int ii = 0; ii < poses.size(); ++ii) { + if (poses[ii]->robot_id == n_odom->robot_id) { + pose_rid_int = ii; + } + } + std::shared_ptr n_pose = std::make_shared( + (*n_odom) * (*poses[pose_rid_int])); + odoms.push_back(n_odom); + add_observation_pose(n_observation, n_pose, association_window); + } + + void add_wall_detection( + const std::shared_ptr &det_L, + const std::shared_ptr &det_R, + int num_false_positives) { + double dtheta = fmod( + det_L->angle_rad - det_R->angle_rad + 2*M_PI, 2*M_PI); + + if (dtheta >= M_PI) { + return; + } + + auto vert_L = det_L->get_associated_vertex(); + auto vert_R = det_R->get_associated_vertex(); + + std::pair key = get_wall_dict_key(vert_L->id, vert_R->id); + auto it = walls.find(key); + std::shared_ptr wall; + if (it != walls.end()) { + // Get the wall from the map + wall = it->second; + } else { + // Create a new wall and add it to the list + wall = std::make_shared(vert_L, vert_R); + walls[key] = wall; + } + + double fp_factor = dipow(false_positive_rate, + num_false_positives); + wall->add_detection(det_L, det_R, fp_factor); + } + + void associate_detections(const RealObservation &n_observation, + const std::shared_ptr &n_pose, + int association_window) { + std::vector> all_vertices; + const int num_observations(observations.size()); + if (association_window <= 0) { + all_vertices = vertices; + } else { // Limit by robot_id + // Get all observations for a particular ID + std::vector rid_observations; + for (int ii = 0; ii < poses.size(); ++ii) { + if (poses[ii]->robot_id == n_pose->robot_id) { + rid_observations.push_back(observations[ii]); + } + } + + // Now find the vertices associated with those observations + int num_rid_observations = rid_observations.size(); + std::set vert_ids; + for (int ii = std::max(num_rid_observations - association_window, 0); + ii < num_rid_observations; + ii++) { + for (const auto &det: rid_observations[ii]) { + vert_ids.insert(det->associated_vertex_ptr->id); + } + } + + for (auto &vert : vertices) { + if (vert_ids.find(vert->id) != vert_ids.end()) { + all_vertices.push_back(vert); + } + } + } + + const int num_verts(all_vertices.size()); + const int num_dets(n_observation.size()); + + // Build the cost matrix + std::vector> cost_mat; + for (int dind = 0; dind < num_dets; ++dind) { + auto det = n_observation[dind]; + Eigen::Matrix2d det_inv_cov = (det->cov).inverse(); + std::vector cost_mat_row(num_dets + num_verts, 1.0); + for (int vind = 0; vind < num_verts; ++vind) { + auto vert = all_vertices[vind]; + Eigen::Vector2d dpos = vert->get_position() - det->position; + cost_mat_row[vind] = sqrt( dpos.dot( det_inv_cov * dpos )); + } + cost_mat.push_back(cost_mat_row); + } + vector assignment; + + HungarianAlgorithm HungAlgo; + double cost = HungAlgo.Solve(cost_mat, assignment); + + for (int dind = 0; dind < num_dets; ++dind) { + int vind = assignment[dind]; + const auto &det = n_observation[dind]; + + if (vind >= num_verts) { + std::shared_ptr new_vert = std::make_shared( + det->position, det->cov, *n_pose); + det->add_association(new_vert); + vertices.push_back(new_vert); + topology.insert({new_vert->id}); + } else { + auto vert = all_vertices[vind]; + vert->add_detection( + det->position, det->cov, *n_pose); + det->add_association(vert); + } + } + + } + + std::shared_ptr get_proposed_world_py( + const std::vector> &world_topology_vec) { + std::set> world_topology_set; + for (auto &it : world_topology_vec) { + world_topology_set.insert(it); + } + return get_proposed_world(world_topology_set); + } + + std::shared_ptr get_proposed_world( + const std::set> &world_topology) { + // Get the active verts + std::set active_vert_ids; + for (const auto &vert : vertices) { + if (vert->is_active && vert->num_detections > 2) { + active_vert_ids.insert(vert->id); + } + } + + // Get the "active clusters" + std::set> active_clusters; + for (const auto &cluster : world_topology) { + if (does_cluster_overlap(cluster, active_vert_ids)) { + active_clusters.insert(cluster); + } + } + + // Build the remapping objects + auto vertex_remapping = get_vertex_remapping(vertices, world_topology); + auto remapped_wall_dict = get_remapped_wall_dict( + walls, active_clusters, vertex_remapping); + + // Get the world data + std::vector cluster_verts; + std::set cluster_vert_ids; + std::vector> wall_verts; + for (const std::vector &cluster : active_clusters) { + auto vert = vertex_remapping[cluster[0]]; + cluster_verts.push_back(vert); + cluster_vert_ids.insert(vert->id); + } + for (const auto &it : remapped_wall_dict) { + const auto &vid_pair = it.first; + const auto &wall = it.second; + if (vid_pair.first != vid_pair.second && + wall->is_active && + cluster_vert_ids.find(vid_pair.first) != cluster_vert_ids.end() && + cluster_vert_ids.find(vid_pair.second) != cluster_vert_ids.end()) { + wall_verts.push_back(std::make_pair( + wall->left_vertex_ptr, wall->right_vertex_ptr)); + } + } + + return std::make_shared( + wall_verts, + cluster_verts, + world_topology, + vertex_remapping, + remapped_wall_dict); + } + + std::shared_ptr get_state(double log_prob) { + return std::make_shared( + vertices, topology, log_prob, poses); + } + + void set_state(const std::shared_ptr state) { + topology = state->topology; + + for (const auto &vert : vertices) { + auto it = state->vertex_info_map.find(vert->id); + if (it != state->vertex_info_map.end()) { + auto vert_info = it->second; + vert->is_active = vert_info->is_active; + vert->is_locked = vert_info->is_locked; + vert->set_position(vert_info->position); + } + } + + const int num_poses(poses.size()); + for (int ii=0; ii < num_poses; ++ii) { + auto pose = poses[ii]; + auto observation = observations[ii]; + auto it = state->pose_info_map.find(pose->index); + if (it != state->pose_info_map.end()) { + auto pose_info = it->second; + pose->x = pose_info[0]; + pose->y = pose_info[1]; + pose->yaw = pose_info[2]; + } + + for (const auto &det : observation) { + det->update_props(*pose); + } + } + + } + + void perform_slam_update(); + + double compute_world_log_prob( + const std::shared_ptr &world, + const std::vector &pose_obs_pairs) const; + + double compute_world_log_prob_full( + const std::shared_ptr &world) const; +}; + +double compute_observation_log_likelihood( + const std::shared_ptr &world, + const std::shared_ptr &pose, + const std::vector> observation, + const std::map, NoisyVertexPtr> vertex_positions_memo, + double log_fp_rate, double log_fn_rate); diff --git a/modules/vertexnav_accel/tests/test_gapnav_accel.py b/modules/vertexnav_accel/tests/test_gapnav_accel.py new file mode 100644 index 0000000..1774a8d --- /dev/null +++ b/modules/vertexnav_accel/tests/test_gapnav_accel.py @@ -0,0 +1,64 @@ +import vertexnav_accel +import math +import numpy as np +import random + + +def test_vertexnav_accel_instantiation_succeeds(): + obs = [] + for ii in range(1000): + label = np.random.rand(4) + label /= label.sum() + ndt = vertexnav_accel.NoisyDetectionType(label) + nvd = vertexnav_accel.NoisyVertexDetection(angle_rad=2 * math.pi * + random.random(), + range=10 * random.random(), + detection_type=ndt, + cov_rt=np.random.rand(2, 2)) + + obs.append(nvd) + + +def test_vertexnav_accel_get_vis_poly_succeeds(): + ll = [0.0, 0, 4, 0, 4, 0, 4, 4, 4, 4, 0, 4, 0, 4, 0, 0] + ll = [float(e) for e in ll] + s1 = [0.0, 0.0, 4.0, 0.0] + s2 = [4.0, 0.0, 4.0, 4.0] + s3 = [4.0, 4.0, 0.0, 4.0] + s4 = [0.0, 4.0, 0.0, 0.0] + s5 = [1.0, 1.0, 3.0, math.pi] + s6 = [3.0, 1.0, 1.0, math.pi] + segs = [s1, s2, s3, s4, s5, s6] + + p1 = [0.0, 0.0] + p2 = [4.0, 0.0] + p3 = [4.0, 4.0] + p4 = [0.0, 4.0] + p5 = [1.0, 1.0] + p6 = [3.0, math.pi] + p7 = [1.0, math.pi] + p8 = [3.0, 1.0] + points = [p1, p2, p3, p4, p5, p6, p7, p8] + + for _ in range(1000): + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + fw = vertexnav_accel.FastWorld(segs, points) + print(fw.getVisPoly(0.5, 2)) + print(fw.getVisPoly(0.5, 2)) + print(fw.getVisPoly(0.5, 2)) + print(fw.getVisPoly(0.5, 2)) + print(fw.getVisPoly(0.5, 2)) + print(fw.getVisPoly(0.5, 2)) diff --git a/resources/images/RAIL-group-logo-flat.jpg b/resources/images/RAIL-group-logo-flat.jpg new file mode 100644 index 0000000000000000000000000000000000000000..802d1b23585c937ee640ae4a37be44471f1b47c7 GIT binary patch literal 55489 zcmbTe2|Seh`#*f!QY4i@8iP(>zZdI&s+d#8Js_2J4Lsj5ZsbI^=uI;8?)X zfOVeeWC%>F{qMB951l?@0#6znuHR(1VdF}pO(w`J>se;hfrF6hwllW+;hCu~87uK(YMo(?#D=osy^ zWF5aJ-+(@0^uIrGN_TLurO|)zB@6%L=E}**%E~Fo%g>oRUt#`yMFmAgr3H%@DlJ&FKv8j_+QLOD7*$o( z`O4}`)G$jHV^lHdBvLZ)jI7)|Ik|ZlB}FC7|K~69OJvbp>AiEzWTaLh(u<^I7DSy zepMi5L*(^)bG3Iqex*vO8(D4adFsME1vT|0OPA^B>f!Kf2pczT-m=wX*KU%9rIodf zvy1Bykob zelH6?{~y=22-YPnD=Q-_kFHBf`Ye3QERvPeGMcm4oGgDRP-WGI$hnxE*Y7=kHBZ}^ zGNS5vs!l;|HK9Xi6kVERW&iIMcH#fm%Ko#k|E{YAnJ*&+nWQ4mQ7$C8fakd~qy0S{q}M zZ2iKEJnw6DZ5MVCyc3cm=GQUtI4SdPhTKw?4AVGuoXkY1#?~Z+NH|LP!mHgD$C+^s zvcWAWN+;aK`z&Gcx)Zk$ShYq$wpL0@J0q_o+9>H@kfP2DKI~g%Hwj7H`R;X08>y^A zanSn4*k6TT%qx7w?1gSyGKih;(u++3e>!-=JY@l8icmTkHF>R+<-OUyWmV zb~A9SL$*viUhR7Mwxngg9F`2BD5DaCJkPGy3*F`<-JM7vo6YgjO(Zx;F>RV=1jd|oK679=r=~#10Ksr6!I_sa6o$>32rAWvijaX}Qk={P_gS8Z5XGb(l*!xT z>|2(D6!(!9e)Az)AVA<2g=qLedFm(>X?Sd_LmXk#bAB6Y~tD zK@uDqxQKUhLL3+2lC8}YnI?5j2@&c93fU|=qZ;Fk45M;lw1m6BXSwyeuUk~l%~{K zhORa8!6Z39s`7?8*7@$0<78B?^LbPTQnwC6CdoV_lQ0)LNEj#e1r13cA^Oo6P?rb{ zZ`r(z8p2$69`Hp9gggmm#ei^-mayCuY&?>jq{$>LLd3jEEy6|MrW!)HEA;hYrCcUq zlIG&)v3TB*bM18uv@)$uXRvq_6&Y(AUv32^skl!`_7R(5BRhxbYp?6G+6Hg0BdvgA zN2n!$ps+?s7=%(sLVz@26q|v-_d!e%`aveGpHJaYYSCRs^*^0}z_0bIP2jUL8~vGq z09!EZ9N0_?;u-{BmXPGSQY|?l$yv&`>>AnSvR8ISmVze&zfc+xcJj4A+da|@kVGFj z4kn46oos;1z_6JML54t(xJf`S_d=wLmQNoEq<0zaz8MfHtrOsl^N+A*xqG3 zeT^%npDja;bIcfM$u2WF9em~#>zc%7D-$k(wTvRv+xYItUg(_=MUsuyF~CSB#(1LE zB!g3pV3N2_QXsbQ?F?JVK;Y&02(o1;9`*q>Og=y>kSQHYCOM%>vtcI~j_!yRcu+S? zt)eX~`=CZ2SWB`?1odPF3uGj;&g}k9Plme_p0t6)$-oqt8HR#%WJvQE4%`AOISe}? zIopo>25xcdR^myzzP=KB1F~srcMWABP_xWOE+ZY|Iv2-I8~_`MW0{kHcu=1I`He~k zhzaYQ(;OX)CfBV-^W`!yOwn@~`1z>R%gupxf|0dz1JwX?jaeqEmBC_yIYHO01)`C; zGMxZ6I61Kiq=MHC3T2>?BWGX~4HAiRh;<0m6(QT&b68$EzD2-yc5*^;CKkuYk;*kG< z!^{2E2F{xq@>KJ%(l*SXI;mw%TC3Y^S$v^kHv82F_hDNX(U%hTHIMu}HSC6UbuN{^ zX6hyzC)lq}yR#Y{3k~zI$7$5H>ZBKS%&f_V2~6p~zq*>Xl&}+r-VTs%9Z)wWxy*V> z9>nZjcjdHqj3%rb#=o>kIi{_d0K;Jxomx zjW5*8Q&X)AAb97bj8A0DhKBMUJ-m{n;v#BGYs*aeAsS(S*n0iUHD*SDoV4XxFYcm1FuPtqpruU-7oOG1De%a(n`FNfi6}_ z2&kVeOPn<)zQ8@+{^mK;21cZ&kEIXw_2bZK>s*v(=phukkKR-^3@ByJyFW*0G!?Da z3eR1EmprllJ6nvv?Pz%?$629Oh}yz9qs`kBp?LdYgor*!OaQ7Nd`THd}wUd2*Gtxww6fC za`FN_^osljLoz(!3|l{h`8~xsLJ_4{2jPTP z12?H)Cx*fUg%38+SqHicK}0raH531}|GIRo9Og`>^du-Zm;zrsiLes2mJ7M$CWa4K z=}M;y3>(}+P~^ErsNJzeHQL%1OeN|9&~ONcs{aC#w2_jo54$8}qAVGdNHSy&gaB|4 z{Z2xjWw05tvfrHT@dO@DWdWG&q`BZZz)nEWL~dcgJK8||*|BwYa_NL5E)vX+OA2O5 zgMLP!)*u>}!H&EFL8t~kq95#iI!A3u2k5y5{*xRBa~tBvQ4UxRISi{FtpCp~lzQ_l zXN}5Ai~@Bn>Q2|L&$ND-vu3M_v*K;HW4liJe>I&G{wB1iia76W{=R{xzg?f*zPG4a z(W<(zRQ7DX;)~hF8EY{jE7;0kQBrz5Esd}0cm3|ZEzU{F1A@9v+Q?9V%3|X#edV$` zF~Yx3hM^6khQbABu>84VMBo}8RoC{g>iWd(v{W&I4n9b)JaQ;)W}GfslO{$MG>z(R z8NC}vAE+zk-xtbNYT%R~d=N~Fkr@Awo1z%~MPlT{RWVZOMEu5VTm3bvOMgY^6$>%a znLEBL)(K0!J^hRREk#qOO4I0(7mKJ+C({rw=raiIID5y&Ey|O1zWxj6VWn%BC$G{!S-+W`N#ZuF*ql{y==?-=2O9PumflcVx{L6tgu@8VJ z`M(EiqJt$&W~Qzl>e{CA&wlVEV}rzq_Ki!#fjX2qLV5NT`KHY9b10Ly+rT~58-I$C zLUf`WOM!}G#Vs*%{auw9kyt{!(x94i5!_pS-XJ33zJS-Wvd1bEbEE zZqum|#3gS5PQZ&m+&09L4`cV;p6&y3t4H;)qf}rqI@pQ+?RL2KP?!JO+0TVyM4fi; z^jY>B(Ah#rO+~58$pay- z8pUA^uO73WdIGaNY3{v>*(cwm^GPrWFZJT5h+_6D3uHmI3ufS#8*W zoteP%N89a)-Dgm>{Vi+M8b((l*J=-NX^w zVU;tZ1*pM6WtP~{+@`B1|9Wy|sPL*ph?iCZ+n$~;H6CNpUm1qkwpXcXi@v0Zkt>;L ze4XLTPe9}=|78WxaBwpJ@$`rG5!?2~qw&i>CAM#ps2#mLKg>a@=IY>%Qi(Chue*afD`b{h_^{vX$Q_zayVE{0(7t#K zrWI{MC5-}1%ij(=r@0omjiohTS}^WHVaIqDn5gTwSk5q?Vw@lB8_vM=ZnP1 z#kO+Ow8OANr51P}paNLzh^}Rmpl$PGc@4P~`lw49`YJI}JB+Hw@0nlYQIaM5VLQB7 zc{+8iqp%2guWkkW73tNOZu;+LU|=&ECy6G?0+^)YMc3;lqT^#!8_d9X(fFYGABGS8 zXXerllA5yLEcWg$(L8#mgJ|<(!CIhL!eTLU8N^z<7}z2)9l7HkjJ1-vi5;Ib^{NDM zO<4XM)VJVa>Vv2?-u7wHf7tO9EX5GbYYY}2)p<;eycs%Z`CDRaN=NLlDqaR%{wrn_ zHxXwyhF>A`uE-ahkN*g^LY)y*b(J6p72ZI_AeqS5B{Dp>(w6T%Dtdu3Gr!IR|4Fhd zH%ph5dVQsTJA1)%RCV(C(cJyZGYUe!T~0r;cFCphcVZtBmyMjx=asgO&?_Sb#E6kU zT_`s&wom?p|5AP9`>}T#KjX4InI`qmn~sJqPLB0V$ljF=UR}`v({eIX0*)MnWZxd? z$Ky#(iZ<{`&}yJ4kX;~MHMecb-pON_J7j8+3|0~V5lM!0b|oY>gg{%n>kzv5T{Mus zMyZu%$YB%?8elvlE6G}taD}95hPewFK*I0z0|F8zL>_=&a3Bu_Kn9`%PX$QskPLQm zPOF4xkF@`4lvx*+#bHUDydp zk90z89rK`p1|G+fV>7nZOHz`5LzoB!IgFDur1D!brOen2FH8`cjU5W~^_4S;ct(lC zv7FS=_-b(56-Z*%8llnHdUZlkCT}uxTU<4+n~4V!HrSls;Be{grNbWQXN0Rk5W*2t zd1YFm1AVk#(E4Jwv(%dYEe*sjdP&I?SdU&;_WBC?99px>`OPHEjiVO~RJ*ZDAaLFx z|E+lP_K_Ul=9cK{ar-T5&k>URil5p!H9tH~6Hk;X7kx#C_*~rX~+*e=*IaO*>}f=y$jCPsA%86_JYfYd-H1Bg-7o-@Qbn>iwoQSbm*k z=zbVFYD?P$CIqM!MOV{Avsch4g;=;bTHaAYRRd6^$=gvmL2Z9`UJC}tx2BZE`#0qoR&2|;_wi`Gw7= z_ko?tp?4I$_`k7)?wT*i;t|}cvnIPo3Ii7OSDbsX3mh*83#$yQi3$E6r2J;~wQAL| zKw;4f{nqlo|Ji16yh_y__AD_{wk@}({`7CIl=l~ik))ZOC@o(^YVxp=74%Xpzm|T2 zu7EO|MjWn$O-FZz_M41?u>is5&Cy`1SN+V7KTro|wsho68wNK0?^j|Z5|xqvZY18n zdzgPBU|u2&pZr&ZoaiTL3P0qnB;*ebfJ@xP6p|sln&n4%#C|N`QNv+34dIfgRQE5FAM^^uz}WDW$*CEbC}n4Ts)# ztg;wZ9*_~q{lgEvizCVc?UpKuu&x*dvYUYH7V7j%(U(+AjiyH9%vm3h5U>n1g)UTd z|5eHD=VBWD>G<&w3`)oMk!l?F@hftmPVJTcd?!~I5q7vrL;xg4Vk`dHrvJ`- zTy^YE;jY643@LjN(}pIKFr6-M;&uX9{KpR-2xS}hh5+3LzW%G@yi~jAIk7GiAym^^3_iHdU3s{<#Oxs z%q;as+YJuixpUg`$r-3UxUPu#NG$C9$(Kp9r+yK|i#AT*f1yI-q!rdx4T^fSu`S7B zPji)V7hlVjSx*4p6r#S#uU^?svZ15}%TPqU^!&8l62elXg z8vrv$KZ|o%YB!<6;}nhIwggiarZYXbNktHz08)`HPl>dG&;*J(5Wd)|#nzFWqN@#b zA;g}Q=zOR0Zl1&P@6%a6EqTu2KeOQQV!;B zFUtaJBTu+psXA8mz=UCAY*xumBoqNql1RAC0_fz@wOZ*!Yo-luwUR74LkmnDDTh(9 z@>wkhXg%FV=Z|`UN<1@!>Nvf6?!}iVo zVFc0pa5;T)K5=GaZZ~1OTRpun{b-fxa!n?L({)#A>#KOr`orv|9?{D$oAz&BX3k?& zOvrt$Twc8?`O5s0es;Xm>?_D%-QOuBHL0_dOAtn}U#{yv(C`lTNZEj4SMS4qxn%|U zIU(r`T>ptb>+GX@H{wkHX6GQ1K0L=f5k%UC3^mNj>}DX6%N9XqF+VfDT3eebD_Q*X zO)6r^pI~j=6k973MM>_yh5Kl~{+XbbdMkt->3(LA@{{n+m?7OY<$1N?124+V{p9w# zk`$6u;H%!R_E5zc=4;!-iP8x(A(-}Lhe zuPHnIK4re%R#3R9igeN4Rj^}BZcIhA8{c^RXs-r_d?2O@yG7LQb@ru9>xtYGj?c=) z$klLvJ>60pdO+Fx5t+zWjd^3^EfdrC@A~6^p6z%#ov0AJ(YNt>?_~&XU!qb4^&7K$ zb5C+I8Nrewg%Jpn*?@~oG?auQFqAIBg*$61pzM$YRfQ~t;|4|xIG8plMF0R=1ogf8 z9BzRp6tyti+USokm)*`f9s?f%X#a(q)Ab9X8lq$bbw(&&LG9_DoL(pu|EJBiIt!nL zT#6@(CPLlvcV$8&d!ZB5NS&lC0g1F&l);)vR~_rQkKx{i%G?ECV-m8?2MRe*{&&!k|c?D*%UrzB+^Yz|&}Af%la&KmbIQpqNZl^9Nj{ zngCRV3fdVE5-N^!A7MG+1MLpk;5gC|3Mad-DY!cWoC~^XAOkomr54BXiZ-gj4Ax`s zWg6?Es-q`R8S(n&cPF?w4Yn=6`gwba{&>7-9^ab3f;CwJaL~@Y`TAl+fo52Zb)b-E zcwNk+s7{4q`FVnkRoKsYHA3#jG1>6O3HhOZdS}51*z9b7$Q8ST721 z8BVp50CiRc+++r8XRS}QY%QR`fCL-p`habPat=cAPL9Ay;h>-hTwB=(sf~e-&OfC^ ziWA}k7D)=~>adI6V0UmFC~TpHILNwSUt1V*CjqDC&c)*@VZ<3Q);bt2RA)hu%F+`# z)@0lImWZusi_*RpoCgms+k+kT2uX>bKK)zNODpbF`1eA>tGAUnlFGkDug{>(sO-7M zzvd#EFT{QaD3qj;%jI|VU|UD9d?!SVG*H`#Q}3I*|2o+?<2)OF%@jFzcTfBD4v>B7 z>vMPc$4d^g@7hy?Jwvrf7*~W#q11zIhfW5@$xH^71qeJv;!!yF&2X?T9H9aS;5FVa z0%*3i+sW&OD%(zQ7gQf}2eb%hU_g-Mx2VY5Lit}|%|+mlbc6=9e`F%~Q0NC(3^iDm zbQB3wp^<}Q--;lUbc_@&{Uq`R_S_)}nmq79)@|rMLF!otNdBT|YZ8cf&Pn#~Qk$8g zl|5Rh#2Z`qs8(it#N(=^)xeXmBh+D+oTMkfPXN=?i`Prpf=Gh|SW;z|2p~80S%T^i z*E@lMcyJ{mQ42Ic#ta1kNZoz^gj!@II0w&L7m^w7uJdsiO0D{Q=ZFkUzt16uOkO=y z+CU7*wou@P{q$(qdse~gbXGl$L)dnEb9;EH738t>U%N_&W=_z*xlR|Ko2m@IPJcxt ze!rA2q&os`>w0UC2vhnnd*(zerOs}o<_a;uIc<4}SM%(~((yz2H@ot)i2-DY-|{ah z(+8Wd(+iv5kB$#WB>WSxqk_qh>STPF*i`_U3%R)*2-fc!JSG^V5AV}wZT1jK?m#5! zl9@Q@Q7O(bq13L-;AF7mDs|T3ShAHEHuO=TH>G1Kyt6Fnq|^W63V4aUg3KCO_^_lI zN*Lrc%JpA#d-$j!@mG&Jc0@P-PM8(_bmMq{KqXydBY&Ab@R2B- zmunSfwMLB036K9pG|y%;22Hn2zn`2vUixHudC+s$!lmOKko1*qbju4*7PUhVcwM*K_ZPC0oI{;+BAlZ)B|osEQtf#4 zyBSc_@3WJ`P!yoKz}Fb+%Pf#{Xd!|9z_EDC4oAZ)&27;>6cG7L=?Ma;K7y8p&|WAE zQfh^D_6A2*H-3bYdGpd!)kFi!AHPoJH zI|!m62gc?%c2kXR`e}4M3S?elfdMk-W}c3Q&k~UKWDw^>0+h^n^=4TLUQ)JZD2fET z=d?AwKy@cZ!J{FG`x33gt3{GfMTK8qqlz0D$BwkMJ4C`1-;a>Pbzg(N2I}FvN~X8< zc9|_zPXl=emz)+OT6+?Z_dbA0*9g88|A>}|JpFr&VZnHp7}3n#kSD;?50J;dg6WmN zgj)4G{MK^K($CdmBwZ=2g|3Os}43!6UQ1gQ#z{Hbh{@%Z%^r|>k0bumRI(Tnm!N6=u^x4Bip^m>flZ(uM43G z$hT#i6*bIn@9;I{MHTP6`Az-xrhu<}lk+803*&{UY~m9!^7>epXkp(Ngmvoyy$;TL za{a>qY1^Xn_jZtQ&m5^YN{5X+-5m!yZnOTrWV=7QgMC|J{Y+G~?G@6Rw<+5x zjaEOSzV$Hf9@zNtuK z|K5bQF3)BC1jA_TVu4%w{{FuWFRe4=&PGu271voO=Pi}GrP*j>Fo-vG{qSCKP3ona zCplNXxxM!JWHfU8m1dex48Xm4{xz3OO-8z}>)y)`IniVP^omsXQA^jiFJ~W|t3R2r zezMNn!ADj0)Z#yKk{XsA(txx=!eRL!T>?{B?JM@#E}N*Ou)_4;1K>cvtAL!(^SZDol++&|p;qL-)F;uK8i z8d2%eHmZtxXf(W?26ZBV6#rw|nC_PqGw!`LLElEKjv(Vs%!J=j7Rfv?pjNc4qJNiWvDv@la);mIU}vF+theO z?)F_B16Ot1L#}*Cu=;dj>&xlAGs_&5l-#atcw)=Ev|)dq&6Wor|9pN0a-3`9tb2JY zJ-Df%Gfm!)PuA|<=eW|!n^iRlsW8pmS(6eEqxX10mueKhVGUYurYRXVPl zr!~4VN3e8;_(nK~&Co}~62sP^GEvPSvG{&#-(aCFq5 zE&wObPJSRC%)SNulCsG>L^yG_!RO4ESC4gyuk}7znsM z8qnAWT6V}xn+z>z5`>lmGMd=p(2N>-3($8$9DydcD+g@t%*|PK(C7(H)6&#eZYleP zN-ea18AGp=#2Ev*|LHd{&{+bu7O?g7VjT=p9ApK(m(q}0BM6V@&4B(yrn#+|JQXak zv()))XiSo>gU||c^$T~+UQ&1qNCt>TpHI5#PBrLSkd8ECLudn&+es%g@Db1$N10@K zGN{lU`5MAfOu;TGTV5myS%R7bYMjHRG`mC&a=7h$2Q7m(;#f1SRsL^E8#*rNl*B8g zzjnn4>Glwt?1_C{IFcm{wyZx*CTW+O>I;hjQJhzEDL!EEHCW}$l0&h9Lo_E*+ePK& z{G)NiC;P>S#j@#e(>eNanS+wFc1;|vQs!sfzSL}pk`NuOK3m34ob;u1QFc?|Ag?u? z7~&NxMlt~EW2gQVY&c<0O?%>2Jvvq{Q`!QhfjUQ5<;%*0PsaZo$9PB8k{RRiOocUD z_2Sg^S7*nXoK4LUrFRG0X0YORPEvhA^@7=Qlgg&s*)N-#lRr|dS|3kn zvL@!-vv@P$eq8g8-YF`Tv=vj_w;W;wv$>9{J4FYsKhFJlQa`Qv;fw6$si97UgVeq; z{*?+f=J`j4foDzjzuvL$mXu&%f>=hC)l?lRxsl$w?$g@i>5=qrYv#~33r1*zk>AQY z^J6#N{7ZM>z^YBfUa?Ru4VLeQy_CwYy)*gnoxW{q_@;B_3Jd&|t28xfY9W?xyyZyS z{_Qqay`QEXzn%0yk^FRf`Pd$x!`x>HOI>)oTowVLN(fh9ddl>_YU#tNI+;#|4EpgMkvF7^d2 zFFZ>0esKRcTJ)2upYHVU7Wo$^zRC@!e_gaZX3IqW-*j(lZ7yG@vsUtI zrQ+~(g`GPec5Aso8%_4rAAdis-+riAk%6QzeqmeK+XZ^pW@tO<<60h%C!f=&hq1y* z{dYvarH9fw2>nl9e=uCRa*k}Oy&FZH$o4KRMs0UJ&h7Z5n|zOVsn6El zPthoNm_J3om+v9GI4VXIl|A~>28V^&1>a3Z#E4}8Cv<8MH;;e$VQTy5_F1yO4Slhy zV~1_+>^TfSNCru&z$iRem!>(L4ykw5KkY4tzBHC+4RA4!Obh4ME6VGdbHcNeBDf zDn|73t6lSXHLc(1uT9_3`|-!2cfqZj*<}1>e0{0ngpS8QCff?No0X6_EQA(vD23MX zP~;AxKMHC{5h{R=t}8K=$qeXxg1|e)Mv1bppL*P2J>-nRU;-ihrXFUPkga*iIde|} zR>*xxb?2Q)-)LqMX>H3qj3OmY@PTL9nNZGf*tafn=A;0`2No5l1FFP}R0J>)>Y0$} z!HEH|mJGbH9pv5V`;JO@@dYl1+%XZ%OD;ko2oU^Cq;|B3vnJ=$&^*+n(V{ z1P%@sp!PZv+BwlCU1(*4VA@M9Invf;JsWyraVS<`gl^&nhol+6A@AMZ9Mv=DcYvKi zFN>wo3eoh@t^3DtyXp*tGqQpu{1rQfvmii;bS;kcrz_CWdZ`62eVVe}xU;6U(Q35n zQcAO(Hq@93!pgDcG^g;k`<7S3Hhhg^LeR1bHQYDeI-fa*=9Nk0o#PzU>;0EW&;v`+ zOyVw+J?gh>%6>f0@pHP!b~sv$40JjQF%!3Q=(!tnW{scL#ET&8$iGYIrW#^4;86>j&!dADe>e~S^}Be3;w`CgyL zX_4-^CG_Y}HKp=YfJC<$YW->2sOGcrc1wUy+QKl~j?24S_7wc#=Q47E@+Lg{l=2S` z=uV58%!;Z|AL$J@u;L1LQWm#~h{;P+W*;bj@tVf^OfJknbBI7IJdsOFW$L$ez9Ekwhy zj|KZT^0ME{$s|^WE^^P&ewl9?8n;_1o2uCOXkTQ5?5ZCfKOY;b?wMJfH| z^TS`^tu4_}wqj)Q>!+fZSFOJ-xfvc_5^x);m2M5iJ`UX{3`nLuHMD}MOQwzYdRqql zZx-Ch(cGse^1A`G^=+8l$25x<9d1>2j83xQyR(2E)1yZ@taT>Q~rGIIDdJEHW#7NdB;_duc zPrZ%RZb9ja4bOWXuXrrz$FDYcwRNW6JmXPBtjbMJGPM=#Cg%jqS8`a=pr!1WGW2EZWTpz6C zTY4rWqiz5VQX%lvLamb>1%gePY<46Zs9CcWd;q5OOyr%yKc_F}q9{305Z|T)T8oD0 z`FFNkigI#$hxvNu0G>lDP`c<&Cy_t4=h{~}$8R-tBFkO_jCWjPOIYAo+R!gY0Zx8g z)KCchkGW&}Lh^a}t=}MhCcYIThivK43$^iP&Vw~4LbuRjx~%}?-lusD#VELFy9u0Q z;4v3MdB{b}7X>}ofVpHt&oAH(fB>3gOQUrqBi|r<&VAGqNLqfAT<4-VBhypEETdX= zrv}p<&fVApDicxXqHBW2_VWO`L5o~?B_la`IGE*Zwgsa39sQS4ghT=$N=a~+rIiqS zqY*x|;@|bjl&%F#+;Y1kK!%Kwk1uQB6c_aAGO5RxvgFCu7Cva3O*Mi`=jh;A5*!UG zYq3s}Ll-`9mPAG^j{7gb21p>lUy`bl9YSH4SDK)QOW?p1nv_J~!A%3kPJ!Iv89T1w zC8RF^BBPijE=$VFga;k~6{B;t;1Xn@3)*Zh_<>szFt`OU7CUd!@B#@=E+BSR8Df9U zZYGYb5qvG4Et5p9~O;2v`Kl=_6oWeSEq9fkWtG}z|I-lP!LwhKtm2W z+E46n?W2}Hu_R&zM(~CoV7CqTQR8Pa!7-$z#g~8&c=!u&_^jMZy#XEJF@5tm(y^ym zZW&>pN9BjsC=1rvhoxq{`EBkwp_W5yiJiX&y0%tbhZI0Nf0KiLb?V>*gh~qISQ5rX z=~~AgJeM zh2%T_z0;Ld6z61l|JlZw+yK3lfaPN34|AdZUr}}GHB|=MtIV59HVJdN!S&&|lq7e> zfh}34gY$NY5f)=sx5PvE*YOMfrc2WhLUO%jT6zwM`2Bu?UYd1_&vb{0!cETZC~3}$ zW|SguW8ui1s&CPp?2a;bj5tXy^8+P|3@E+C!DdByIVV&1J0 zocq-JHduGZB3rNVoIsBwv(_PzFNh;CE>`V_Taq4s%6d4j4GIDMi}=mQ?%t@mTQL4J zOqt$kTTSfLC}b>s@4?}h9{pL<9YDMrp6biINPU>%drn6FLbuNCC7KG4Wa%b?=c5{r zjMS=Dl}ree1x{hkBW^p-9`t^!Iid}@vDy#XYMCLQKE@^U1; z;%boN?$2|d8Sg}1{%Y@DGIJCgeSSJs|3`kSOu4R-*Y4))3*O(NHtms#cyp>~<`VIS zKly-rN5+tL&zp}VD-+icdk6jK)CP^(eh94A!nq_CQfJPN&`#k5hU;{aG$&f@dCy8! z&QGwie}-QaeSqvV3?$nF?Bl(H(3sF)!=C|!tBi#_^(0-mq_KZXx5TnTDG0Uf^p-2} z7u~kg-+#w`Xnt+Pm?ciKxA4u+0=oAU+8Uc*FJkuO7S%=f+bC(^H1Pg+CS?2IBoJa` z(;v&u5Pz*|N)oMJlU8=~ z-sDJDc|}g@?M&y+rPnQUeuwdHR~&}b2K1Ux=M&GYQ9V~FZ;FThuz_CzLNMq<9%1p` z@nwcKICe%a8V~LyL&yt}W!yMImH_Wi)<&)OB|u+fw#F|SgX(ALw>w=TeZW^{f_@i- z$}3_PF;Up1MiRltbMBz^phx^`uK(79Y^~AK=T=es>i7ty;rp%ebIzegQo)DuMcwxa67og=iqFCujc$FC28G9=^hK=N)CD zC8hcx8zty5fJ2bvRo%%cP!W!ykeTx`FVBbKcY-98Hdmb`8bcd6%fX^&t!O<;(lXfcL;iC&!5Q9fvAz_l{yF)!ELM^T#$ulyJMNyDL3v^Ix zgX5em>9}z?Zv}X^Ss9#00i=crrOG-Bd<2vQ&;zUxsAqYn*h0^M72Y=j&dNcRi}a7V z2C{i*6_zSzfJi4%oTJyHrLo5OR2)VMPIf`80>vsgvzN}aq2(D}woAMRr#7}=ULS4~ zj?yxSBaUt1^5cEyCDyyG82TNdDK`xydwO89uhgK?(Q8?IS=vM+)}F_}^-)5OR;Cp` zuDSYxu!GP9cJornq4-FegQ)Ep^cQrMAJ%lZb*gl-u1JiS-WXdP>ZW7=`8P~X<|SYM z15xw$y-ns)5)F_9uexE<1kBdX~~=WG-h zDNJ9Pe1FpO(;jyCX)J4En;w6rt zXx*nyGlu-ZIdZ{d>eEwRM|^NoI?xM5Z^e2jo$n}~x1<}lx;SaU?K3T<*LF=e*OTuh zkjzZIx2TRZL+AIx_{CxSM`hnslm`$$vEP1MyX&ZC#Rd8@UM|;h6Qesj9@qG7@%~4X z`78*rh?pTwoslp37Zg0oGN9EAi{<|aaUDE&FCcI~y+bE z)qB`&xrbKUtc_cf{^)yWYT0{YYre6NE!Ya)O1&)4g&mMub^QC$df(~NQC?%;-9P%A z{5CD}d#b+2`D*Q#-E~_g51NaD+Zr3=(;Pnbbn{khbXapd$mZtGreSX1B^~bFZvpoo zV|n)+NPi4zHtGeAJK=InP_R=PZ48zTnvdUD$xj)M&pVTN8h*MZnjpzp290AU56Xxz zwCKlTWINQkEjEUx`oE`pYnsjpaiZ5lw|L!E4^ETBs^|V|)gyyOE{)6_cu61aqAjtc z9ThcLVdhgV{A@?*7!-6zg&Dx1)eVHh*zR6mB^GvlPgF;vZ@On}(u+n>|iCDd=G z9|Cu;uI`SVP!c08S3F3lv6t9&Ju#xA3`ymqv!VtnFRdclnNJxvZCl~ox#ha!z0A|9 zt9Nb4YI+`j_Z;@FCOD((xo%aCPwl}YG1awM9D@e?}jsD7){|(MJL!_zy2#|Hh)~{zpHNRE} zzdC$@P>j|^W4@<>j1-n1=ObTVH69luiOt<*!Dw{8mliz}&tXwIAMYUO0Gy5ccIo1yglWhb0?#V5dwU%ruD!&G;FKSlh&FUVfR9EL2n(X10h(LT zMtrp-CmiM_Jkb45kDR1|455;(9pJz}*$UqvIjfCUMkArVTfYQ+Apq}?sl@ojIo!}A zli%`geMmw3#Q_><{Q>r_Ytd-q(*@0M zC$oPXr4_^kJ^1_i-iGgtuHa&~p#@~+rQe(U`HTT-k*)uhBhQ$-3RXqiKF6BL>y}*Q z%g?SH@X#%N+9WuBY{nt(qP6B-LzOR6(^VsekH62lzD_wb#40Fi3$LKh%j6B7coC3Y z=9%!zIN;#J^!4m)c8(JEA7_M+zs0D+?RG$DcNFP5-cDe6i8o(tBQfw|3XD z&4Y#=%p-tH=RNT7sgMSRxNAqH$ueN&HJx_l~>7F?*U!k__j{LEvCmFr;mOWpHH-ZN@6ub*zuBd#j zp%kQ9ap3k$RJvcFzX|DvV6Eoz?8S!<)n0P49Ls&toD}|E1fasjly6xv8Qve70t*sn z|2XDKAN^X;Kb>#CEu$tiSJV1gnyRS2WW@o+&KqAwAATxWLKzHVk&7!r%`+i^x6nZ-3K99eM5M`FEkIy@Qcb5FrbkPB+wn^n~ z|E?u5x<&mzPag_}zkq>p+bW5(e#; z%xnYi0}gy$xR$@DCBSjk2StEXBu?h*3PytR#Hbi~fsZOMZ8r_054#19)p(7iRj%OY zx@{TwW3%XzUjn0c)bHY`_ak}4;{)-R)`N+EG6)k0Wvy#9dI@kc8OM(Or(q5L(8~fY z6yE1S^JIpk^JYJE-u%bO2s;m@hFAS=ym?_Q%85R&fp(j186Cb{JlKf^{O5n<5Ikrr z`ls_|Te#Fii=f=r$e~}w;l~ZBLS12rrC=}QzK8Y)e4m)+77wIm_GDe;)3PTxm8;_L zjhFi_GmIoa8T2}t10+I{e&i`ReQmHLQwzm9=9zWhMB9b97Xa-sf_6KAhq&zfotRqO z0L128ZoRFG6&J0*LW^=WrUJ^h;AR@UuaTJ<(%nhRY#e*+cJ<+nZG00jx7mrs>ou5o zZc(Nc_b4IB`5CyZZg58#5DtUSK^w#fXVHeA1ZZD{za4^B2jCBTSg2yi9!3oyQgBxM zpL5~}tIh(qY~83#4Mqh}wowT1z33W|!z z6Sz`<{sVYrBe!1dCME)Uu%(mZc}WWBSurz6oABjKFMx&2p=MEs&NhKIBSM8B7Cf7m zS}d7~kHsgPCO{!T397fk86m_;7s5eq#mJ-(5cR6uu?thf&Ao84PGv-DWY>;rLHmrV z^QW?Z>bFTrl!nx$qeqAOr$2h18iY)Qh<#z$DqKZ_8o*5eNOI7ug803Jzh6`W z%3tT`rc_Iep223E_P($sL$wdP<)jCmzv!FcvVoh+N(wtt3@j;WnnymoOg@Gqr=COP zj?l~33D$yvGlWR0WWT__;cX@60i)YL=f}}Wcm5tn!R64Ca0;=IU*9}=kWamc+^n$WCxwlVdCC#%R4 z`;lRzY@@K|>(hpfWdlKf6kZIjJVQ-NS><&naIeRl+U2jY3&(e8xrMwaVd!E9e=aYz ztEb-7?CGs}**>3MrZtjMZsO~>&gIFzBeco(o`A-yXIP>(tM%o>{Mfk^?uR$4NoS#x$F>1TEp}{M$*;JJ-1Eb7T0r11*=nFpt03IgV|9SH(?BkEc!poysgX?}cQwoxmN*+851hkDg+f{s)a`y5M zFE78spK;1vaS_`|Bl#6-{11;_P2Lg){a<9g30RDM)IUB65gBc09aP#RsVr?%XqR@S zmC}xsqIE{nzNti#hE_>U(W+%=wWYljS|-}JX`O0j{LdZF`~KeRe_aok$4r@K?)!Vr z`D}*=O$)-r1PE5i;}U;ZHu<{CaU2=TI>X1@diSW?!V~NEU#%sd=?b<>4--E!2bzX6 zlDIE?Y1y^p9OClxrQAp+_Xod8P->_%b3B3@3>E2KVPzIkvqpC-dGbKM!RN_r{x$%X zLU3O)7>C_MG%sHtSmQH$!8$+C8-<OsYLt#WOjj}jHKAlSw_rqLY z&OJaj0XJE)_+0cSg2jxA_Y}_Cr&6dP<%2Tr`*Hm2(90cWH1pe3qPe?eZ!C7u@r9J{ zymAV5TTVWgQRmZ52pyoNAtqYV}nPfIil+~beRN(<}4@XAM(_W;b0}bCuGp#T6HXRY`T5`Kaev$gQkgX zZDgV8U3;@wXEyR~(l&FT?6dvgR+*I&H;<<4{J@0JdIcs^{?>?GB(W%KYauW`kiS$2 zZ0kdyasMXs82lw#8@Nna-vbbpeLzM>Tn5BRw=HC}`=F0cc+jS{pG}dgkLe`Pr`7r8X#pe` zDBMC;uNg#?T#qy4IHaVG$9B#f=zI*d#tMunsRk~0Dl#)CffLZM0n9SrN(Q1~UL2;f)7b)gUa4i}eOq+j-{5OeixClk1S;ad%^e5#zFhX(m!kj0Mn3 zV^p>_)cIfIsyrtUO(tMVO@Aesy(Ca%4py%(tzn_U)8P^pMANb7u#}0Mq7Zi=$H2al z>ztkmgaO{&4m)&w?t^l1Hx@LV0?L~qZZuetrc=36(Tm~r7$-L7e?WO{*;R$Yv!F3Zm= zU{=e!PtWqDek8&r)k0!~$5!=PX5G;7)XQu!3K7#0FZOq6nvN&y@+GGQa-K_Qv*I~x zr}|s=YrA<+E>-yjRHN#(9~;=atcRitMeCwDGt1^msPkBAU=2;f|Eu zp&9-`Z7ax=vF0>=u)~+1;(p@>OPgg*kKmHYL}lN(?gHK;g5)lYYYz|Q=KC@mg*m;M zr%t!!^T~0?(MK+*-)5dERS51Nt*FP<~Kx$*}fg+ZCE0Ccv-fD@CQd;l_ETf~Gu;tk0@# zddBCszE-@Kc{AvIw$6E3)qQ?b-=%&PEG(a#8(m&$d}5isxhdQ7^X;_nMTPh=&3U36 zd?~&P|jv3y*{{6Zir61lBW3ISr_AFrX`LAzO0)x!~$6abZ}l+ZbxPJPe-Kzqr608(=8P{I0Kuv8hxtsP^1aZdbJF zE4S5g`o!Jwt_=B96+xPzFdVpS`RM#SdR}WceYnM5 z98fYLm-9@kjR8b#U~Z^>L~N6I&3J)i{XihD^H2+1yi1?;Tm{G8oWdI@LvxZQdH)uxm|3YDd%-q6CT4DVeEt?2? z*I>-@SRmRjo>GKQwifE+ebR zRs%$L8xp1yIp08l*P2oiR)3c`=LAi#&?3jfzZz3O!fwtn#bxKY)6z)Cxy;5jr>F4b zcZJwRt}<)}U|>rHu20gk(L=aQfcLqBV1z5rlta=T!C46YCUbF*Y0wL)Z5V&Jz<-h= zmgB+VDw87ilKXCu`qtzS@E%?g5fIDZ;@|=K6{_pd0kB(vst0ila2#=Fk$d2noQ!bP zr-cpGq5VT1r|Y(uBC z6Omal!>a)fS{0a@jiLgsE*YqCzc{N&YL7kQucd3XZT6dJXp^j>?U@Ve@Z{!Q(%o1y?%2LaA@h`j7VjrLN&$-Xljv zac&5J*~>6efD51@+N@)stNG=%Omy3LsXscBc+A?g^pTDSa1QIXgxDx{ z(A1qOG9s3(Pv;1FZH}41C$DTGX%t_x>#%K?l9%LpNd7t_k|J)FA-OYhCQHS^(bxQ~ zRl=wx_KRb6x`j`iMpcJ&I;VxThFv`RIk9CHLsgl4hdWGaD+rRh4z~qiIC?&x8jUMi z6S84hzd%#wZ3%l$kVI=B2{iep2BS&Rp#TC{KP`*SSdfuY_i-2RX z6b*~U}w2A30(5TV4kL0csGvG)qHZJf<|>(DHG6ar3;xFH>~pKzN(&Q|Q)i-KyE z?<@=Ql;}Xco2Ea;>b!xb5aTNO>Ua0nGowfu)$Lk<==vFKJyad{hO{vyK(7==v`1W# zC3~vEfS8E8y=GRxsKw74de5!{K{BnL??Tfu#fC_qnL%w)5L)kQ%0E%+GKU@z?XJ{E zXbKexluw>H^Rwz?{P4&NqAQ8~1z&6SYM6m{gljqUzae1)ypP(gT(?0%BmiduN~{4G z&j)}jZ;gEbpMby_%W@IN-&8c)hTdPh$iY3_X7Du$*D zM7;;RKbu_tpAiAh*2=h8m7DaMV>qTOySDy4ntSqb3Ah2wyy_~z84>xU;kup?@|+tC z2YJC%%nO>KYK~o@vRZL@*0gryrdmT?IC7o>A-ykqKXUpMCuhhNv)0iXu?G6$h7|0g&{Nr{Rc8 zMTWfD?qO}ntv>e<(q0caKRfdRiGDTWMCgZv)?72dyob~v8Z+YvZP z7WhO`Xsn9uR3nYn@dwpSOtu@3{FPg&OvB8Pbs+Zl@3;U68_F?Ql^m?f(??i)xYXdn zXnu^vD9KEFASd#dPVkY)yW*OyfW-i=I|revL0SsM8dOCi4-8`;q*n`#w7?zdqJ*y< z?x9SwFv4{flEx(4NG>vE!zaR7s#yM@_G{YQc#5csmXB_ziuw|{DxP%;gkH~gJ#>$f zvZlK%MSa-g7YOfx^oW#v?DeZB(#{FfK45>^6R3Mj0#+nuj7^ke$a#b?LFINObyxGi z1n*;DMdZIS)I%|H9XfK+%II$HUY1V!asIBr(~WFKjpX(bnZuloZ69LV9z?TiXSo`< z@jB!$!H;p1@mKHlO@d$rK0g-b6X4ZAx)2pgni{bH491O|SyoI?4F1Hqs2E0;9C41_C3!dV>XhFDQEyKVQ}%evPsO`s$H`e-Tp#p=3k zS0oeW*}r0c(A~z**kTynw+YVF%y?!%FZu%5G4*et*mZg1I9oD_a=tzk!55keNxcAM zOf%%*n$jvcvKG>YUFsz@zTQ1(+;Bti*DZPM(812{1sS*S)0Oy`0~En*6tiLFaL(*^ znwzX#jM`a?fk^KML8Y!epM&08KH5ij`wlR39B2Q;3C7{V>gu$y@WB)rrL5)o!C}$Z z^csBkUawusd2sPvUhi{Gx~yjb({dJpAf+Fm4y zdob5)zHks)>na&Z(lAHcNVcl@5>j5(SiQ=;bXSdAqMH!&YHQN4vS+i#o*k=X=5Jc6 zuj+|18GV^E1q#td!0yHaTZ%}Rk^oprrA;V0R$kob^oK`n^S71HfXm^FD0UM~%p-2` z_C9z!5cHmAxGk?wvwe9f7jI3C8= z|I^)*E*~I-E3CHYoy3ndlo>v?E09u;Ntc$do&-4NAAJ))@pG#&MwgC zilH*I(u1~Z$m*(Zg8!8{cgDZHz1{RLey<(f-lqCWWa}e{S_=pAVZ-Kiiop2YF>7s5@PKD@2)`J7*y-mgA`o0(d1Vn5KI(NAp z@hB7n8pmn@c@NzDPbJQm@IMt}KD0u2z{SD%g^j>6Q@+^(UjN)|lx?i;F9EU6(DD&r z{QSQ<)MhSd=rtQagFvLk*6=9DrVJn;61x{M2W+$Ys{#Q~HU9q%{bKrkUJwpHGi;Ak zXk}6x*VWQQG)#X`FXf?sA7$*F4WWQJh66vA^Qu{&ZrJRCYd(d+C`rey{>N{tGWL$) z;@1FBd;kP@8wEWr6-Tw|1J40K2V>!r&50#``qN@EltgIMOObjZ;``c*sNnym7wPN+ zxeWW?C~g)ySQv2T+K6RQ)4{S9zvsD{HG8<&FqVwQenk~Asx>{)L)^ca!~WU=KS7Mv zMtJrcKPW$&G>4yZA_qSUupwwA=-qcMZP{nse|EKJkb)-*mDQIq70n>Iko=W)02WuRzMuRWX{9teqFHS}ts zzPheCA-PD9Uu{~KY80l@hpHCM9+SjuNSX>MGZ}MlTABh37g26x_ddJ9W=fPL3*+Le z?W?B=!?xFUNe&VF#6Q#QDLl#nADS4abtD5sMbOa;OZ>(Q=ZqT^%Jp5Ya`DP)y0Xg3 z8?HYTpjgLE`FdVsDD-LmK`G~77s9T5ouxl4pEkh#u1RXgeJn5=9*Jb}DraHPP9>JMku_p5J}d@Fkg1nZxz;0GEm=vW-Ni=ri!fKe zb8qJA*_Il);83X?iDAWPHAfm6Hn(;P*b9yu%)5}T>Kj^>g=4hS#@mar#L3#v3;_Um- zqURo+JfPqn_O@@pK+%rI@l%~A`lcJ7$iLPqOmvZb#GB@3N^2!U#D0aapQ*W@46 zwLQf-lmjLVu4;5yhze>ag|043$-2-t(Vq$^(kt2!C2$_S*KL2{W}B9HcsiR?%<02{ zLpH%=?6)%Vbs|~7*dW-fbvSfl=3+*yZp7^^PQuLLlvLhlSUc%R)tj%z&Ww9V|3UE; zIO#oIob=4&$1mSILk+?7vEzNr?Ej#4o}uVs=6PG;LZXpq*Y7jxZMonakbRC>cSpW1 zcllh;q-0T3jE3|q`fJ?uHd2)&5mU6cLAJ-dl{9zImT>|;Y4|Ss{B8>DaAJVio$^*W z5&f#5X}>gC*&<8#UgAulJluVC>;cBg-Z5y#AJk{KI3||DrtB%_KdBD%_3aE^&sWNT z#R};{QS1XCkj?>VlX3%gjBLcFfk~xV8iCZrksupL$B|3U;y2z`JfWr=EB*ks<#hdR zD3G`rWE%*gCuRkxt@!RE1epU@pQflzLdJb#W(kC~U!ifX$KAzPjwAHUP&K5sBlHZT zi6+Ltj;>w(gBk#6?4Km~9MDFh_W~@}{j|`r0dm!i$@-&`_>h1Gc47|6{U}RJ)iHhJ zY&dh|7j{}pCV&fj4#LHbwYN(hkrYB)N;)VD$a-}}wRDEsxwg|&JXKVv_Lv3AA^dDd zr&0au+zUKgOL03c_EFu2F=5{Rc`v4~9(da4;&5`?&a21p91`hEs*F9jFr(O|CVcI{ zoVhT*RxbyR8odw++NC+eCYnj#ZR}!qwV?Bgihpm*8x=!(7XH`k$$k>daEQlGRDKLA zxMYcDrzTaG^a%~u zh64t5TkjlG;d7lHB1AEGNNk0gFHS=v{rU?x>9pJ8w4d3C$k%(LhGo^IHxkt)%3F%I zl1@wEq^U>yYAx&E`q?i&m0Q>3^d;9elO1{~?8mr;f~`bLxUX2zA4Xs>Rf;nUakRTjYx1^f zfQn2@DM?ZusdY;qNiXRb_EqY2IJrIf8}n+s?KN~1ZpSb~B2Y1n;ZyKQN^IimPCL&B zSKkWUSt5qwo$ug>JgCtpY>#8+cT; zY+Y#jj8u=bHx5CLr}KZ9sn4;tchnMiimh#yCnWV$uqU+-H!;cbF|DPPV||&a!c~vg zSahm-4wClJ_TfhyJ2bmJv{a<2QkDdc@qrbp+4E+>(Uy7rqIv1*O*biF^@OFL_(hAJ zZNZUKHOD3%g8h;}W;@;JRq-a}hW$g?q#N8Cn!l}l{$2_Oa4E1}d6sl?F=r*~g+lD! z`oW03%95ZQwmk)=zU$cEQE-G`v)whx%jz1>FF@?%T}LnbQF=mYvU722?MupjjqPiF zCpgX=etz+$5PRx6?^t@flZs@2mcx&g!wcG0kEtbt4U^<+C+1R(@U`FPoZR7ahnH<8 z=bwfZt`uw`}l>2RsQ5bXJxI(iXz%&Sib641@3D?JGL1<1rUI=-2WIzVzK5KFU2}TkI4^ zlPBwkzBV8C`vVKK}67%r1#iU8+{-WZF zqWO%3TYV?ojic#I`TOa=J)LN$q=lwaWH#Q2_kU2b$5Zgrb0~6#3d66u0;IMOha(O$x}d4nIzbd;{ME2}`kc5h`1@z>oDx)@AUU z6@s`>sGVju{8V9Bn-peH8h2i+Pm9kpY=J+XV8w287BVW_`<=4Fq72P;b+U?kToky= zY7ERtSR`n954`xbo_*((EeAf&b?pRWd%Gr0v|j|XIJ%c{uWR8^1Qv!@J~*VuF%(;$ zNB?EAbz?XLYzOrbqofFcsFnILD!1s>d$A~60{ zsO6F%AbwLXJ$Y9%S0BPhrO0Z-9zH}ZA;6{>e#<#KSXcGckqvjvVJV*M<*a5{y!O>a zT+;&80`5h#G_M`n>H;qy6A%&7{ZD0u=@ecNs2AFef>c2d0eI#naM^4WR^Xy!LN>)h zIte@_BOmeiL)v+Ju$H*%{eMOqgn2>`P@tFq*Sv4kA-)SyXG7E)LP>3?AvV}72qu)) zfszWlql%Gw29gkP<8bp=OXx(NfAH=TQbra3sT}qPsv~+hoQDngZ!!kv^#7n%52F5{ zIu^fy)C^SE@_$v>DexxhZ==3hUicB^5cf6MM>JmfIYrzh(F=y(D5k`HmENOZmR~&Ad4n!k~^^i-o_3 z{|e4dysgwA?uy4Nocxi`{iYCJrv&@UNqRBcIdFi!A`F>4>*aWnKK1p-Q2}wrHP1aM zUx|eNvA5Co6>ert^Z9Oim#=#sHElAvd>6~g&nx=>+YoJ^DBNwd1!Ek|TA+RX%EXJxJzpLRxP(-^l(C-W+4}S_ zm1k@AyO)Qo`q3V`v2O9z6uyf;xZWQuE&kqodg|rz#21@xoQb-~I=FbMVUJ@>Wk{`dsm=7MnTW=LAO%k5Yv1TkY%GkvhoK*}eSK zJJ2V~@?1^Kqg*#9=7okm4%+j1Z?rzK7)QD!3ogar{aT-&Txqs@Pu`K2OMBw)d;Q8N zdws~a;cteQHLSi1Jfvu-6&$g)weCOd?3ajkyNIoQy7f)L^*U#ZG`JkowHe%239{aH zu`P0rh1W_x9@{h0?`Ec)6aAd7?yBjv&*=B1mkp1YazclLP1{ww#N-d<{=iKc&8}n{ z=pBd~Xt6jkl97H#xL=JNCo5O$VLI~U(pTqApLJ&q9|tMB5jwp)OGQV1-FkH@z)bd} zdE4XUL5b)@s;Rltt$l*4Su6r>e7bY9ao%Saq?82m_4itnKdEk8{xDMTUZ`2PCKaUJ-Ro-=vFCmAtLj>3;o#wp``dll7LXgE*h`FYS7o7p_J?+*e)qOSw$6 z&X+EE?CZ0Z?NOXO3s>DEZuUQFZty6zIZ*XBKBOdd#eb{08jmMS?xwQm6;$7%?^ zSNG2HO#g&5+sMOB;$kx{5!K`8?)6}DC+9C79Zc?apSn>nYR^Xb!v@`zP%ZBsy?z{m6k)4kAAP( zY~4{3^|5Qm_@f%j=vR4He`__~yf5~~q0Hgdb*a!p3L%$v2f zU?Y{(!MjL8afrIK&O=ZypkmGHQ_pUon3=;(3=x5vrj4>eh`@H8$Pe5Lr_uy)dO>7; z{i3FS9-dvqxea&|$g#gwBOHT5^FO`t0}Tn!S9d|x!1ZTfQPAz)Hr-Gzv@gkjHX|zs z?0rYq_Jd=#NZBAgQfvnb1Yn?};DTgV2zG|a3{GNj>jZ5Pc=43AWR)w(06-Dl3<;=;au0xa(j112Lr^vxkDeD}*J2eL6D#1n zwDBB-S^Q_&;c5e!G@R{F2HK$b!o%aLTR_UT@dV`6Bb9;~3BW>7OE}|C8Ze!Q&|SbJ z&%u~gT>JpIH1GXcTssZVgEo%)%!ZC`tJJ1QWL2r!MljZ27oYaLZf-Mb5 z>|;h^wXUIdqcZ@SvymH;YW#5=%Wz>0kfdF!?-A9)ZN_%++J9IE&J~%?%8FwC$>hes zuT!gXlwPe*yHLX;nBs8L$7X7J$GqH6YU%AB59B z+jM_1iwi`d8G$Dr@f<3@W;CPwnILsSM(R#Ru6*~Tdnrpn)bho-t2T1fmMp0+r`;@3 zEA!%GI`-}iCA0aw$jU-%^;0TgHH;R_Ye&dWDFtLRdMcw+-sOSz9>UR|+=UY-q&4tX zbCP2}&zQE+L@x6USoe2LFKGwz;Mb@SiGYb$wj0h2CD zu4kp5XjGByQo327|I)Qb>gG-HLHtg)UK1}37wCE$42YFPLBmvWCiHWrB(Y$ z9acJ%^V9mo&k#|*Cu52X?l=nHATg97Wbxs8K1YX9UqI!$_l|>Uy^OhK`8nM4E7yfS z2^2t-)NWkK((S3I6k8(-F2;AL+Rv=K%PY$)bmY8^51LuD!Z;{xFf!S6G~l(y($TM} zzJtpuj+8&BV0kpkCv;Y`)8O!2YF@#uPhm4}*LmmZz6+ku{Cj?4OICt2NOK{N!iA!D z&GavMa1(ZZv;w#$*j_&M=+}d*6_Blm5v417?bK zf+!zztkx-XVy(U3r14jZgVC{LCl6J`-NnyqRbc?Hu7s90mUZ>^a{L2miOD^nGf2a% z9gxg6`W5N4BTm^x+V;!(b|t;%TJN{!f4?`+ z>_v&5Th5c_8eKzD=fj5M-aTgQ`|>t6b-v%3^LU$ZYIUVx8a+^CI=zyGfT!pp>V zy8qcX6paYqZ0lz!U+0B5gU2)t7bk5Wli1~Qt4_U~u(+DDQhJ-il2ma)k}iIJyYkLl z6L$^Isp}=vI((MS{l263)w#5eSx3BMrV!uOY{q@E5WO=cRie*f@%|MxRDIV42Q*vm zWQoa~7K1{QtR>k=Z>}R_BW_zX*Rn*ZmvQVD5^7GA$eCjz>8$IMHDeNodhV7;`82+< zs@=naMe0 z!klgjR(Jb-6+dM<@UN$-tym0^t`fGX^ZQ{V4jR1HYW(EM(m(hb^WiA%W#)s7uhIDu zrUIuh`zDA_C@FN?*2`xyUH+gd4cEih(97yLeb?Z0uBZ zwP`2KaIV`I_6PjHe>Wv|US{1QWH-FoUa)J`d+;0~(uS|ecG}XN&Reo}ziJS3hL-m- z_Dd6{80R#yr$$Zok_V&)u}qmiuaVywJ*-bCd)vcAjFziYx8cuLi4$ysma@e#Ze7Pcy=JuF6*Kb>k<`l$t zX?8FwMFI|AIegwN-TRclE8pVW_47GnUfmX$NGTrS&^pty%b$|8%~%$eh-}n~b!nHC z3$hb9bkJ3z&{oZkM=B;6x!dX8ivlW1^IdV#B?Q#u?uj)4TB(`gQDI4e1oX_?#Y=%~ zfva;-WMxu={w5d3{vf3Yhpmd?vV@Us25x?j(<`rwNI+2Ief)0cODcP-+HBr-P}hrL_*M97u@W$4A-EaGJEcWlH= zq*+SM!?SekVk|1#$FZee@KlYzJDamv%IC%#)0-}H(nn7kQd90d`8L&S^+wkkKB+A@ zVRO|EYpTZJejcn-%Bf`hJJSeSh^PLDnqr-t{^k$2syxLn7%A@dXf~lD6!>yoMZQguyAI^7c#0KoX-Z2Y{nTm?5#W5>(YM&MTndp*> zqC?mzpd)NUj>||TMc;l~iuKR6dgk)9avEE!9O8RoN@_6tYJg~-Pnvnq+nUtxXMcG` zC=5^3kB&(KsqT!A=)s_?#N8aSbuM+w+YMSt_ut(z6uBnLdB^|KaLVLe!#G)`DbtIm z*2M%$D~CzDeC%$zzjS-JM>hBUUCR&->8_jc)Xo&!a5*$j--lA(kk}#?Z4U801}Yh4 z!?uJDosLS`B1ij#FP_>O?I9?aN=Vu?cO&{1v zySBI9mU-NQw*B{$7jF*RE__wJ^_H=dEdal6Ff_`io7hA`4-6}8r=zJ@s$YYV%tl!Jv54bh=0`w|_K9IAR zw^)hV`D@oZ&hDpDj|)zmH(pp7-W809mg{YIf7{Z_`?D(k#Xcs?r~!5>_bJeA@Sdw^X~nb`&~6RGb6+1*`9xZik$f(Bx=HY0z|xZi>~We7)(3sHXTbKg ziSxiFIsWutRjb3qS&N#jlmn}s{>TFdTHeJl3t^PsLBLzfMPq90ThhDLw2SN3C=$EZ z6bef=V?POyO@djNc5TWErf-&^qaNyqcTk7WXJI1xJ}vZ3Zsi`nAx$({<+?g9DS+p$ z?A()DOr?!iC2nBxi`hsShz5qo0@-j$H0Yrd^ap86j8A0%D%%xjR32}{Z}%feFxp<` zQsU~FRGGb$v6GQzPl-B<(tSrqK@3D12!lNlO*R45TO5>o(=dZJ!7mz})88o60^YJ& z9_%mL{YdxjStE?8u(yTR^0J`8Ub-qq`vF+;&}?}4jQZAuAjl%z`uJeGp}OLod$84;ZLhFZ+Zu2!AZd1d`VO|l ztM3&?BnvlyKrsaL2fh*|wHcBVk8B#1^D}ac(>byQf(S)Cc)`lTh3vou&pZqicb=s{ zvMbYhh*}9jKpt2Gu>o2^$RhFtSYxdLGPP)s9}B1-MPQrc9niPmc(z4A4Axz2fwkih zt5UtO;QF0~_wiIQScMCk1;f*^Aa4Vv23G!RAzlB*N?&JGj(4VjGmt*WhymW0t?*4C zNEBgF9tEA-`2^V?0SaS~!h?4g0d^3$2PDQrwiyH@=k}oH-<;c*{U83zw0&Txfq*@A z%L{N{Z6}7B6CRAeLM^I*(wH4O`F9AP0(T7r@B98iCA;zCzn=kt+yC*rEX7Z3R|Ucd zm3jTagvPk)zLeSHvs02iq|5tSX&OEJamg;_nCK|NFUb$`ZH!njJS|IqQ*|P@d3Iq3cvT_m!W{Jk1GZKvhAL_8r~_R;U&t~@Z`%ctZfEI=?5JXS5p>j*%xkL zc_;g4PNn~d-pAfuPTZ~cb{x-p%i*+PP1rd8J$hA$v2zw;0P}G8>15(VtPA$huynXg z<4(-lL4~!9!7y3^hQ%Y=<-+hE)PcxVzU8#8p)zU@S?)Gd(z6fPrCNo_+&Q79^Ig9e zXkRzEpw3unR34wKK_4uUm*#lS@3d?C;;VrzVoOd(Lor%1^7~XSX(}s=@!NqUPdr7kpQ`Ly?M4&qDuInrmAtSCAjRP7?YxHz5A%S^yk+*!Gehu+;=J zln2JGp6Z`ZYpP(p=Pak}jk^5fmVEIpvmdhPNt^fUHm8ND`ke6zDG$#2I|yUCt8Oks zoT7-JRfxeU}d_x*Vv)B+rixCJAzQQcO zB0bIRDTQODW*e`ZHFN@krcrWXZMc5V7~e|pLcXNro3Nej73c_2L2ZG_iGgnlGn#W| z5&N&MYU2t>#`{|4xhXb9M3EomY)Jx>i|A#wIqreGHJs`y&v#hbOmy&dN2-OI?BBfk z)~W`cH^nfZ33o7kS?cyN(p5K;Ydh-pV&~hgi$({sK4;vmxfE{J2D*SFuV9XS%EP}} zbVlUY3l_a8?o&&(oL~(78hJc2h1l5=duw`0zJC6}}nn^@veCf+g@2(3k z^E3wzJ&)TSz)m%P{jFFp>s#$JK1VbEia7mbZ^u)orew!$w@s|2j~B|84JuEz;{<41 zsSy$|vq8gT!#= zg(&AI6b_NA6{!}F8;pCK9-1(m>I(3;XRYv&8pr8wg_qag4%19iiQN_KlXcHm+^2%~ z=?5u@GxKGYi!vC6jHHo)lBt<~m3BMPUwTs81V=8)+B{i55DzpQMr~=~2!8QqPXgoH z%~cG$*YNjs31GqE9SU;sY=Us}_45pe`+&qF|0eiZcU=Q+XcX(#Q)&F@Ic@*dvm>7+!No0~ab9}vxbC*SO5cI;hK)uF;3CP1icEEX|F}iPx^~XDfl}zN8CIwI7EI zm&+L!<=4(B5u)+TyY?{^jPElC~UMma?7{GT6ZGt`np$9Y4e``ivvQLVJoia zk%1(Wj9XP-{fw49T^3d5DaZ5n-lLtk{^AzTbt$=TT(^&Xiimr!i>WPAQM!Xe`{XFA zd_j7|1nMaHC{C1iVD2@yd&wk+>rLq!h4r5vW6a#wN8Xa+uEhnXi8t|->C<_W+#PSa zJFde=vsz6yTz@~AvOc@4j-l8oVOuCa@MELIpa3nL#}cuIbj4xEoRBJJ`UmE#(<^bB zW|kQhBm0TuMpzZ!gI(Sc2S<{&jnIDjPyev#TUhci49oxhEk<l(>S$u#T!t5)LXNWtir>U&QC>>@ z#7{Y<&p!8Y<9TB(R8bx9FZz>#q27qo1_L#uC#=Z=q3AI@%jw65h+gwAQx0@7Hq&|5 zfY-ZK&@rt4l;nP4$K2+-r>j>MbkZdB@Bp`!ez**p1-UcWxvQ!Tu;KZRVix-pQ1vx9PRXZ;rq_AH}4N?~o znF<>huX9kbfs1$q;!OLvyG>0F+DR^>4a@YoAQyNXr2|jB5(3};_HM`}%w__@3;s25 zA;Yd3Syk9yBiqc=0GMy)EV$J=Lla<6A8V(fx+iZ4k{|I8nKnQ+?Cn%+YlpZc0DO@} zLhVLmq^bP7atyjjRwT2p_#OP|5+wF*O5O!*U=|l@25@39UH~O}3BJVxSTF^)w0*E$ zOtD1HIK)WI!a@g@Re{5L2^Ran0tk@7LZ*f)DhtdZ&`-m*E(rAKhxSwvtazvru4;+X zuBZHXouPlMl3euv=TO7<{Oun53CU)NHitSo7z8`XFe_b_-~MYJO<*BHt%@|g`k0d2 z5aA36ZervYxJ(xZrbqN?hZwvpP#Ycj@dMp0i^RtV2RAbL-~tTe0I99G&#O3tbI3Xb z1p9^7ktu?RUIa@|A+DC0ab#C@3$5LJ!SJOgYYZ*E1csBf%+0cGTYT!__rBT~xd3AMRq;KZl*Do9$Hm6FW6c!62 z@OCZtK1VxqCcuK`7Py#uTEy2?eI{%BiEnkhYIkr3Ih)Kz78o2;i%OQvTW>hG76$^OuV z;u%d3ruO6paO|V14MLqZ$ivh3NPb})VYK_T)Xnm_`UyNtynK^8=iwgh&okHB@@@vl zkqbgQ?Fu|Uo-%zTeS0XfD8BH=LZ)TjteyV;mgq~U*!UXUBNDp$H zcjbJcO`Li1B~5KSEmHXb>!`{mMq4h$-k_#k-cn00-<5r&j%%lm{$3s-rC);mp@8|u z-0*p5%WVC5DCV@k35r))(y(NMZy!#MGUsp4yLr|)n!M`JSx2Q)a6RwR1gl$% z*MmjFX9s04;-ukEhlU=J*^-I5 zV;$dCFyBNO8hGwCdIE;dme+@MgHpUFMw5OP$dOjTD$8Y7s0xIJK>Tp`#uG?xSJC&Z zmKg0}7+64~Sr2e?I$t}l| z^o#}UQSad|BxBf!!L^g-dJ5uAyr{JHss-EOW|h&%Md@#OLc?bCy8jm&T_)5IFl$mI z-=&a39jX%b;|$ef3N9Oby`xZuqI~^=1*=dF+?pCqo zxjmd~@=#6@6820iiSV|8(wPR3UO~x-`|2i_3`!!+?WIw)O-|Bzjz_g#gk2;%{3ai? zS(tH!TMN5&?RzqBlz7BGFGVhtevkZgjTpr-eo&c1&+=lbn#=C`8`5i^L#M(O6DM1D z=>;_8GP-OeD`OJczn?D@zA?^z3!_&b_r>fX^-)6~DQcF{`^xnMZ%EUAxvyG=V;Sjj zmxC@Ue3bSUkYqa*aQy?JsYberG8-k&c8e;Z@3lJLG1K@A^+Nd$%1p_{d?cabgtAzJ z`b8ekZ%r?$1ht}MN4_W2%QyT(Z=e^5q#8+Tt$Qd5O)xDCJ(0loMA0NB>=XOw*{kRk zZRQEd!947$K$Y}+(e(@8b8MHQY@HdM;)Hv~x0sC!TRNu2t>tR=c-obC^$=D$aUDkZ zhFA(S6YZ80W_gJ{9~0|@*-~}ZKQKj_zAx#~`gs}spp@}_80BZ9j2gRqY-}*&a89^C zxes}`>TQ~5uOD2ibD*w!$=yWFq2fxum94!p6CkJMEfs7I+^m4{VSIor84ZB=tdC$9 zZ<@t3zO_DP9QYHD;AoG_Ay`XD)A^*lKU1CO zMHv+7#|r~>*e!iNapcmV4A(jBBToXogpv#+A6f|>Q}80bj+?Tad;U@Mbh%xiJ1C~e zdB0;Mjmuk06s>id>&+e(h=l4rFD)Fq;pSG4EkV~mu{x}BP&_f3{tz0`G42P4GTtgo z7(F$4aBokNYU>6SrYn*A7r=WAIaJ1SHQ!Y8~!t6p#EYr1d@G zlCRP-_mUH!$K-1L#)0j{%5LTr>y8;-!pE9R%x(!g@Qa~tYzdfNcffztDr=%MAAp-Y zGvCRHFC!GzE_~>3ieIZ8 zc5|-4Z^sbaNhP>@0mgT%1EeVdXPt2I5V_20sPA|!dYvT^SC5lan0;U0@#|`H#?Oy# zp{Epg3EL>E*ui!mD(76hih$23IdHA%wUn+oo2$&717afYmf0lHR5l;!DJk;tc9nxZ z!FBV;g*v77cp3Q&@ZG}96w&gg^Cru^KJ(>$4A;68lN}#-DGv}wiNRUUw3ok=)-!&^ zvHL_*iOY*^*IFZ_icQv8cl&&LH#0ityAS`)Z44Vbfqp;BHCpl-avPE;#Hr6OK9dQ3 zf%5)|HU1IqM;<>(y9kHTRM)a*)AP!~fyj!cH3j@wr@W+j(Rrn+a9TfQ|7ue=Bo)QS z;x>;d;o(DDJ2g3I%W+(IxjArUT__jMH1snLzp9M~6!7fdkuLc&*6k}!XdDi_XC}65 z$1LW?RfdQj^nxdhBZpFz<;vl}ypl9DANc8O_LRAM2tPKw@d(Q>(juE-w$t`24C`(H zsw6p@CP?-VLXW(YGDoO|^YocDi4nz}CD2UV%PBWt5U))Z8MB{Y6# zv6K;FDh-ky^2SJ1QNw==2r%>G7*O23QV~`lz5ACiq}XoeLdgL$TUp9p>L%)#ysjsn zGDLSK#@c z2q&G^{(0Q9F=Qz^(*P)rBJ3xk!6{@!Aye&ejGnPb163VD0cbaYREX zB?XB`chV!(HeAJ9#K4PY1RKOQMQ(xJWD?>ECZQRL&$I7*sK%Zow!^xJ725sTbsS+M z(R6))w4tSgyK~PO#y~d1+x?2YCDoYmHe>v)SbF>rW-p`Pbz{GbT8FtkqmOqrR>oG3 z(H}$L_qi4*2ljPDxZcF=Y4S6Tfu?$ha8)}aY1N={6oIuxYzhf?WV}0JXVOL}?|yyS zVSxaAC%6^g+t|M7TWy6LWDRhw0xt0J5GxqiaZWee?ef%1`p3-Uub+<16xw={#zbsc^$zb$ zF#rFmy7E9M*Y-X35=o{)W$F}0CCO+JhB{--Ug=0_JGK@_r3D#L)MP1JrNvmLXmgyX zRH%g0IY$_xwAeb?vojcTe%CWP-}n9g==+YDci#7T?&p5)_kQl>x+I3~?OXbLe=pz3 zZA8T*;pCOk?j0@TGBm+$p-Y7@A9g%7dGx{dI_HgPh1S{dN_Kiocb}%Ga{Nrqy}RAB zt}U}{(8<3hntN#|^JdCQ6Zr=_{;<3gQfs61Qfq&|;S~QKASQ@Vx4 z=L?FPDJQ-v0e*Xk`C@s9vS35?`0|E-C}y+zE4ml267KDzyg7ka(T|p{E{zsWBI82# zl`lzSd8oKG>{L8v6aTs>C(-lV_`Cp@jw!z{s!X1kF7Ro2$~;#%r8;1IW$M8_lHNfj z^rp&*>1+kp)`GzwysbiG>u+_tU5?SV<1XIHGTsCbidYVDZv4qEd}y9cgqdfifuXZli# z?=+u#GU7nn|7cNGz3IRU~?q-m2Jv3iJ|*`+w0=| zKBY?u>U3i|4qNhze#L`0DJ2_f|MgUV{?r>w8&Zyh8yPsD_ij<~YGt1ti~Fcq59_;I z@=nF}?SFm9`rV0B+2~Tn& zoCI7(X2DN4we;TqC}20gp4PXnWGmE!L}?96cUVbpGMR{o{# zi!;~k4LQV|U)-C$_-%k7Ju135U>Ch(yV~NoWdd{{H@686L>}0J7s(ft2xK>z2$+8q z>9f5)Nw$Y zFki*J;X5lyN0li|amkyYzsfXMY^#iy!IaX!6SuKRJ|t2^?lHXE)Be1c_0b?yF7WFE zlO--2C)6fT9`z+$;B`&-fCTy!Cw{9FE#F+YuKhwhx?D|8&hMT3aztagz_RK3@@|D= z*1n6AR&_*u$@eHe3h?~;F`r>Cb*tlDy6+oQUJNL8fPZ5j;QI6x~ndvw4!WjNSf zcmxa}Y^4dAJA>OwbIu88HPe4@8vHYnInsV-;8x>I<-UrS;i=O5WRdAy7+lNgF9Z&S3Qf>`GQ988 zF(IwbOpexuy^!ww=vJ?Rf^VJ`@9)u+tA$#sI|C1U1dDKN=rz@7f zYrpm4J%TgE+m(1BmxSuHJ|7{eg}bvKT^o7XfBv0x;MkV1`r1`Dnwwb>^!T{0GK$ix zx{ijhBNljNoF25(?lIwIY!Mz?!e!e$vEAYq6?dfhSw#%nd+0-7%Bu|%j~zs2G0%nq zT@NFpWw)(Gj^i1dVEce#a`^AeDA65vBTlK`7W?@@XWi(cO+Ts@Vd-)R@MXR^u`wA^{!T>Fx?MqMl6;7oS zOaBatRROvzu3VM=9|w~}8K70E^~b)!J%0Xz#6fq8V10i=k#(?DmXAbQel#n?bZ|1}N{FgdbDb>6|4jB_5J(sa3&e%h(b+F{HzhehFhgsiBnVfi z(}7itPJ11e)O=ezY6m(P(OH3jYk0DbxB(+`H|LjjJ8IggSZZ#SefuWK5w1ES$iT^G zIZM1ua4{!PVIZXi^o*8I4Fa!|AT$zAe^%C9_g!lw4!9y=kAUl#ey^qR;ghTVhQ$cR z->Yzyk=QYw48v}FuUacoK;R>D%ooh+lMn(a!WfbIe0H;2!x#fVl!rYWM4vB1wJM6& z&{hv0ZWW2tN5huO{Oee1Ndh6wh#=$x1Y3r>n?sS0P&MYat*+ZKv(NrYv*J3*{+GL! zWVIEix^$T@>dR<1<9fBt346AOCtTnAwlM3K&2Pmko2{<)Af5Co%7hi%*LQ4~_FJFl zy;ZlGO!giRv3~dLp$hBkwr|>TmlxcszSz#`_mDf@>ej23I($!ksQah013z@myYW{6 z!Wn**|4{Z_nLW#HkJ-#M^ZxWQtvosWt0=EdJ!ju%<0qGWSf6iX4(Lrq^@)k0K^9B< zT(Aq}H^qVCTR(1$FNe*S)pLqf))U;j9NuXx;L`dYSsBYR0Yc;iD%syvDmu?CP$r&w6|M zsKKTs6&80RL#i5-cM8t6(3aZAmsc@zSJmD(vU&B@n%(###UycGD^q1#?%}Kt{R8F4 zqDF6zY+3QS)OnMFqW{AWPfctbH^p&G`vqE0LzIuN*(2I@6h~7^HhT8G8%e`rxbd}O zv_LpNRgw*Tk?ypE?;8dlO@}HPhC4;n)t z9QDX!3iT$R-_83LSG%iF+q5NTMAeYmamX*H%8he7@sXup-|FG%Mh|(0t>Mqip6s8Q zvu9Tb@1j!L<1b3Pm1=X0NxQ*N;dt=j<9AAw=d$+aJ-jmaVEl)mJ+#EYqp{=LQ==4J zin|tn8;*~ny@(vT;|iFuPhr|)b0WR4a_!Au;HZ|F-y3bercwG^Tae!wp&n0QP+VJY zf5~t5^^A8Vp$4a;DSuy1`77Sz2T>(^W|JVgMN|E-fp_xmx%*arJn`)BzstrgRfnf- zHeDEes88>esye@;Y1xsNhll5`aGHB#b(}4;*}u$Y;Nkw{Ql9;R*=4MG>!R{o^X-RU zFK=G*vheamys4H&vV(A;QAX2p-E${Rt>;ec-}|L3{*(PLCLldJV>$*H zt+a|%$T+fK*f3#lzy6r%S##j|@=&}8xn9Gjy0PfeTLHRnKlZzS{Hx?klIOB-Wm${+ z?SAaIbLbUc^#rgd6->6&{3%`g8s~Wy%tZvEj5+hTtZMhd z>j8>}Yi3{iX`yA>BPU_Ooxp&#M}p?PZ5#IpTzBF41JTs+Y}3?*mBHKh8J=I|WT<*& zv3Z-#m(_KWPb<*q`s=qVjRy`jZ0obgG&T>~|KkNW%h`V(@vpkNcDd!j@cJiq>xT2I zugiT9G6PgvQXagy&vaaJ^TD`#_WMsqQj~W4HN}m!EMYb-ArP_m^4q`p2QB&Y$Jl^A z*Ymj*6hUB%`&*9#_llHXnGV7YSMW8l?rf7V935>@wC^l2DowxhnR(?zkU@pc{MGu} zu?PJJ??;w`6e_Rcta|JR!>eEOfBu~_Ywqr|fj>-_8!&l&fA2pOqtaFa0BaBOMwHQKa&?u{qILQXP|zU`%*?%CB_7R9(8ylvTl&%o5v zK@WQxqf`WSk2=|T2Ws!6H*C$0OpEN^(j#|y`S}AMd55E~KXA48=N!{ma_#nqM4B=8 zt0p z6n6g-*Rmo7V~07#e(EL7^t)U7H=SwHS2ON zV7z_KJE@5F+`WCB+g|#xZXVw4^T*v5dUi)^_zB6K8x+14SPuL2b-=Dh4bSNx4b-~7 zd3(jDh+Qx92jxqNg&;&0Oq1>L?D*U(Mdk=Vsn30deS)a$)AmfLm9 zG0{!e=w1KMSLdx_J}Iysn?BT{-qY=G@MC+rxAKQSEdMm=`n;3YD;AuTR}xV5A*fQ}*qAJltxvb4MpAgdi3FiZB;*Dbm8sPXxJWvap{a#FG-%gMEV>{Q*DSV zgJN0kg*1)<~R}waKu8V5paUQkGM&~RF8-U--LTDG|wc%#d zoL-OESvy%*R-5e=S1I&>_M^4&9I6yX>sn{^e4aIC^1byLrBHqZTNkle4}rmCY&N|B zwF}E9o)vuw>}^7^ff9{yzg|2{g0ovS*7mk$5APDPkG~yQyqT~}2?!myyqlR1TAbyL zzN4rB7{yTvxR~JXeVS#Sk%6LNU9ID21YethBM{1aLmef*#-X?aapnX{hM23DLvi*2 z`?{Gd(+Dd@$>)74UzJ3Dfp|1U-pzi{Q6gChB_Qd->N--{N1nyoc! zXJ8s=&(ND0fg>Jz_a#s$tw<`K3Dzn(p(S`?#u??3QdS^sT#%7|Pxf*c!2}3r$%a`} zvD9wQ&`791>XSQ@95Z*a6BqI_7_VmnduK5nS%*p)Ms=3r%B}SzxuGe^ktSF-2sCq4w$;s$awT<0!f;$P6@*)$*t9p0^Of`-5ZaAkzP$U`I&+_@h{dR*HG z#m$JwDsrL-%LUjunV!Y2?Q%fSNjcTnD)P9gir%>`v3t~UeiBn?VqeBi5j+|m@DtpB zhMfFPShIAu!k^D`#*PgSlnJ#yt1rr`o}1#w_=hso`IY|UzqLBMu;Eau13GrlKWk!r zCNnW7L1rjn8wCO&(xi&hF=kH;R*4!fEp%oQ2M9Yj*M};g?G`Yv-dt%ezv^?Sygnx6 zNmh|eid50#Qn8gIKNd3yAvi#n2qcEY$%15ua7veS=4<5UitQ7sq)^sHIAN#YI#AXD z7y_HiaUljFD+^*+TTYC}6K|=6KE1J|?6iLlj^h;AbqtQ12Z|d$-J7lo(sAJ9Cc*RG}RyrjM_X|$EfOBrPbsl zVcfy^@bv;r_{PfPX_@BM#JW4(@aAsR$?Z5GeeN?y$H-9&IOHxfoSmx#o2P8B0v{An zdkPSodd%*U2+0psEb8-hNUyCxFEb>W!F601lHlxQHUqkQIGH^EC1k$KmPJ*7a*>UP zl6|q30={CBFmS5Pq=f+tBgF34IL65Ht}=S+eg?l!kB) zm+F#*1p-I8QL=Gx;(73yO;!?bLI`4_$JM%`VApmf*z-M&A?$Y1{*Zw5|4-%}iy*k4squlPYwSw> zqCp?jm$ehi&F)_(*aw1dsJCKpneu=8jf*)-40*TThorefyz+$%(pWMm){@*k8I zc$Nh$a-E|D$B0m!Sa{FlH-}2_IW`io9^~aHPwz(dm23>M2Ief)4DwDUdqsz|q!U73 z18cnF>?&)(NkfN1(M`i@1$gW*|nU6HXaibu;eNiVQ~X z<(msS?RX|WOG1G|?Y)4WQ9`8zWEg|#z$%hs1)!za46^TX5c)}fh$B+AZlGg-WlTmLYEH^&T#>!Udp9!Ago5X^1L=bRO1NtgiF;u-wEw$xXWop0a@Di1)#2 zU&Us6&%<19192L}npi@DW`^D1&i_h?nw4<5&e;HT;e`0axhTg5hU`MDl-cX>0x4l* zSP8vqe=J6J`G|i^mG?u2PaN{g|m=*l)IWQ6`fYe7E62MX7h-aXqK9 zoDHC=*fKMG|L`ww*ZSO>D*Bl6nKvHDKE9bP@al;YAnd=?aj11C>aH_s4;o724A6+T z8Ep}Vy!t;mbzS)|6#K(rHZ3!~yFIqRF}rK1FC#owx01c!Vrev#^t84Ujl=HSr1TzbZsuz=rqno0^!@io6RB$7 zm_|;SmYtg`aNAT%Q@I+ZVv2CHwvetA)#xRf5pCJ;(U<;y#aP)zukrOvCp;nWt%tyo zsV*mct$ryR(aUD!JWNnThqBT>%`}w_D9ZRbwZ`YA9An2{Ucyt{U~m*BXQ`YSd%r@oBo?BM zrVTFk)ow>E2`Bx%{siVc!Hs;JK5lN}n=ORUOT*Y-tZJYl6e6aw;gf<&S$5Nu8q;t* zewO8LyRZ;t7=G16DsAMLik8?RfMMv@E6CsGO-&@HNcYQ;E2pz%8LQNJ$R+j0U+ zfk`_E9BG(Cn^jE_-g?bhu(A~?>Sh(fh3b*w#lu1bv440`qf!fm$Fe}odUD9j2uvVe zM3pOzf6u2sB1eLc4iT*w7O~JFcn>g@ zV{e_tnZaI&Jx#H|>mddjfhQKJPxo((wnP?*EaLD+lcLErHmg}Qbh{Yxt9~T{3L z3gOW`Wx`iHeq}T?*{8?e{yreJz7)ZF!ujw^6Ay;JN9P zniGSV7}>?RKA&8lQV*#d-%RvP-H82CIV;2(7dQj^lPUE6009NeG|ftxkS98Hzoe*J zy26c#t#&(|%=tLBI1_HCc*-J%1i4%xh!_sCz)!li8F9oLAQP8|2>2FcgZK|YBg4l{ zg+A`BFVxSCjKVMheDvT`Y~elP)n#phK-hxnC@82>W{cSFU_dWJ#WJ$suBqr1ub7_r zH!5{Q8KNo&r_r~E$xT(YU#Lf#p21D`g;X@C<5s_4%pCLo6_si=|B6+6I_AX39J zJ8J*;Ct2HuF%7Ot2T2nB#rpBEG)hKbz-P z*X4pIUGAbv42YSlQWFy3Kn%*YMyPCsSY>aq7=N$X?4Fz1a`_Y23Ju(KX5zVcBg5EovTreW`h|a9B{5M-qszKER1h$k-j138(U=89W|PGE={y8^bOIeEaCi_$V8S^1wq~ah;DK`n&ourqFa7aNX@+yv*4e}_ zb%aZ#AP%SyUxqkHr2sy!hhqeoS~yzYkz&bd9K~>zD|n<{u*2Mp929KGflZ9Oo&e%= z>tq?nX*k8=JO@t}$JL~(wwt8R5X$rE6%05>gsOu+%S?CqVJkXS0mSHzi166gIO^jN zllweirF}wIwfkOpP6TS`ylCq1;ofzqq=U)1GjLRJz`rEq0zp}q6K?Ihks>A%zo)R2 zEzhpobaE}p_4bCVr4v_AKGtT14xT}IZjxC_9P8(U=~4yY(z>jX@ECrgY*ibbU@C1? zvRM_23PXt%^b+KZRW%ZJk{C;9kkcs+`4mOiYCNu#6hB^ykIUDmUBVJjo)3PF3W6hw z%V(I-v34pNHIHAkTljcO=v&C~0E16?UXCww@s0Oj`u7K|FwqIZy-&4URJGgIqaVro zR6AN;wCK+V;p?kNMk(32>4ff%!oh+PDp4QhTxBKwyj)r`5Y)hA{NCcrr1<1Iy2O-p z$xC@!-jwI*)aeP16xnr7WWf5kHz1U7Iqx}Ig|uV?9p&;c?VZjuOmH;D|L;zU3ssO` zA%hPS3Nq94D8cRHL0L?S^}LqNkF?vdjXGVw@`tkd4j(>V>{W>!lm9@PtM+?ok+ZFs zJzzn*jgOp-B7!zJVlE)HoH!{Z8*G$}s=_e_HAd#F`8dczmki9#kl>dNPN0$;#mT7R z26Kj^_Y8z$z*3nMpC>Itbw<>ZATe%W0jqIFLIJ(g9LHUqAm?LTbMrI~cLpDW4*M~U zgg;rjD-ggGpRNGOFFqqk$|G1aJy$}J>RhXNhU#RFKnsu%WpzPXK;jV4&UPrcyI9M0 zfZH#I00X2KP!(0vKvi!eg9Hqz5LMVQNPrVTlH-ljFfueaQjic)(q#%y7J(w8P#+z0 zv1)g3l)>3zGtLL`SpNA?e4^R8d1i?9AVwj+SFR`e{&5_)-MH7FKBF_duD0;+iL;_5 z$5+2#%irYZ^~`LqHyJz@$4m@b5%pWn?~6?KHA~nl+IO8Rv0tv2HTEXNB-rrNBauqE z6mv+J(qbkU>V4NLT3R60S7<)5uYcdkxfS>3{navdZQX;R1Yw}ScPb28kC{*}omm?z z@bFOdM{UpNaD;zeiws9sKdV$7tNN?BCl(`x_mUER3g!U-KR!P_z|@nO zRs58>wW2H~qBuJy7k*S-KRa5grLK5?i%6wFuCI{X^HXVjz`VaqZ%yx-*h|w0nai#m z;)>?H7BNzK3k%6#sq97!CB*(>;8c^FBEz1QdHcj;FmYnnc#+}+dCP`t(Xc#rwm z)fyTRREi?=f9|Qi@n0dC_w_Vo{X@AzuKWTASE;Nhf_n-n($C=n4{br+7jUgOeHZ9v zL0@l8c&vu^Ja)B^-2y44L^ME3G=T<@Qc$L@EgqkW$M3^k@62PrJeC@=I!nYzhm;O} zHu^p#t#e#J+=zIP(a%hc!nso6Ed_F>br4c|OIh)umBs<7fnMEYISn53zmXY{TSm52 z6#GXBI@hZW6*%-|Ff~N#F@@{?z2$(pulrx7-)|YB9y@wtP)Vrd(8t5UXQ;Pso?yTX zD^@WEIc@xkCF&Ai>q*lnR8JXAVJMY~n0@J@Id#PzV;X}r;dHW=(WTKfhkqSQfaYBl z&1o%m7^5-7Uy+-R^nMUU-jn->B87&Ve)qh&(ckasE&j6RAIe`NTr}qNL8 zBB-?-b7(Aa)F9c+=lh*`Atpk@-Tsh3Og=P-D-06&BBd6nB$6Z2f7r3!;hsj7SOoX9 zTY8G^na$58Cw)dR+WS`26EjG25QxZLarGZcKUSdUUEJXa?a#py+{fma`WdTvst?CI zIjn*^&`itmPM2!IS_|VpS=jx1^L>5eP3g2z8e}obEKR^Tyl?plwUgy&gGhv7C^vcn zR|oNjqr{Sf%MKA#FHq9(UOYC9D9&c=-1jkZ*csyu3q*ONnomN@@-*JYcB~M2hUCE$ z6$;SF`(3y^Ce2h`&qKqTc7`m8_3U)5Sl{A~6&QC5(Q7Hu(sHSkG59q;w=ike8t6Ik zx}K9K3FF_a<0qxp|2h_hrMW8%7Qn6C@HI5#5}D=FU`X(mTv^~0u|e^O+m>Vd)TC|r zF54+`zyOz@6nGW{pTPNtY(zbwUPZ)Zc(Vg$LO-&SwhYhMeG4bn)BdWctq^z=DUuW4 zF>Z=~a0*fQiip#V$NxK$go*;S5nlJ!lk4ZdA49k0G{{^@==!hF__Wv*MLA&wSxrmm zv(B}uWRp8enH!!m-O#fY63l>qH(>UCUQF`A8>N`R87F(lP#m-_1!%mFtXU}hYhs@t z?2~JDECWSRb=Z66So~^HqXJJo6S0hyodi{I}&+h1_uj#*)S@W2mRt>YvaMKQoNBEH0cRF7u>%=cGF3r;UZ@5^|m!b ztYMu97O;ZgGAv11|! zve8?M?TdPEcxx1q{pk_Md+<5lKmCK1hgc>=r92H%G`tsy8sddMa%B|}ks`0jZG*&) z<}`IX@h~zsj9wY5#~X|x#q7OtoUK|hr!S?`OfcU27q_QFl3P6eQi)p+(}&VQ-lE(JV)jk;ABA15-l(!xCyvS;)sw` z4*uqvTl!o2>i^E2;^Uo`Lq`TeULHYXS;7V?qpR)a?kEA8H)oFg_lF~cfw=Bu%-xLZ z%#oenP9lmJGzEo;-h`P5PL2Ty&BN_>VyWGftW-o6R2-&+labD&7;(&ed_r@P!9oq< z)nqryQMg(DX484)s}j_?fDuKxp&0|e&Icb~u7b{CYnId;1|pnh)619p6!-*HA{<}u zhMeqzbjI|TUoo3qEY);X91s|}3GU0JF&OtPGl^5DP?fBsxPY200eMP2DA6L!esp(a zUkpkpYPh@Sg=yHnHaZj#xzf2(3}UGGHqLxvvmcf++V}+eo z)K|b;C;J5&Snd9L$~xI?!(%7-Uu29FU9}QTD)mgc?y4w^&@+x>wg$4Y5=$EaSNL@a z2@39&b~u-)@q~DuOh&mTm6Czs(9wvbO;zDg6g4%$ri)w7MA;|^H%N9#h2fN}bJiR% zujI^h8B2$ty$jAr;$$dRjDj%yWPBJugv=K*X38Ra9*T1ofTmDtdSzj47>MGfaKhMo z3W4p2Q&U+w8Qk@J=V9XXQeDhsuL@kAB-`wsQN@xyH5C#inR}g3j0~$OBfj|*H#q>c zj!>tBQ`0ybw`iV6+Y#nO*wHyUBo$F9CZClzs!T5eI{uf%z+@gihG$fXPFssHu49#GCfcN_^7M}jNIq$RcL_GjprVxsq`l11vC~95AqJ!s2k$vme9(k7OJE^KUnVO9YIBGFCMv zH(`n*s<{{m&ux$#BFT!C>n}i&&89*T7UKxfX%jp_fXo5Hx^F>Nc_8_7~iBaGq^4i?@^fI ztTUb3v6Inc|M$Z8JZhy6%kGc)$p&`ix-!$t)oy+z9B*k?!2&uxqg*zg;VvU41D$%# z>I6zt&c~r_#q-KSU}RV)yGp#zAe^FeB)}VblVi4y;d#|om?=Tj$H1(F3x%oaPb3wZW$i6cd!=7ud zm{G-|z9xs}^-f3+R!Tb6i=Q`Xh$_+fr=@dt18cdCzS(JBTHNI@lH?|uOlbQ;<&j&a z)rKy>CS5x7LPC?ZEh00yz#bv?0W%~;38suLJIs`F8C?hEH%SJTNAI)?Sl77o zp`KyhRA&m*2OpraLy|u|L2McEU(R1SW}0O0fqmklISZ*=#1)RDUBFv%HIL4q>cJG8 zI&bCUJ!xjKPxQS3;CCJ;dL2rx{6_vz25}(JZ3<3@=?R`uigU=1D@k&^x zkDIQShkd48#~#%=OV41aOT$Pb9ZFP(@a`fhYy-Ut{~u%WU&A7OMiZM;9X4dA7J49b z^#Ffcd!IR|Z zC?F)lkzKPJ?8as?%h$jx*+35}5iW8eF-L$JPS(N@#m9$^3p#NdLalLAvJZAof~8tQ z{O*D^t20d1!TyWC|$`-t`@IQ7X1YtAQyt*S==W=Vq925raC>9Jb|)MEgc4yRGIu3K^mVa#(a!yJ>)b+$)2=JhmoC+Cvl}P zqsaxq1r#TILOzv@3c~OpXR)oBK_;X^y-cX%v8+Ep+a%>Tu&4_ZaQ*GYHftczg^C!v wEHOCx{utOouuzMwR^?O" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Generate the map and relevant data\n", + "\n", + "known_map, map_data, pose, goal = environments.generate.map_and_poses(args)\n", + "\n", + "# Plotting\n", + "plt.figure(dpi=200)\n", + "lsp.utils.plotting.plot_navigation_data(\n", + " plt.gca(), known_map, map_data=map_data, \n", + " robot_pose=args.base_resolution*pose, \n", + " goal_pose=args.base_resolution*goal)\n", + "plt.title(f\"'{args.map_type}' environment, seed {args.current_seed}\")\n", + "None" + ] + }, + { + "cell_type": "markdown", + "id": "1d47fca3", + "metadata": {}, + "source": [ + "## Planning to the Goal\n", + "\n", + "Planning in this grid is relatively easy using the functions built-into `gridmap.planning`. The following code generates a path (a series of waypoints) that the robot can follow to get from its starting position (blue) to the goal (green)." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "18673099", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position(\n", + " known_map, [goal.x, goal.y])\n", + "did_plan, path = get_path([pose.x, pose.y])\n", + "\n", + "plt.figure(dpi=200)\n", + "lsp.utils.plotting.plot_navigation_data(\n", + " plt.gca(), known_map, map_data=map_data, \n", + " robot_pose=args.base_resolution*pose,\n", + " goal_pose=args.base_resolution*goal,\n", + " planned_path=path)\n", + "plt.title(\"Planned path from robot (blue) to goal (green)\")\n", + "None" + ] + }, + { + "cell_type": "markdown", + "id": "75050219", + "metadata": {}, + "source": [ + "Realistically, the robot is going to have some non-zero size, which will require that it plan to be at least somewhat far away from the walls. For this, we can include the inflation radius, which \"inflates\" (or \"grows\") the objects in the map so that it will plan farther around them. We also add a soft cost to the planner, which discourages being close to these newly inflated obstacles though does not outright prohibit it. We will also make the generated path sparser and \"flipped\" (so that the first point is the robot pose, rather than the other way around; this will be important later).\n", + "\n", + "We will next inflate the grid, by a predefined amount `args.inflation_radius_m`, and replan with that grid to see how the plan changes so as to avoid being so close to obstacles. Notice how the grid and thus the path change." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "id": "8b0fe732", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Inflation Radius (meters): 0.75\n", + "Inflation Radius (grid units): 2.5\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Compute the inflation radius (in grid units)\n", + "inflation_radius = args.inflation_radius_m / args.base_resolution\n", + "\n", + "print(f\"Inflation Radius (meters): {args.inflation_radius_m}\")\n", + "print(f\"Inflation Radius (grid units): {inflation_radius}\")\n", + "\n", + "# 'Inflate' the grid; puff up the obstacles\n", + "inflated_known_grid = gridmap.utils.inflate_grid(\n", + " known_map, inflation_radius=inflation_radius)\n", + "\n", + "# Plan in the newly-inflated grid\n", + "cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position(\n", + " inflated_known_grid, [goal.x, goal.y], use_soft_cost=True)\n", + "did_plan, path = get_path([pose.x, pose.y],\n", + " do_sparsify=True, do_flip=True)\n", + "\n", + "# Plotting\n", + "plt.figure(dpi=200)\n", + "plt.subplot(131)\n", + "lsp.utils.plotting.plot_navigation_data(\n", + " plt.gca(), known_map, map_data=map_data)\n", + "plt.title(\"Occupancy Grid\")\n", + "\n", + "plt.subplot(132)\n", + "lsp.utils.plotting.plot_navigation_data(\n", + " plt.gca(), inflated_known_grid, map_data=map_data)\n", + "plt.title(\"'Inflated' Grid\")\n", + "\n", + "plt.subplot(133)\n", + "lsp.utils.plotting.plot_navigation_data(\n", + " plt.gca(), known_map, map_data=map_data, \n", + " robot_pose=args.base_resolution*pose,\n", + " goal_pose=args.base_resolution*goal,\n", + " planned_path=path)\n", + "plt.title(\"Planned Path\")\n", + "None" + ] + }, + { + "cell_type": "markdown", + "id": "5fc6d743", + "metadata": {}, + "source": [ + "Now the agent's plan looks much more reasonable.\n", + "\n", + "## Putting it All Together: navigating to the goal\n", + "\n", + "Now that we have a path, we should make the robot move along it! To do this, we'll instantiate a `Robot` object:\n", + "\n", + "```python\n", + "robot = lsp.robot.Turtlebot_Robot(\n", + " pose,\n", + " primitive_length=args.step_size,\n", + " num_primitives=args.num_primitives,\n", + " map_data=map_data)\n", + "```\n", + "\n", + "We want to robot to move along the path, which will require a loop: every time the agent moves, along the path, we should generate a new path that begins at the new location of the robot and then repeat this process until the robot is within some distance to the goal.\n", + "\n", + "
\n", + "In principle, it is possible to only compute the path once and move the robot along it, however, in practice this will not work. First, the robot is not confined to the discrete grid we use for planning and instead follows short motion primitives that may put it slightly off the perfect path we have generated for it. Second, a real robot will not be able to perfectly execute these motion primitives to infinite precision, which means that our robot may deviate slightly from the path—continual replanning is one way to overcome this limitation. (One could also handle it on the control side; look up Pure Pursuit for details.)\n", + "
\n", + "\n", + "By providing this robot object with a path, we can move along it and then replan from the new state, repeating this process until the goal is reached. Putting everything together, we can plan all the way to the goal:" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "id": "1e8e578c", + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAcEAAAFfCAYAAAA213fbAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/bCgiHAAAACXBIWXMAAA9hAAAPYQGoP6dpAAAvLElEQVR4nO3de1xU5b4G8GcNzAygMHhJLgEeNa8ZeiRDUvOGEqXilq5aWbudxwJL2Z2MdmW22wezU6ZF1G57tHaZZVstNUNFwTIxJclbqXi84BFwp8IAygAz7/ljbYcmAZnrmmE9389nfVyzZrHWz9dxHtbtfSUhhAAREZEKaZQugIiISCkMQSIiUi2GIBERqRZDkIiIVIshSEREqsUQJCIi1WIIEhGRavkrXcBvWSwWnD17FsHBwZAkSelyiIjIxwghUF1djcjISGg0rR/reV0Inj17FtHR0UqXQUREPq60tBRRUVGtruN1p0ODg4OVLoGIiNqBtuSJ14UgT4ESEZErtCVPvC4EiYiIPIUhSEREqsUQJCIi1WIIEhGRajEEiYhItRiCRESkWgxBIiJSLYYgERGpFkOQiIhUiyFIRESqxRAkIiLVYggSEZFqMQSJiEi1GIJERKRaDEEiIlIthiAREamWUyG4cOFCSJKEOXPmWJfV1dUhLS0NXbp0QceOHZGamoqKigpn6yQiInI5f0d/cM+ePXjvvfcQGxtrs3zu3LnYuHEjVq9eDYPBgPT0dEydOhU7d+50ulhnaDQaaDQ88CWi5gkhYLFYIIRwajtKfdeYzWana5ckCX5+fi6qqO0sFgssFovH9ws4GII1NTWYPn063n//fbzyyivW5VVVVVi2bBlWrlyJsWPHAgCWL1+O/v37o7CwEMOGDXNN1XaSJAkpKSkYM2aMIvsnIu93+fJlfPTRRzhw4IDD29BoNEhNTcXIkSNdWNm1mc1mrFmzBt98841T2xk3bhwmTZoESZJcVFnbbN26FevXr3c6xB3hUAimpaXhzjvvRGJiok0IFhUVoaGhAYmJidZl/fr1Q0xMDHbt2tVsCJpMJphMJutro9HoSEmtkiQJI0aMQHp6usf/cYnIN1RWVmLnzp1Oh+Do0aPxxBNPuLCya2toaEBJSYnTIRgXF4f09HSPHskKIXDp0iVs2LDBN0Jw1apV+OGHH7Bnz56r3isvL4dOp0NoaKjN8rCwMJSXlze7vaysLCxYsMDeMoiIiJxmV9yXlpbiqaeewscff4yAgACXFJCZmYmqqirrVFpa6pLtEhERXYtdIVhUVIRz585hyJAh8Pf3h7+/PwoKCrB06VL4+/sjLCwM9fX1qKystPm5iooKhIeHN7tNvV6PkJAQm4mIiMgT7DodOm7cuKvOlz/yyCPo168f5s2bh+joaGi1WuTl5SE1NRUAcOTIEZw+fRoJCQmuq5qIiMgF7ArB4OBgDBw40GZZhw4d0KVLF+vyRx99FBkZGejcuTNCQkIwe/ZsJCQkKHZnKBERUUscfk6wJYsXL7beJmwymZCUlIR33nnH1bshIiJymtMhmJ+fb/M6ICAA2dnZyM7OdnbTREREbsUuVIiISLUYgkREpFoMQSIiUi2GIBERqZbL7w4lIlLK7jO7cfT8UfTp0gfxUfFKl0M+gCFIRO3CvC3zsOi7RdbXz9z6DF4d/6qCFZEv4OlQIvJ5u8/sxqIdi4Efp8uTRYNF3y3C7jO7lS6NvBxDkIh83tHzRwGLFtj3e3my+DUtJ2oFT4cSkc/r06UPoLsEPDzu6uVEreCRIBH5vPioeDxz6zM2y+YNn8ebY+iaeCRIRO3Cq+NfxdT+U3l3KNmFIUhE7UJNDfDYHfEA4rF3r9LVkK9gCBJRu2CxAFeGOxVC2VrIdzAEiahdCAoCtmyR57VaZWsh38EQJKJ2wd8fSExUugryNbw7lIiIVItHgkTULjQ0ALm58nxyMuDnp2w95BsYgkTULly+DEyaJM/X1TEEqW0YgkTULvj5AbfcIs9LkrK1kO9gCBJRu9ChA7Cb/WWTnRiCbiSEgNlshtlsVroUxWg0Gvj7+0Py8K/mZrMZjY2NHt0nuY6/vz/8eD6TPIAh6EZCCPzjH//A5s2blS5FMXFxcXjkkUcQGBjo0f3++OOPWLZsGerq6jy6X3JeUFAQHn30UQwePFjpUkgFGIJuJITAnj178D//8z9Kl6KYqqoqPPDAAx4PwVOnTuGjjz6C0Wj06H7JeaGhoRg/frzdIVhb2/ScYEEBoNO5vjZqfxiCRNQumM1AYaE8z27TqK0YgkTULgQGAl98Ic/785uN2siuHmNycnIQGxuLkJAQhISEICEhAZs2bbK+P3r0aEiSZDPNmjXL5UUTEf2WVgtMnixPvKeG2squ35eioqKwcOFC9O7dG0IIfPDBB0hJScG+fftw4403AgAee+wxvPzyy9afCQoKcm3FRERELmJXCE660h3Dv/zlL39BTk4OCgsLrSEYFBSE8PBw11VIRNQGjY3Ajh3y/OjRgIY9I1MbOPwxMZvNWLVqFWpra5GQkGBd/vHHH6Nr164YOHAgMjMzcenSpVa3YzKZYDQabSYiIntdugSMGydPDQ1KV0O+wu7LxwcOHEBCQgLq6urQsWNHrF27FgMGDAAATJs2Dd27d0dkZCT279+PefPm4ciRI1izZk2L28vKysKCBQsc/xsQEUE+8vvXCSl2m0ZtZncI9u3bF8XFxaiqqsLnn3+OGTNmoKCgAAMGDMDMmTOt6910002IiIjAuHHjcPz4cfTq1avZ7WVmZiIjI8P62mg0Ijo62oG/ChGpWceOwMGDSldBvsbuENTpdLjhhhsAyL2B7NmzB0uWLMF777131brx8fEAgJKSkhZDUK/XQ6/X21sGEREAwGiUT4XyVgRyhNOXji0WC0wmU7PvFRcXAwAiIiKc3Q0R0VWMRnnswNGjgbIypashX2TXkWBmZiaSk5MRExOD6upqrFy5Evn5+cjNzcXx48excuVK3HHHHejSpQv279+PuXPn4rbbbkNsbKy76iciFbt4EThzBqiuBioqAP6+TfayKwTPnTuHhx56CGVlZTAYDIiNjUVubi7Gjx+P0tJSbN26FW+++SZqa2sRHR2N1NRUPP/88+6qnYhUrnt3YPt2oLISYH/b5Ai7QnDZsmUtvhcdHY2CggKnCyIiao3RCJw8CVw5wdSzp6LlkI/j46RE5DOuXAMcNQrYu1fpaqg9YDezPsLTg9K6iq/WfYWv1++LNBpNi+0uSU0Te4SxdaW/Zme3oTYMQR8wYsQI3HnnnT75Ae3bt6/PPgITExODadOmITQ0VOlSVCUgIAD9+/dv9r3gYGDTJuDUKWDgQA8X5sX8/PwwefJkREVFObWdYcOG+eT3jDMYgj4gLi4OTz/9NPx8tGt8X/1PFRkZiVmzZiEmJkbpUlTNaAR27QKSkuTXwcEMwN/SaDRITExE4pVRhZ3gq/9fHcUQ9CFq+3B6A1ecYiLH1dbK1wB37wY++QS4+26lK/Je/Jw6hmfVichrBQYCffsCISFAC51OETmFIUhEXkujAf72N/lO0CFDlK6G2iOGIBF5FaMR+OtfASHk1xoNnwUk9+E1QSLyGo2N8jXA774D/vlP4E9/Uroiau94JEhEXsPfH7jnHqBTJzkMidyNIUhEXuWpp4CjR3kNkDyDIUhEijIageefB+rrm5Z17apcPaQuvCZIRIoRApg6FcjLA0pLgQ8+ULoiUhseCRKRYiQJeOYZeRzAp55SuhpSIx4JEvkwoxFYulR+jOC555qWb9oEFBUBt90mTwBw+TLw+uvyfGYmcKUXvq1bgcJCICEBGDdOXmY2A1lZ8vzTTwMBAfJ8QQHwzTdAXJztjSv/9V+AxSIHWXCwvOy774Bt2+QhjyZPblr3tdcAkwl44gmgc2dgwgTg+HH5wXgiT+ORIJEPq64GXngBeOkl2+Xr18vLt29vWlZXJy974QU5sK7IzZWX5eY2LTObm9Y1mZqWb9smL9uwwXZ/8+fLy6urm5Z9+628bO1a23VfeUVefv580zIGICmFR4JEPiwoCJg5s+mo7ooRI+Qgi4trWqbTyesCtsMQxcfLy+Pjm5ZpNE3r6nRNy+Pi5OXDh9vu7w9/kIM1KKhp2aBB8roJCbbrPvywHMghIXb9VYncgiFI5EPOn5efo3vtNfkRgk6dgPfeu3q9adPk6dc6dGh+3bvukqdf8/dvft3Jk21PbV6Rk3P1sqSkppEffm3JkquXESmFp0OJfEhmpnxKcvp0+UiPiJzDI0EiH/Lf/w388ot8Xc1Hh5ck8ioMQSIvZzY3BV5ICLBmjbL1ELUnPB1K5MXOnweGDQNWr1a6EqL2iSFI5MWys+Wx9ObOBS5dUroaovaHp0OJvNif/gRUVsqPIPz68QMicg2GIJGXuXRJfnhckuRrgW+8oXRFRO2XXadDc3JyEBsbi5CQEISEhCAhIQGbNm2yvl9XV4e0tDR06dIFHTt2RGpqKioqKlxeNFF7df68/CD6/PlNI6sTkfvYFYJRUVFYuHAhioqKsHfvXowdOxYpKSk4dOgQAGDu3LlYv349Vq9ejYKCApw9exZTp051S+FE7dFXXwHFxfKD6v/8p9LVELV/dp0OnTRpks3rv/zlL8jJyUFhYSGioqKwbNkyrFy5EmPHjgUALF++HP3790dhYSGGDRvW7DZNJhNMv+qc0Gg02vt3IGo3HnwQqK2VO73u1k3paojaP4fvDjWbzVi1ahVqa2uRkJCAoqIiNDQ0IDEx0bpOv379EBMTg127drW4naysLBgMBusUHR3taElEPuniRdsBZWfNAgYMUK4eIjWxOwQPHDiAjh07Qq/XY9asWVi7di0GDBiA8vJy6HQ6hIaG2qwfFhaG8vLyFreXmZmJqqoq61RaWmr3X4LIV50/D4wdC9x3n20QEpFn2H13aN++fVFcXIyqqip8/vnnmDFjBgoKChwuQK/XQ6/XO/zzRL7s4EHgp5+As2eB//s/oEcPpSsiUhe7Q1Cn0+GGG24AAMTFxWHPnj1YsmQJ7r33XtTX16OystLmaLCiogLh4eEuK1iNhBBobGyE4O2CbWb2kd6lR40CvvwSiIpqCkAhBMxms2r/vSVJgkajgUbjm315mM1mNDQ0KF2GQ660uyRJSpfiMU4/J2ixWGAymRAXFwetVou8vDykpqYCAI4cOYLTp08j4bcDipFdCgoK8PTTT6vqg+ms//3f/0VdXZ3SZTTrwgV57L2uXeXXEybYvn/q1CksX74cFy5c8HxxXiAoKAgPPPAAbrrpJqVLsZvZbMY//vEPHD16VOlSHDJ+/HhMnDhRVd81doVgZmYmkpOTERMTg+rqaqxcuRL5+fnIzc2FwWDAo48+ioyMDHTu3BkhISGYPXs2EhISWrwzlNrmxx9/xI8//qh0GeQCFy4AiYlyp9h5eU1B+GsVFRVYsWIFTp8+7fkCvUBoaCiGDx/ukyEohEBBQYFTl4iU1KFDB0ycOFHpMjzKrhA8d+4cHnroIZSVlcFgMCA2Nha5ubkYP348AGDx4sXQaDRITU2FyWRCUlIS3nnnHbcUTuSLfvkFKCuTjwR/+aX5ECQiz7ErBJctW9bq+wEBAcjOzkZ2drZTRRG1V336ANu3yyHYr5/S1RAR+w4lcrMLF4Dy8qZn/xh+RN7DN2+/IvIRV64BjholPw5BRN6FIUjkRpIEaDRNExF5F54OJXKjTp2ALVuAc+eAvn2VroaIfoshSORmnTrJExF5H56gISIi1WIIErmJyQRotfLEEcKIvBNPhxK5UWOj0hUQUWsYgkRuotMBZ87I8x07KlsLETWPIUjkJpIEXH+90lUQUWt4TZCIiFSLR4JEbtLYCCxeLM8/+STAsaOJvA9DkKgFzo6pZjYDzzwjz//HfzAEfYGaxtEjGUPQB8THx2P8+PEe/w/6/fffY/PmzU6NcN6/f39MnjwZOp3OhZV5RnR0NEJCQhz+eY0GmDFDntdqXVRUG4WGhuKuu+5CRESEZ3fsAoGBgejTp4/H9xsQEIB77rkHsbGxHt+3sywWC3Jzc7F3716lS/E5DEEfMGzYMLz44ovw9/fsP9fSpUuxdetWmM1mh7fRv39/ZGZmOhUmvkqrBVasUGbfnTp1wsyZM3HzzTcrU4AP0uv1uP/++5UuwyGNjY24ePEiQ9ABDEEfIUmST56quVK3L9buy9ju9vP1tvL1+pXCu0OJiEi1GIJEbmIyAaGh8sRu04i8E0+HErlRVZXSFRBRaxiCRG6i1QJHj8rzHTooWwsRNY8hSOQmGg3Qu7fSVRBRa3hNkIiIVItHgkRuYjYD774rzz/2mDyqBBF5F4YgkZs0NgLp6fL8gw8yBIm8kV2nQ7OysjB06FAEBwejW7dumDJlCo4cOWKzzujRo20e1JUkCbNmzXJp0US+QKMB7rpLnjzc2Q8RtZFd/zULCgqQlpaGoUOHorGxEc899xwmTJiAw4cPo8Ovbn977LHH8PLLL1tfBwUFua5iIh+h1QKrVytdBRG1xq4Q/Prrr21er1ixAt26dUNRURFuu+026/KgoCCEh4e7pkIiIiI3ceru0Kp/PQncuXNnm+Uff/wxunbtioEDByIzMxOXLl1qcRsmkwlGo9FmIiIi8gSHr1RYLBbMmTMHw4cPx8CBA63Lp02bhu7duyMyMhL79+/HvHnzcOTIEaxZs6bZ7WRlZWHBggWOlkHktUwmoGdPef7nn4HgYGXrIaKrORyCaWlpOHjwIL799lub5TNnzrTO33TTTYiIiMC4ceNw/Phx9OrV66rtZGZmIiMjw/raaDQiOjra0bKIvMrZs/KfTgzJSERu5FAIpqenY8OGDdixYweioqJaXTc+Ph4AUFJS0mwI6vV66DnkNrVDWi2wb588z27TiLyTXSEohMDs2bOxdu1a5Ofno0ePHtf8meLiYgDwyRGuiZyh0QCDBytdBRG1xq4QTEtLw8qVK/HFF18gODgY5eXlAACDwYDAwEAcP34cK1euxB133IEuXbpg//79mDt3Lm677TbExsa65S9ARETkKLtCMCcnB4D8QPyvLV++HA8//DB0Oh22bt2KN998E7W1tYiOjkZqaiqef/55lxVM5CvMZuDvf5fnp01jjzFE3sju06GtiY6ORkFBgVMFEbUXjY3AI4/I81OnMgSJvBE7cyJyE40GuOMOeZ7dphF5J/7XJHITrRbYuFHpKoioNRxPkIiIVIshSEREqsUQJHKT+nqgd295qqlRuhoiag6vCRK5iRBASYk8b7EoWwsRNY8hSOQmWi1wpWtdDqlJ5J0YgtQuCSGu+VxrW0iSBEmSHPpZjQYYPtzpEhwihIDFYoHFRw9BnWl3R3nDZ4Y8jyFI7dKhQ4fw2WefwWQyObyNmJgYTJs2DZ06dXJhZZ5x4cIFZGdn++Tg1oGBgbjnnnswYMAAj+63rq4On332GQ4fPuzwNjQaDSZPnoyEhAQXVkbuxBCkdunYsWNYsmSJU4M0Dxs2DJMmTXI4BM1m4MowmlOmyKdHPaWqqgoffvih53boQqGhoRgyZIjHQ9BkMmHNmjX48ssvHd6Gv78/oqOjGYI+hCFI5CaNjcA998jzVVWeDUEiahuGIJGbSBIwapQ87+enbC1E1DyGIJGb6HRAfr7SVRBRa/iwPBERqRZDkIiIVIshSOQm9fXA4MHyxG7TiLwTrwkSuYkQwI8/yvM++sw6UbvHECRyE60W2LxZnme3aUTeiSFI5CYaDTB+vNJVEFFreE2QiIhUi0eCRG5iNgNffy3PT5jAHmOIvBFDkMhNGhuBiRPleXabRuSdGIJEbiJJwM03y/MaXngg8koMQSI30emAPXuUroKIWsPfT4mISLXsOhLMysrCmjVr8PPPPyMwMBC33norXn31VfTt29e6Tl1dHf74xz9i1apVMJlMSEpKwjvvvIOwsDCXF+/tJEnCqCvDCDhh5MiR0PB8GtnBYDBg4sSJPjuobq9evZQuw6doNBqMHTsWAQEBTm1n5MiRLqrId9gVggUFBUhLS8PQoUPR2NiI5557DhMmTMDhw4fRoUMHAMDcuXOxceNGrF69GgaDAenp6Zg6dSp27tzplr+AN5MkCXfeeSfuuOMOp7cjSZKLqiJPqa8HxoyR5zdvBv71X8QjOnfujCeffBJxcXGe26kL8Zc++2g0GkyZMgUpKSlObUeN3zV2heDXV+73/pcVK1agW7duKCoqwm233YaqqiosW7YMK1euxNixYwEAy5cvR//+/VFYWIhhw4a5rnIfoMYPFDURAvjuO3nebPbsviVJgkajgR8HMlQFftc4zqkbY6qqqgDIv3UCQFFRERoaGpCYmGhdp1+/foiJicGuXbuaDUGTyQSTyWR9bTQanSmJyGv4+wNr18rzgYHK1kJEzXM4BC0WC+bMmYPhw4dj4MCBAIDy8nLodDqEhobarBsWFoby8vJmt5OVlYUFCxY4WgaR1/LzA6ZMUboKImqNwyfe09LScPDgQaxatcqpAjIzM1FVVWWdSktLndoeERFRWzl0JJieno4NGzZgx44diIqKsi4PDw9HfX09KisrbY4GKyoqWrxLTa/XQ6/XO1IGkVezWIAdO+T5ESPk06NE5F3sOhIUQiA9PR1r167Ftm3b0KNHD5v34+LioNVqkZeXZ1125MgRnD59GgkJCa6pmMhHNDTId4eOGQNcuqR0NUTUHLt+N01LS8PKlSvxxRdfIDg42Hqdz2AwIDAwEAaDAY8++igyMjLQuXNnhISEYPbs2UhISFDdnaFEkgQMGCDP845/Iu9kVwjm5OQAAEaPHm2zfPny5Xj44YcBAIsXL4ZGo0FqaqrNw/JEaqPTAYcOKV0FEbXGrhAUQlxznYCAAGRnZyM7O9vhooiIiDyBJ2mIiEi1GIJEblJfD4wfL0+1tUpXQ0TN4U3bRG4iBLB1qzzv6W7TiKhtGIJEbuLvD3z0kTzPbtOIvBNDkMhN/PyA6dOVroKIWsNrgkREpFo8EiRyk3XrgIAAYNQong4l8lY8EiRyk8xMIDkZ2LhR6UqIqCU8EiRyg/p6udPsujrgV8NrEpGXYQgSuYFOB7z/vvyYBAf8JvJePB1K5EYMQCLvxhAkcrH6euDMGaWrIKK2YAgSuVh+PhAdDSQlKV0JEV0LQ5DIxQ4flscPjIpSuhIiuhbeGEPkYnPmAA8+yNHkiXwBQ5DIDbp0kSci8m48HUpERKrFECRyoRkzgPvvBw4cULoSImoLng51MyGE0iUoSghhndq7ujpg9Wrg8mXg2WeVrkbmy+0u+fBDlr7c7mrDEHQji8WCrVu3orCwUOlSHFJYWAiLxeLUNn7++WcsWrQIer3eRVW1zU8//QSTyeTRfWq1wJYt8iMSsbEe3fVVLl68iPfffx9fffWVsoU4ICAgACkpKejbt6/SpdjNYrHgq6++wi+//KJ0KT7l22+/VewXB4agGwkhsHnzZrz++utKl6KYw4cP4/Dhw0qX4RF+fsDw4fKktIsXL+Kvf/2r0mU4pFOnTujXr5/PhuDGjRuxkb2m+wxeEyQir8JTieRJDEEiFygtBV55Bdi3T+lKiMgeDEEiF1i/HnjhBflBeSLyHbwmSOQCvXoBKSnA2LFKV0JE9rD7SHDHjh2YNGkSIiMjIUkS1q1bZ/P+ww8/DEmSbKbbb7/dVfUSeaWkJGDdOuDJJ5WuhIjsYXcI1tbWYtCgQcjOzm5xndtvvx1lZWXW6ZNPPnGqSCIiInew+3RocnIykpOTW11Hr9cjPDy8TdszmUw2z3MZjUZ7SyJS1KFDQEwMEBysdCVEZC+33BiTn5+Pbt26oW/fvnj88cdx/vz5FtfNysqCwWCwTtHR0e4oichtUlPlzrLz85WuhIjs5fIQvP322/Hhhx8iLy8Pr776KgoKCpCcnAyz2dzs+pmZmaiqqrJOpaWlri6JyG2qqgCzGbBYgMGDla6GiOzl8rtD77vvPuv8TTfdhNjYWPTq1Qv5+fkYN27cVevr9XqPd6lF5CoGA3DsGHDmDBAaqnQ1RGQvtz8n2LNnT3Tt2hUlJSXu3hWRYjiKPJFvcnsInjlzBufPn0dERIS7d0XkUezdi8j32R2CNTU1KC4uRnFxMQDgxIkTKC4uxunTp1FTU4P//M//RGFhIU6ePIm8vDykpKTghhtuQFJSkqtrJ1LUli1A797An/+sdCVE5Ci7rwnu3bsXY8aMsb7OyMgAAMyYMQM5OTnYv38/PvjgA1RWViIyMhITJkzAn//8Z173o3bnyBGgpAQ4eVLpSojIUXaH4OjRo1vt5T03N9epgoh8RXo6cO6c/IgEEfkm9h3qRpIk4dZbb8WlS5eULsUh+/fvx3fffefU0DY9e/bE2LFjodVqXViZZ/To0QMdO3a0WVZXB+h0gEYDSJJ7ToWGhYXhwQcfxIULF1y/cTerrq5Gbm4u/vnPfypdit30ej2Sk5Nx/fXXK12K6uzbt0+xwccZgm4kSRJSUlIwceJEpUtxyNtvv43CwsIWn/Fsi0GDBmHhwoUI9sHuVDQaDfz8/KyvL18GJk+WO8t+5x05CN0hJiYG8+fP98lx9U6dOoWffvrJJ0MwICAAf/jDH2CxWJQuRXVef/11fP/994q0PUPQjSRJgp+fn80XqS9xRd0ajQZarRY6nc4FFSlrxw4gLw/YtQvIyAD69HHPfjQaDTTuSlg302q1kCRJ6TIcIkkS/P35lehpQghFP+/8Fydqo6Qk4O9/B7p3d18AEpFnMQSJWnHpkvw8YIcO8uvp05Wth4hcyzfPuRB5wKVL8kC5d94J1NYqXQ0RuQNDkKgFJSXA998DRUXyM4FE1P7wdCi1e7t3A0ePytfx4uPb/nOxsUBuLtDYCAwZ4r76iEg5PBKkdm3ePGDYMOChh+Q/581red2yMuC99+RBcq8YNgwYMcL9dRKRMngkSO3KL78AW7cCP/8sh9nnn9u+v2gRMHUqUFoqP/IwbZocdABw4gQwaxbQo4c8QG5MjMfLJyIPYwiST2toAAoL5dOWubny9btrPWN+9CiwcSPw6adAdHRTCA4YACQnAzfeCNTUuL92IlIeQ5B8Tnk58MUXwNdfA9u2AUaj7fs33SQHW3098MEHV/98nz6AVisHYEJC0/LQUOCrr9xaOhF5GYYg+YSKCmD1ann65hvbo70uXYDx4+WH2SdMACIjm97r1g147bWm1/PmyTfHxMcD993nufqJyDsxBMmrmc3AW28Bzz9v+6ze0KFyP55JSfKdmy318LZokTzKgyN3hxJR+8cQJK+1bx8wcyawd6/8+t//HXjgATnUundv+3auHPkREf0WQ5C80qefyl2Umc3ytbrXXgN+/3v3jdxAROrEECSvNGYMEBIiX+tbsgQID1e6IiJqjxiC5JW6dQMOHrS9yYWIyNV4com8FgOQiNyNIUhERKrFECQiItViCBIRkWoxBImISLUYgkREpFp2h+COHTswadIkREZGQpIkrFu3zuZ9IQRefPFFREREIDAwEImJiTh27Jir6iUiInIZu0OwtrYWgwYNQnZ2drPvL1q0CEuXLsW7776L3bt3o0OHDkhKSkJdXZ3TxRIREbmS3Q/LJycnIzk5udn3hBB488038fzzzyMlJQUA8OGHHyIsLAzr1q3Dfey2n4iIvIhLrwmeOHEC5eXlSExMtC4zGAyIj4/Hrl27mv0Zk8kEo9FoMxEREXmCS0OwvLwcABAWFmazPCwszPreb2VlZcFgMFin6OhoV5ZERETUIsX7Ds3MzERGRob1tdFodGsQil+Pxkoe46vtLkmSIvv11fbyda5od35mfItLQzD8X139V1RUICIiwrq8oqICgwcPbvZn9Ho99Hq9K8u4ihAC+fn5sFgsbt1Pe/Ptt986/R/r6NGjeOutt9z+b+wOkZGRmDhxIkJCQjy637KyMqxfv94nLw1cvHixxbM+3s5kMmHTpk0oKSlxeBt+fn4YM2ZMi9937mKxWLB9+3bs27fPo/t1lW+++UaxEHdpCPbo0QPh4eHIy8uzfgiMRiN2796Nxx9/3JW7sosQAhs2bMDGjRsVq8EXCSGc/mAeOHAAhw4dclFFnjVs2DCMGDHC4yFYWlqKhQsX4tSpUx7dr6v46i+bdXV1+OCDD/Dll186vA2tVovFixd7PATNZjPWrVuHd955x6P7dRVXfNc4yu4QrKmpsflN6cSJEyguLkbnzp0RExODOXPm4JVXXkHv3r3Ro0cPvPDCC4iMjMSUKVNcWbfdlGxktfPVL0Wl6hZCwGw2+2y7+SohBCwWi1PtbjabFfueuVI/2cfuENy7dy/GjBljfX3let6MGTOwYsUKPPPMM6itrcXMmTNRWVmJESNG4Ouvv0ZAQIDrqiYiInIBu0Nw9OjRrf6mI0kSXn75Zbz88stOFUZERORu7DuUiIhUiyFIRESqxRAkIiLVYggSEZFqMQSJiEi1GIJERKRaDEEiIlIthiAREakWQ5CIiFSLIUhERKrFECQiItViCBIRkWopPrK8J0iShLi4ONx4441Kl0I+pFevXujQoYPSZTikY8eOGDVqFLp27ap0KXYLCgpCdHS00mX4FI1Gg/j4eNTU1Chdit2EEDh06BCKiooU2b9qQvDuu+/Gk08+qXQp5EMkSYJOp1O6DIdcd911eO655zBkyBClS3GIVqtVugSfotFocN999+Huu+9WuhS7CSHwxhtvYN++fYqMh6iKEAQAf39/6PV6SJKkdClEbnclwDmOpzpIkgStVuuTvzwIIeDvr1wU8ZogERGpFkOQiIhUiyFIRESqxRAkIiLVYggSEZFqMQSJiEi1GIJERKRaDEEiIlIthiAREakWQ5CIiFTL5SH40ksvQZIkm6lfv36u3g0REZHT3NJh24033oitW7c27UTBfuGIiIha4pZ08vf3R3h4uDs2TURE5DJuuSZ47NgxREZGomfPnpg+fTpOnz7d4romkwlGo9FmIiIi8gSXh2B8fDxWrFiBr7/+Gjk5OThx4gRGjhyJ6urqZtfPysqCwWCwThxMk4iIPMXlIZicnIy7774bsbGxSEpKwldffYXKykp89tlnza6fmZmJqqoq61RaWurqkoiIiJrl9jtWQkND0adPH5SUlDT7vl6vh16vd3cZREREV3H7c4I1NTU4fvw4IiIi3L0rIiIiu7g8BJ9++mkUFBTg5MmT+O677/C73/0Ofn5+uP/++129KyIiIqe4/HTomTNncP/99+P8+fO47rrrMGLECBQWFuK6665z9a6IiIic4vIQXLVqlas3SURE5BbsO5SIiFSLIUhERKrFECQiItViCBIRkWoxBImISLUYgkREpFqqGOhPCIGdO3ciICBA6VKIrunkyZOoqalxahtVVVX4/PPP8f3337uoqvbv8uXLOHnypFPbsFgs2LFjh2sKUpHCwkIIIRTZtySU2nMLjEYjDAaDy7er0Wjg5+fn8u0SuZrFYoHZbHZ6O/7+/pAkyQUVqYMQAmaz2ekvY37X2M9sNsNisbh8u1VVVQgJCWl1HVUcCQLyF4s7GpnIWzU2Nipdgirxu8a38JogERGpFkOQiIhUiyFIRESqxRAkIiLVYggSEZFqMQSJiEi1GIJERKRaDEEiIlIthiAREakWQ5CIiFSLIUhERKrFECQiItViCBIRkWoxBImISLUYgkREpFoMQSIiUi23hWB2djb+7d/+DQEBAYiPj8f333/vrl0RERE5xC0h+OmnnyIjIwPz58/HDz/8gEGDBiEpKQnnzp1zx+6IiIgcIgkhhKs3Gh8fj6FDh+Ltt98GAFgsFkRHR2P27Nl49tlnbdY1mUwwmUzW11VVVYiJiXF1SUREpDKVlZUwGAytruPyI8H6+noUFRUhMTGxaScaDRITE7Fr166r1s/KyoLBYLBODEAiInKF6urqa67j7+qd/vLLLzCbzQgLC7NZHhYWhp9//vmq9TMzM5GRkWF9XVlZie7du+P06dPXTHA1MhqNiI6ORmlpKUJCQpQux6uwbVrGtmkd26dlvtg2QghUV1cjMjLymuu6PATtpdfrodfrr1puMBh8psGVEBISwvZpAdumZWyb1rF9WuZrbdPWgyiXnw7t2rUr/Pz8UFFRYbO8oqIC4eHhrt4dERGRw1wegjqdDnFxccjLy7Mus1gsyMvLQ0JCgqt3R0RE5DC3nA7NyMjAjBkzcPPNN+OWW27Bm2++idraWjzyyCPX/Fm9Xo/58+c3e4qU2D6tYdu0jG3TOrZPy9p727jlEQkAePvtt/Haa6+hvLwcgwcPxtKlSxEfH++OXRERETnEbSFIRETk7dh3KBERqRZDkIiIVIshSEREqsUQJCIi1fK6EOQQTMCOHTswadIkREZGQpIkrFu3zuZ9IQRefPFFREREIDAwEImJiTh27JgyxXpYVlYWhg4diuDgYHTr1g1TpkzBkSNHbNapq6tDWloaunTpgo4dOyI1NfWqzhvaq5ycHMTGxlp790hISMCmTZus76u5bX5t4cKFkCQJc+bMsS5Tc9u89NJLkCTJZurXr5/1/fbcNl4VghyCSVZbW4tBgwYhOzu72fcXLVqEpUuX4t1338Xu3bvRoUMHJCUloa6uzsOVel5BQQHS0tJQWFiILVu2oKGhARMmTEBtba11nblz52L9+vVYvXo1CgoKcPbsWUydOlXBqj0nKioKCxcuRFFREfbu3YuxY8ciJSUFhw4dAqDutrliz549eO+99xAbG2uzXO1tc+ONN6KsrMw6ffvtt9b32nXbCC9yyy23iLS0NOtrs9ksIiMjRVZWloJVKQuAWLt2rfW1xWIR4eHh4rXXXrMuq6ysFHq9XnzyyScKVKisc+fOCQCioKBACCG3hVarFatXr7au89NPPwkAYteuXUqVqahOnTqJv/3tb2wbIUR1dbXo3bu32LJlixg1apR46qmnhBD83MyfP18MGjSo2ffae9t4zZGgvUMwqdWJEydQXl5u004GgwHx8fGqbKeqqioAQOfOnQEARUVFaGhosGmffv36ISYmRnXtYzabsWrVKtTW1iIhIYFtAyAtLQ133nmnTRsA/NwAwLFjxxAZGYmePXti+vTpOH36NID23zaKjyJxhb1DMKlVeXk5ADTbTlfeUwuLxYI5c+Zg+PDhGDhwIAC5fXQ6HUJDQ23WVVP7HDhwAAkJCairq0PHjh2xdu1aDBgwAMXFxapum1WrVuGHH37Anj17rnpP7Z+b+Ph4rFixAn379kVZWRkWLFiAkSNH4uDBg+2+bbwmBInslZaWhoMHD9pcuyCgb9++KC4uRlVVFT7//HPMmDEDBQUFSpelqNLSUjz11FPYsmULAgIClC7H6yQnJ1vnY2NjER8fj+7du+Ozzz5DYGCggpW5n9ecDuUQTG1zpS3U3k7p6enYsGEDtm/fjqioKOvy8PBw1NfXo7Ky0mZ9NbWPTqfDDTfcgLi4OGRlZWHQoEFYsmSJqtumqKgI586dw5AhQ+Dv7w9/f38UFBRg6dKl8Pf3R1hYmGrbpjmhoaHo06cPSkpK2v3nxmtCkEMwtU2PHj0QHh5u005GoxG7d+9WRTsJIZCeno61a9di27Zt6NGjh837cXFx0Gq1Nu1z5MgRnD59WhXt0xyLxQKTyaTqthk3bhwOHDiA4uJi63TzzTdj+vTp1nm1tk1zampqcPz4cURERLT/z43Sd+b82qpVq4RerxcrVqwQhw8fFjNnzhShoaGivLxc6dI8qrq6Wuzbt0/s27dPABBvvPGG2Ldvnzh16pQQQoiFCxeK0NBQ8cUXX4j9+/eLlJQU0aNHD3H58mWFK3e/xx9/XBgMBpGfny/Kysqs06VLl6zrzJo1S8TExIht27aJvXv3ioSEBJGQkKBg1Z7z7LPPioKCAnHixAmxf/9+8eyzzwpJksTmzZuFEOpum9/69d2hQqi7bf74xz+K/Px8ceLECbFz506RmJgounbtKs6dOyeEaN9t41UhKIQQb731loiJiRE6nU7ccsstorCwUOmSPG779u0CwFXTjBkzhBDyYxIvvPCCCAsLE3q9XowbN04cOXJE2aI9pLl2ASCWL19uXefy5cviiSeeEJ06dRJBQUHid7/7nSgrK1OuaA/6/e9/L7p37y50Op247rrrxLhx46wBKIS62+a3fhuCam6be++9V0RERAidTieuv/56ce+994qSkhLr++25bTiUEhERqZbXXBMkIiLyNIYgERGpFkOQiIhUiyFIRESqxRAkIiLVYggSEZFqMQSJiEi1GIJERKRaDEEiIlIthiAREakWQ5CIiFTr/wFzrVfaJu90ewAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAcEAAAFfCAYAAAA213fbAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/bCgiHAAAACXBIWXMAAA9hAAAPYQGoP6dpAAAvOUlEQVR4nO3de1xUdf4/8NcZLgOKDILKJcDM8h6WZEipecELeSvZyrTNWjcfFlpKbUa/NrPv7mL22DUtctvWNLeI0tRKK1NLTBNTlLwViesFE7BUZhBjwJnP74+zjE6CMjNn5szhvJ6Px3mcM2cO57z9OMyLc/scSQghQEREpEMGtQsgIiJSC0OQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbgWoX8Ft2ux0nT55EmzZtIEmS2uUQEZHGCCFQXV2NuLg4GAxX3tfzuxA8efIkEhIS1C6DiIg0rqysDPHx8Vdcxu8Oh7Zp00btEoiIqAVoTp74XQjyECgRESmhOXnidyFIRETkKwxBIiLSLYYgERHpFkOQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItIthiAREekWQ5CIiHSLIUhERLrFECQiIt1iCBIRkW4xBImISLc8CsF58+ZBkiTMnDnTMa+2thaZmZmIiopCWFgYMjIyUFlZ6WmdREREigt09wd37tyJN954A0lJSU7zZ82ahXXr1mHFihUwmUyYPn06xo8fj23btnlcrCcMBgMMBu74ElHjhBCw2+0QQni0HrW+a2w2m8e1S5KEgIAAhSpqPrvdDrvd7vPtAm6G4Llz5zBp0iS8+eab+Mtf/uKYbzabsWTJEuTl5WHIkCEAgKVLl6J79+4oLCxEv379lKnaRZIkYdy4cRg8eLAq2yci//frr7/inXfewb59+9xeh8FgQEZGBgYMGKBgZVdns9mwatUqfP311x6tZ+jQoRgzZgwkSVKosubZuHEjPvnkE49D3B1uhWBmZiZGjRqFtLQ0pxAsKipCfX090tLSHPO6deuGxMREbN++vdEQtFqtsFqtjtcWi8Wdkq5IkiT0798f06dP9/l/LhFpQ1VVFbZt2+ZxCA4aNAiPPfaYgpVdXX19PUpLSz0OweTkZEyfPt2ne7JCCJw/fx5r167VRgjm5+dj9+7d2Llz52XvVVRUIDg4GBEREU7zo6OjUVFR0ej6cnJyMHfuXFfLICIi8phLcV9WVoYnnngC7777LkJCQhQpIDs7G2az2TGUlZUpsl4iIqKrcSkEi4qKcOrUKfTp0weBgYEIDAxEQUEBFi1ahMDAQERHR6Ourg5VVVVOP1dZWYmYmJhG12k0GhEeHu40EBER+YJLh0OHDh162fHyhx9+GN26dcPs2bORkJCAoKAgbNq0CRkZGQCAkpISHD9+HKmpqcpVTUREpACXQrBNmzbo1auX07zWrVsjKirKMX/KlCnIyspCZGQkwsPDMWPGDKSmpqp2ZSgREVFT3L5PsCkLFixwXCZstVoxYsQIvP7660pvhoiIyGMeh+DmzZudXoeEhCA3Nxe5ubmerpqIiMir2IUKERHpFkOQiIh0iyFIRES6xRAkIiLdUvzqUCIitew4sQM/nv4RXaK6ICU+Re1ySAMYgkTUIszeMBvzv5nveP30bU/jpWEvqVgRaQEPhxKR5u04scMpAAFg/jfzsePEDpUqIq1gCBKR5v14+kfgQhCwc5o82A0X5xNdAQ+HEpHmdYnqAlwIAdYtlmfc/BZgqJPnE10BQ5CINC8lPgWzbnscC7qvlGdIdsy+fTYvjqGrYggSUYvwjzF/wX03N1wdupUBSM3CECSiFiMlPoXhRy7hhTFERKRbDEEiahGqq4H4eHmwWtWuhrSCh0OJqEUQAvjpJ7WrIK1hCBJRi9C6NbB7tzwdFKRuLaQdDEEiahECAoCbb1a7CtIanhMkIiLd4p4gEbUIdXXAe+/J0w88IO8ZEl0NQ5CIWoTaWuChh+TpCRMYgtQ8DEEvEkLAZrPBZrOpXYpqDAYDAgMDIUmST7drs9lw4cIFn26TlBMYGIgAF1MsIAAYOVKe9vHHjTSMIehFQgh8+OGH+OKLL9QuRTXJycl4+OGHERoa6tPtfvfdd1iyZAlqa2t9ul3yXKtWrTBlyhTcdNNNLv1c69bAZ595pyZquRiCXiSEwM6dO/HWW2+pXYpqzGYzHnjgAZ+H4LFjx/DOO+/AYrH4dLvkuYiICAwbNszlECRyB68OJSIi3WIIElGLcO4c0LWrPNTVqV0NaYVLIbh48WIkJSUhPDwc4eHhSE1NxWeXHIQfNGgQJElyGqZNm6Z40UREv2W3Az/+KA9CqF0NaYVL5wTj4+Mxb9483HDDDRBC4O2338a4ceOwZ88e9OzZEwDwyCOP4MUXX3T8TKtWrZStmIioEa1aAV9/LU+z2zRqLpdCcMyYMU6v//rXv2Lx4sUoLCx0hGCrVq0QExOjXIVERM0QGAj07692FaQ1bp8TtNlsyM/PR01NDVJTUx3z3333XbRr1w69evVCdnY2zp8/f8X1WK1WWCwWp4GIiMgXXL5FYt++fUhNTUVtbS3CwsKwevVq9OjRAwAwceJEdOzYEXFxcdi7dy9mz56NkpISrFq1qsn15eTkYO7cue7/C4iIAJw5A3z8MRAWBtx9N3uMoeZxOQS7du2K4uJimM1mrFy5EpMnT0ZBQQF69OiBqVOnOpa78cYbERsbi6FDh+Lw4cPo3Llzo+vLzs5GVlaW47XFYkFCQoIb/xQi0rNZs4Dly4GOHYHx49WuhrTC5RAMDg7G9ddfD0DuDWTnzp1YuHAh3njjjcuWTUlJAQCUlpY2GYJGoxFGo9HVMoiInLz0ElBaCrz6KmDgzV/UTB73GGO322G1Wht9r7i4GAAQGxvr6WaIiC4jxMV+QmNigK1b2W8oucalEMzOzkZ6ejoSExNRXV2NvLw8bN68GevXr8fhw4eRl5eHO++8E1FRUdi7dy9mzZqFgQMHIikpyVv1E5FOWSxARgbw7LPA4MHyPAYgucqlEDx16hQefPBBlJeXw2QyISkpCevXr8ewYcNQVlaGjRs34pVXXkFNTQ0SEhKQkZGB5557zlu1E5GO5eQAGzcC338vHwYNCVG7ItIil0JwyZIlTb6XkJCAgoICjwsiImqOOXOA48eBJ59kAJL7+BQJItKMCxfkm+IBOfjefVfdekj7GIIa4euH0ipFq3U30Hr9WmQwGBptd4sFuPNOYOJE4LHHVCjMzzX01+zpOvSGIagB/fv3x6hRozT5Ae3atatmb4FJTEzExIkTERERoXYpuhISEoLu3btfNv/dd4Ft2+RzgPfdB0RFqVCcnwoICMDYsWMRHx/v0Xr69eunye8ZTzAENSA5ORlPPfUUAjTaBYZWf6ni4uIwbdo0JCYmql0KAZg2DaisBMaOZQD+lsFgQFpaGtLS0jxel1Z/X93FENQQvX04/YESh5jIfefPy+f+DAb59ocXXlC7Iv/Fz6l72K8CEfkliwUYNgzIzJSfFUjkDQxBIvJLX38NbN8OvP++fCsEkTfwcCgR+aVRo4B33gG6dQOuvVbtaqilYggSkd+wWORHILVuLb+eOFHdeqjl4+FQIvILFguQni7vAdbUqF0N6QVDkIj8wn//C+zfD+zdCxw9qnY1pBc8HEpEfuGmm4D164HgYKBnT7WrIb1gCBKRaiwWwGwGEhLk1/36qVsP6Q8PhxKRKhrOAd5xB2+BIPUwBInIZ+rqAJtNnq6ulrtBq6oCTp9WtSzSMYYgESmuuhooK3Oe168f0KoVcPCg/Pqaa4DNm4FNm4Cbb/Z5iUQAGIJE5IFTp4CCAuc9uQ8+AMLDgcmTnZeVJHkv8IcfLs6Lj2cAkroYgkR0VWYz8OmnwMqVzvPT04FBg4AtWy7O69RJHp8547zsW28BJ04Av/udV0slcgmvDiUiJ5s2Ad98A4wefXEvbf9++Sb2hATnEOvZUz6nV1d3cd5NN8kB2Lat83obeUQgkeoYgkQ6VVkJvPKKHFhvvHFx/r/+JR/SDA29GILdu8uB16OHfEiz4dGWy5bJjzm6VFDQ5QFI5K8YgkQasWMH8OOPQJcuQEqKaz/71ltAfj4wadLFc3VCAPPmyefqFi6Un9sHAMOHywF46Q3rkZHy3uBv/TYAibSGH2EiDZg2Tb668sEH5fHs2fJ8u11+8GwDsxno3x+IiQHq6y/OLy0FNmwACgsvzouOBmbOlAOw4bYFAJgyRd7DS0/35r+IyD9wT5DITx09Cvz73/Ie3OHDzu/Nnw/U1gJvvgk88ogcZIB8VWZxsdwBdWnpxfNwGRlA587ArbdeXIckAQsW+OJfQuS/GIJEfqa2Fnj5ZeBvf5Onm1JTA/z6q3yItIEkyVdwxsTIodcgOVkeiMgZD4cS+ZENG4BevYDnn5cDcOBAYM6cxpe99145AD/5xHn+yJHyFZrBwV4vl0jzXArBxYsXIykpCeHh4QgPD0dqaio+++wzx/u1tbXIzMxEVFQUwsLCkJGRgcrKSsWLJmqJNmyQz8MdPgzExQHvvSf3qPLCC8DjjzsvO3u2fAHLDTcAgTyeQ+Q2l0IwPj4e8+bNQ1FREXbt2oUhQ4Zg3LhxOHDgAABg1qxZ+OSTT7BixQoUFBTg5MmTGD9+vFcKJ2pJ9u+X77+z2YB77pF7VZkwQT68Ccjn/AoLgeXL5fG8eerWS9RSuPQ35JgxY5xe//Wvf8XixYtRWFiI+Ph4LFmyBHl5eRgyZAgAYOnSpejevTsKCwvRr4lnpFitVlitVsdri8Xi6r+BSNMqK+Ub0S0W+fDnf/4DGI2XL5eS4vqtEUR0ZW6fE7TZbMjPz0dNTQ1SU1NRVFSE+vp6pKWlOZbp1q0bEhMTsX379ibXk5OTA5PJ5BgSGh4sRqQDQgB//KP8KKEuXYDVqxsPQCLyDpdDcN++fQgLC4PRaMS0adOwevVq9OjRAxUVFQgODkZERITT8tHR0aioqGhyfdnZ2TCbzY6h7LddzxO1YP/5D7B2rXwRy4cfyjelE5HvuHxKvWvXriguLobZbMbKlSsxefJkFBQUuF2A0WiEkX/6kg6dPAk88YQ8PWeOfFUoEfmWyyEYHByM66+/HgCQnJyMnTt3YuHChbjvvvtQV1eHqqoqp73ByspKxMTEKFawHgkhcOHCBQgh1C5FM2yXdoHih4QApk6VO5++5Rbg6acvfU/AZrPp9v9bkiQYDAYYNNonm81mQ/2l3fVoSEO7Sw1XZOmAxxdX2+12WK1WJCcnIygoCJs2bUJGRgYAoKSkBMePH0dqaqrHhepZQUEBnnrqKV19MD313//+F7VXutNcZcuXA+vWyYdBly1zvs3h2LFjWLp0Kc789llEOtGqVSs88MADuPHGG9UuxWU2mw0ffvghfry0BwMNGTZsGEaPHq2r7xqXQjA7Oxvp6elITExEdXU18vLysHnzZqxfvx4mkwlTpkxBVlYWIiMjER4ejhkzZiA1NbXJK0Opeb777jt89913apdBCvnpp4uHQV94wbmjakA+erJs2TIcP37c57X5g4iICNx+++2aDEEhBAoKCjw6RaSm1q1bY/To0WqX4VMuheCpU6fw4IMPory8HCaTCUlJSVi/fj2GDRsGAFiwYAEMBgMyMjJgtVoxYsQIvP76614pnEirsrPljq779gX+9Ce1qyHSN5dCcMmSJVd8PyQkBLm5ucjNzfWoKKKW6uxZ+Vl9APDqq+zthUht2jzzTKRReXmA1QokJTk/0YGI1MEQJPKhhoMpU6Zc7BKNiNTDECTykZMngT175KexT5qkdjVEBDAEiXxm3z553KULEBWlbi1EJGMIEvnI/v3ymD3DEPkPhiCRjzTsCWrw9jeiFoshSOQj5eXy+NprVS2DiC7BECTykYbHZoaEqFsHEV3EECTykbo6eRwcrG4dRHQRQ5DIRxr2BBmCRP6DIUjkI3a7PA4IULcOIrqIIUhERLrFECRqgp6eqUYy/p/rD/uw14CUlBQMGzbM57+g3377Lb744guPnnDevXt3jB07FsEaPBGWkJCA8PBwtctwS0REBH73u98hNjZW7VJcFhoaii5duvh8uyEhIbj33nuRlJTk8217ym63Y/369di1a5fapWgOQ1AD+vXrh+effx6BPn7uzqJFi7Bx40bYbDa319G9e3dkZ2drNkyU5Mu/Ydq2bYupU6filltu8d1GNc5oNOL+++9Xuwy3XLhwAWfPnmUIuoEhqBGSJGnyUE1D3VqsXcvY7q7TeltpvX618JwgERHpFkOQyEcabpEgIv/BECTykZ9/lsd8jBKR/2AIEvmAzQZUVsrTcXHq1kJEFzEEiXzg55/lIJQkoEMHtashogYMQSIfOHZMHsfEAD6+04WIroAhSOQDu3fLYw3eh03UojEEiXygIQSTk9Wtg4icuRSCOTk56Nu3L9q0aYMOHTrgrrvuQklJidMygwYNcrpRV5IkTJs2TdGiibSmqEge9+mjbh1E5MylECwoKEBmZiYKCwuxYcMG1NfXY/jw4aipqXFa7pFHHkF5ebljmD9/vqJFE2lJfT2wf788zRAk8i8unaL//PPPnV4vW7YMHTp0QFFREQYOHOiY36pVK8TExChTIZHGHTokB2FYGNCxo9rVENGlPDonaDabAQCRkZFO89999120a9cOvXr1QnZ2Ns6fP9/kOqxWKywWi9NA1JLs2yePe/UCDDwLT+RX3L5Y2263Y+bMmbj99tvRq1cvx/yJEyeiY8eOiIuLw969ezF79myUlJRg1apVja4nJycHc+fOdbcMIr93aQgSkX9xOwQzMzOxf/9+bN261Wn+1KlTHdM33ngjYmNjMXToUBw+fBidO3e+bD3Z2dnIyspyvLZYLEhISHC3LCK/s2mTPO7bV906iOhyboXg9OnTsXbtWmzZsgXx8fFXXDYlJQUAUFpa2mgIGo1GGI1Gd8og8nuVlcCOHfL0qFHq1kJEl3MpBIUQmDFjBlavXo3NmzejU6dOV/2Z4uJiANDkE66JPLVuHSCEfH/gNdeoXQ0R/ZZLIZiZmYm8vDx89NFHaNOmDSoqKgAAJpMJoaGhOHz4MPLy8nDnnXciKioKe/fuxaxZszBw4EAksasM0qG1a+XxmDHq1kFEjXMpBBcvXgxAviH+UkuXLsVDDz2E4OBgbNy4Ea+88gpqamqQkJCAjIwMPPfcc4oVTKQV9fXAxo3yNA+FEvknlw+HXklCQgIKCgo8KoiopSgsBKqr5ecH8iZ5Iv/Eu5aIvGT9enk8bBjvDyTyV/zVJPKSwkJ5PHSounUQUdMYgkRecvSoPO7aVdUyiOgKGIJEXmC3A8ePy9PsL5TIfzEEibygvFy+OjQwEIiLU7saImoKQ5DICxoOhcbHy0FIRP6JIUjkBceOyeNrr1W1DCK6Cv6NSi2SEOKq97U2hyRJkCTJ5Z9r2BNUKwSFELDb7bDb7eoU4CF3290Tan9mSB0MQWqRDhw4gA8++ABWq9XtdSQmJmLixIlo27atyz/bEIJqXRRz5swZ5ObmavLh1qGhobj33nvRo0cPn263trYWH3zwAQ4ePOj2OgwGA8aOHYvU1FQFKyNvYghSi3To0CEsXLjQo4c09+vXD2PGjHErBBsOh6oVgmazGcuXL1dn4x6KiIhAnz59fB6CVqsVq1atwscff+z2OgIDA5GQkMAQ1BCeEyTyArUPhxJR8zAEiRQmxMV7BBmCRP6NIUiksMpKoLZW7i/0Ks+cJiKVMQSJFHbypDyOjgaCgtSthYiujCFIpLCGEIyNVbcOIro6hiCRwsrL5TFDkMj/MQSJFFZRIY8ZgkT+jyFIpLBffpHH7durWwcRXR1DkEhhp0/L46godesgoqtjCBIpjCFIpB0MQSKFNYRgZKS6dRDR1TEEiRTGPUEi7WAIEimMIUikHQxBIgVduACYzfI0Q5DI/zEEiRR09uzFaTeewEREPubS8wRzcnKwatUq/PDDDwgNDcVtt92Gl156CV27dnUsU1tbiyeffBL5+fmwWq0YMWIEXn/9dURHRytevL+TJAl33HGHx+sZMGAADAb+vaIFDYdCIyKAQBWf1mkymTB69GjNPlS3c+fOapehKQaDAUOGDEFISIhH6xkwYIBCFWmHS7+mBQUFyMzMRN++fXHhwgU8++yzGD58OA4ePIjWrVsDAGbNmoV169ZhxYoVMJlMmD59OsaPH49t27Z55R/gzyRJwqhRo3DnnXd6vB5JkhSqirzJX84HRkZG4vHHH0dycrK6hbiJf/S5xmAw4K677sK4ceM8Wo8ev2tcCsHPP//c6fWyZcvQoUMHFBUVYeDAgTCbzViyZAny8vIwZMgQAMDSpUvRvXt3FBYWol+/fspVrgF6/EDpnb+EoCRJMBgMCAgIULcQ8gl+17jPoz+3zP+7AiDyfzdEFRUVob6+HmlpaY5lunXrhsTERGzfvr3RdVitVlgsFqeBSKt4jyCRtrgdgna7HTNnzsTtt9+OXr16AQAqKioQHByMiIgIp2Wjo6NR0dCr8G/k5OTAZDI5hoSEBHdLIlKdv+wJElHzuB2CmZmZ2L9/P/Lz8z0qIDs7G2az2TGUlZV5tD4iNTEEibTFrevXpk+fjrVr12LLli2Ij493zI+JiUFdXR2qqqqc9gYrKyubvErNaDTCaDS6UwaR3zlzRh4zBIm0waU9QSEEpk+fjtWrV+PLL79Ep06dnN5PTk5GUFAQNm3a5JhXUlKC48ePIzU1VZmKifwY9wSJtMWlPcHMzEzk5eXho48+Qps2bRzn+UwmE0JDQ2EymTBlyhRkZWUhMjIS4eHhmDFjBlJTU3V3ZSjpE0OQSFtcCsHFixcDAAYNGuQ0f+nSpXjooYcAAAsWLIDBYEBGRobTzfJEesAQJNIWl0JQCHHVZUJCQpCbm4vc3Fy3iyLSKoYgkbawWwYihQjBECTSGoYgkULOnwesVnmaN8sTaQNDkEghDXuBQUFAWJi6tRBR8zAEiRRy6T2C7MaRSBsYgkQK4flAIu1hCBIphCFIpD0MQSKFMASJtIchSKSQX36RxwxBIu1gCBIppOFpYU30FU9EfoghSKSQkyflcWysunUQUfMxBIkUUl4ujxmCRNrBECRSyE8/yeO4OHXrIKLmYwgSKaC+/uLh0I4d1a2FiJqPIUikgBMnALsdCAkBoqPVroaImoshSKSAo0flcWIiu0wj0hKGIJECjh2TxzwUSqQtDEEiBTTsCV57rZpVEJGrGIJECmjYE2QIEmlLoNoFtHRCCLVLUJUQwjG0ZA17gv52OFTL7S5p+OSqlttdbxiCXmS327Fx40YUFhaqXYpbCgsLYbfbPVrHDz/8gPnz58NoNCpUVfN8//33sDY85t0H/O2c4NmzZ/Hmm2/i008/VbsUl4WEhGDcuHHo2rWr2qW4zG6349NPP8UvDR3JUrNs3bpVtT8cGIJeJITAF198gb///e9ql6KagwcP4uDBg2qX4VU2G1BWJk/7y+HQs2fP4l//+pfaZbilbdu26Natm2ZDcN26dVi3bp3apVAz8ZwgkYdOngQuXACCgthlmhJ4KJF8iSFI5KGG84EJCUBAgKqlEJGLGIJEHuLtEUTaxRAk8pC/XRRDRM3ncghu2bIFY8aMQVxcHCRJwpo1a5zef+ihhyBJktMwcuRIpeol8jvcEyTSLpdDsKamBr1790Zubm6Ty4wcORLl5eWO4b333vOoSCJ/VlIij7knSKQ9Lt8ikZ6ejvT09CsuYzQaERMT06z1Wa1Wp/u5LBaLqyURqebsWWD7dnl6wAB1ayEi13nlnODmzZvRoUMHdO3aFY8++ihOnz7d5LI5OTkwmUyOISEhwRslEXnF55/L9wn26AFcd53a1RCRqxQPwZEjR2L58uXYtGkTXnrpJRQUFCA9PR02m63R5bOzs2E2mx1DWcNdx0Qa8PHH8njsWHXrICL3KN5jzIQJExzTN954I5KSktC5c2ds3rwZQ4cOvWx5o9Ho8y61iJTw00/A6tXy9F13qVoKEbnJ67dIXHfddWjXrh1KS0u9vSkin8rJAaxW+VzgrbeqXQ0RucPrIXjixAmcPn0asexPilqQEyeAN9+Up+fO5dPkibTK5cOh586dc9qrO3LkCIqLixEZGYnIyEjMnTsXGRkZiImJweHDh/H000/j+uuvx4gRIxQtnEhNL7wA1NUBd9wBDB6sdjVE5C6XQ3DXrl0YfMlvfVZWFgBg8uTJWLx4Mfbu3Yu3334bVVVViIuLw/Dhw/F///d/PO9HLUZhIbBkiTydk6NuLUTkGZdDcNCgQVfs5X39+vUeFUTkz2w2IDNTnn7oISA1VdVyiMhDfJ6gF0mShNtuuw3nz59XuxS37N27F998841Hj7a57rrrMGTIEAQFBSlYmW906tQJYWFhTvNyc4HduwGTCXjpJe9sNzo6Gr///e9x5swZ72zAi6qrq7F+/Xr8/PPPapfiMqPRiPT0dFxzzTVql6I7e/bsUe3h4wxBL5IkCePGjcPo0aPVLsUtr732GgoLC5u8x7M5evfujXnz5qFNmzYKVuYbBoMBAZc8G6m4GPjTn+Tpv/0N6NDBO9tNTEzEnDlzNPlcvWPHjuH777/XZAiGhITgj3/8I+x2u9ql6M7f//53fPvtt6q0PUPQiyRJQkBAgNMXqZYoUbfBYEBQUBCCg4MVqEg91dXAvffKF8OMHQs8+qj3tmUwGGAwaPMBL0FBQZA0eqmsJEkIDORXoq8JIVT9vGvzN43Ih+rr5fN/hw4B8fHAW2/xlgiiloIhSHQFtbXAPfcAq1YBgYHAe+8BUVFqV0VESuG+P1ETzp0Dxo8HNmwAjEbgww+B/v3VroqIlMQ9QaLfsNuBd94BunWTA7B1a+Czz4BRo9SujIiUxhAk+p/6evnRSP36Ab//vdxBdseOwMaN7BWGqKXi4VDSLSGAX34BioqAlSuBNWuAhkdfhoUBzz4LzJoFhISoWiYReRFDkFqUX36R99x++EEOtNOngTNn5J5ejEYgOBgICADKyoCSEqCqyvnn27UDJkwA/t//A2JiVPknEJEPMQRJ0+rr5b4816+Xh6IieQ+vuSRJPuQ5cqR8FejAgfJVoESkD/x1J82pqAA++kg+f/fll4DF4vz+jTfK5/Xat5dvZ4iKkvf+6uouDtdcA3TpAlx/PRAaqs6/g4jUxxAkTaisBFaskIevv3be24uKAoYNA0aMAIYPB+Li1KuTiLSFIUh+zWYDXn0VeO45oKbm4vy+feXuy0aMAPr0kff0iIhcxRAkv7VnDzB1KrBrl/z65puBBx4AMjLk83hERJ5iCJJfev99YNIkeU8wIgJ4+WXgD38ANNqvNBH5KYYg+aXBg4HwcPlc38KFvF2BiLyDIUh+qUMHYP9+XuRCRN7Fg0vktxiARORtDEEiItIthiAREekWQ5CIiHSLIUhERLrFECQiIt1yOQS3bNmCMWPGIC4uDpIkYc2aNU7vCyHw/PPPIzY2FqGhoUhLS8OhQ4eUqpeIiEgxLodgTU0Nevfujdzc3Ebfnz9/PhYtWoR//vOf2LFjB1q3bo0RI0agtrbW42KJiIiU5PLN8unp6UhPT2/0PSEEXnnlFTz33HMYN24cAGD58uWIjo7GmjVrMGHCBM+qJSIiUpCi5wSPHDmCiooKpKWlOeaZTCakpKRg+/btjf6M1WqFxWJxGoiIiHxB0RCsqKgAAERHRzvNj46Odrz3Wzk5OTCZTI4hISFByZKIiIiapHrfodnZ2cjKynK8tlgsXg1CcenTWMlntNrukiSpsl2ttpfWKdHu/Mxoi6IhGPO/rv4rKysRGxvrmF9ZWYmbbrqp0Z8xGo0wGo1KlnEZIQQ2b94Mu93u1e20NFu3bvX4F+vHH3/Eq6++6vX/Y2+Ii4vD6NGjER4e7tPtlpeX45NPPtHkqYGzZ882edTH31mtVnz22WcoLS11ex0BAQEYPHhwk9933mK32/HVV19hz549Pt2uUr7++mvVQlzREOzUqRNiYmKwadMmx4fAYrFgx44dePTRR5XclEuEEFi7di3WrVunWg1aJITw+IO5b98+HDhwQKGKfKtfv37o37+/z0OwrKwM8+bNw7Fjx3y6XaVo9Y/N2tpavP322/j444/dXkdQUBAWLFjg8xC02WxYs2YNXn/9dZ9uVylKfNe4y+UQPHfunNNfSkeOHEFxcTEiIyORmJiImTNn4i9/+QtuuOEGdOrUCX/+858RFxeHu+66S8m6XaZmI+udVr8U1apbCAGbzabZdtMqIQTsdrtH7W6z2VT7nmmon1zjcgju2rULgwcPdrxuOJ83efJkLFu2DE8//TRqamowdepUVFVVoX///vj8888REhKiXNVEREQKcDkEBw0adMW/dCRJwosvvogXX3zRo8KIiIi8jX2HEhGRbjEEiYhItxiCRESkWwxBIiLSLYYgERHpFkOQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItIt1Z8s7wuSJCE5ORk9e/ZUuxTSkM6dO6N169Zql+GWsLAw3HHHHWjXrp3apbisVatWSEhIULsMTTEYDEhJScG5c+fULsVlQggcOHAARUVFqmxfNyF4zz334PHHH1e7FNIQSZIQHBysdhluad++PZ599ln06dNH7VLcEhQUpHYJmmIwGDBhwgTcc889apfiMiEE/vGPf2DPnj2qPA9RFyEIAIGBgTAajZAkSe1SiLyuIcD5HE99kCQJQUFBmvzjQQiBwED1oojnBImISLcYgkREpFsMQSIi0i2GIBER6RZDkIiIdIshSEREusUQJCIi3WIIEhGRbjEEiYhItxiCRESkW4qH4AsvvABJkpyGbt26Kb0ZIiIij3mlw7aePXti48aNFzeiYr9wRERETfFKOgUGBiImJsYbqyYiIlKMV84JHjp0CHFxcbjuuuswadIkHD9+vMllrVYrLBaL00BEROQLiodgSkoKli1bhs8//xyLFy/GkSNHMGDAAFRXVze6fE5ODkwmk2PgwzSJiMhXFA/B9PR03HPPPUhKSsKIESPw6aefoqqqCh988EGjy2dnZ8NsNjuGsrIypUsiIiJqlNevWImIiECXLl1QWlra6PtGoxFGo9HbZRAREV3G6/cJnjt3DocPH0ZsbKy3N0VEROQSxUPwqaeeQkFBAY4ePYpvvvkGd999NwICAnD//fcrvSkiIiKPKH449MSJE7j//vtx+vRptG/fHv3790dhYSHat2+v9KaIiIg8ongI5ufnK71KIiIir2DfoUREpFsMQSIi0i2GIBER6RZDkIiIdIshSEREusUQJCIi3dLFg/6EENi2bRtCQkLULoXoqo4ePYpz5855tA6z2YyVK1fi22+/Vaiqlu/XX3/F0aNHPVqH3W7Hli1blClIRwoLCyGEUGXbklBry02wWCwwmUyKr9dgMCAgIEDx9RIpzW63w2azebyewMBASJKkQEX6IISAzWbz+MuY3zWus9lssNvtiq/XbDYjPDz8isvoYk8QkL9YvNHIRP7qwoULapegS/yu0RaeEyQiIt1iCBIRkW4xBImISLcYgkREpFsMQSIi0i2GIBER6RZDkIiIdIshSEREusUQJCIi3WIIEhGRbjEEiYhItxiCRESkWwxBIiLSLYYgERHpFkOQiIh0iyFIRES65bUQzM3NxbXXXouQkBCkpKTg22+/9damiIiI3OKVEHz//feRlZWFOXPmYPfu3ejduzdGjBiBU6dOeWNzREREbpGEEELplaakpKBv37547bXXAAB2ux0JCQmYMWMGnnnmGadlrVYrrFar47XZbEZiYqLSJRERkc5UVVXBZDJdcRnF9wTr6upQVFSEtLS0ixsxGJCWlobt27dftnxOTg5MJpNjYAASEZESqqurr7pMoNIb/eWXX2Cz2RAdHe00Pzo6Gj/88MNly2dnZyMrK8vxuqqqCh07dsTx48evmuB6ZLFYkJCQgLKyMoSHh6tdjl9h2zSNbXNlbJ+mabFthBCorq5GXFzcVZdVPARdZTQaYTQaL5tvMpk00+BqCA8PZ/s0gW3TNLbNlbF9mqa1tmnuTpTih0PbtWuHgIAAVFZWOs2vrKxETEyM0psjIiJym+IhGBwcjOTkZGzatMkxz263Y9OmTUhNTVV6c0RERG7zyuHQrKwsTJ48GbfccgtuvfVWvPLKK6ipqcHDDz981Z81Go2YM2dOo4dIie1zJWybprFtrozt07SW3jZeuUUCAF577TW8/PLLqKiowE033YRFixYhJSXFG5siIiJyi9dCkIiIyN+x71AiItIthiAREekWQ5CIiHSLIUhERLrldyHIRzABW7ZswZgxYxAXFwdJkrBmzRqn94UQeP755xEbG4vQ0FCkpaXh0KFD6hTrYzk5Oejbty/atGmDDh064K677kJJSYnTMrW1tcjMzERUVBTCwsKQkZFxWecNLdXixYuRlJTk6N0jNTUVn332meN9PbfNpebNmwdJkjBz5kzHPD23zQsvvABJkpyGbt26Od5vyW3jVyHIRzDJampq0Lt3b+Tm5jb6/vz587Fo0SL885//xI4dO9C6dWuMGDECtbW1Pq7U9woKCpCZmYnCwkJs2LAB9fX1GD58OGpqahzLzJo1C5988glWrFiBgoICnDx5EuPHj1exat+Jj4/HvHnzUFRUhF27dmHIkCEYN24cDhw4AEDfbdNg586deOONN5CUlOQ0X+9t07NnT5SXlzuGrVu3Ot5r0W0j/Mitt94qMjMzHa9tNpuIi4sTOTk5KlalLgBi9erVjtd2u13ExMSIl19+2TGvqqpKGI1G8d5776lQobpOnTolAIiCggIhhNwWQUFBYsWKFY5lvv/+ewFAbN++Xa0yVdW2bVvx73//m20jhKiurhY33HCD2LBhg7jjjjvEE088IYTg52bOnDmid+/ejb7X0tvGb/YEXX0Ek14dOXIEFRUVTu1kMpmQkpKiy3Yym80AgMjISABAUVER6uvrndqnW7duSExM1F372Gw25Ofno6amBqmpqWwbAJmZmRg1apRTGwD83ADAoUOHEBcXh+uuuw6TJk3C8ePHAbT8tlH9KRINXH0Ek15VVFQAQKPt1PCeXtjtdsycORO33347evXqBUBun+DgYERERDgtq6f22bdvH1JTU1FbW4uwsDCsXr0aPXr0QHFxsa7bJj8/H7t378bOnTsve0/vn5uUlBQsW7YMXbt2RXl5OebOnYsBAwZg//79Lb5t/CYEiVyVmZmJ/fv3O527IKBr164oLi6G2WzGypUrMXnyZBQUFKhdlqrKysrwxBNPYMOGDQgJCVG7HL+Tnp7umE5KSkJKSgo6duyIDz74AKGhoSpW5n1+cziUj2Bqnoa20Hs7TZ8+HWvXrsVXX32F+Ph4x/yYmBjU1dWhqqrKaXk9tU9wcDCuv/56JCcnIycnB71798bChQt13TZFRUU4deoU+vTpg8DAQAQGBqKgoACLFi1CYGAgoqOjdds2jYmIiECXLl1QWlra4j83fhOCfART83Tq1AkxMTFO7WSxWLBjxw5dtJMQAtOnT8fq1avx5ZdfolOnTk7vJycnIygoyKl9SkpKcPz4cV20T2PsdjusVquu22bo0KHYt28fiouLHcMtt9yCSZMmOab12jaNOXfuHA4fPozY2NiW/7lR+8qcS+Xn5wuj0SiWLVsmDh48KKZOnSoiIiJERUWF2qX5VHV1tdizZ4/Ys2ePACD+8Y9/iD179ohjx44JIYSYN2+eiIiIEB999JHYu3evGDdunOjUqZP49ddfVa7c+x599FFhMpnE5s2bRXl5uWM4f/68Y5lp06aJxMRE8eWXX4pdu3aJ1NRUkZqaqmLVvvPMM8+IgoICceTIEbF3717xzDPPCEmSxBdffCGE0Hfb/NalV4cKoe+2efLJJ8XmzZvFkSNHxLZt20RaWppo166dOHXqlBCiZbeNX4WgEEK8+uqrIjExUQQHB4tbb71VFBYWql2Sz3311VcCwGXD5MmThRDybRJ//vOfRXR0tDAajWLo0KGipKRE3aJ9pLF2ASCWLl3qWObXX38Vjz32mGjbtq1o1aqVuPvuu0V5ebl6RfvQH/7wB9GxY0cRHBws2rdvL4YOHeoIQCH03Ta/9dsQ1HPb3HfffSI2NlYEBweLa665Rtx3332itLTU8X5Lbhs+SomIiHTLb84JEhER+RpDkIiIdIshSEREusUQJCIi3WIIEhGRbjEEiYhItxiCRESkWwxBIiLSLYYgERHpFkOQiIh0iyFIRES69f8BXhqaDRVcu5AAAAAASUVORK5CYII=", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAcEAAAFfCAYAAAA213fbAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/bCgiHAAAACXBIWXMAAA9hAAAPYQGoP6dpAAAvLElEQVR4nO3de1hUdf4H8PcZLgOKDILKJcDMUjTFVlIcUzPFiLxgsXbRWrtsPrZoKbUZbVvZb1vMnm4WuW3ram0Rq6aWWppaYJmYouStSF0vmIDrhQFRRpz5/v44y+gkqDNzZs4czvv1POc5M+cczvn4dZg35/qVhBACREREOmRQuwAiIiK1MASJiEi3GIJERKRbDEEiItIthiAREekWQ5CIiHSLIUhERLoVqHYBv2a323HkyBG0a9cOkiSpXQ4REWmMEAJ1dXWIi4uDwXDpfT2/C8EjR44gISFB7TKIiEjjKioqEB8ff8ll/O5waLt27dQugYiIWoEryRO/C0EeAiUiIiVcSZ74XQgSERH5CkOQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItIthiAREekWQ5CIiHSLIUhERLrFECQiIt1iCBIRkW4xBImISLcYgkREpFsMQSIi0i2PQnDWrFmQJAnTpk1zTGtoaEB2djaioqIQFhaGrKwsVFdXe1onERGR4gLd/cHNmzfj3XffRXJystP06dOnY+XKlVi0aBFMJhOmTJmCO++8Exs2bPC4WE8YDAYYDNzxJaLmCSFgt9shhPBoPWp919hsNo9rlyQJAQEBClV05ex2O+x2u8+3C7gZgqdOncKECRPw3nvv4S9/+YtjusViwbx581BQUIBhw4YBAObPn48ePXqgpKQEAwYMUKZqF0mShMzMTNxyyy2qbJ+I/N+ZM2fw4YcfYseOHW6vw2AwICsrC4MHD1awssuz2WxYsmQJvvnmG4/WM3z4cIwePRqSJClU2ZVZu3Ytli9f7nGIu8OtEMzOzsbIkSORlpbmFIKlpaVobGxEWlqaY1pSUhISExOxcePGZkPQarXCarU63tfW1rpT0iVJkoRBgwZhypQpPv/PJSJtqKmpwYYNGzwOwaFDh+IPf/iDgpVdXmNjI/bu3etxCKakpGDKlCk+3ZMVQuD06dNYsWKFNkKwsLAQW7duxebNmy+aV1VVheDgYERERDhNj46ORlVVVbPry8vLw8yZM10tg4iIyGMuxX1FRQUef/xxfPTRRwgJCVGkgNzcXFgsFsdQUVGhyHqJiIgux6UQLC0txdGjR9G3b18EBgYiMDAQxcXFmDNnDgIDAxEdHY2zZ8+ipqbG6eeqq6sRExPT7DqNRiPCw8OdBiIiIl9w6XDo8OHDLzpe/uCDDyIpKQkzZsxAQkICgoKCsG7dOmRlZQEAysvLcejQIZjNZuWqJiIiUoBLIdiuXTv06tXLaVrbtm0RFRXlmP7www8jJycHkZGRCA8Px9SpU2E2m1W7MpSIiKglbt8n2JLXX3/dcZmw1WpFeno63nnnHaU3Q0RE5DGPQ7CoqMjpfUhICPLz85Gfn+/pqomIiLyKj1AhIiLdYggSEZFuMQSJiEi3GIJERKRbil8dSkSklk2HN+Hn4z+jW1Q3pManql0OaQBDkIhahRlrZmD2d7Md758a+BReHvGyihWRFvBwKBFp3qbDmzD7q78B63OBA3I3RrO/m41NhzepXBn5O4YgEWnez8d/BuwBgDAAZQ84Tye6BB4OJSLN6xbVDWhzErj5pYunE10C9wSJSPNS41Px1MCnnKbNuGkGL46hy+KeIBFpXmMjMDbsZYy+Pwv768p5dShdMYYgEWleWRkwcCAQF9cfhw/3hySpXRFpBQ+HEpHmVVYCHToAv/kNGIDkEu4JEpHmjRkDHD0K1NaqXQlpDfcEiahVkCTAZFK7CtIahiAREekWQ5CINK2wEEhNBd5+W+1KSIsYgkSkaUVFwPffAwcOqF0JaREvjCEiTfvTn4AhQ4AePdSuhLSIIUhEmpaQAIwfr3YVpFUMQS8SQsBms8Fms6ldimoMBgMCAwMh+fjmLZvNhnPnzvl0m6ScwMBABAQEqF0G6QBD0IuEEPjkk0/w5Zdfql2KalJSUvDggw8iNDTUp9v94YcfMG/ePDQ0NPh0u+S5Nm3a4OGHH8YNN9xw2WWXLwfq6oBhw4CYGO/XRq0PQ9CLhBDYvHkz/vnPf6pdimosFgvuu+8+n4fgwYMH8eGHH6KWd09rTkREBEaMGHFFIfjaa/KFMX//O/DII14vjVohhiARadbAgUB9PTBokNqVkFbxFgki0qyXXpJvj+CVoeQul0Jw7ty5SE5ORnh4OMLDw2E2m/HFF1845g8dOhSSJDkNkydPVrxoIiIiJbh0ODQ+Ph6zZs3CddddByEE3n//fWRmZmLbtm24/vrrAQCPPPIIXnzxRcfPtGnTRtmKiYgAVFcDnTqx1wjyjEshOHr0aKf3L730EubOnYuSkhJHCLZp0wYxvEyLiLxICLnbpHPn5AtjevZUuyLSKrfPCdpsNhQWFqK+vh5ms9kx/aOPPkKHDh3Qq1cv5Obm4vTp05dcj9VqRW1trdNARHQpVVXAiRNATQ3QpYva1ZCWuXx16I4dO2A2m9HQ0ICwsDAsXboUPf/3Z9j48ePRuXNnxMXFYfv27ZgxYwbKy8uxZMmSFteXl5eHmTNnuv8vICLdiY0FLBagvBzw8d031Mq4HILdu3dHWVkZLBYLFi9ejIkTJ6K4uBg9e/bEpEmTHMv17t0bsbGxGD58OPbt24euXbs2u77c3Fzk5OQ43tfW1iIhIcGNfwoR6YnRCJw5A/zrX0C3bnJPEkSucjkEg4ODce211wKQnwayefNmvPnmm3j33XcvWjb1f5/KvXv3thiCRqMRRqPR1TKISOeeegp45RXn9y+/rF49pE0e3ydot9thtVqbnVdWVgYAiI2N9XQzREQA5POAAwc6ByAAzJ4NbNqkSkmkYS7tCebm5iIjIwOJiYmoq6tDQUEBioqKsHr1auzbtw8FBQW4/fbbERUVhe3bt2P69OkYMmQIkpOTvVU/EenMxo3y0Jyff+ZhUXKNSyF49OhR/O53v0NlZSVMJhOSk5OxevVqjBgxAhUVFVi7di3eeOMN1NfXIyEhAVlZWXj22We9VTsR6VCvXsBvfwssXnzxvG7dfF8PaZtLIThv3rwW5yUkJKC4uNjjgoiILiUhQT4k+mszZnAvkFzHB2gTkaZ8/jmwdi0QGAgsXAicOsWrQ8l9DEGN8HWntErRat1NtF6/FhkMhhbbvaEBeOwx+fW0acAdd/iuLn/X9LxmT9ehNwxBDRg0aBBGjhypyQ9o9+7dNXsLTGJiIsaPH4+IiAi1S9GVkJAQ9GihW4jZs4F9+4C4OOC553xcmB8LCAjAmDFjEB8f79F6BgwYoMnvGU8wBDUgJSUFTz75JAICAtQuxS1a/aWKi4vD5MmTkZiYqHYpuieEHIAvvCC/f/VVoF07VUvyKwaDAWlpaUhLS/N4XVr9fXUXQ1BD9Pbh9AdKHGIiz5w5A/z+90BBgfz+0UeBu+9WtyZ/xM+pexiCROS3fvwRGD8eKCsDAgKAt96SQ5BIKexZnoj8jhBAfj7Qt68cgFFRwJo1DEBSHvcEicivHD4MPPIIsGqV/D49HZg/X+45gkhp3BMkIr8ghBx2vXrJAWg0AnPmyPcFMgDJW7gnSESqOnYMWLZM7hJp/Xp5WmoqsGABkJSkZmWkBwxBIvKpY8eA0lJ5+PprebDZ5HlGI/Dii8ATT8gXwhB5G0OQiNzW0AD89JPce0PTcOrU+flCAKdPy9Pq6oATJ4Bffrl4PTfcAIwbJ18JevXVvqqeiCFIRC44e1buxqioSB42bgRa6E70kq67DkhJAfr1A8aMAf7XTzeRzzEEieiSTpyQL05Zvly+YKW21nl+ZKR87q5bNzncoqKc54eGyk93CQsDwsPlZU0m39VPdCkMQSK6yLlzwOrVwLx5cvidO3d+XqdOwPDhwNCh8nDddQAfVkJaxRAkIoe9e+XbFBYsAI4cOT+9Vy8gM1M+dHnjjYCBN1dRK8EQJNI5iwX47DN5r+/CfrE7dADuvx946CE5BIlaI4Ygkc4IAfznP/J5vs8+ky9waTrcaTDIT2h56CF5ry84WNVSibyOIUjUyjU0yPfkbdwIfPedPFRXOy+TlARMmAA88ADgYZd0RJrCECRqZQ4flgOvKfS2bgUaG52XCQoCzGb5PN/o0fLFLUR6xBAk0ii7HThwANi5E9ixA/jhB6CkBKiouHjZ6Gg59AYOlIe+feVbF4j0jiFIpAEHDgArVshhd/Cg/P7gQflQ568FBADJyc6hd/XVvI2BqDkMQSI/deAA8I9/yBev7NjR/DLBwUDPnvLVm717A/37y09hadvWp6USaRZDkMjPNDQAr7wC/PWv5/f0DAZg0CBgyBCgSxd5z65zZ3kI5G8xkdv460PkR5p6T9+3T34/ZIjcwWxGxsWPIyMiz7n03Ie5c+ciOTkZ4eHhCA8Ph9lsxhdffOGY39DQgOzsbERFRSEsLAxZWVmo/vW12ETUrDVr5LDbtw+IiwM+/li+h++++xiARN7iUgjGx8dj1qxZKC0txZYtWzBs2DBkZmZi165dAIDp06dj+fLlWLRoEYqLi3HkyBHceeedXimcqDXZuRP47W/lfvXGjZO7J7rnHl7MQuRtLh0OHT16tNP7l156CXPnzkVJSQni4+Mxb948FBQUYNiwYQCA+fPno0ePHigpKcGAAQOaXafVaoX1gr5Yan/9iHqiVq66Ghg5Uu6dYcgQuYd1o1Htqoj0we3H4NpsNhQWFqK+vh5msxmlpaVobGxEWlqaY5mkpCQkJiZi48aNLa4nLy8PJpPJMSQkJLhbEpHmCAH8/vfAoUNyV0RLlzIAiXzJ5RDcsWMHwsLCYDQaMXnyZCxduhQ9e/ZEVVUVgoODERER4bR8dHQ0qqqqWlxfbm4uLBaLY6ho7k5folbqX/+S7/8LDgY++UTum4+IfMflq0O7d++OsrIyWCwWLF68GBMnTkTxhY+ed5HRaISRf/qSDh05Ajz+uPz6+efZUwORGlwOweDgYFx77bUAgJSUFGzevBlvvvkm7r77bpw9exY1NTVOe4PV1dWIiYlRrGA9EkLg3LlzEEKoXYpm2Gw2tUu4JCGASZOAmhq5f76nnrpwnoDNZtPt/7ckSTAYDDBotNNCm82Gxl8/rFUjmtpd0tEVWR7fJ2i322G1WpGSkoKgoCCsW7cOWVlZAIDy8nIcOnQIZrPZ40L1rLi4GE8++aSuPpie+s9//oOG5p4p5ic++ABYuVI+DLpggfMN7wcPHsT8+fNx4sQJ1epTU5s2bXDfffehd+/eapfiMpvNhk8++QQ///yz2qW4ZcSIERg1apSuvmtcCsHc3FxkZGQgMTERdXV1KCgoQFFREVavXg2TyYSHH34YOTk5iIyMRHh4OKZOnQqz2dzilaF0ZX744Qf88MMPapdBCvnll/OHQV94Abj+euf51dXVWLBgAQ4dOuTz2vxBREQEbrrpJk2GoBACxcXFHp0iUlPbtm0xatQotcvwKZdC8OjRo/jd736HyspKmEwmJCcnY/Xq1RgxYgQA4PXXX4fBYEBWVhasVivS09PxzjvveKVwIq3KzZV7c+/XD/jjH9WuhkjfXArBefPmXXJ+SEgI8vPzkZ+f71FRRK3VyZPAwoXy67fe4nM/idSmzTPPRBpVUABYrXJXR/37q10NETEEiXyo6WDKww/zkWhE/oAhSOQjR44A27bJ3SJNmKB2NUQEMASJfKapY9xu3dgrBJG/YAgS+cjOnfKYT4Yh8h8MQSIfadoT1ODtb0StFkOQyEcqK+Xx1VerWgYRXYAhSOQjTd1mhoSoWwcRnccQJPKRs2flcXCwunUQ0XkMQSIfadoTZAgS+Q+GIJGP2O3yOCBA3TqI6DyGIBER6RZDkKgFeupTjWT8P9cfPsNeA1JTUzFixAif/4J+//33+PLLLz3q4bxHjx4YM2YMgjV4IiwhIQHh4eFql+GWiIgI/Pa3v0VsbKzapbgsNDQU3bp18/l2Q0JCcNdddyE5Odnn2/aU3W7H6tWrsWXLFrVL0RyGoAYMGDAAzz33HAJ93O/OnDlzsHbtWthsNrfX0aNHD+Tm5mo2TJTky79h2rdvj0mTJuHGG2/03UY1zmg04t5771W7DLecO3cOJ0+eZAi6gSGoEZIkafJQTVPdWqxdy9jurtN6W2m9frXwnCAREekWQ5DIR5pukSAi/8EQJPKR//5XHrMbJSL/wRAk8gGbDaiull/HxalbCxGdxxAk8oH//lcOQkkCOnVSuxoiasIQJPKBgwflcUwM4OM7XYjoEhiCRD6wdas81uB92EStGkOQyAeaQjAlRd06iMiZSyGYl5eHfv36oV27dujUqRPGjh2L8vJyp2WGDh3qdKOuJEmYPHmyokUTaU1pqTzu21fdOojImUshWFxcjOzsbJSUlGDNmjVobGzErbfeivr6eqflHnnkEVRWVjqG2bNnK1o0kZY0NgI7d8qvGYJE/sWlU/SrVq1yer9gwQJ06tQJpaWlGDJkiGN6mzZtEBMTo0yFRBq3Z48chGFhQOfOaldDRBfy6JygxWIBAERGRjpN/+ijj9ChQwf06tULubm5OH36dIvrsFqtqK2tdRqIWpMdO+Rxr16AgWfhifyK2xdr2+12TJs2DTfddBN69erlmD5+/Hh07twZcXFx2L59O2bMmIHy8nIsWbKk2fXk5eVh5syZ7pZB5PcuDEEi8i9uh2B2djZ27tyJb7/91mn6pEmTHK979+6N2NhYDB8+HPv27UPXrl0vWk9ubi5ycnIc72tra5GQkOBuWUR+Z906edyvn7p1ENHF3ArBKVOmYMWKFVi/fj3i4+MvuWxqaioAYO/evc2GoNFohNFodKcMIr9XXQ1s2iS/HjlS3VqI6GIuhaAQAlOnTsXSpUtRVFSELl26XPZnysrKAECTPVwTeWrlSkAI+f7Aq65Suxoi+jWXQjA7OxsFBQX49NNP0a5dO1RVVQEATCYTQkNDsW/fPhQUFOD2229HVFQUtm/fjunTp2PIkCFI5qMySIdWrJDHo0erWwcRNc+lEJw7dy4A+Yb4C82fPx8PPPAAgoODsXbtWrzxxhuor69HQkICsrKy8OyzzypWMJFWNDYCa9fKr3kolMg/uXw49FISEhJQXFzsUUFErUVJCVBXJ/cfyJvkifwT71oi8pLVq+XxiBG8P5DIX/FXk8hLSkrk8fDh6tZBRC1jCBJ5yYED8rh7d1XLIKJLYAgSeYHdDhw6JL/m80KJ/BdDkMgLKivlq0MDA4G4OLWrIaKWMASJvKDpUGh8vByEROSfGIJEXnDwoDy++mpVyyCiy+DfqNQqCSEue1/rlZAkCZIkufxzTXuCaoWgEAJ2ux12u12dAjzkbrt7Qu3PDKmDIUit0q5du7Bw4UJYrVa315GYmIjx48ejffv2Lv9sUwiqdVHMiRMnkJ+fr8nOrUNDQ3HXXXehZ8+ePt1uQ0MDFi5ciN27d7u9DoPBgDFjxsBsNitYGXkTQ5BapT179uDNN9/0qJPmAQMGYPTo0W6FYNPhULVC0GKx4IMPPlBn4x6KiIhA3759fR6CVqsVS5YswWeffeb2OgIDA5GQkMAQ1BCeEyTyArUPhxLRlWEIEilMiPP3CDIEifwbQ5BIYdXVQEOD/LzQy/Q5TUQqYwgSKezIEXkcHQ0EBalbCxFdGkOQSGFNIRgbq24dRHR5DEEihVVWymOGIJH/YwgSKayqSh4zBIn8H0OQSGHHjsnjjh3VrYOILo8hSKSw48flcVSUunUQ0eUxBIkUxhAk0g6GIJHCmkIwMlLdOojo8hiCRArjniCRdjAEiRTGECTSDoYgkYLOnQMsFvk1Q5DI/zEEiRR08uT51270wEREPuZSf4J5eXlYsmQJfvrpJ4SGhmLgwIF4+eWX0b17d8cyDQ0NeOKJJ1BYWAir1Yr09HS88847iI6OVrx4fydJEm6++WaP1zN48GAYDPx7RQuaDoVGRACBKvbWaTKZMGrUKM12qtu1a1e1y9AUg8GAYcOGISQkxKP1DB48WKGKtMOlX9Pi4mJkZ2ejX79+OHfuHJ555hnceuut2L17N9q2bQsAmD59OlauXIlFixbBZDJhypQpuPPOO7Fhwwav/AP8mSRJGDlyJG6//XaP1yNJkkJVkTf5y/nAyMhIPPbYY0hJSVG3EDfxjz7XGAwGjB07FpmZmR6tR4/fNS6F4KpVq5zeL1iwAJ06dUJpaSmGDBkCi8WCefPmoaCgAMOGDQMAzJ8/Hz169EBJSQkGDBigXOUaoMcPlN75SwhKkgSDwYCAgAB1CyGf4HeN+zz6c8vyvysAIv93Q1RpaSkaGxuRlpbmWCYpKQmJiYnYuHFjs+uwWq2ora11Goi0ivcIEmmL2yFot9sxbdo03HTTTejVqxcAoKqqCsHBwYiIiHBaNjo6GlVNTxX+lby8PJhMJseQkJDgbklEqvOXPUEiujJuh2B2djZ27tyJwsJCjwrIzc2FxWJxDBUVFR6tj0hNDEEibXHr+rUpU6ZgxYoVWL9+PeLj4x3TY2JicPbsWdTU1DjtDVZXV7d4lZrRaITRaHSnDCK/c+KEPGYIEmmDS3uCQghMmTIFS5cuxVdffYUuXbo4zU9JSUFQUBDWrVvnmFZeXo5Dhw7BbDYrUzGRH+OeIJG2uLQnmJ2djYKCAnz66ado166d4zyfyWRCaGgoTCYTHn74YeTk5CAyMhLh4eGYOnUqzGaz7q4MJX1iCBJpi0shOHfuXADA0KFDnabPnz8fDzzwAADg9ddfh8FgQFZWltPN8kR6wBAk0haXQlAIcdllQkJCkJ+fj/z8fLeLItIqhiCRtvCxDEQKEYIhSKQ1DEEihZw+DVit8mveLE+kDQxBIoU07QUGBQFhYerWQkRXhiFIpJAL7xHkYxyJtIEhSKQQng8k0h6GIJFCGIJE2sMQJFIIQ5BIexiCRAo5dkweMwSJtIMhSKSQpt7CWnhWPBH5IYYgkUKOHJHHsbHq1kFEV44hSKSQykp5zBAk0g6GIJFCfvlFHsfFqVsHEV05hiCRAhobzx8O7dxZ3VqI6MoxBIkUcPgwYLcDISFAdLTa1RDRlWIIEingwAF5nJjIR6YRaQlDkEgBBw/KYx4KJdIWhiCRApr2BK++Ws0qiMhVDEEiBTTtCTIEibQlUO0CWjshhNolqEoI4Rhas6Y9QX87HKrldpc0fHJVy+2uNwxBL7Lb7Vi7di1KSkrULsUtJSUlsNvtHq3jp59+wuzZs2E0GhWq6sr8+OOPsDZ18+4D/nZO8OTJk3jvvffw+eefq12Ky0JCQpCZmYnu3burXYrL7HY7Pv/8cxxrepAsXZFvv/1WtT8cGIJeJITAl19+iVdffVXtUlSze/du7N69W+0yvMpmAyoq5Nf+cjj05MmT+Pvf/652GW5p3749kpKSNBuCK1euxMqVK9Uuha4QzwkSeejIEeDcOSAoiI9MUwIPJZIvMQSJPNR0PjAhAQgIULUUInIRQ5DIQ7w9gki7GIJEHvK3i2KI6Mq5HILr16/H6NGjERcXB0mSsGzZMqf5DzzwACRJchpuu+02peol8jvcEyTSLpdDsL6+Hn369EF+fn6Ly9x2222orKx0DB9//LFHRRL5s/Jyecw9QSLtcfkWiYyMDGRkZFxyGaPRiJiYmCtan9Vqdbqfq7a21tWSiFRz8iSwcaP8evBgdWshItd55ZxgUVEROnXqhO7du+PRRx/F8ePHW1w2Ly8PJpPJMSQkJHijJCKvWLVKvk+wZ0/gmmvUroaIXKV4CN5222344IMPsG7dOrz88ssoLi5GRkYGbDZbs8vn5ubCYrE4hoqmu46JNOCzz+TxmDHq1kFE7lH8iTH33HOP43Xv3r2RnJyMrl27oqioCMOHD79oeaPR6PNHahEp4ZdfgKVL5ddjx6paChG5yeu3SFxzzTXo0KED9u7d6+1NEflUXh5gtcrnAvv3V7saInKH10Pw8OHDOH78OGL5PClqRQ4fBt57T349cyZ7kyfSKpcPh546dcppr27//v0oKytDZGQkIiMjMXPmTGRlZSEmJgb79u3DU089hWuvvRbp6emKFk6kphdeAM6eBW6+GbjlFrWrISJ3uRyCW7ZswS0X/Nbn5OQAACZOnIi5c+di+/bteP/991FTU4O4uDjceuut+L//+z+e96NWo6QEmDdPfp2Xp24tROQZl0Nw6NChl3zK++rVqz0qiMif2WxAdrb8+oEHALNZ1XKIyEPsT9CLJEnCwIEDcfr0abVLccv27dvx3XffedS1zTXXXINhw4YhKChIwcp8o0uXLggLC3Oalp8PbN0KmEzAyy97Z7vR0dG4//77ceLECe9swIvq6uqwevVq/Pe//1W7FJcZjUZkZGTgqquuUrsU3dm2bZtqnY8zBL1IkiRkZmZi1KhRapfilrfffhslJSUt3uN5Jfr06YNZs2ahXbt2ClbmGwaDAQEX9I1UVgb88Y/y67/+FejUyTvbTUxMxPPPP6/JfvUOHjyIH3/8UZMhGBISgt///vew2+1ql6I7r776Kr7//ntV2p4h6EWSJCEgIMDpi1RLlKjbYDAgKCgIwcHBClSknro64K675IthxowBHn3Ue9syGAwwGLTZwUtQUBAkjV4qK0kSAgP5lehrQghVP+/a/E0j8qHGRvn83549QHw88M9/8pYIotaCIUh0CQ0NwLhxwJIlQGAg8PHHQFSU2lURkVK470/UglOngDvvBNasAYxG4JNPgEGD1K6KiJTEPUGiX7HbgQ8/BJKS5ABs2xb44gtg5Ei1KyMipTEEif6nsVHuGmnAAOD+++UHZHfuDKxdy6fCELVWPBxKuiUEcOwYUFoKLF4MLFsGNHV9GRYGPPMMMH06EBKiaplE5EUMQWpVjh2T99x++kkOtOPHgRMn5Ce9GI1AcDAQEABUVADl5UBNjfPPd+gA3HMP8Kc/ATExqvwTiMiHGIKkaY2N8rM8V6+Wh9JSeQ/vSkmSfMjzttvkq0CHDJGvAiUifeCvO2lOVRXw6afy+buvvgJqa53n9+4tn9fr2FG+nSEqSt77O3v2/HDVVUC3bsC11wKhoer8O4hIfQxB0oTqamDRInn45hvnvb2oKGDECCA9Hbj1ViAuTr06iUhbGILk12w24K23gGefBerrz0/v109+fFl6OtC3r7ynR0TkKoYg+a1t24BJk4AtW+T3v/kNcN99QFaWfB6PiMhTDEHyS//+NzBhgrwnGBEBvPIK8NBDgEafK01EfoohSH7plluA8HD5XN+bb/J2BSLyDoYg+aVOnYCdO3mRCxF5Fw8ukd9iABKRtzEEiYhItxiCRESkWwxBIiLSLYYgERHpFkOQiIh0y+UQXL9+PUaPHo24uDhIkoRly5Y5zRdC4LnnnkNsbCxCQ0ORlpaGPXv2KFUvERGRYlwOwfr6evTp0wf5+fnNzp89ezbmzJmDv/3tb9i0aRPatm2L9PR0NDQ0eFwsERGRkly+WT4jIwMZGRnNzhNC4I033sCzzz6LzMxMAMAHH3yA6OhoLFu2DPfcc49n1RIRESlI0XOC+/fvR1VVFdLS0hzTTCYTUlNTsXHjxmZ/xmq1ora21mkgIiLyBUVDsKqqCgAQHR3tND06Otox79fy8vJgMpkcQ0JCgpIlERERtUj1Z4fm5uYiJyfH8b62ttarQSgu7I2VfEar7S5Jkirb1Wp7aZ0S7c7PjLYoGoIx/3vUf3V1NWJjYx3Tq6urccMNNzT7M0ajEUajUckyLiKEQFFREex2u1e309p8++23Hv9i/fzzz3jrrbe8/n/sDXFxcRg1ahTCw8N9ut3KykosX75ck6cGTp482eJRH39ntVrxxRdfYO/evW6vIyAgALfcckuL33feYrfb8fXXX2Pbtm0+3a5SvvnmG9VCXNEQ7NKlC2JiYrBu3TrHh6C2thabNm3Co48+quSmXCKEwIoVK7By5UrVatAiIYTHH8wdO3Zg165dClXkWwMGDMCgQYN8HoIVFRWYNWsWDh486NPtKkWrf2w2NDTg/fffx2effeb2OoKCgvD666/7PARtNhuWLVuGd955x6fbVYoS3zXucjkET5065fSX0v79+1FWVobIyEgkJiZi2rRp+Mtf/oLrrrsOXbp0wZ///GfExcVh7NixStbtMjUbWe+0+qWoVt1CCNhsNs22m1YJIWC32z1qd5vNptr3TFP95BqXQ3DLli245ZZbHO+bzudNnDgRCxYswFNPPYX6+npMmjQJNTU1GDRoEFatWoWQkBDlqiYiIlKAyyE4dOjQS/6lI0kSXnzxRbz44oseFUZERORtfHYoERHpFkOQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItIthiAREekWQ5CIiHSLIUhERLrFECQiIt1SvWd5X5AkCSkpKbj++uvVLoU0pGvXrmjbtq3aZbglLCwMN998Mzp06KB2KS5r06YNEhIS1C5DUwwGA1JTU3Hq1Cm1S3GZEAK7du1CaWmpKtvXTQiOGzcOjz32mNqlkIZIkoTg4GC1y3BLx44d8cwzz6Bv375ql+KWoKAgtUvQFIPBgHvuuQfjxo1TuxSXCSHw2muvYdu2bar0h6iLEASAwMBAGI1GSJKkdilEXtcU4OzHUx8kSUJQUJAm/3gQQiAwUL0o4jlBIiLSLYYgERHpFkOQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItIthiAREemW4iH4wgsvQJIkpyEpKUnpzRAREXnMKw9su/7667F27drzG1HxuXBEREQt8Uo6BQYGIiYmxhurJiIiUoxXzgnu2bMHcXFxuOaaazBhwgQcOnSoxWWtVitqa2udBiIiIl9QPARTU1OxYMECrFq1CnPnzsX+/fsxePBg1NXVNbt8Xl4eTCaTY2BnmkRE5CuKh2BGRgbGjRuH5ORkpKen4/PPP0dNTQ0WLlzY7PK5ubmwWCyOoaKiQumSiIiImuX1K1YiIiLQrVs37N27t9n5RqMRRqPR22UQERFdxOv3CZ46dQr79u1DbGystzdFRETkEsVD8Mknn0RxcTEOHDiA7777DnfccQcCAgJw7733Kr0pIiIijyh+OPTw4cO49957cfz4cXTs2BGDBg1CSUkJOnbsqPSmiIiIPKJ4CBYWFiq9SiIiIq/gs0OJiEi3GIJERKRbDEEiItIthiAREekWQ5CIiHSLIUhERLqli47+hBDYsGEDQkJC1C6F6LIOHDiAU6dOebQOi8WCxYsX4/vvv1eoqtbvzJkzOHDggEfrsNvtWL9+vTIF6UhJSQmEEKpsWxJqbbkFtbW1MJlMiq/XYDAgICBA8fUSKc1ut8Nms3m8nsDAQEiSpEBF+iCEgM1m8/jLmN81rrPZbLDb7Yqv12KxIDw8/JLL6GJPEJC/WLzRyET+6ty5c2qXoEv8rtEWnhMkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItIthiAREekWQ5CIiHSLIUhERLrFECQiIt1iCBIRkW4xBImISLcYgkREpFsMQSIi0i2GIBER6RZDkIiIdIshSEREuuW1EMzPz8fVV1+NkJAQpKam4vvvv/fWpoiIiNzilRD897//jZycHDz//PPYunUr+vTpg/T0dBw9etQbmyMiInKLJIQQSq80NTUV/fr1w9tvvw0AsNvtSEhIwNSpU/H00087LWu1WmG1Wh3vLRYLEhMTlS6JiIh0pqamBiaT6ZLLKL4nePbsWZSWliItLe38RgwGpKWlYePGjRctn5eXB5PJ5BgYgEREpIS6urrLLhOo9EaPHTsGm82G6Ohop+nR0dH46aefLlo+NzcXOTk5jvc1NTXo3LkzDh06dNkE16Pa2lokJCSgoqIC4eHhapfjV9g2LWPbXBrbp2VabBshBOrq6hAXF3fZZRUPQVcZjUYYjcaLpptMJs00uBrCw8PZPi1g27SMbXNpbJ+Waa1trnQnSvHDoR06dEBAQACqq6udpldXVyMmJkbpzREREblN8RAMDg5GSkoK1q1b55hmt9uxbt06mM1mpTdHRETkNq8cDs3JycHEiRNx4403on///njjjTdQX1+PBx988LI/azQa8fzzzzd7iJTYPpfCtmkZ2+bS2D4ta+1t45VbJADg7bffxiuvvIKqqirccMMNmDNnDlJTU72xKSIiIrd4LQSJiIj8HZ8dSkREusUQJCIi3WIIEhGRbjEEiYhIt/wuBNkFE7B+/XqMHj0acXFxkCQJy5Ytc5ovhMBzzz2H2NhYhIaGIi0tDXv27FGnWB/Ly8tDv3790K5dO3Tq1Aljx45FeXm50zINDQ3Izs5GVFQUwsLCkJWVddHDG1qruXPnIjk52fF0D7PZjC+++MIxX89tc6FZs2ZBkiRMmzbNMU3PbfPCCy9AkiSnISkpyTG/NbeNX4Ugu2CS1dfXo0+fPsjPz292/uzZszFnzhz87W9/w6ZNm9C2bVukp6ejoaHBx5X6XnFxMbKzs1FSUoI1a9agsbERt956K+rr6x3LTJ8+HcuXL8eiRYtQXFyMI0eO4M4771Sxat+Jj4/HrFmzUFpaii1btmDYsGHIzMzErl27AOi7bZps3rwZ7777LpKTk52m671trr/+elRWVjqGb7/91jGvVbeN8CP9+/cX2dnZjvc2m03ExcWJvLw8FatSFwCxdOlSx3u73S5iYmLEK6+84phWU1MjjEaj+Pjjj1WoUF1Hjx4VAERxcbEQQm6LoKAgsWjRIscyP/74owAgNm7cqFaZqmrfvr34xz/+wbYRQtTV1YnrrrtOrFmzRtx8883i8ccfF0Lwc/P888+LPn36NDuvtbeN3+wJutoFk17t378fVVVVTu1kMpmQmpqqy3ayWCwAgMjISABAaWkpGhsbndonKSkJiYmJumsfm82GwsJC1NfXw2w2s20AZGdnY+TIkU5tAPBzAwB79uxBXFwcrrnmGkyYMAGHDh0C0PrbRvVeJJq42gWTXlVVVQFAs+3UNE8v7HY7pk2bhptuugm9evUCILdPcHAwIiIinJbVU/vs2LEDZrMZDQ0NCAsLw9KlS9GzZ0+UlZXpum0KCwuxdetWbN68+aJ5ev/cpKamYsGCBejevTsqKysxc+ZMDB48GDt37mz1beM3IUjkquzsbOzcudPp3AUB3bt3R1lZGSwWCxYvXoyJEyeiuLhY7bJUVVFRgccffxxr1qxBSEiI2uX4nYyMDMfr5ORkpKamonPnzli4cCFCQ0NVrMz7/OZwKLtgujJNbaH3dpoyZQpWrFiBr7/+GvHx8Y7pMTExOHv2LGpqapyW11P7BAcH49prr0VKSgry8vLQp08fvPnmm7pum9LSUhw9ehR9+/ZFYGAgAgMDUVxcjDlz5iAwMBDR0dG6bZvmREREoFu3bti7d2+r/9z4TQiyC6Yr06VLF8TExDi1U21tLTZt2qSLdhJCYMqUKVi6dCm++uordOnSxWl+SkoKgoKCnNqnvLwchw4d0kX7NMdut8Nqteq6bYYPH44dO3agrKzMMdx4442YMGGC47Ve26Y5p06dwr59+xAbG9v6PzdqX5lzocLCQmE0GsWCBQvE7t27xaRJk0RERISoqqpSuzSfqqurE9u2bRPbtm0TAMRrr70mtm3bJg4ePCiEEGLWrFkiIiJCfPrpp2L79u0iMzNTdOnSRZw5c0blyr3v0UcfFSaTSRQVFYnKykrHcPr0accykydPFomJieKrr74SW7ZsEWazWZjNZhWr9p2nn35aFBcXi/3794vt27eLp59+WkiSJL788kshhL7b5tcuvDpUCH23zRNPPCGKiorE/v37xYYNG0RaWpro0KGDOHr0qBCidbeNX4WgEEK89dZbIjExUQQHB4v+/fuLkpIStUvyua+//loAuGiYOHGiEEK+TeLPf/6ziI6OFkajUQwfPlyUl5erW7SPNNcuAMT8+fMdy5w5c0b84Q9/EO3btxdt2rQRd9xxh6isrFSvaB966KGHROfOnUVwcLDo2LGjGD58uCMAhdB32/zar0NQz21z9913i9jYWBEcHCyuuuoqcffdd4u9e/c65rfmtmFXSkREpFt+c06QiIjI1xiCRESkWwxBIiLSLYYgERHpFkOQiIh0iyFIRES6xRAkIiLdYggSEZFuMQSJiEi3GIJERKRbDEEiItKt/wenGK0WSnYxnQAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Compute the inflation radius (in grid units) and apply\n", + "inflation_radius = args.inflation_radius_m / args.base_resolution\n", + "inflated_known_grid = gridmap.utils.inflate_grid(\n", + " known_map, inflation_radius=inflation_radius)\n", + "\n", + "# Define the robot\n", + "robot = lsp.robot.Turtlebot_Robot(\n", + " pose,\n", + " primitive_length=args.step_size,\n", + " num_primitives=args.num_primitives,\n", + " map_data=map_data)\n", + "\n", + "counter = 0\n", + "\n", + "# Planning loop: iteratively move the robot and replan\n", + "while (math.fabs(robot.pose.x - goal.x) >= 3 * args.step_size\n", + " or math.fabs(robot.pose.y - goal.y) >= 3 * args.step_size):\n", + " # Compute the cost grid for the current robot pose\n", + " cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position(\n", + " inflated_known_grid, [goal.x, goal.y], use_soft_cost=True)\n", + " did_plan, path = get_path([robot.pose.x, robot.pose.y],\n", + " do_sparsify=True, do_flip=True)\n", + "\n", + " # Plotting (plot every 5 steps)\n", + " if counter % 5 == 0:\n", + " plt.ion()\n", + " plt.figure(1, figsize=(12, 4))\n", + " plt.clf()\n", + "\n", + " lsp.utils.plotting.plot_navigation_data(\n", + " plt.gca(), known_map, map_data=map_data, \n", + " robot_pose=robot.pose_m, \n", + " goal_pose=args.base_resolution*goal,\n", + " planned_path=path,\n", + " robot_poses=robot.all_poses)\n", + "\n", + " plt.show()\n", + "\n", + " # Get the motion primitives: primitive motions the robot can execute\n", + " motion_primitives = robot.get_motion_primitives()\n", + " \n", + " # Pick the \"min cost\" primitive, which best moves along the path\n", + " costs, _ = lsp.primitive.get_motion_primitive_costs(\n", + " inflated_known_grid, cost_grid, robot.pose, path,\n", + " motion_primitives, do_use_path=True)\n", + " best_primitive_index = np.argmin(costs)\n", + " \n", + " # Move according to that primitive action\n", + " robot.move(motion_primitives, np.argmin(costs))\n", + "\n", + " # Update counter\n", + " counter += 1\n", + "\n", + "None" + ] + }, + { + "cell_type": "markdown", + "id": "785767b0", + "metadata": {}, + "source": [ + "# Next Steps\n", + "\n", + "In [the next tutorial](./RAIL-onboarding-02-visual-simulator.ipynb), we'll explore using the *visual simulator*, which we use to generate images onboard the robot. While those images won'be be used for anything just yet, they will eventually serve as inputs to the learned models the robot uses to inform its behavior." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "32765b1a", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/resources/notebooks/RAIL-onboarding-02-visual-simulator.ipynb b/resources/notebooks/RAIL-onboarding-02-visual-simulator.ipynb new file mode 100644 index 0000000..26e67cf --- /dev/null +++ b/resources/notebooks/RAIL-onboarding-02-visual-simulator.ipynb @@ -0,0 +1,395 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "7c1c9baa", + "metadata": {}, + "source": [ + "# RAIL Onboarding 02: The Visual Simulator\n", + "\n", + "Previous Tutorial: [RAIL Onboarding 01: Navigation in a Known Grid](./RAIL-onboarding-01-known-space-navigation.ipynb)\n", + "\n", + "**Goal**: to run our Unity visual simulator corresponding to a procedurally generated map.\n", + "\n", + "### Imports and Setup\n", + "\n", + "These imports are effectively the same as in the previous tutoial, and for clarity we will use the same arguments." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "id": "35ae822f", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Python Version and System Information\n", + "3.8.10 (default, May 26 2023, 14:05:08) \n", + "[GCC 9.4.0]\n" + ] + } + ], + "source": [ + "# Imports & Setup (same as the previous tutorial)\n", + "\n", + "import common\n", + "import environments\n", + "import lsp\n", + "import matplotlib.pyplot as plt\n", + "import numpy as np\n", + "import os\n", + "import math\n", + "import gridmap\n", + "import sys\n", + "\n", + "print(\"Python Version and System Information\")\n", + "print(sys.version)\n", + "\n", + "# Set the arguments (usually done via the command line)\n", + "args = lambda: None\n", + "args.current_seed = 2005\n", + "args.map_type = 'maze'\n", + "args.unity_path = '/unity/rail_sim.x86_64'\n", + "args.save_dir = './'\n", + "\n", + "# Robot Arguments\n", + "args.step_size = 1.8\n", + "args.num_primitives = 32\n", + "args.laser_scanner_num_points = 1024\n", + "args.field_of_view_deg = 360\n", + "\n", + "known_map, map_data, pose, goal = environments.generate.map_and_poses(args)" + ] + }, + { + "cell_type": "markdown", + "id": "3856bb6a", + "metadata": {}, + "source": [ + "## Spinning Up the Visual Simulator\n", + "\n", + "Our simulation environment is built in the Unity game engine and called in the background by Python so that we can communicate with it over TCP. From Python, we instantiate an object via a helper class `WorldBuildingUnityBridge` from `environments.simulated` and using a python `with` statement, which requires a path to the Unity environment (set to `/unity/rail-sim.x86_64` within the Docker container running this tutorial).\n", + "\n", + "Let's see what the simulator looks like when we simply load it and ask for an image:" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "8ba8486c", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "## Create the Unity Bridge, which talks to the visual simulator\n", + "builder = environments.simulated.WorldBuildingUnityBridge\n", + "\n", + "# Open the simulator and generate an image\n", + "with builder(args.unity_path) as unity_bridge:\n", + " # Move the robot and generate a simulated image\n", + " unity_bridge.move_object_to_pose(\"robot\", common.Pose(0, 0))\n", + " pano_image = unity_bridge.get_image(\"robot/pano_camera\")\n", + " \n", + " # Plotting\n", + " plt.imshow(pano_image)\n", + " plt.title(\"Simulated Pano Image (of an empty universe)\")\n", + " plt.show()" + ] + }, + { + "cell_type": "markdown", + "id": "02f4d0da", + "metadata": {}, + "source": [ + "You should see... basically nothing. The output is just a blue rectangle. That's because without any instructions the simulated environment is a blank canvas. **We need to add stuff to the scene!**\n", + "\n", + "For this purpose, we provide helper classes—also in `environments.simulated`—that communicate information about our generated map to the visual simulator. We instantiate one of these `World` subclass objects, specifically an `OccupancyGridWorld` meant to build a visual simulator instance from an occupancy grid, and then call `unity_bridge.make_world(world)` to populate the simulator. We move the simulated robo into place and then collect the images we want." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "a4a19f4e", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "## Create the Unity Bridge, which talks to the visual simulator\n", + "builder = environments.simulated.WorldBuildingUnityBridge\n", + "\n", + "# A helper object for passing map data to the simulator\n", + "world = environments.simulated.OccupancyGridWorld(\n", + " known_map, map_data,\n", + " num_breadcrumb_elements=args.num_breadcrumb_elements,\n", + " min_breadcrumb_signed_distance=4.0 * args.base_resolution)\n", + "\n", + "# Open the simulator and generate an image\n", + "with builder(args.unity_path) as unity_bridge:\n", + " # Populate the simulated world with objects via the 'world'\n", + " # helper object.\n", + " unity_bridge.make_world(world)\n", + " \n", + " # Move the robot into place\n", + " unity_bridge.move_object_to_pose(\"robot\", args.base_resolution * pose)\n", + " \n", + " # Generate a simulated images\n", + " pano_image = unity_bridge.get_image(\"robot/pano_camera\")\n", + " pano_depth = environments.utils.convert.depths_from_depth_image(\n", + " unity_bridge.get_image(\"robot/pano_depth_camera\"))\n", + " pano_seg = unity_bridge.get_image(\"robot/pano_segmentation_camera\")\n", + " \n", + " # Plotting\n", + " ax = plt.subplot(221)\n", + " plt.imshow(pano_image)\n", + " plt.title(\"Sim Robot's Pano Image\")\n", + " \n", + " raw_depth_image = unity_bridge.get_image(\"robot/pano_depth_camera\")\n", + " ax = plt.subplot(222)\n", + " plt.imshow(pano_depth)\n", + " plt.title(\"Depth Image\")\n", + " \n", + " segmentation_image = unity_bridge.get_image(\"robot/pano_segmentation_camera\")\n", + " ax = plt.subplot(223)\n", + " plt.imshow(pano_seg)\n", + " plt.title(\"Segmentation Image\")\n", + " \n", + " ax = plt.subplot(224)\n", + " lsp.utils.plotting.plot_navigation_data(\n", + " ax, known_map, map_data=map_data, \n", + " robot_pose=args.base_resolution*pose)\n", + " plt.title(\"Robot at blue dot\")\n", + "\n", + "None" + ] + }, + { + "cell_type": "markdown", + "id": "c812e117", + "metadata": {}, + "source": [ + "Now we can see much more! In addition to plotting an RGB \"camera\" image, we can also generate depth and semantic segmentation, both useful for downstream applications. All images are *equirectangular projections*, and so contain full panoramic and \"up-down\" information at the location of the robot. Often, we crop off the top and bottom, keeping on the middle vertical \"half\" of the image, since the ceiling and floor are not so often useful for our purposes." + ] + }, + { + "cell_type": "markdown", + "id": "3b85a56a", + "metadata": {}, + "source": [ + "## Generating Observations During Navigation\n", + "\n", + "With our newfound capabilities, we can augment the code from the previous tutorial to also include generating images. Thus the simulated robot will move from start to goal and generate images as it does." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "id": "0724a7cb", + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAvEAAAEHCAYAAAAnGxl4AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/bCgiHAAAACXBIWXMAAA9hAAAPYQGoP6dpAACafUlEQVR4nOy9e5wcVZ33/z6nqi9zTyaXmYQkELkYUCCSkBBB5BLJIroi8XlgYTWyrLxkExbI/lbMPgrKuoJ4y6LRuPso6CoPLOsCgm4UwxJWCSEEUa7hTgJhJte5T3dX1Tm/P+rS1T0918xMTyfnzavormufOlU1+Zxvfc73CK21xmAwGAwGg8FgMFQMstwFMBgMBoPBYDAYDMPDiHiDwWAwGAwGg6HCMCLeYDAYDAaDwWCoMIyINxgMBoPBYDAYKgwj4g0Gg8FgMBgMhgrDiHiDwWAwGAwGg6HCMCLeYDAYDAaDwWCoMIyINxgMBoPBYDAYKgwj4g0Gg8FgMBgMhgrDiHiDwWAwGAwGg6HCKKuIX7duHUcddRTpdJrFixfzxBNPlLM4BoPBYDAYDAZDRVA2EX/33XezevVqbrzxRp566ilOPvlkli1bxu7du8tVJIPBYDAYDAaDoSIQWmtdjh9evHgxp556Kt/97ncBUEoxe/Zsrr76aj7/+c+Xo0gGg8FgMBgMBkNFYJfjR3O5HNu2bWPNmjXRMiklS5cuZfPmzX22z2azZLPZaF4pxf79+5kyZQpCiHEps8FQyWit6ezsZObMmUhpusIYDAaDwVDplEXE7927F8/zaGpqKlje1NTEiy++2Gf7m2++mS9/+cvjVTyD4ZBl586dzJo1q9zFMBgMBoPBcJCURcQPlzVr1rB69epovr29nTlz5vDZFWeRTNqgQaPR2o84ag1oHXyPL89PSgXfw/+Kt1OxY/mHI/ih+AKCpaURIBDRdxAIQWwSCCn8TwFSCATC/xQSKYP1UiClPy+lRAqBJaU/WRIpJZZtYVkWliWxLYm0JJZlYVsWlm1hy+AzYWHbNrZlk0jY2IkEyWSCZDJJIpkimUqRSqawkylEIomQNkgbhI1/u9j4XSlswIpNMjhJQeyEYzUU1pIKJi82uf4y7QbfHbTrgnLwcjmcXJZcMDnZHDknR85xcHMurufgOi6u6+G5CtfzcD1/3vU8lOviehrPUyil8FwPTylUOK+CT61RSqFV/t5QShXdC/H7JX/PoXXsthjIneZfZyB6gySEf4dEn/5NgxD+fYAQ+XtFyNh3Ed1f4f1DdKzYLwbfszmX79/xCHV1dQOUz2AwGAwGQ6VQFhE/depULMuitbW1YHlrayvNzc19tk+lUqRSqT7La6pSpJKJmAj3RZWKhHhMtBeJd6VVtF7FhHvhvkTCDR0TaFqjEQWanlLiLRBVgS6LFJUoEGbB90DMy2CZlAIZE/KySMjnRbzlzwfi3bItLFvmxbtlYdsWlmWTsP3vdsImYdv+ZzJJKpkimUySTKdIJdMkU2mSKV/EY9kImQxEfIK8kLdinzL6DKvBcRy01kHDwgrOW1Mo4t3YZ2zSDtpzwHXwHJtcRpK1BbYFOSmwLIFtCRxL4DgCV0pcy8WxPKTj/44UICV4QiClhycFnou/3MOf90Ao8BQIpVEClNBI4d8fUkj//pDhvSAKG4aRiPe/+/dB7FYQsSZN7EaIrn1MsAuIrn00SYGMC/jiBl+RqI/fV+F9FmJbTp9lBoPBYDAYKpeyiPhkMsmCBQvYuHEjF154IeD73Ddu3MiqVauGfJxEwo8mlxbqCiWCZUqDVvmougIQKF+HIyIxnhdi0FfAa60Lov75bSjYL0L4C8JIK2hfZMXFWyi8lP9dBYJda+ELSi2QSqKlQEuNlhJtEYlFDVil3gXEFvm/4QViVSA9hScVUukgGu2hYtFprf0ItNBhrWj/VAr0Xxh1l9GktX8dn3/+GbY+sZme3m6am2Zy+hln0dw8I7a9jn1XReUOVXG+MaWCqLg/eXjKw/M8PE/heX7E3XE9XNfFjS33XBV8V7iuG333lAoi80FUXoXH1+hovqiBpzWq+D4I6yd2A8T0e3CvBNdah9ci+J/UsTc1scoNqlXI+Nsa/+2LL+rz8wXLhPT3IS/o44dUqiz91w0Gg8FgMIwRZbPTrF69mhUrVrBw4UIWLVrE2rVr6e7u5vLLLx/yMZKJJMmEjSYm3PuIPo0SCqECISM1GoVWEiEUAo0OdVRA3jThL49H9H33RKF1Jx6FjX1EUfj895h1oljEh99VXsiHYl5LjdbSF/YaLK3RUmNZMSuQFRY2LE/pS5uP6iqk9JCuxJUelnSRloVlO1iujWW5CMtCKAuEQguN0CpQo3F7TPxTkMlk2Lx5E26ul5Rt8fZbr9Haclwg4uPb0/c4gYDXWvmNLhUIc9fB9Vw8N7TN+MLddUIrjevbZLxwcnHdQOAH23uewlUxgR/eH57Gi2w0sfun2HYV3QNEDbvIRhNd97DRJvxvgZIXwp8vCIKrQMgH28fdSOG9IIX/1kXE3soU2KoicV8o6gX+Z9y+o7SJwBsMBoPBcChRNhF/8cUXs2fPHm644QZaWlqYP38+GzZs6NPZdSBSqQSpVKJQwEfiXeF5GqU9PE/gecIX7UqhkGgUaIEmFNaFYr7YV68KPou99xBJuJIBT1ForRGAsEBYvl0mLtqEQmrlW3ukbwmRGqTwgqi8RkuBtPzySK3RVlhOC23F+wdYgUzO+378NwJxb34JG08gEIWUWEL6+0iJFgKhZXgC9PXB+7aemTOa2bv7HZTymDSpntraavKCvZQn3gPtoXF9X7znoV0XN5fDcXI4OX/KOQ6O6/jC3nFxXH/y/e/5757r4boq+O7iev7bBs8NPoNovP/mIS7e8yI+7o0vbrTlxbsufbn9+HsUadfCF/Jo0DJfc+ggDh8FzQMBHu8vIf3+D1IG/RyC79GyIlGfj8wXWnUMBoPBYDAcWpS1Y+uqVauGZZ8pJlWVIp1KRB0SQ2EWWSU8hef5wlgID6UEricAz49sS41UvsjKK/h4SD4m3OMR2gK/PJGQ9/f2ha0KOnz6kVDfLx76oMP/pBCoSLgF4lgG4isQ0VoItAAtPDQShYelPbQHWnm+iFcaZeXfQNjKKrCBaG2hVT4SHO+kG55HRKj4gkXJoPTCxn+LIfKmb4H2TeWxDq6ppM2ZH1zKgf378DyPRDJJU9NMfL+7plC4u75wx/HXqxzac9BuDjebJZvtJZvJkM1myGaz5LI5crkcjuPgOA65nBtE6l0cJ+jQ6nhRBN4NI/BezH4TWmm8/JsaT6mg7vKdW/NWHvoIeb8OiwR8kSMGwgaSjr1t0QjlX18lQSrQVmipocAv7zfoArFu+Y0jSwadl4O+EFawPC7u/T4UMibkw8ajSStpMBgMBsOhREVkp+mP2uqqIBKft0iElgrXtQJftMR1PYQUeK4HBHJSB0I+Elk6r181EAr1QNB5JaKzSguUloG4tvFlrSywzhDzKBd3QqSgA6Mo6tgo8xlqhESIRNS5ESF8j7zQKKGBHEp5aO2hpIfSGltplO0LVdtTaNv3nod+73zUOe+Bj95iRN5xP5Kd9FzsZBppe2B7COGBcNHYoPNZagQSLSR1tSnqao+I+hkI4QGOb5EpiMLHOrKqoCNrLoeTy0TiPReMEZDL+VlpnJwbiHiXXC7nC/hAsLtOKNx9O00o3kOffL6Bp/CURin86+ppPKXR2o5Ee4EnvqiDtH9jhI2S4BxjJqqwsZS/ljp64yJj3QI0IuoC4O+ZF/AisNJYlow6B0edlO0w61CYgSjo4ByJeSsS82EfDBl0LjYYDAaDwXBoUNEivq6+hlQyERPuoYfawwl80o7l+hFKV+AQRLWJR1cFKmY5iKwxoZjTOhB8vpjztERpKxDvVqGfPnacgtSBIjSdFGYeib7HLBShxzm/XkZR2ShLjcjbXfxt0kGjQKO1g6ddlOdgKRdlKTxLRdFmT9l+Y0dZvqhV+c6f+XoMo9sOTipH0smSTGVJJlPYiSTSDrPWhKknfWuQDju5hpYdv0aDGgkEvM6LeK38NJLadfHcHG4uFOxZctlMFHn3xbsv3B0nX7ZczgmutYfruHmvvOvFOriGaSQtPCVQOuU3uoRGSb9TtBJ+h1atNIRpJQkaOfj9D7RS/ned7zGRT0GqQPsNRIFCCjd406L8xqH0xboMqkcGfXm11IGlq7DXcF7AiyhVaMK2sW2LRJgiNMgyZNthytAwC5Ev8kMxH95jiUR+sDSDwWAwGAyVT0WL+MmNjaSSNq4TCjwnEneO45BzHGRO+qIqZgyOrBJSI5RGCF9VxbPMhALe13WBcBcJVBRz1THZVZAKpkDIx3N5I2Ne9Gh9oSedaJmM8sZH0fpIwFv5/PF99k9EDQiFi6MzuG4O13OCNxYKz7bwbBvPVtieh2t7gTC2SSRcEgm//hK5HLlsgkQySzKZIZFIkEimSCSTJOwEViKBCMS8kDKvUiPPfLxCAwGv/A6rynP9HO5uDtcJPe+5IA+84/vgg+sZincnaFy4jheLxOetM5FwVxpP22gl0TLlN7QsC6H8PgRK+X0jpFKgAp++FCg8QPrLhYiS56j4de2TocfvdIyQUeNQ6WSw1s/wY2kPKRRWmCHJ8vs5hPeYDFuWItboi1KJ+lH3RJgaNOlnZEomEiSSCZK2TSKZCK5N8GkngnEDbL+xJwTd3b0jecQMBoPBYDBMUCpaxE+d1kQ6lSCXC2wXmQyZjO+fzmazWFkLS+YIc2MHfRJ9y4hUvidd5GPG/kZhtFWgSfnRWiFBgdC+6C/2zRemHSGWOpAonWT4EXVyjSL1vg2emHiLW27CKHw+Gi8LBLyMovF9J9/ikkKj8bRD1svgKgfb9bBtz4/iuhaW7eHaFrbtC3k/j7yLbef8AaFsf1CohJ2IBojyo8AJbNv2xaJlBTYOX9BGVRJ5yhXK84K+Cp6fccZ1/QwzQWTddRxfqAfCPXqrEkbfYx1XfRHvBOJdobTEIwUiibYTyFhO9/CaIoJ0o/5VwMOPnAsVXgs/TK514fURwTXuK+ILI+h97oXAh65EAi38xoClFVopLLwgM5LfmJSxzsfE3shYUgZRd4tE0iaZTJAKBudKpYIpnSadTpFKpUml0yTCNyaBiEdIUl3dQ3qmDAaDwWAwVAYVLeKT9dOpqUlS7WZwsxl6e7rp7emip7snErcQCHcdeKEtFWXxCAPGUdJEDZoEOrSJKJCBxUJJ7c/LIKhMP4loYuStNHFPfEz2BZH2vEAMM8cU2W6iKZaBRObFfWirKR4sqBALIdIo7ZFVvTi5LJaTDewYLk5oy7BdbCf0X8fsGuFAUbaNZduBePejvWEnS2lZfkMjfpJB3esoY5BXYNvxgswyYfrIvCXK97p7MYtUYdRd4bigSINMI4SNFXtLks8mo/2MRNpPkem/c5EoggwxIUH0XYXpGbVEaBV1TNXQN1d+2EFY+A2GUgMpFTTIpABho6VASYknNeAitOf77mVcyBM10sKOrAnbJpmwSSWTpNIpqqrSVFVXUV1dQ3VNLemqaux0FcJKxQbosgCB5RoRbzAYDAbDoURFi3ghJyHsBMJKkUiksGw/8hhG2/2OrR6u6wuhcATMeKQ8SvlNAmGnkJaN9jQoL+iEGcg9pVAyP4siirzGUzj6BQuTBUYzsRV9I/F573zcJ1+8LB9xz0fn84I+st/EfPbFuQWFALRECQutq3G8DG62F9vJBQLd8ztNRpMXiHk3EO4WtuXGOlfakW0jHDk23niCsJNo2GE2P1BTmP6xoC9DUb+GKMNMfL2SaFIgUmg7aDRQ2GgIr0eUoccviG/HD8YJkEh/26hjc7x/gvBTQeqwAUaQiSev28PLCSKK1EcFCFZGHZwFweBN8caY8G1RVgosiZIaJVwULlHf2ViP1/A6W4H3PZm0SaVSVFdXU1tXT1VtHTJVjZBVINJACn+EXStqnBoMBoPBYDh0qGgRD2nABqFAesjI3pEXvBCLsut8B9UoNzgpsFJIafl+bc9D6sAjH4bbhfJzswe52wuEPBqh/Q6zcULrRT7CXrQuWi/yHvIiv3yhrUbmvfGR3UL0GfAn3gjo87uBCJUKv0MvVSiVIqdzuE4G23OwPQ/Ps/OdQm3bz3ATs6YIgT8QlaXznTBDUW9Zvj8+qMCwMeW6bj6lo+vFbDRBvncn5ncPRXyYNtJVvsdd1iFkEimCDpuaPucaTwEpwuwyYVkAqRQ6tFFJEYh57efAFwIRWmlEYKHR+NH44Br7gj1+FXUw1kDYkBNF15bYSKv+pxXaoILJzwFvIaxq35svFUpnUZ5GWSp/z8YbJcRFvY20EyCTIJL4Aj4NJOjq6uY3v3kQz/MGe5gMBoPBYDBUEBUu4nvROgE6g3Z6yfV2+5aa3nhecSfIbOIEHSIDkahslKxFiASW8jtc+oPx+FYMgUZqGSh56ffJFKpAv4XRWo32rRZxYio+L8pLCfi4JgzFfN5PL4LOjsREYIH4i/niC3KDB79XXCQNaCkDj7i/ndIpPJVAqRzKzYL2ojJL6fvNtfZ7CUgpsW2bZDJFOp0mXZUmXVVFMlWFnUxhWYlAxAs/daXy8NwcTtZPG9nb20Nvby9a++Jea+3ncnc9cjk3n0LSdXFcjaeTIKsQMtH3PDWFXnUNWohIlEdCHqLc9nkbTcz7XmxD0vnrEAp4hH+NdVipsdz6/k8XvvmILn8suh82eKLBmaxw4CYrmAJLkmWBVY0nNTmVQ7ge0nF80R7PEW9bWHYCy7IR0iJRLfw2rSDw/ngo1YsUWVzlDPGZMhgMBoPBUAlUtIh3et4i69nkcr3kenvp7e2hp6eHTG/Gn7JZMpks2WyObNbxPx1NTtWiZMpPpqJCSwyRtSY+o4Ms8DoU2AqU8NeH4i0aK6rIU1PCIR18iOh73nJT6JmPZ7bxhTsFkfYwGu8L+XhKypjwJy8m4yXwGyTCj0pLGUWQtU7h6iRaOUjtFdwcQvhR30TCIpVKUlPr2zhq6xpIVtchEtUgqoAkWks8T5GwJX4e+CxVqgcv201vVzsd7W2AxvM8cjmBDqL1juOSzTnkHI2n02iZRgirhJVI5F8rxBpDeSuNCFJACr8jq6RAdIciX0rhC3kp/U7LFPZJiN6uCPxIfHTNY8sR/TbiitOJ5t+g5Bth+UGaSgziJCWIFDmlUJkcnudGg1OF1qNc1qG3t5fqri6qqqtJVVWTSFZhJZIImaQ6Jbng/CV0dfXw+T73o8FgMBgMhkqlokX8rjdfJZ1KFOU2d4N0hS45J/RWKzJZl55sElcnEdLCCiO1QuGbnf1osxWO5Bp0jpT4aSZlIBi1UH7SESUC4aYDmwX0NaEXfcZmRN+tY0uDbeKR9YJobkwIxgS8lHkvvCh6E+DPBR00ZZCxRUqU8rO7+1lZLN9yhCSnNLUJD9uWkT0pKqMAISS2ZWMnkwg7BaIaqAbSbN/+HC88/yc+/OGLSKXTICywFDLh+FFj4Ytr1/XIOQ7ZnEMmkyOTVbiqGm0lkX6+loKItizoG1CcDCaIluPnZA9Ft5L4b1SCjqs6tB7FLTRRPQfH0/H6CmuNqKGQj/zHcrwXqfg+Ef4om5CIvUWxYh1XgwGbpAhGZ40N2iRslE7QnfPIuDlq3Jwv5j1FznHJZHN0d/UEKSaDjseWjbRkVF/dPZmSz5DBYDAYDIbKpKJFfC6XpSqdJJVKk67yfdJKKV/M57JkMr309PjTvvYcrk7lhRFEOeClJC/gtcYKhtTUgZnet834ck7iC1BdZFfp07k1pJSnpfi7KFoc2TAosMbEhWyBLz4W7fWD/OFbgEIRH3q8EUGecgVYQR0EfQb8FglUpS2ammqC1JC+n12jyeZyeErhOC6ZTIaurk7S1bWkqmqwElVIK8mUhgzzT5yJl3uDXkejnAy5bBe93V10dXbQ2dFJV1cP3T299PRk6M16eCqNsKqQtowsSpF2DiLe8bcNhfVWyjfkn0vQXiE00fiXVAfiVuftLoRvL8LvMYt7Yei9MKofLcqXQRRd48JMQ2HkXQb2GN8+Y0mJsHwBH44FENptRNRiAcdN0t7tMnVKFdXVadIpP2+/bdv5UVm1IpfL4QUpPbXW9PSYwZ4MBoPBYDiUqGgR3zRjJlObmrES9SCryeU0md5e6uprQHXjZtvoOrCHvXv3sO9AlrbOwIcc2Gek0oV5waUIfPB+1hI/5V9+EJ8oeksolnVMz/WNxgZLR048it5H1BdGefsI+H6FfKxUMnjDIEWQNlP70WwpmDxlCu9530l4Thfd7Qdob2uju7uHTDZLT3cvXV09CNEedawM88lLy7e/aK1p373D97bncmRzObIZ397kTzkyOQ9Pp0mk6kglU1iWRRhiz4+GGrMWibjY7u9NBn3StwfVETWCtBBoGXZiJTp2uF0YZY+5dPz9C9ppBeq+T1niDS8BSPJe/qiDa8wXL624taZwXsRfD1hg25Kjj57LpKlTSVVNwrJr6c06CCFIp5Jo1Yub6yTb3UFPdxfZTBZV3PPaYDAYDAZDRVPRIj6XzdLb1YlluyC76Ozq5sCBfeDNxHN66O1pp7NtPwf2HyCTyWHZtZGQ0hqUVAjPF1QqEHUyEngSKXQ+BaEUaCV9g4UQiMiOERkqCgK0IX3GgooLzBJis5Ai000oYoNVheko/YWhvI0+C3Yv/WOSfGdXjfbrQGkyGT8FZVdXTzRlslk8z0MIgW1bpNMpkkmb2rp60tW12IkqlD8AKq6XJdPTSUd7Oz09vfRmsnR39dLdk6E3J1FUkUymY7nmraDOikV8/lwi/3tY36KwOgmyyeRtMHlxXmhPIn7wwenzoqXUaxcKL1lRw4tQwBOPxuej8mH/hijjkJCBnSZ/UP8tgiaXy5HNZNAig5Ww2f7CS0gpefe849Aqg3KyOLkcrucGjTNZurwGg8FgMBgqkooW8VX1zSiVYf87b3DgQBsdHV109Xo88/SzZDNZesMRXDM5HM9i1qxJ0b5Ka3+kzjDKG3m9850QCzzToYgUxWK4QEKWIG9RiW+j807rSCAOSU6KPl/y3/scIBSzsSKGmxa3LITwR6UNluzdu5/f/uZRIOFnj/F8/7rjuNiWIJ30qE6BlJK6Oovqmhpq6qcg7VrefON1jpg1h1rbozdp4eaydHd1Ryk9ZbIWS3sIrXzxHkSe/UGW8uXTgYVEhKHw8CSj0y3yoRN0MNZR/DwfPheF2w2ptmPCXUcL+rvO/RM1uoK5/BsUme/LIPL+9YIOyuTtQ1JIpKVxnByPbXkBy5L5wbeCRtCuHS+TtD2q0gnq6mpobGykcfpMatzUsMttMBgMBoNh4lLRIn5P6y4aJ1XR1dXN/v1t7N3fi0cdnV0ZMhmPTFaRzWocB2xLkkwmUFqjPD+lpC4SxFGmkYKl5CPdkRVFR7YPHx1FgftQSitqQmVK/v+x1ZrQvN33oFEGHR1tHApXQWj30YFFKFgfReRLNRVEcEY6roJRSqJ1KshnDhIPS0lcV6CFpDenaOvoZPfeXeze28a0fQdoajpA3eRmqqtq2b93H4mEorNtN7tb97B/fzv7DmSoqp2OnRBYbsZ/8xHzfcedPv4bjOLGSf7NQoG4jreGCpb1UeHFW5Ws3yjLTdEhYosKG2C6cP/4eeRLTtBILDyluDUojNrnGylB9D7cWYKFxJM2nd1+ZF1KD8sWJGxBwpbkHIfeng48p5PqKovJk+qZMmUyVVW1GAwGg8FgOHSoaBG/7Q+vUVtTRXt7G21tbUiZoLl5comIpkBISCQSuK4bdOCkSJ3lB9IJR8uMZF4o1HR+21C5RR0wdaE0DInczDHvR6indZibMhLbwYBKQke/H28mFIw+Cn4HW0lh5Lk4Ak1g+Qmj2cWKNPyl4CTjFpYw3SFCIJU/Eq7reVhSoLGQdjVvt7Tz2lvt1NV1UFezl5qaN0gkkmityTk5erp76OntJZdzSCSSvGtyEqWUnz5RExPwxY2LeE3m33bkO5DqaGCnaOuYotc63CZuzwn30X2qoag2YuJdF4j6QvHeT0OgyJsfv3V0id8L56NrHFyH8LpEDTL8iL0dZLJRWkdvjeLWHC2SdPbavLpjN1WpdhomtVNdVY3BYDAYDIZDh4oW8VpBR0c3nV1ZenpdqquTka8a8oIpFM2eUv6ol8EImHFhF42GqRRKq/wypfuKq3g0vDjCW5S5JBLYsRByqENFIOS1DrLGxESff6j474qgfBolNEIpf/RYLZGBCT3y38c1PTFLjY6VK2wkROI9Lh6DXC7BK4iCxlBwgKifABLXA9cDx4WcE4pRRTaryDoa1wNPCWz87Ctaq3wZdV68hgtVrEFR0j0UVGSBiI+p64K2FsEovbHrrAquf3E9x3cOG1KhkA9XxX83ti46g/yN51/bfL1GjcXgXtNKooRCSoFSAiEUSgmkUKhgXxkKf42fLUjl+2XEL2sY7heB2Hdc3z+fynoI4RZXoMFgMBgMhgqmokV8KLJVMCS9FwwapJTCU8oXPIFwQykymUwk2pRS/qT9z+g4KrZOefn1MWGvdCkBSCT6QkKRLnQ4cJCOlgPB6KJEkXcRRoqLPkPxroVGaYVQAiWC1oRSIPy0jELmo7Zh+0EEUfkwEB9XnJF4LmjI5MsmPeWXVwiU59etp1RwLFHQEAqvgSpuBMXXaX+AJ89TeJ4KIvIenmchpfL7IRREzOOImEgNKKrv+Hx4bYiJeP86B9c6uDdKRunDfWMttnwDLX7d49WZ/7+I3q4EjTTyDTC/EeYLdU8IhFIIIfA8f7yCMOLuRR4ugkaYCM7BI+e40f0tEP79oPw69cJ7Oqp/FV0Dg8FgMBgMhw4VLeJ7enoByOVyOI6LlH76Qsd18VzPF/SBaFQastlc5EGOou7Kj2yqQFR62hfunso3BpRSaE8XiPloItR2sch2iBAxIQ9RhpEoEq9Rwhd9oYAPxhoNRLC/jVYKLUQQgfXLEc+AoqUvbaXnC/Yo3aT2rTRRusRYaDsqs469aVAxUSxAOxrL873XSimcoGOrb4HBr2fPxfX83Pw5x4lsHlorcjkHx3VwPBfXc7Fci0w2Gwz05Oee90eC9aJMLEDB2w//FOPpMvMivljn67za7hNhjxoYkchV0fUPhX2BmI9peBWPyuviXywRiRcaFEHan6DRqJXf0Ao6U3vBmw3P86L9wmPG58O3MCDQ2hfqjuPiBbawsAOwQKC0xg2ukeu6/iBo0gquWa7vA2QwGAwGg6FiqWgR39HZhRTQk+klk82g0fRmMuRyOXJuICBdF9fzkErjOI7vxQ5tG2HUPRTwwfdIwHsqEn5aecGQ97pA9KHyQrjYGp3PrhJ2XQ3ng/Uxka9jQj4vrBVagQoitr6QV7449PLHkARiLpb5BGLit08HUSK7ikYVCt58mB5HO1FOfX8QLS8Q6r6wz2ZzfsYa1yHrWMisRKOwXRutNa7rkM3myOYcXNcDJJmMP+iQ4ziowFZjWdJvhMhgkK2w7graQzFfeH5p4fnE6x0KBHxoQ1HxhltwLQvfrsQaNNF1KGU7ikfi428wwkh8UH4VSX0U/gjBYYdVr+h+tigmfIOQb3h6nofrueRyjv/2Rggs5TecLGXhOq5//zs5v86F4zec+rzZMBgMBoPBUMlUtIjv7O5ACEE2m6M3k0Vp6M1kyOay5HJOlBLRdT0saeG6HtLKJ12Mizqv+NMLIrWeh1YKT+XtGJHHWsXEH/QJDYf56H0nSPAl1KZRZ9Yg4ht2Pg1sM/583gokBPgeCwmEQl4jpCQarCqWHjNsPIh4qyHfJzQffS8SpaEUDiPvYaRXBVYlx3V9XzuQzWbJBA0mmfOzp3h4WF7QCdZ1yWV9wRlGnDPZLAJBznEIffCW9BsFlrQCHzkFolxQ2CCJGilx20rYTIoi8YVvGFT45iUQ89qLv4kpsl4VvaEouE7hZ/BFFTfeYmVB+5dLaQVK+tdB+baZSMH38frnd9XaH2AsPF+/EenhOi7ZXDayNVmWxPIspJS4rksmlyGTzZLzHBSK3qzE8YqbDAaDwWAwGCqZihbxJ536ASzboqu7i/37D9DZtpfeTC+ZXAYn5+I4ru8fdj1sW/sCVFu+yIWYOFWRnz4cqt632Hh+lF6rKAIfdorsE7n1jxjzVQRqNEpFGeWpIdw09K1rLaJMM2E0XoXWmtALH4wuiwLwI95aCKQmNmJrMJBVXPBCaaEYiFSlKDoPv4ye59GbyUT1pAOLked6SMtCa00ml8VO11A7pQ7d3E2qwaaqOkUimQChyTo56FU4XR653h5Eh6I304sUEsd1o0qwpJ8BR0md7/9b1O6gIFd/mBZTxNslUf1ris4pHonXGh29efGijq4qtp1Wqm8jTecFfTipWMS/L74xSvrdClBSBcI9/hrF/1/UOCi6P7CC8QzCRqdWeK6H4/rRdd86FRv1NRDxvdksOQ31U5uorq5hUsMkqmtrYMPmEuWcOCil2LVrF3V1dUXjGBgMhlJorens7GTmzJnBm8yJh3muDYbhM9Rnu6JFfPOsWSitkAeSuICnXXoO7Cbj5nBcX8S7ji88ESJKLymFDCK+eUtN6J9XQcfYwgi9DjzUoS8+sGJALGpbhM57m6MMkPkE4PkMkEHkNvTGK62Rypd0SupY9DZ+7CAKLQVaaqTKp2kUskTEOrKhFFpOlIbI41/kQ3cdh0ymN/y5fH14HpZloaWFSNcztamazqPeQh+RIT0JqmsgkfBAg51z0F05kq21TN85F7dXk+3uQQTe7nD82fB6KEshgw6s+Sh8+DaBgoZK1E84/o9CFDEPo+mhXSgm1IPGWHRdvSAKH/Z3KMpkU2A10oXrwnqMfjMqM+F7FxQgghcnfYW8BleDFW9necF1sLC0jhpoUYNT+W9Dso6LFhopNFIJhOX3KVBaYNdNoqm5jvq6BhoaGqitq/PreIKza9cuZs+eXe5iGAwVx86dO5k1a1a5i1ES81wbDCNnsGe7okX8q1MfRSQ0vY0ZRHsVNdOTyJ46ZJcgl3XIZXLkMi5O1kV2SjzPj/4qIfPZPgIB5/viQwEfeuJDu02ReC+KwPfrNw7El0QEOeEDsabw87tDPnivfc+01KCDjqs61O9S5oW8BqRGIAEZeOpVMOqn33EySgEJxP4XpT+MNx50rIFSYLGxbOqbZuM6WXK9PXiei+O5oBxEIkntpClU19biHdGGnpujpr6BqqoUqWQCS/oe7ZxjYaUEvbbL5O4m3KxFuzxAb8d+3Fx30MjI20VsWyGDHP/xOgztNDJsmIR55cM3HSGhsKZYeOffukQWGq2jtyx+Np3CtyyquANz3EIV1WFezMftP/H3LpEBSoHUgZCH4BVMqZckQQg+aGAJFW9w+o0oLQTTjjwGy5YIW+HWdOGmepFSYNlJ7ESKXG0HueoDdKZTOOkUOjfxPfF1dXXlLoLBUJFM5GcnLNsZfBibRJlLYzBUBi4Ov+NXgz7bFS3i25JvUTM5ScISyDndgCahNdWeRy7nksnk6O3J0dOZJbPNwnmzHq101Lk175n2BZwXCHm/g6vOZ6ZRefHex15B/3aKUMap0Pgh/Oi3BOKKT0Mg7DU6FPiBWJRSFQp54dtI/GP4nng/UhtGqXUUrQ5LkX8DUBiJ17FzCoU8+PO1tfWcsPA0XOWyn7dp1a+xz22l191Pr6Po1G/59VjlkWgXuBmP3qRLImFH6ScdxyWbccj05tgnt1JnzcKyqpHpWt8z39sNge/edx3ZQeYbWWAHCs9HxQfxCmu5r4aPOpr6HY/Dtw4q34k16teQTzHq++TznvnC65xvFCgomNcxS0yxXSosZDgok98JOejTEHy6+B1aw4xFOrQESR3UhYqWK+X5nbQTCY5/zwm409pom/4yTk0H2F5wH/SitCLhejiORzbbTldOkXMnvifevGo3GEbGRH52oiANCWxhRLzBMCRCS/Egz3ZFi3hpCWzLwrYtP4IbCHNXeljCDaK1AlyBY/tpELWVt59AXsyqoow0flpKjfLyfuq4iM93Dg1LExfy+VFSI0t8sNwX4THvfCjahYhFdQksNQqFjAn5QJKH2UqE8Ds+ysIRahE68o/7OxQazSMRqvIR53g0PrTOiIRiX8123kz/gZ5sN5leB531wPHtMloIpOW/EXA9D3LguaGYxPfQaw8s8Gp62DvrRdI1U5i8ey6JZJJcqhqntxvHyyKCjq5SWkHEPSbkow67ukjEi0IRH7sMxX54HbPTRHnUVTwCXyTgiz91sXgvJeLjZdFB32UdldePyKsoCq+D7s5B7D3urwrK5afyDCPxYb8NKWB/zQ7apj6PnQJbWNgkAouWf9/4zVSVv+dEkSXLYDAYDAZDRVPRIr5tXyc51095KIUV5cq2c2nquo5A9Tp4PVmSbdWod/bjOB1RJD7euonni8+nlYxZaYJovYY+3vFC8RY3UsQpXKbw00JGe2kIQ/S+/xyQCqn8aK1GgvRFHcLPrY72O7T6aSp1ZDURwhd+OorE+6Leb1CEPvG4tzsWoY7EriKTzbB/3352d+7jQLoLh5wvTAWkqmzspEUyZZNM2SSSNolE0JgKRHj4G67n4boeTs7PVJPt7YG9e5my62i8Dujt7SXT043X24Xj5rCkCs4hn2lHCOkfU8TWRWcnCrLu+B99Pex9Gy0lBn+K933oI+TDVJxFKTn7EfHhdS3o3yz866SlQCt8/7/v/YnkvMbPSCO1H4WPNzY95eG6LmhN7w7NpLb3Ieoc9jRsJ5M6gJThUWIdtYPzc3omfiTeYDAYDAbD0KloEa/Qfr5shT+5+B0mczkmtZ9AfUctdk8PvT0ZqhIK187gOjmkpUL5l/dPK53v7Khi0dlSmWgGEG7FEfm+gj4se17I67Dna5CJMPRQ+0I+jKcGUWcpgj39dQUZaSI7DTFxW5S/JSbio+i7VkUi1k8v2duVpdadSbOdZH/dm3hVvbi1XSSrbNJVCdJVCRLJBMmETcK2sS0LSxa+5fC0/wbEcf1MQdmsQ7a2jfZJz9P05smk26voTVeRydSQ7e7E7e1EeG6QJtPPHS8IPf8iJuKFn0IzPMfoNPN+9QIbTHjtyFtpdBSB10MQ8DrfgFPxhkLxvZDvkhvOxb+FHV0RvsnKL6Mvvi0N2gp+U6qCHula+w1M7CR1jdNR3RKNTY03iSZl80r143iJXqQlEBYICZYtsIQVdaQ2GAwGg8Fw6FDRIr5+cjWJKgvPVXiOwsl5kNV4OOys+SNHZN6HzFhIKUimq6id2kxvRxtOdwciGGiIsNOjDgf/KYzAhx1aI0EY2R0OXhWFQl6pmGDrI+RBhhYM6e8TplmMW00EoZUmllMdCjS8jqw8gbCN22cC8e4pRSKZYvrM2VhCIpRNXXYade5U3k7+ASV7sKT0335IiSUksmCyopSIOhgtVkv/nGwJytKopKa3posD015jijMPrdIIAVJIsokUTqYbN9uDCDIFSSF8a4mMWWqCKHah9z/W1SAS1zq6blF2mkjA5601cdGuY9e9dF+I+LGL7FHF3Vs1wYi9hf0VfCuUCEZ1FVFjUmqBlH7GGSX88QE0IOwE6UmN1DRMJl1dRTKVIp2qQtYodjU8g6zKkkomsBMWli2Rtog1fCCbdg/6fjUYDAaDwTBxGHbeuUcffZSPfvSjzJw5EyEE9913X8F6rTU33HADM2bMoKqqiqVLl/Lyyy8XbLN//34uu+wy6uvrmTRpEldccQVdXV3DLnxNdYrq6hTVNSmqapNU1yWpqk+SrBVk6vezY9pWqHFIJlMkEwkSiRTpukkkG6airSSuqwK7h/IbAkGeeE8pPB231QTCryjNZEF2m9iy0lORnzpqMORFY15Mh8JaE44SG2XIiY0i68UnXTjSbLTci09e4RTYM1zPHxDLU5qmI47k1A+cy4zZRxLmcdRa44gcWdmNchWuo3AyHrmsh5PLT7lgcpxgCr/n/H2iKadQrmZ/1Q5enf47MlVtSNvCTiRIpFIkq+uwaxvRyRo8Lfxr5LnRaKUF1yn4dIMpOuegg3K8HpSn0J5XUIcqXrfxwZ8G6MxckLIyLvx1/Hi68HqWWOcFb3+8YFAxz/PvQ9f1gnP28JDYNZOomTqT2slTSFdXUVVVRXVVNdTleLXpf3AntVNdn6SqLkVVrf881FSnqamuora6yv+sSg/7+RqIW265BSEE1157bbQsk8mwcuVKpkyZQm1tLcuXL6e1tXVUf9dgMIwd5rk2GCqLYYv47u5uTj75ZNatW1dy/a233sptt93G+vXr2bJlCzU1NSxbtoxMMHAQwGWXXcZzzz3HQw89xIMPPsijjz7KlVdeOezCJ6zAxmFb0ZRIShJpi0TKIlvdzs6pT0GVh51IYCdsLNsmkUyTqJ2MrKrHQ8aEbV4IKi8mqnWR2ItbNPrkFe9f+BULwMifHQrG+JsArQtEZUFjwfPQBfnsvSirjhfkEg9FenhubvBdBYLe9Ty8SBArEulq5h5/Eu8+cT6pqqpISHrKIyN62FH/B7plm9/wyXnkMh6Zboee7hy93Tl6evxMQL09Wf+zN5z87DSZnnByyPW6uDm/HD12O69P30Jb/U4sW5JIJEgkkiSSKZI19di1jZCqxcMX857rC3n/uxudV3HjJBq4K5h08FnQsFF9xXwo3sPRW1X8mkXXuu9gUMX3QoEPPx71L/i98Fr4U/w+VFoiq+pJTZruNzxTaZLJJKlUilQyharJ8Ebz78nVtJFISv/etyUJ2yJh2/nJsklIG0uOXlaIrVu38oMf/ICTTjqpYPl1113HAw88wD333MOmTZvYtWsXF1100aj9rsFgGDvMc20wVB7DttOcf/75nH/++SXXaa1Zu3YtX/jCF/jYxz4GwE9+8hOampq47777uOSSS3jhhRfYsGEDW7duZeHChQB85zvf4cMf/jDf+MY3mDlz5vDPIkjxESb3EPidPqUFPel9vDbtcWbkTsTKBSkMpT/KpZWqwhMSN9ODm+lBK68g7WKURrLYSuOfbKkKyI+WmndTFFg9hC5MixjkD4kSDwoVJaHxB4ASvr9ZB8v9MZ4CW0bQYzL0w4ce+FIZiXT44zHRqbQCaZOun8zkqdNJVdfSm8kiZY5sNovrumRkNzsb/khPei9WkNddBx2AhRsc0sOPIFtW1Gk47NDpj/QaCNTgjYcKUlkKIZCWQCc99k57iaSqorpzim/XsS0818WzLdxEAi9VjZfrReV6wXMRKN+iovKDWxXcD2Gaycg+ROmIenFDrJ9GWfGbFL9OC7/Hfjp/A4ggmWlg/dHEMuyIvN1FI/18NokUdlU1dlUNiWQKy7aRQV8DaVloW9FVs4c9U59DJbtJxlK26SjrTf6ZyPeLGJ0UdF1dXVx22WX867/+K1/5ylei5e3t7fzwhz/kzjvv5JxzzgHg9ttv5/jjj+fxxx/ntNNOG5XfjzNRR6g0TAxU8SB5RcRT8Y7F8eHg7tGhHH+0mEjPdcl/wAyHDgc78KAaQpKGg7mHhmKVHuvjD4NR9cS//vrrtLS0sHTp0mhZQ0MDixcvZvPmzVxyySVs3ryZSZMmRQIeYOnSpUgp2bJlCx//+Mf7HDebzZLNZqP5jo4OABxHgSNikcxw8lNDKi/ItGLv543GJ5nReyIim8h7ysFPz5hMI5B42V5ULuNnLIn7nyNfNXmBWFTG6JLGVHuomyNVr0XpDcmL+bATpFCl/O5hvvRCb7ifhrBQzBZ7xNHaT2UZiFOERKbqSFTXkkyn8ZQmk8kghMCyLFzPJWN18ebkJ8mm2rFtgWX7fmvLkliWn15SWMJ/JkWYW8U/k7wz3G9VCSkQtsBCgJQICcLyG1qeLfBsReusZ5ix+yTqOptxXRfP9YIpiLwnEnjpGrxc1r9W2SzgBfVW+FDlG1zx/gwlLE2x69xH5MctM2FGon4z0+jYsxnzxUd2+XjqTx0NWCWk33lXWglEugorlcayE0hpRaO1BpeX7tQ+9k17Gbe+g6Rlk/Rs/x6XGk8qhPCitKpagiWDekfgeaOTnWblypVccMEFLF26tOAf+23btuE4TsGzP2/ePObMmcPmzZtL/mPf33M9FGzbJpfLjfAsDIc677zzDkccccSA23zyk5/kjjvuGNHxs9ksVVVVA25z+umn8z//8z8jOj5AIpEYted2MCbKcy1sm7ZfHDWykzBUBJ8+ajOfnfT2iPZ9pFdy89EnDbhN74WLyF25f0THzzo20z/24oDbiIXvpe2mzIDbDETDR14fWkNkiIyqiG9paQGgqampYHlTU1O0rqWlhenTpxcWwrZpbGyMtinm5ptv5stf/nKf5bmci7Z13grjepHdw815uI7f4VW5mqxs583Gp5jqHIedrYrlEAlEkpSIRBohLFQuh3IyfmQ+EvEQifcSmUi0/xFEXQNhHY/GF0Tg89vkp9ggTSK/LozKIzQqJuT9iH+4T3AmorSYDcuOAqwEMl2FnarCSiSwg0gvAhzXReSySFvSVv02rfXbcdOdJG3LF+4xEW9b0vexWxIriMBLKfIjroYNmXjkXymUZwV2l7Afgoy+a0eSm7aP/fUdKEfT0DabZKYqEvT+p+tH5pNpvJSL52Twsr1o1/FfV8Q78kK/2WqKI+z9259K7xPv2Fog5AvujxhCB3ncg+skJVg2MpVGJpJYCRvLsgvSa4b15wmX3bVv0T55J0K6JBwL11LIXKFwRwm05aIsP42qFP41AUE265Qo1PC46667eOqpp9i6dWufdS0tLSSTSSZNmlSwPP7sF9Pfcz0cJvIgN4aJzcFE4oe630iPPxqJE4bKRHyuDYZyICowjVtFZKdZs2YNq1evjuY7OjqYPXs2TtZDycBb7Ab5yB0/J3kk5HOhkFf0iA7enPQHmjPHk8jWkvccxP6gS4lIJBHSQjs5tJNFKzcYzTQWgy/IJKijbClhsN3X79pfo/MKPvxa+Le9RFRe50f5FNrPl46kULiLfKQ2OIk+pgm/vBJhJ7CrqrFSVVhBPwLLsrFtGzthB2Je4lkOb099js66XYiEJm3ZvnBPWNi2L+RD4R5mqImmomw54a/36QSsrSAfvw46q6og4q7IVu32O9m6iu7JrUzZfwz1bUegcvgCPpg828O1XTzXt9q4Tg7l5PByGbSbi3zrYTQ+H0GPiXL6E+kDCP6YPafQYhWPutP3lVlYL7aNSCSRVgIZ1Lmw4oN15e8prTW9yXb2N75BrrYDW0lsxwq28xDazzevPY1KaJStsWwLKXWU6jNM1ZnNHFx2mp07d3LNNdfw0EMPkU6PTifZ/p5rg8EwPpjn2mCobEZVxDc3NwPQ2trKjBkzouWtra3Mnz8/2mb37t0F+7muy/79+6P9i0mlUqRSqT7LMz0Otg4juV4+Eu94+SmKyGuUq/C0yzv1L9LgzSbd2VAQ8QhtNkIIPzJvJxHSRruuLwxdB4JBnyI0ebkqhB9tDVIK6jA/twjFuw4iMyIS+X7qwXhUvnBU0mIxH5UxtGeErYESUXgsCytZHUTdg2ivbWHbwaeVF/B2wsap7mHP1BformslYcugI7DEjgn4eHpJKaXv1Q6ivnEhGqWZjISy31kzzNbi2YGg9yR2GKH3lH/9AhuNm3DYm36B7vrdTNl/NOnOydiujeu4uI6LJW08y8W1XSzbxksmfe+86/iTk0U52agjcNxSQ78ivn/xHu1XMF8k4OPeeOH3vxCWjbQTCCsYDCt4a5Efabfw7QUacjJDd+1eOia9g7A9LM/CczVCBMYrLfzOui4oFzxbY9sKy1YF10dI/1rkDlLEb9u2jd27d3PKKadEyzzP49FHH+W73/0uv/71r8nlcrS1tRVE7VpbW4f9XBsMhvHBPNcGQ2UzqiJ+7ty5NDc3s3Hjxki0d3R0sGXLFq666ioAlixZQltbG9u2bWPBggUAPPzwwyilWLx48bB+r7c7RyK0Y4RTmKLP9fAcD8/VfmdKR+G5GuVqHNFNT/2LVMnJTGqbhfTCzoHFHQ6DUUNtG6RE20mU54LroD3Xt28E0XbwBbfuI+R1bFCi0FqjI9tM3HZSIILjYj7eAIhsNEF5/Y+8x9qykckkVrIKK5nyI+a2hWVZUXYeO/geincrYdFdt5eW6X9EpbMkbdsX7kHOcTuMuluBaLcKxXsYhY9H4kPyVhZZkJHHCtN4SuV/txTSU1iWwrIlnmdh2R6e7ZFL7OPtmv3Ut8+icd/RpDIpbMvCkS6uZWG5Fq7l4nn+p2VJPNvGS6YCq5WLcnJ+pppcNhilVaE8p7DPQ38R+Sj6Xuivj2w0GpDS72SMQNgJpAAh7ZhQF1Gn31DAFwj5wNnvWDna6t6mu24PKulhaYF0ZfCaT/tvdbQCBdrD98Q7Cs+28CyNtEIRL2KeekGu5+BE/LnnnsszzzxTsOzyyy9n3rx5XH/99cyePZtEIsHGjRtZvnw5ANu3b2fHjh0sWbLkoH7bYDCMDea5Nhgqm2GL+K6uLl555ZVo/vXXX+fpp5+msbGROXPmcO211/KVr3yFY489lrlz5/LFL36RmTNncuGFFwJw/PHH82d/9md85jOfYf369TiOw6pVq7jkkkuGnZkm1+3ieTJK1acKxLyH8gIB72o8T6NdjfY02gOtFF3JvfRO7qDxwJEke2rzB44LeClQys8y4EdXE2jLjoSg9hy0UqBcP9quVUzIk/+Mou46ymATF+dR5hIdb0DkI/fxtwRA5ONHSKSdRNoJrFQKy0pgWXYgukMBH6bhDGw0oYC3bUh77G3czoHJryOTmmTCLoy8W0FH1ph4t2RhJN63bcTsG6VMPVqj0GglfDEvBVJJPOGhlIg68ioZdvb0J8+SSMfDlR4d1g46a96hoW0OjfuOJilSSMv1t3ElnushpcSTHtJzkZ6HJSWulCjLj/TLZDp4A+AhPDdK5amdnD+6lt/DlUCtQ8w+k18WNJ8sq8jKlPdJxd+mEHQu9QdfKoy+h5Nr5+iu20t37T6U7Y9YK5Tw+78IjT/MK7hh0UIR7wY2Gkv7DaHYtcnfM+AcpIivq6vjve99b8GympoapkyZEi2/4oorWL16NY2NjdTX13P11VezZMmSsclgYTis2fLWFl7a9xLHTTmOxbOGF/wx5DHPtcFQ2QxbxD/55JOcffbZ0XzofVuxYgV33HEHn/vc5+ju7ubKK6+kra2NM844gw0bNhT47X72s5+xatUqzj33XKSULF++nNtuu23Yhc/2ulhK5AfWCT8jQa/z312FdjXKI8jH7oshR2ZpnfQytfY0ajumIbVNlD1EClASIf3IJ1Iiw4isEGgp0ZYVi9IqXwgqz/+O31gQod1C5Du46ihNpCgU8iIfqY/bbDQCKS20FH4mE9v3VFt2AmlJpPSj7WEqQl98520zkY0mFoEXKc2bM7aSrTmAlfDtM3ZCBn75QLSHwt2SWNIqiMJborAzqwhSR5XqXCuC89KW30fATw3pj0jqhQ0VBF74RqHgrUgoRj1c6bLffpWuqt3YvdU0HJhNqqsBISRSuMGoroGNRbp40kMIgackQoS59T2UkChpRT59admR1adv5pqY9z2yX8Wz0RQiioR8aHWKIuNhh1MJbjJDb1Ub3bV78RIuQoLUwm8QKv9+0J4f+VdaBw0N/Ei8BGn5b5c8qbEsFUT4i/snQK537LNcfPvb346e52w2y7Jly/je97435r9rOLy4/qHrufWxW6P5z73/c3ztQ18rY4kObcxzbTBMXIYt4s8666wBe84LIbjpppu46aab+t2msbGRO++8c7g/3Qen18XTMkoJWSDmPeVbDZT/qcOUk6GA950wACgU7dUtdCX209Axg6qeBl94BQJMItFSobUIOkyKSNwVZD/B8g8Yrx8d5voV+fBpLGIbWmp0ZJUJUtII3xojbDuyYkjLzou0cAoFfBght6xCC41t5z8TVhSBV1U59ja+TK6mPRDwVhSBlyUEvAwEfL4TayjgrZhYDN4wiCIRr4NeAwI00q/4MFWsErEhx/Keo6jLsYawWvNbKXI17fSmDtBes4vqzqlUd0yjunMKdtbOv0UJBLMnBMJTSCGCAZ6En5LRE0jlp+xUUiBUcJ2VRsu+1pq4iA9FfX/EhXwk4oOGoZYemXQP3TX7yKa60JbnNxg1BT2jtfYzCvkCPuhYEdp/PIW0wPIESoKUOniLoZFSxRpB4bMy+iL+kUceKZhPp9OsW7eu34HgDIaDZctbWwoEPMCtj93KRcdfZCLyo4R5rg2GyqEistP0h5PzsEQ+choNcR8f+dTTBcvCKbRGxPW2Z2fZ1/AmqXQNtV3TSWVqEToUpIH4RAbpAvNC3k8moos0XTiXV6CRjz36jGckKfbiy8hWIuK+89AqYYXR8FiWmCIBXxiFt4KsNAm8qgw7ZmwhV9URLJdR6sjCbDOhLSMU7MFEIJCRhQI+tI8UReKFCLP05PPwSD/VDgiFRvoDWUk/vKxl0A4KqtyvZwvLLnC4BLWs6KpvpaOqBSbbVHdOpba9iWRvDVbWDuoVPOFH5IXn+aJeKFRk5ZEIpZDC73yrhYpSThb75f1LXdihtRTFIl5LTS7RTW9VG9l0F24iB1LnG4tBvQSJaQJrVvBd+Qt9Me93EpZSBNF4gZQaLaQv4oWO0kqK2LHd3PjkmzYYxpKX9r0E++fCf30HqvbDRZ+KlhsRbzAYDjcqWsS7OQ8divhA3IQiPRqJMxTwoY84nAqyicSUmNBkUp1kEl1U9U6isW02QoVRUiLxjtD5CHNRuppwPhTr+WPnrSZ9rBYiH6nNfwa2iHjk25LRvCXjAr5QxPudUe0gt7uFTiqkJeiu2cPeKdvJpTr8/O5WTLzHItiyuFER+y96YxCdWz4KXyJHTpCAU4eJOMNaIpStBf/1acz49hj/TYjEsnw7lBWIeyu8fFrh4dDRsIu2mreQ2SSp7nrSPQ2kuycjcxaW4+fDF54ffQ/FvJDKt64ogVC+IJZa9ckdT7GQJ3/rxJtwAlBCoy2P3lQH2WQPuWQXrp2N3joIKfIvZIoqzO/8HNyaCl/sq/xXNCjpN3r8ugElVGAlEsFIv/kDC8DNGhFvqHyOm3IcNL4Ol32k73KDwWA4zKhoEe85yg9069DjHhPvcQEW8znnLQmFky/HfdO6QKClpreqjT2WQ013I1WZBqQnA3+3CLLJEH1CXphG4wWIuIyKifqYcA8jsQUCXsQ6iwYeb2nFxXzoTxdRBD7yxEedUX2B7qYy7J20g+66PaRFDZmaA0hbB/uEHUhL5Xgv/MyLdgFh+kzw7R/hR1iPoo8uzW8QEdhD4scNf0/3L+rDhoxWfi50LUFbfvabsCGHFqhkji5rNx3VregGiXRs0j0NiJxFTdcUrFwKywmsN0GnWi38SLYfiRe+h7/EBLpAxIfNEyfRiysdetNtOFYGJ5FBSy863bBS8tcdokZPCTEf+om0yleoFrH7V4EKGiD5PhWxeyp/0+G64zeEu8EwViyetZjPvf9zBZaa60+/3kThDQbDYUlFivhQQDk9/qBAOlxW5F0uFPMUCrHieYi2QYV2DX+AqJ6aDhKJKmoyk6jqmYTUdj92ikjGh7NBRpuYuA+tOBR1ZhXxDq06yDyTb1Bo5XeqJS6W8TO9WNoXspEPQ0k6U3s50LCDXFUnJB2EkmSsLqyMCKwzAuxAACdAWRrP0lgy6CQpFW6UgUYU2GysQPRDmFoytNXEzj1v7Y7qSkefvtXJ/x6kmoz6MwSDQAXftVJ4wTpP5Tsp+6O9ht91bARYvwOz5/lZiZSn8ZSL0g69yW6UpdmTfBPpJEn31pLqrY/e1qQzddgqlc9YE7t/VNT/QeNYWTKpjuAe0WQTndheFT2pNhy7N387qGCKN+YCv0xkoQouZtS+Czv59ukU669TYeNPUtC46dMwjBqLPm5WFTw7BkOl8rUPfY2Ljr/IZKcxGAyHPRUp4vft2wfAtn9+Y5x/+e1x/j2DYXTp7OykoaGh3MUwGEbMK6/A3316MVOmLOb++8tdGoPBYCgfFSniGxsbAdixY4cRJCMgHAZ7586d1NfXl7s4FUml1aHWms7OzmGPxWAwTDS6u+H3v4fYoOAGg8FwWFKRIl5Kv3dgQ0NDRQioiUp9fb2pv4OkkurQNHgNhwJHHgk//znEhh4xGAyGw5KKFPEGg8FwMFxzzTW8+OKLZS3DXXfdxeTJk0e0709/+lP+7d/+bZRLNLG4/PLLueSSS/osnzQJLrpo/MtjmPiIn06ldkemrGV4+1qX+uqRlaFj83SO+O+eUS7RxOLbV5/LZz/wk3IX45DBiHiDwXDYsWXLFrZs2VLWMmSz2RHv+9prr/Gb3/xmFEsz8fjgBz9Y7iIYKoyGFzrRf3iurGVwV5004n2rdmvk754evcJMQJy/MB3RR5OKFPGpVIobb7yRVCpV7qJUJKb+Dh5ThwZDeejqgqeegmQSTjut3KUxGAyG8lGxIv5LX/pSuYtRsZj6O3hMHRoM5eHVV+GDH/Q7tu7aVe7SGAwGQ/moSBFvMBgMhsOTVArmzYNp08pdEoPBYCgvRsQbDAaDoWKYNw9eeKHcpTAYDIbyI8tdAIPBYDAYBuPNN6G3d/DtDAaD4XDBiHiDwWAwTGheeQXOOAM+9jEj5A0GgyGkIkX8unXrOOqoo0in0yxevJgnnnii3EUqOzfffDOnnnoqdXV1TJ8+nQsvvJDt27cXbJPJZFi5ciVTpkyhtraW5cuX09raWrDNjh07uOCCC6iurmb69On8/d//Pa7rjuepTAhuueUWhBBce+210TJTfwZDeWhthQMH4K23oLOz3KUxGAyGiUHFeeLvvvtuVq9ezfr161m8eDFr165l2bJlbN++nenTp5e7eGVj06ZNrFy5klNPPRXXdfmHf/gHzjvvPJ5//nlqamoAuO666/jlL3/JPffcQ0NDA6tWreKiiy7i97//PQCe53HBBRfQ3NzMY489xjvvvMOnPvUpEokEX/3qV8t5euPK1q1b+cEPfsBJJxXm+zX1d3ixZ88eksnkmB2/trZ2zI4N8Oijj3LyySeP6W+MJfH0raefDr/9LcydCxPhz3wymaS9vX3AbSzLGqfSGIbDm/9+Iratxuz4k1Jj+6roqCeq+HzTQ2P6G2NJo7UZqCp3MUqStD3e/s/3DLiNlB7V41SeoVBxIv5b3/oWn/nMZ7j88ssBWL9+Pb/85S/50Y9+xOc///kyl658bNiwoWD+jjvuYPr06Wzbto0zzzyT9vZ2fvjDH3LnnXdyzjnnAHD77bdz/PHH8/jjj3Paaafxm9/8hueff57f/va3NDU1MX/+fP7xH/+R66+/ni996UtjKmgmCl1dXVx22WX867/+K1/5ylei5ab+Dj/q6+sr+prV1NRQX19f7mKMmFdegaoqOOIIf34i5YQXQlR03R7OVKdzJG2v3MUYMTNT7cxNjG0A4HCmNj3yQfjKQUXZaXK5HNu2bWPp0qXRMiklS5cuZfPmzWUs2cQjjBI1NjYCsG3bNhzHKai7efPmMWfOnKjuNm/ezIknnkhTU1O0zbJly+jo6OC558o7Ct54sXLlSi644IKCegJTfwbDePLKK3DWWXD22fD22+UujcFgMExMKioSv3fvXjzPKxBJAE1NTbz44otlKtXEQynFtddey+mnn8573/teAFpaWkgmk0yaNKlg26amJlpaWqJtStVtuO5Q56677uKpp55i69atfdaZ+jMYxg/bhkTC/7Qr6l8pg8FgGD/Mn8dDkJUrV/Lss8/yu9/9rtxFqRh27tzJNddcw0MPPUQ6nS53cQyGw5qjjoJHHoF0GoraxQaDwWAIqCg7zdSpU7Esq09GkNbWVpqbm8tUqonFqlWrePDBB/nv//5vZs2aFS1vbm4ml8vR1tZWsH287pqbm0vWbbjuUGbbtm3s3r2bU045Bdu2sW2bTZs2cdttt2HbNk1NTab+DIc9WkNPjz9pnV/uOP6yXK5w+3Bbpfpumy2ynj77LMRfgh15pBHwBoPBMBAVJeKTySQLFixg48aN0TKlFBs3bmTJkiVlLFn50VqzatUq7r33Xh5++GHmzp1bsH7BggUkEomCutu+fTs7duyI6m7JkiU888wz7N69O9rmoYceor6+nhNOOGF8TqRMnHvuuTzzzDM8/fTT0bRw4UIuu+yy6LupP8PhjudBTY0/xduzX/2qvyyWkRWASZP85bt25Zf98z/7y668snDb+fNh6VLYtm1sym4wGAyHGhVnp1m9ejUrVqxg4cKFLFq0iLVr19Ld3R1lqzlcWblyJXfeeSf3338/dXV1kQe7oaGBqqoqGhoauOKKK1i9ejWNjY3U19dz9dVXs2TJEk4L0j6cd955nHDCCXzyk5/k1ltvpaWlhS984QusXLmyIN3boUhdXV3UfyCkpqaGKVOmRMtN/RkOR7QGIcb+d+rq4NhjIfYC0WAwGAwDUHEi/uKLL2bPnj3ccMMNtLS0MH/+fDZs2NCnQ+Hhxve//30AzjrrrILlt99+O5/+9KcB+Pa3v42UkuXLl5PNZlm2bBnf+973om0ty+LBBx/kqquuYsmSJdTU1LBixQpuuumm8TqNCY2pP8Phxssvw6WXwk9/Cu9+N1hWfrClYPgJANasgb/7u76dUPfv9z+rY4mV//Zv4bOf7bvtzp3+McejwWAwGAyHAhVlpwlZtWoVb775Jtlsli1btrB48eJyF6nsaK1LTqGAB0in06xbt479+/fT3d3Nf/7nf/bxah955JH86le/oqenhz179vCNb3wD+zBND/HII4+wdu3aaP5wrr/vf//7nHTSSdTX11NfX8+SJUv4r//6r2j9UEazNVQe11wDTz4Jq1b580JAba0/xcV2MukvK+4THm4r5dC2NQJ+fDHPtcFQ2VSkiDcYDOPLrFmzuOWWW9i2bRtPPvkk55xzDh/72Mei/PfXXXcdDzzwAPfccw+bNm1i165dXHTRRWUuteFg+fGP4eKL4Wc/K3dJDGOBea4Nhsqm8kOEBoNhzPnoRz9aMP9P//RPfP/73+fxxx9n1qxZg45ma6gcHMfP0Q4wbRrcdVd5y2MYO8xzbTBUNiYSbzAYhoXnedx11110d3ezZMmSIY1ma6gMXnkFjj8efv3rcpfEMN6Y59pgqDxMJN5gMAyJZ555hiVLlpDJZKitreXee+/lhBNO4Omnnx50NNtSZLNZsrFk4R0dHWNVdMMQ+cY34NVX4f/8H/jQhwq97IZDE/NcGwyVixHxBoNhSLz73e/m6aefpr29nf/4j/9gxYoVbNq0acTHu/nmm/nyl788iiU0HCy33eZniLn+eiPgDxfMc20wVC5lFfHr1q3j61//Oi0tLZx88sl85zvfYdGiReUsksFg6IdkMskxxxwD+IOHbd26lX/+53/m4osvjkazjUftBhtJec2aNaxevTqa7+joYPbs2WNW/uHyf/7P/8GyrHIXoyS///3vR+1Y7e3Q0OB/Tybhm9+EP/7xj3zrW/9v1H5jJCxbtoyzzz57zI6/bds2Pv/5z4/Z8Y866ig++9nPjtnxR4vD7bm2f96IN0EbqNOe7UIPvtmI+dq+Y/nhL5cOvuEYUveefVwyd2Qjuv2hfQ5wYMBtal/Yz557po3o+EMhM01Qc9buwTccJ8om4u+++25Wr17N+vXrWbx4MWvXrmXZsmVs376d6dOnl6tYBoNhiCilyGazBaMBL1++HOg7mm0pUqnUhB4E6xvf+Ea5izDmvPwynH22n+P9uuvyy1944QW+9rWvla9gQH19/ZiK+GeffZZnn312zI5/+umnV4SIL+ZQf64n/3ji+vnHUsAD/Meb72Pu58t7/rv/5v38/CPvG9G++9pqedcgIt7b/gqN218Z0fGHglj4XtrOGrPDD5uyifhvfetbfOYzn4lGWl2/fj2//OUv+dGPfjRodEQpxa5du6irq0OYxMIGw6Borens7GTmzJnIEfgk1qxZw/nnn8+cOXPo7Ozkzjvv5JFHHuHXv/71kEYDNkxM7r8f3n4bfvhDuOqqvrnbDYc25rk2GCqbsoj4XC7Htm3bWLNmTbRMSsnSpUtL9nov7ijz9ttvc8IJJ4xLWQ2GQ4mdO3cyawTj2u/evZtPfepTvPPOOzQ0NHDSSSfx61//mg996EPA4KPZGiYmf/d3kEr5ueCNgD/8MM+1wVDZlEXE7927F8/zaGpqKlje1NTEiy++2Gf7/jrK/PCHP6Q6Pp63wWAoSU9PD1dccQV1dXUj2v+HP/zhgOvD0WzXrVs3ouMbyoMQcPXV5S6FoVyY59pgqGwqIjtNfx1lqqqqqKqqKmPJDIbKQGvfbWnsZwYArUEp//sE7btrMBgMhkEoi4ifOnUqlmXR2tpasLy/Xu/9dZRRSqHCf4kMBkO/mOfEEGfXLpg1yx+ZNZcrd2kMBoPBMBLKIuKTySQLFixg48aNXHjhhYAvMjZu3MiqVauGfBzP8/A8b4xKaRgpQoio86TWOpoM5cM8JwaDwWAwHFqUzU6zevVqVqxYwcKFC1m0aBFr166lu7s7ylYzFIw4nJjEs58IIcx1mgCY+jfEmTED9u0rdykMBoPBcDCUTcRffPHF7NmzhxtuuIGWlhbmz5/Phg0b+nR2HQhjp5mYCCEi77XWGqWUEZFlxjwnw+fJJ58kkUiMaN81a9bwq1/9asBtHn74YaZMmTKi4w+FY489tt91UkJj48Ed/5vf/CZLl47dwDEDDSg0GNOmTeOPf/zjKJamkFwux6mnnjpmxzeMHS99fxFYI/v36Og7PaxHnhpwm1e+dRqqduzefH65bj0wdh1ZWq55Px3vccbs+MmGLkY6ikB9XQ8v/csYPnee4Lirnhi7448BZe3YumrVqmHZZ4qpBDtNKGgPpkNhpVlSlFIF52sEZPmZ6M/JROTEE08kmUyOaN/4CJf9cfzxxx+UUC03c+bM4aSTTip3MUqSSCTGtGzxlMeGymLyEe0k7ZH9PXRqGweVz9bMHqbV94zo+EOhQWaBscvKl5mqaZo18IBK5SJhqTEtW86tvF7+FZGdpj+UUhNGnMR94OH8wYr34mOVEvMmym0YCqYhZYjT0QFr1/oR+S98odylMRgMBsNIqGgRX85IfFy0lxLw/Y2KGYr6gcR9KMqLxXko5uPCXUpZMG9E/dAYyjUqRX91O9HrfaI0dg0Tg85OuPFGPzuNEfEGg8FQmRgRPwyKhXvxMvBFdSkROJzIfNxPXspGI6WMvObhfCgiw4g9THxhOV4UX5NS16h4fX/EI9rxui2+JuH6iRIBNyLeEKemBj77WZMj3mAwGCqZihbxruviuu6YHT8uvOMCPBSBQxHwB2OrGchGE/52sZCPfy/et5J89SMhfn3C+fg1KXUtivcZjPh2YX3HB1IKxXzYoCr1piS+z3gxls+JofKYNAm+//1yl8JgMBgMB0NFi3jHcbDt0T+FUPhJKQsEe/E0mIDvLyo/XOJiPh7ZHUjIl7LthNl8JlKE+GAJr4FlWWitCwR8XLCXsjzF9z+Y344L82LLU3GmnnAd5KPj43EtHGfssg0YDAaDwWAYfypaxHueN6oRxmK7TKmI7UBWmeL5/gT8QOsHipgXR3rjxyrlny+21xRH9ivZblMcYQ8/i9+YxLcPGcgPHyd+fQaqp7iYj/dVCEV6+D1ezvi1iV+PscLYaQxxHMfv1GrsNAaDwVC5VLSIz+VyBxVJhbygsyyrX/vMQFH4UoKwvzINJTJfKsd6qfVxURa3bPQXjY9HheOT1hrP8ya8oO/vzQjk67s/0T4cAV/c5yFOsSWm1L6lOh2X+u55Xh9xH/5G/I3JaCClNHYaQwE//CH8zd/AZZfBv/1buUtjMBgMhpFwWIt4y7KwYqGo/qLpg0Xh45Qqz1Ajv6X2syyrpKCLi8Jw24Gi8aXOoVg8TsS8+6FoH+g6FX+WaoCF3w+2gQV5604pMV/cybjUNYhH4YvPJZ6ZyPO8UYnQJxKJCXddDeVl717QGtLpcpfEYDAYDCOl4kX8cD3noZCLe+njxxgoc0mpKPxQ9j3YtwXFEd74ceNR91AEFgv8YsJ9Q2FXXGbXdcsemQ/fjgDYtl1SlJfyuBd/H6zux6KBVXwe8XqOW5uKrTelGh/hW5LwcyRks1kzOI2hgOuvh7/+axjmn0+DwWAwTCAqWsRnMplhCc1QGMZHYewvYjuSKPxYCPh42UsJ+eLfKxWNL/7s73sc13VH3BkyPO5IRGd4jUpZZAa7VsXrBrPRjFUDqz9bTanIfH8R+eJjQT6l6kjq1Yh4Q5xEAip4sFiDwWAwcAiI+KEKGtu2SaVSA3aIjC8LGaqIHwuBWMxAgnGgMhZ3cC3etlR9aK2H3UiKHy88xlD2D7e3bbuP7z2+vlS5+xO/xZS6FqPZwCq2q5RaFlIcke/vWpR6AxQKecdxhnVtcrncsM7JYDAYDAbDxKaiRXx3d/eA0eJ4hLOqqopUKjWgCIzT3/L+Oj4ONt/fb8S3G4roHUiMx9f3JyIHswrFy9Ld3V3wW/H6LI4eD4VS+wshSCaTBW9H+mMo12qgxkmcsWpgFZdrIN97qTcn/ZU3jtaarq6uPssGujZGxBvirF0LuRxceinMmlXu0hgMBoNhJFS0iO/o6CCRSAxpWyEEdXV1JZcXfw4WGY0vL/5eattSv9lfB1gYeKTVeJQ7vqyUMByovKXOO47nebS1tfV7DgeLEIJUKkUqlSpZruJlxbaZwd6oDCTSB7s+Iz2f/kR5uL4/20w8yl58Lv010trb24dVPpMn3hDnm9+Et96Cs882It5gMBgqlYoW8fv27evTQbU/gZxOp4cddR9o/WAifqBjDRYFLmWbKT7GQCJ+sO1LrS/G8zw6Ozv7WIaE8L3u2Wy25JuD/qw04TLLskilUlRVVfX7+/0J2IEYjpVmtAV8/LjFVqfBOrUO9bjx+lBK0dbWVjLiHqanLP4Nk2Ly0OK5557j2WefHXCb8847j8mTJ5dc98lPwttvw+zZIy/DY489NqZZj0466SSOP/74Ee3b29vLL37xiwG3mTt3LosWLRrR8Q2GsaB11yRSbw/8VnrncQ0cnxy7oMykl6BNTR+z42dn5Wia0TayfR2b3qcbB9wmN9Vj+tx9Izp+JVLRIr61tbVgPpFIMHny5EggxtPzFYur4Qz2M1zrzECNhaHaOAYS8kP5/VICeijiMRxMKqS4cRCK82w2S2dnJ9lsdsj9EpLJJJMnTyaZTI7IflS87VDejgzWABuI+LUayjkO1IAq9SakP0vSUOw0rusWjFAbNrByuRxdXV1kMpkCgXWojNBr8Pn5z3/OjTfeOOA227Zt61fEf/WrB1+Gb3/72wd/kAH4p3/6pxGL+AMHDnDJJZcMuM2KFSuMiDdMKBq3Jpj6g8cG3GbzhcdyXvXzY1aGSf+2mUljdnTY/Tfvh4+MbN+u7jTvunHg+um9cBG5K0d2/EqkokV8S0tLQXSyvr6+4B+tgWwuQ4n0Fq8fjYGlhrv9waR5LPbFD+V8h/O2IrTchJlP4vuXitI3NDQwZcqUQd9UDPa7gzGc4/e3TfG1Hko6yXDfob5BGe76cJuBvoeNsJ6eHtrb2wvyzhsMBoPBYDh0qGgRX2q0y8Gi0sXr4gxlwJ/BOFgBOZxjHYwwi/uwh/Ib/YnruLAt3qa4fANZfoZS3tFgqCK+v+UHI+KHw0BvEvrbNk6YW96IeEMxrgtCQGz8NIPBYDBUIKObomMCMNKBe8Zy+/FmpOcznP1K+cxLWUZGg4H6H4wFI+07Mdq/PdHvM0Nl8tBDfp74c84pd0kMBoPBcDAcciLeYDAYDP2zZw9o7Qt5g8FgMFQuFW2nKcVIOvAN12owkhzp48lIzme4+xXXc+iBH8gTP1L6y1U/VvT3G+NhSSnVqdhgGE0uvRSWLQOTddRgMBgqm0MqEl9KOA4khIrXDaXj4lDKMJJ1Y32sUvsP1uAZSFCW+v0wvWE4DeW4Q2UsGgTD3eZg9h0uw2lYjYfYv/nmmzn11FOpq6tj+vTpXHjhhWzfvr1gm0wmw8qVK5kyZQq1tbUsX768TwYpQ/mxbWhqMvnhDea5NhgqnYoW8bW1tdTV1VFXV0dtbW1B7nEoLTzj4mgw8VNK5B8Moynih0KpaPlgvzdcAZtMJqmqqoqmdDpNOp0uWBZOiURi0IbSUBoLw71uw9k33CbsFBpO8U6iY/Xbwz1+qe/hNbdtu8/zcTBs2rSJlStX8vjjj/PQQw/hOA7nnXce3d3d0TbXXXcdDzzwAPfccw+bNm1i165dXHTRRQf1uwaDYewwz7XBUNlUtJ1m5syZWJY1pOwo8e/hYDjWIOkZ4oK/OAtO8XaDZckJlyulhtT5diCxO5jQ7W9+KCIxHkWPl7XUvul0mqamJqD/TpjF16a/4x1sdL6Unae/TDFDteQMt9E2UIOjVFmLvw90nKH8dphxKJFIMGXKlIK69zyPfftGPgDGhg0bCubvuOMOpk+fzrZt2zjzzDNpb2/nhz/8IXfeeSfnBD0mb7/9do4//ngef/xxTjvttBH/9lhw0003DVofg/19qFTuuAN274Y//3OYN2/kx7nmmmtYvHjxqJWrmJNOOmnMjn2w2LbNnXfeOeA2U6dOHafSjJxD7bl+5dJ6En/+/gG3qbP2jFNpKpP2y06j/Zixi+9mZudoGrOjHxy2pdhx48D3j1OrmUpmnEo0OBUt4idPnlwwYiv0TRMZChnbtkdskxhMCA5VxIfrBhPyBxOtHs3IdSKRKFgXnpNlWdTW1lJdXT3gcUtRaqCt/t6YHMybi/g1KK7vsfLVD/Tm5mC87sX1IYSgqqqq4Pjxa5NKpfocY7RHbG1vbwegsdEfPW/btm04jsPSpUujbebNm8ecOXPYvHlzyX/ss9lsNMYAQEdHx6iWcSDOO++8cfuticb//b/w+9/D0UcfnIg/44wz+MQnPjF6BasgLMviL/7iL8pdjFGn0p/rqe8xAv1gOTBPMHnB7jE7fsOYHfngkULTsHjszn0sqGgR39DQQGKIKRZKCRvoG20vFo/9RXSLRXzxusGEfJjjvlj8j8TyMpDFYiiR4FLnYFkW9fX1YzaserGoLi5XcVnjkxAieptSPPLpQBH44mOOppAf7Nr1dx3Cz+KRhftryITlbmhoGNa1cUaxF6NSimuvvZbTTz+d9773vYA/8FoymWTSpEkF2zY1NdHS0lLyODfffDNf/vKXR61chqHx53/uC/jjjit3SQwTCfNcGwyVR0WL+NraWpLJ5JC2DUV8f2K2mP5EXhjVHamlpnifg4k2DzTfnxVkIKtNfJ2UkpqamhFZO4ZDfw2hUgzlWg1V0CulRtUuUaq+BxLuxd9L7dcfQohhX5tcLjfkbQdj5cqVPPvss/zud787qOOsWbOG1atXR/MdHR3Mnj37YItnGITPfa7cJTBMRMxzbTBUHhUt4qurq4cs4kNrSNyqUkrA9ifOS4nyYstGXBQOxTYzXErZbPqzbBQvG0r0Pv4ppezTUXgsiQvv8DwHuz7FEfWBGk6lrsVoXZ9SAn6o2XlKvfkpXh5+D+tlJNem2HY2UlatWsWDDz7Io48+yqxYepPm5mZyuRxtbW0FUbvW1laam5tLHiuVSvX7hsxgMIwf5rk2GCqTihbx6XR6WH8sBsr9XUo09SeA4/sOFH0fTSFfSsAPNh8uKzXF15XaN/RdjzfFkflSnWtLieB4YytuuQkbVqWuxWhcn/4aVvFlcavMQPdYqfMrttmEFqLhXpuDvQe11lx99dXce++9PPLII8ydO7dg/YIFC0gkEmzcuJHly5cDsH37dnbs2MGSJUsO6rcNo4dS8Pjj8Oqrvp1mDPulGioA81wbDJVNRYv4kbT4QyvMQKJpsEwrcUtNcTS+VMfasRCKcR91OB8v32BWoVIR/Hi9SCnLFk0pJdqLv5cS6aUi8oPVvdZ+/4Ti6zYYxXXYH0Pp3DqQyI9vG55HObKmrFy5kjvvvJP777+furq6yA/b0NBAVVUVDQ0NXHHFFaxevZrGxkbq6+u5+uqrWbJkyYTLYHE4c+mlcPfd+fnPfQ6+9rXylcdQXsxzbTBUNsNWlo8++igf/ehHmTlzJkII7rvvvoL1WmtuuOEGZsyYQVVVFUuXLuXll18u2Gb//v1cdtll1NfXM2nSJK644gq6urqGXfhkMhkJ+aFOiUSiwNM+mFVjsIj8QPaW+DZDzTM+1P2GkgO+lDgfinUjTFM43LodrSmRSPSxJg10nfo711Ln1p/wVkoV5Ibv73qE12Sg4wzn7c5A1yO+zrKsg7omQ7Wd9cf3v/992tvbOeuss5gxY0Y03R1ThN/+9rf5yEc+wvLlyznzzDNpbm7mP//zPw/qdw2jx5YthQIe4NZb/eWGwxPzXBsMlc2wI/Hd3d2cfPLJ/NVf/VXJAR9uvfVWbrvtNn784x8zd+5cvvjFL7Js2TKef/550uk0AJdddhnvvPNONLjE5ZdfzpVXXjlo3t1iEonEkLPTlCLe6bE/20lxxppS0fjiaG88c0qcUPiF6/qz9wxFSBYft1QUvj9B2986IcSoeadHk3iEPX5NQsL6j1+HeJR+MFtNnIMZ0Ks/G01/3weLwId530fDjnWwWYaG0gBNp9OsW7eOdevWHdRvGcaGl17qf7mx1RyemOfaYKhshq3Yzj//fM4///yS67TWrF27li984Qt87GMfA+AnP/kJTU1N3HfffVxyySW88MILbNiwga1bt7Jw4UIAvvOd7/DhD3+Yb3zjG8ycOXPIZTlYEQ99BSLkRXhxlHSgDq7Fdo4woj2QUB8upSLJ/R1roLcLpcTjQHn0JwLFdRvWd7FnPi6Ai0V9fLuwDkazY+tgAr5Uw6nUunAgstHsFD1WqUINlUN/KSVNqkmDwWCoTEY17Pr666/T0tJSMDBEQ0MDixcvZvPmzVxyySVs3ryZSZMmRQIeYOnSpUgp2bJlCx//+Mf7HLe/wSNGQ8QXUxzpHahjZSmRGBft8Yj8weQk7y86Xyzq+4vCF4vF+OdoRXrHm1JvI8I3I8VvWML54tzy4X4wMjFfSrwP9PYjvm2pxthQRhEeKUbEGxYvhjPOgHgGweuvN1F4g8FgqFRGVcSHnWKamgoH1Y0PDNHS0sL06dMLC2HbNDY2DnvwCCnlqIuewbLNDBTh7a9ja7jfcMX8QNaagQR8KXFZPD/cjpwTkeLOq/0J9/BcS70hKSWqBxtNN2SwRlU435+dKW6vGuvOqpXYUDOMPiee6Iv4P/9z+Id/MALeYDAYKpmJZ4AuQX+DR9i2PeYe7mIPdbGtpnh9GO0tFk3FlpuBBHQpK0ycUt7r4n2KxWLcZlKO7CbjSXFjqtR8caOqPytMMf01qIobW/0J+pDxvg4Tsa+DYfx5803/86MfNQLeYDAYKp1R/Zc9HPyhtbWVGTNmRMtbW1uZP39+tM3u3bsL9nNdl/379w978IjxEPFxSgn2Up1bi60bxceIfw7394vFYn+dWouFe6VH3UdKcT+HuJ2mvzckQ702/Yn3/t6glDMabkS8AeCNN/zPI48sazEMBoPBMAqM6r/sc+fOpbm5mY0bN0aivaOjgy1btnDVVVcBsGTJEtra2ti2bRsLFiwA4OGHH0YpxeJhhobK5ecuFYUvJeRHaqMp9XulRGEpAR9uDwwp6n+4UcoiVaqxM9SBwfrbpvgY5b4Gxk5j0DofiT/qqLIWxWAwGAyjwLBFfFdXF6+88ko0//rrr/P000/T2NjInDlzuPbaa/nKV77CscceG6WYnDlzJhdeeCEAxx9/PH/2Z3/GZz7zGdavX4/jOKxatYpLLrlkWJlpwM+dXW5rSLGQ9zyvwE5TLBLDz8HsNANF7PvzWYcYwTYyBhLnQ2Wi1n25n5OJxmuvvUZPT8+YHb+9vX3QbbZv387evXtHdPzit5lDYd8+6O72v8+ePaKfLWDnzp08++yzB3+gfmhqamLatGljdvwDBw6MafkN48/uvfXo7Nj9rTu62x10G++dalo7RzZQ4oz28meIS+8TtL49ecyOn6zPMrlu7P72Jjo9do5h+Q+WBl4f1eMNW8Q/+eSTnH322dF86FVfsWIFd9xxB5/73Ofo7u7myiuvpK2tjTPOOIMNGzZEOeIBfvazn7Fq1SrOPfdcpJQsX76c2267bfiFH2U7zXAFXCk/dThfKhd5f8K8OJ3lQBT74Qfydg+V0YwSFzdYxoNS53ww9THaDFSW8aonY6cp5NJLL2VLmUc5Ouuss8b190IrzYwZEPtzPGLi/ZTGgn/6p3/iH/7hH8bs+L/4xS/4xS9+MWbHN4w/x307i/7Dc2UtwzHXPV7W3z9Ymtc+Rmlj8+iw+2/eDx8ZOxFvb9zGcRvH7PATjmH/y37WWWcNKIyEENx0003cdNNN/W7T2Ng47IGd+vutsYx8DjQo0GjuNxyhWTyo0ViW61CkVB2MJM1kf/tM1Dout53HUH5CK43xwxsMBsOhQUWH58baEz/SY4+1iJuo5aoEStXBSOqlv30mah1P1HIZxo8wEm/88AaDwXBoUNEi/nDOumIwDAfznBi2bvU/zQitBoPBcGhQ0SK+UkcbNRjGG/OcHN5ks7Bhg//9/PPLWxaDwWAwjA4VKeJDD3kmkzERRoNhCGQyGWBidPQ1jD//9/9CezvMmgWLFpW7NAaDwWAYDSpSxO/btw+Az372s2UuicFQWXR2dtLQ0FDuYhjGka4u+OpX/e9r1oB5KWMwGAyHBhUp4hsbGwHYsWOHESQjoKOjg9mzZ7Nz507q6+vLXZyKpNLqUGtNZ2fnsMdiMFQ+//iPsGsXzJ0LV1xR7tIYDAaDYbSoSBEf+nsbGhoqQkBNVOrr6039HSSVVIemwZvnsssu4wMf+MCYHf+Xv/wlL7zwwoDbXHXVVdTU1IxZGZqamnjsMfjmN/35f/5nSA1xDJp58+bx//1//9+Yla2lpYWf/vSnY3b82traMS3/ePDNb37T2N+Gya5zGkiftGTMjj/1sVa8l18bcJu3/uH9uDVjd90+V/svI953/rS3+eOKsaufqv0e6QeeGLPjp9IOB8aw/GON0DDp3x73h88eJSpSxBsMBsPBcPXVV4/p8Xft2jWoiL/hhhtobh67YVXefBMuuQQ8Dy69FD760aHvO3/+fObPnz9mZdu6deuYivj6+nq+/vWvj9nxxxqtNd/+9rfxPK/cRakoqs8d/kjGw6F731TSg4j4f/nr73J6emJ61i6cso1nLp4xZsff8UYjxz0wZoenNp2Fi/eM3Q+MBz+VoEfvuZ6Yd5rBYDAYRsxTT8EHPgA7d8Kxx8L69eUukcFgMBhGm4oU8alUihtvvJHUUN8NGwow9XfwmDo0TDQ8Dx55BFasgIULfQH/7nfDww9DXV25S2cwGAyG0aYi7TSpVIovfelL5S5GxWLq7+AxdWgYbzzPH7DpN7+B55+Hffsgl4Nk0v/+0kvQ3Z3f/i/+AtauhenTy1Zkg8FgMIwhFSniDQaD4XCgvR0eeAB+8Qv47W/hwIGBt588GT7+cbjySli8eHzKaDAYDIbyYES8wWAwTDC6u+FLX4LbbvOj7SENDbB0Kbz//TBtGqTT/vr6ejjuODj6aLDNX3WDwWA4LDB/7g0Gg2EC8dhj8Jd/Ca+/7s/Pmwef+AR8+MNw6qlGpBsMBoPBx/xzYDAYDBOIujq/U+rs2fC978FHPlLuEhkMBoNhIlKR2WnWrVvHUUcdRTqdZvHixTzxxNgNLlAp3HzzzZx66qnU1dUxffp0LrzwQrZv316wTSaTYeXKlUyZMoXa2lqWL19Oa2trwTY7duzgggsuoLq6munTp/P3f//3uK47nqcyIbjlllsQQnDttddGy0z9GcaDE0+E++/3O68aAW8wGAyG/qg4EX/33XezevVqbrzxRp566ilOPvlkli1bxu7dYzvIw0Rn06ZNrFy5kscff5yHHnoIx3E477zz6I6lq7juuut44IEHuOeee9i0aRO7du3ioosuitZ7nscFF1xALpfjscce48c//jF33HEHN9xwQzlOqWxs3bqVH/zgB5x00kkFyw/n+nv00Uf56Ec/ysyZMxFCcN999xWs11pzww03MGPGDKqqqli6dCkvv/xyeQp7CPDhD0NtbblLYTgcMM+2wVC5VJyI/9a3vsVnPvMZLr/8ck444QTWr19PdXU1P/rRj8pdtLKyYcMGPv3pT/Oe97yHk08+mTvuuIMdO3awbds2ANrb2/nhD3/It771Lc455xwWLFjA7bffzmOPPcbjjz8OwG9+8xuef/55fvrTnzJ//nzOP/98/vEf/5F169aRi/euO4Tp6urisssu41//9V+ZPHlytPxwr7/u7m5OPvlk1q1bV3L9rbfeym233cb69evZsmULNTU1LFu2jEwmM84lNRgMw8E82wZD5VJRIj6Xy7Ft2zaWLl0aLZNSsnTpUjZv3lzGkk082tvbAWhsbARg27ZtOI5TUHfz5s1jzpw5Ud1t3ryZE088kaampmibZcuW0dHRwXPPPTeOpS8fK1eu5IILLiioJzD1d/755/OVr3yFj3/8433Waa1Zu3YtX/jCF/jYxz7GSSedxE9+8hN27drVJ6pnMBgmFubZNhgql4oS8Xv37sXzvAKRBNDU1ERLS0uZSjXxUEpx7bXXcvrpp/Pe974XgJaWFpLJJJMmTSrYNl53LS0tJes2XHeoc9ddd/HUU09x880391ln6q9/Xn/9dVpaWgoaOA0NDSxevHjAxnU2m6Wjo6NgMhgME4eRPNvmuTYYxo+KEvGGobFy5UqeffZZ7rrrrnIXpWLYuXMn11xzDT/72c9Ip9PlLk5FETZQhtu4vvnmm2loaIim2bNnj2k5DQbD8BjJs22ea4Nh/KioFJNTp07Fsqw+GUFaW1tpbm4uU6kmFqtWreLBBx/k0UcfZdasWdHy5uZmcrkcbW1tBdHkeN01Nzf3yfQT1vWhXr/btm1j9+7dnHLKKdEyz/N49NFH+e53v8uvf/1rU3+jzJo1a1i9enU039HRMax/8Lu6usaiWKPCUDISdXd309nZOWZlqK6uxrKsEe3rOM6Yep57enrG7Njgv42Md+ovRSKRGHGDXWs9oe+/cnIwz7VWmu5scqyKdtCkPT3oNjudKeywd45ZGRqljRxh/LXTmzym9SuzYxsXVlrQm0sMuI0tFanEyDPCjfX91zDKx6soEZ9MJlmwYAEbN27kwgsvBPw/1hs3bmTVqlXlLVyZ0Vpz9dVXc++99/LII48wd+7cgvULFiwgkUiwceNGli9fDsD27dvZsWMHS5YsAWDJkiX80z/9E7t372b69OkAPPTQQ9TX13PCCSeM7wmNM+eeey7PPPNMwbLLL7+cefPmcf311zN79mxTf/0QNlBaW1uZMWNGtLy1tZX58+f3u18qlSKVSo3oN13Xpb6+fkT7ThSOOeaYMT3+tm3bChqlw+HnP/85f/EXfzHKJRo/WlpaOOKIIwbcZsWKFdxxxx0jOn4ul6v4+28ojOTZPpjnGuUx8+PPj2zfCcLt7z6S2zlyzI7/0vpFNM3ZP6J925+YzpwvPTbKJRo/DrTX8K5Lnx5wm94LF5G7cmT1k3Otirv/KkrEA6xevZoVK1awcOFCFi1axNq1a+nu7ubyyy8vd9HKysqVK7nzzju5//77qauri151NjQ0UFVVRUNDA1dccQWrV6+msbGR+vp6rr76apYsWcJpp50GwHnnnccJJ5zAJz/5SW699VZaWlr4whe+wMqVK0f+R7lCqKuri/oPhNTU1DBlypRouam/0sydO5fm5mY2btwY/cPe0dHBli1buOqqq8pbOIPBMGLMs20wTGwqTsRffPHF7NmzhxtuuIGWlhbmz5/Phg0b+nj2Dje+//3vA3DWWWcVLL/99tv59Kc/DcC3v/1tpJQsX76cbDbLsmXL+N73vhdta1kWDz74IFdddRVLliyhpqaGFStWcNNNN43XaUxoDuf66+rq4pVXXonmX3/9dZ5++mkaGxuZM2cO1157LV/5ylc49thjmTt3Ll/84heZOXNm9MbMYDBMTMyzbTBULhUn4sH3fR/u9plitB7cq5dOp1m3bl2/+YABjjzySH71q1+NZtEqlkceeaRg/nCuvyeffJKzzz47mg89r6El4XOf+xzd3d1ceeWVtLW1ccYZZ7BhwwbTSdhgmOCYZ9tgqFwqUsQbDIbx5ayzzhqwoSiE4Kabbjok3joYDIcT5tk2GCoXk2LSYDAYDAaDwWCoMIyINxgMBoPBYDAYKgwj4g0Gg8FgMBgMhgqjrJ74devW8fWvf52WlhZOPvlkvvOd77Bo0aJyFslgMFQAQgjOOeecchdjQlNXVzemxz/xxBOj8RDGgqOOOmrMjn2wCCE499xzx/Q3Hn744SElLDjU0KfPL3cRJjQi7Y3p8a3jj8VtrBmz42emwkRNuCyEHvP7T/z+6VE9XtlE/N13383q1atZv349ixcvZu3atSxbtozt27eP6T8MBoOh8rEsi4ceegghRLmLcthyww038IlPfKLcxSgLyWSS3/72t2N2fK01iUQCzxtbwTbRELZN+/8xI+EOxFiro1cvncrkBXvG7PgNTNzrm7AUHWN8/zV8xAI1es912ew03/rWt/jMZz7D5ZdfzgknnMD69euprq7mRz/6UbmKZDAYDAaDwWAwVARlicTncjm2bdvGmjVromVSSpYuXcrmzZv7bJ/NZslms9G8Uor9+/czZcoUE4kzGIaA1prOzk5mzpyJlKYrjMFgMBgMlU5ZRPzevXvxPK/PKKtNTU28+OKLfba/+eab+fKXvzxexTMYDll27tzJrFmzyl0Mg8FgMBgMB0lFDPa0Zs2aaBQ5gPb2dubMmcN1iyFVEWdgMJSXrAvf3jL2nR0NBoPBYDCMD2WRwFOnTsWyLFpbWwuWt7a20tzc3Gf7VCpFKtW3P3PKNiJ+IqIBJw1aguWA7ZS7RIYQYz8zGAwGg+HQoCzm2GQyyYIFC9i4cWO0TCnFxo0bWbJkSTmKZBgllISnPwI/Wg/fuwP+4xbY+Z5yl8pgMBgMBoPh0KJscezVq1ezYsUKFi5cyKJFi1i7di3d3d1cfvnl5SqSYRTorYONfwXdjf58x3R41+9g9nPlLZfBYDAYDAbDoUTZRPzFF1/Mnj17uOGGG2hpaWH+/Pls2LChT2fXQ4Gayc0kq6qjeSETzJj3fqYeMafA3qC1Zu/bb/LOi5vRKu9ByfX20H2gZVzLPFKEgmQWujUg/PlEb7lLZTAYDAaDwXBoUVZH+apVq1i1alU5izBqWHYSYSWYcewppGpqOeqUDzH1iHchhGTau06mbvLUgu1lIomUVh8Rr5SHcnIF23Ye2MOe1/6E1oq9b73KG3/4LdnuLt55+Sm05+C5hduXk6pOuOQG2N8EWGBl4Miny10qg8FgMBgMhkML0y10hAghqZs6k6bjFtF01Ls57rQPUzOpifqmOdiJZLDN8DoRCiGwLBvLKrwsjTOOpHHGkYAv9E+/+DpcJ0dH6w6621p56fFf0fr6dlpffoLOvbvQWo3OSY4AAUx/Gaa9nJ+fiAhhUdPYFNW1tFMc+b5zqG2YPOi+Xe0HePMPD6Ncf+wCz3Pp3t+K1ofX6IoGg8FgMBjKhxHxw0DaCWYcM59jl3yEpnedyJEnnUmyui4S7eNB2DBIJFNMmX0sU2Yfy5wTz8B1cuR6OnnzT4/S+tqfeHnzL3nnladRbnlSw0wU8S4tG2knmHncKViJKo465UNMmXkkViLFrPe8n2Q6HW5JIlWFtKxBj6k8DyfbC/iNpVwmw1vPPYbnZNn39pu88YeH8Jxedr30FMp1UJ47didoMBgMBoPhsMSI+EFIpGtoPOJojlvyEU44czlTjzweO5mecKn67EQSu2EKx3/g48w740JOv+Rz7HnzeV7Y9HNeevyX7H/7VZxMd7mLOeZIO0F1w1SOmHcq0448gXefcSHpmnoajzgGGUTdD/baScsiVV0bzaeq6zn+AxcC/puSM//y71Gey/63XyHT1c6Lv7+PvW88z9vbn6SnfW/ZGlYGg8FgMBgOHYyIL4mgftoRHP/Bi3nPBy+k6eiTSVbVTjjh3h9CCBKpKmYet4AZx57CGZetoeWVP/Lco/fy4qZ/p2PP2/jZ3A8N7GSapqNP5l2nns+sd7+POSedQSJdg53oO7bAWBPeI5adYNqRxwMw+z2n4TpZnEw3O/70O97a/gde2/pftL76R9xcZtzLaDAYDAaDofIxIj6GtBPMOn4x8868hPee9THqph4BVPYAOUIIUtV1zDnxdOaceDqn/+/reG7T/bz46P/jrReeqNiocKq6nunvei9Hn7qM48+4kKlHHo+07Al7rexECjuR4t2n/znHvf+jnPWpf2Dvmy/wwv/cy6tbf8Pu158h29NZ7mJWHFofOo3RSqSS619rXdHlNxjGAmEeiYpC6Ar8K9bR0UFDQwOfP310RmyViTSzTzyLRR/7a45d9Gckq2oO/qATnFxvFy9v2cAT9/9fdj67CeVUQERYCBpnHsOJH/ok807/CFNmHUuyqnbw/SY4ud4u9r31Ei/+/kGeeejf2L/rVRilx1IDCMi68LXfQXt7O/X19aNy7NEmfK6HijWE/guGkeFnyhq4g7yUcsI2mgE8b+CO5kIIpCzLeIdDYrDyx6mE5/osPoYtEoPvIM1zPWZoNfi/LUKAmLjPBWoIz8VEvoeGUn7A1Q6PcP+gz/ZhHYm3U9Ucf+ZyTv3Y3zDjuPdhJ5IT+h+l0SRZVcsJH1zOcUs+yq6X/8DW+9bx4qP/iZvrKXfR+pCqrmfOiWew6KJVzHz3Qqobph5S1ylZVcuMY0+h+Zj3sejCq9i1/Um2/Od32PnM78n2dBzUsbsnwwN/D6oDOH90yjtRGI7IMYw+g4n8iY7W2txDE5EhihzDGKE1VHqmtcPoHjosRbwQFnMX/hmnXriS4xYvxbKHEB04BPG98ymOfO9pzHr3Kbx09qVsvW8drz+5YUKkS6ydOouTzr2EUy74ayY1H4mdTA++UwUjhKBm0jSOXXw+R80/i7bWN/nDL/8vf/rt3XTte2tEx/TSkK0HTIIcg8FgMBgOKQ4rO420bJqPmc9pn1jNvDP+nES6+pCK6B4sWmucTA8v/u5+Hvv3b9Dy8h9GdBxlgZOEZO/wU01Ky2bKnBN4z7l/yfwPXUrDtBmICfzKe6zRStG+ZxdPP/T/eG7jv7FvxwvDSlmpAW1B1oFb/6cyXrsbDIbhUQnP9ZDtNAaDwdhpimlonssHP/VF3vPB5aRqJuYfu3IjhCBZVcNJH7qUKXPmcfvVZ+Dmeod9nKcuhKfOh79cDdVDdYMIQfPR8zntf13Du9//56RrJ5kGFiCkZFLTLD542f/H4o/9Ndt//wse/4+1tLz6xyH55gUgPJCV7XwwGAwGg8FQxGEj4ucvW8H7zv+0EYZDxE5V+R1cRsCcbTDlNUgOwV4vpMX0ue/htE9cy/FnXkSqut5coxIIIaiqm8zJyz7FrPcs4QefeR9OZuL1XzAYDAaDwTA+HFIiPlsFmVqo39PXxnE4WzLGm+lvAG8Mvl3jEcdxxmXXc/wHPm4i70NECBH04Sisq67JIL1hvPkwGAwGg8FQ0RxSyjZXDR3TGL4R21ASKS2sRKrvZCf73UcDbgL0ANegqq6R0y5ew19+/Te87/zLqaqbbAT8QfLqWfDSknKXwmfdunUcddRRpNNpFi9ezBNPPFHuIhkMhoPEPNcGw8TjkIrET+6s4tT3XMC0y05Aq1zBujknnl6mUlUmNQ1TOO/q7zH7+PdhWYW3Saa7k8f+/Zu89Pv7+3jmvSS8eDrMfQpq2guPmaxu4L3nXMxpn/hbph15ghHuIyRd08D7L/47PCd/j58BUAWdy97h+U0/x8l0FewzXr3X7777blavXs369etZvHgxa9euZdmyZWzfvp3p06ePUykMBsNoYp5rg2FiUtHZaf52uc2UA3khOO/Mi/j4mjtIHOKpCCcCTi7DC4/eyyN3fIm2d14vWJdr8EVjqkjEL/rE3/Ghz9x02Kb0HA881+G1PzzKoz++ibdf3Byp94yruflRd8yzWCxevJhTTz2V7373u4CfS3z27NlcffXVfP7znx9wX5OdxmAYGZXwXJvsNAbD0DksstP89TceZbrKj9hZVTfZCPhxIpFMc+K5l3D0wqV07W8Z0j7Vk6YjrYq+5SY8lp3gmIXncOR7T+PAO68TqvjOzi5unv/+Mf3tXC7Htm3bWLNmTbRMSsnSpUvZvHlzn+2z2SzZbDaab29v77ONwWAYnLGMxY3Wc+3ijN8rQYOhwnFxgMGf7YpWVEc2vmfC5sY9HAgHJ6qZNK3cRTHECFOFNr3rvdGyqo6x7/G6d+9ePM+jqampYHlTUxMvvvhin+1vvvlmvvzlL495uQyGQ53Ozs4xe4s1Ws/17/jVmJTPYDiUGezZrmgRbzAYKpc1a9awevXqaL6trY0jjzySHTt2GFtNP3R0dDB79mx27txpAhj9cDjVkdaazs5OZs6cWe6iRJjnevgcTvfsSDnc6mioz7YR8QaDYVSYOnUqlmXR2tpasLy1tZXm5uY+26dSKVKpVJ/lDQ0Nh8Uf6YOhvr7e1NEgHC51NNbC2DzX48fhcs8eDIdTHQ3l2T6kUkwaDIbykUwmWbBgARs3boyWKaXYuHEjS5ZMkPyXBoNhWJjn2mCYuFR0JF5r3cf0b9IWji/D7VAlYMQjwRqGTvF1Ga8kVKtXr2bFihUsXLiQRYsWsXbtWrq7u7n88svH5fcNBsPoY55rg2FiUtEi/mfXX0BVKn8Kx5y6jA/85ZoB9jCMJr1dHTxx73fZ89hvOGk/KMAN9LmtIamhyoMqF9JZsC/+FNanLzdjcY0xbi7LC/9zL9seWE+o3Xuz7rj89sUXX8yePXu44YYbaGlpYf78+WzYsKFPp7hSpFIpbrzxxpKv4g0+po4Gx9TR6GOe67HF1NHgmDoqTUXnif/8+yGm4Zlx3Cn8r5t+zuTmIwu211qjPBfLTphI/RAZ6A2H1poD77zBL75+Ba1/+B+WP+dy9N7+B8p9swG2zQR1/gV86Pr11E87wlyHg8Bzcxx45w2SVQ3UNk4rqMuOPW/z3z/6Is/+9924mfxAXFkXbnls7PNJGwwGg8FgGB8qWsQ/NQnqAv2yowF210BD87uYOvuYgu21Uky/4C848n9dbsTjEDnQsoMN3/lbJh3xHo58zykIKbE0SAWde3fx+3//Fh3vvMbCVjj3FbAGuIuyFvz7ifBag6C++UjOuOwLzD/vUhKpqvE7oUOIA++8wb9cuQC7ahLNR7yLqVlJY6DX9775Ah173uKo/ZopscF0OzWc0mZEvMFgMBgMhwoVbac5ug1COXLMgeDLc68Br/Xd+Jgzx6dQhwi5TDevPvkQ6nf3s6sDjj4AR3TDlC5oBI4KtqvLDSzgAZIefPgl+O1Rmpe9N/ivf76KFzf9O+f/7T8zZfa7TcNq2Gg8J8usN17j/b95jaZuqB7ELTP2WeINBoPBYDCMJxUt4oeCBpTw+1IK+rd8GPpS7cLJO+ADOyHhjbzuBDClBz7xAjzTBL99l8OrT/6GH119BgsvvI73/+9VpKrrjZgfIpaGk/fAB7f710hU3Ls0g8FgMBgMB8shKeLb0/DsVF+8A7zTAEfNgFPLW6yKwxP5KPtoyGtLw8ktkNDw27lwoH0fj/7ki7z0+/9gyf+6jhPOvphE0nRaGQxXebxRp3ltPjT3wplvQlNnuUtlMBgMBoNhPDkk88QnPXhpCmycCxvfBc9PgT9t+y/efnErSnnlLl5FoJUiZ8HmWXDPCfD8VGip8d9sHAwCOKEV/uIZmNoNaE3LK0/zi69/hp9/5ZPsemmbuUb9oJTHru3b+PX669krM+yrhuca4eGjoPsQaPusW7eOo446inQ6zeLFi3niiSfKXaSycPPNN3PqqadSV1fH9OnTufDCC9m+fXvBNplMhpUrVzJlyhRqa2tZvnx5n8F4DiduueUWhBBce+210TJTRxMD81z7mOd6+JjnenAOSRGf8GDp6zA11rHvrec3829/9yE2fOdautv2lK9wFUB32x62/HwtTq6XrA0vT4Z750FbenSOL4Bp3XDmDqhy/GWem+PFR+/hx9eezf23XM6u7dtQ3vikRZzoKM9l1/Ynue+Wy7njurPZ/rv/RCsFwKQcnPUGVGfLW8aD5e6772b16tXceOONPPXUU5x88sksW7aM3bt3l7to486mTZtYuXIljz/+OA899BCO43DeeefR3d0dbXPdddfxwAMPcM8997Bp0yZ27drFRRddVMZSl4+tW7fygx/8gJNOOqlguamj8mOe6zzmuR4e5rkeInqYbNq0SX/kIx/RM2bM0IC+9957C9YrpfQXv/hF3dzcrNPptD733HP1Sy+9VLDNvn379KWXXqrr6up0Q0OD/qu/+ivd2dk55DK0t7drQLeD1v1MCvQ7tejbFqFvPBN94wf96UtnSf2dT52g//Twz7Xr5IZ7+oc0rpPTf3r45/o7nzpBf+ksGdXZjWei/3kxek9N//U9kskD/U4N+kfvQ38pdo1u/CD6q+fX63tvuVy/8/LTWnleuaumLCjP0++8/Ad9782f1l89v76gfm48E/2dheiWWv9eH6yu2/2XKLq9vb3cp1WSRYsW6ZUrV0bznufpmTNn6ptvvrmMpZoY7N69WwN606ZNWmut29radCKR0Pfcc0+0zQsvvKABvXnz5nIVsyx0dnbqY489Vj/00EP6gx/8oL7mmmu01qaOJgrmue4f81z3j3muh86wI/Hd3d2cfPLJrFu3ruT6W2+9ldtuu43169ezZcsWampqWLZsGZlMJtrmsssu47nnnuOhhx7iwQcf5NFHH+XKK68cdgNkIATQ1AUXbYd6J79ca8XeN5/nvq9eyr/f8AneeHoTnuv0e5zDAc91eOPpR7j7huXc99VL2fvm82itovWTc/Dxl2FK9wAHGQESaOqGy/4EC3cVdtDM9nTw9H/dzu3XfJBffOMztLzyNN5hEpn3XJd3XvYtRrdfcxZPb7iDbE9hfpmpPfC/n4fpXZXfWTuXy7Ft2zaWLl0aLZNSsnTpUjZv3lzGkk0M2tvbAWhsbARg27ZtOI5TUF/z5s1jzpw5h119rVy5kgsuuKCgLsDU0UTAPNcDY57r/jHP9dAZdsfW888/n/PPP7/kOq01a9eu5Qtf+AIf+9jHAPjJT35CU1MT9913H5dccgkvvPACGzZsYOvWrSxcuBCA73znO3z4wx/mG9/4BjNnzjyI0ylEADPb4ZJn4D+Oh/1VRIrHc7Jsf+wXvP6HRzhp2ad5//++lskzjjpsMqRorQHNgXfe5Pf/vpZnfn0Hud6iRIQaJmd9AT9r/9iIRYHfh2Hp69Be5Vt3dOyHst3t/OFXP+KFR/+TY9//55y09JMcddL7sVNVh9S10lrjZnt540+/508P/ZSXHrufbHd70UaQ9uCITjjvVZjWU/kCHmDv3r14ntdn9MempiZefPHFMpVqYqCU4tprr+X000/nve99LwAtLS0kk0kmTZpUsG1TUxMtLS1lKGV5uOuuu3jqqafYunVrn3WmjsqPea77xzzX/WOe6+ExqtlpXn/9dVpaWgpaSQ0NDSxevJjNmzdzySWXsHnzZiZNmhQJeIClS5cipWTLli18/OMf73PcbDZLNps3/XZ0DD3rtQBmdPlRy38/AfZXF67P9Xbw5H238eL//AcnnfcpFl14FQ3TZiHkIdldAPA7rbbveYsn7v0ef/rNT+ja/07J7Rp7/Xpr6h57sZj0YPnz8Ivj4Lnpfddnutp45jc/4dnf/oxZJ5zG/D9bwdELz6NuykysRGKMSzd2eI5D575dvPrkb3h6wx289fwWdKmOvRrmtsOHXofmDpMu9XBh5cqVPPvss/zud78rd1EmFDt37uSaa67hoYceIp0epc46BsM4YZ7r0pjneviMqogPW0KlWt7hupaWFqZPL1Rptm3T2NjYb0vq5ptv5stf/vKIyyXwhej/egE2HAdv1tJHAXXt28Vj/+8Wnv3tzzhuyUc4edknOWLeIoSUh0TEV2uNVh5vv7iVP/7633hp8wN07Hmr5LaWhhP2wBk7YPo4CHjI/8a798HsDj896JMzCt+eAGjlsfPZ37Pz2d9TPWk6R558Dgs+cgUzj3sfVfX+a8mJfL10MEByb8c+dr30B7Y9+EPe/ON/09PWT0cvDUkFi96G096C2kPQ+TV16lQsy+qTYaC1tZXm5uYylar8rFq1KrIbzpo1K1re3NxMLpejra2tICJ1ONXXtm3b2L17N6ecckq0zPM8Hn30Ub773e/y61//+rCvo3JjnuvSmOe6f8xzPXwqIk/8mjVrWL16dTTf0dHB7Nmzh3UMATR3+akN7zoB3migpDrt2LOTJ3/xff746x9z3Ps/wnvPuYS57zubVE3DhBaH/aG1Jtvdzut/+G+e3XgXL21+ECfb0+/2aQc+/Kov4m3V72ZjQsqDkwItq4Hj98Lm2fB0E+Ssvtv3tO3mhU138eL/3EPjEcfSfNxCjjvtzzjq5DOpbpiKnUxPiGumtcbNZehp38sbf3yUlx7fQMtLW9n/9iulo+4BQsOcTjjndZjddoimkgKSySQLFixg48aNXHjhhYD/unnjxo2sWrWqvIUrA1prrr76au69914eeeQR5s6dW7B+wYIFJBIJNm7cyPLlywHYvn07O3bsYMmSJeUo8rhz7rnn8swzzxQsu/zyy5k3bx7XX389s2fPPuzrqNyY57oQ81wPjnmuh8+oiviwJdTa2sqMGTOi5a2trcyfPz/apji9lOu67N+/v9+WVCqVIpU6+ETYAkg5fmfXTUfCM1Mh108NONkenvvvf+f5TT9n+twTmXfGxzjhzIuYMvs4rERqQojD/tBa4zlZ9u7czguP/icv/u5+dr/+7ICCEQ0zenzBeMy+8ls1BDA5A8tegeP2wmOz/YaXKuEj0cpj384X2bfzRZ7b+FNqJjfROPs9HHniacw95UNMajqCyTPmIqTfEhjLaxdG2rXyOPDO6xxofZs3nnqIN5/ZzP6dz9N9YAj5bDVMysKCFjj1bUgfBv15V69ezYoVK1i4cCGLFi1i7dq1dHd3c/nll5e7aOPOypUrufPOO7n//vupq6uL3lA2NDRQVVVFQ0MDV1xxBatXr6axsZH6+nquvvpqlixZwmmnnVbm0o8PdXV1kZc4pKamhilTpkTLD/c6mgiY5zqPea4HxzzXw2dURfzcuXNpbm5m48aNkWjv6Ohgy5YtXHXVVQAsWbKEtrY2tm3bxoIFCwB4+OGHUUqxePHi0SxOSQRQl4ELtsPR+2Dj0bAvRb+qVSuP1lefpvXVp/ndnbcw890LOG7JR3nXgqVMO+p47GQaKUuEiccZpTzcXIY9bzzPa9t+y0ubH2TX9m14zuAJxC0F794Pf/YK1GXLL+DjWBqOOQBHtsPzTbBpNuxPM2Ahuw+00n2glZ1/epjH7vo6djLJzHmLSFbV8p6z/hfJqlrqph3J9COPg0DQ28kq5DD6QSilcHPBQARas/vN7XTu2UGup4vnNt1DrqeLt198As/JobwhemC033BZ8I4/sm2tM7GuxVhy8cUXs2fPHm644QZaWlqYP38+GzZs6GPNOxz4/ve/D8BZZ51VsPz222/n05/+NADf/va3kVKyfPlystksy5Yt43vf+944l3RiY+qo/JjnOo95rkcHU0eFCB2GDodIV1cXr7zyCgDve9/7+Na3vsXZZ59NY2Mjc+bM4Wtf+xq33HILP/7xj5k7dy5f/OIX+dOf/sTzzz8fdVQ4//zzaW1tZf369TiOw+WXX87ChQu58847h1SGjo4OGhoaaAfqh3e+BWj8AYx+dSy8OgnUMPwKyeo6aiZN45hF5zN19nEce9qHqZ40jXRNw0GUaHhkutrpbtvDy1t+xb6d23llywa62/eQ6+kc8jFqc3DGTjh1ly/mJzqdSfhDMzw2CzIH0Z81WV1PdcMUAKRlc8ziD1NVO/Rr19vZzitP/CoakKqnfR+5nqF3uC5AQ0MWFr4D81ugLjeywwxEB9CAn9asvv5gnhqDwWAwGAwTgWGL+EceeYSzzz67z/IVK1Zwxx13oLXmxhtv5F/+5V9oa2vjjDPO4Hvf+x7HHXdctO3+/ftZtWoVDzzwQNSiuu2226itrR1SGUZLxIc4Ep6aCb8/AjoGiMr3hxASK5li2px51E+fzawTltB8zMlYiTQz370AO5H0t5M20rKGZOfQWqM8N7LAuE4uiKxnaHnlj7z1/Gbad+9k744XcXMZf0ifYVLjwCXPwqyOyor4KgG7av1Or9tmwM764TXAJgpSQVMvzNsN7wvE+1hdByPiDQaDwWA4tBi2iJ8IjLaIBz8q35GCjXPhhangjIJDRlo2DU1HIi3/YNPnnsTM494XWTgGLpBm10t/YPfrfwJAeR5trW+iR2PAIw2NGViyE05p8S0rlYgGXAmvTIaXpsArjdCVLMwzPxFJO3BUJ5y8C97VDkl37BtRRsQbDAaDwXBoYUR8Ea7wI7uPzYbXJoN3qCXk1jA9Axc/B43jlD5yPFBAxoZXp8Bz02BXDXSmJoagF9rP9DOjE96zB45qg6m949t4MiLeYDAYDIZDi4pIMTme2BqOaoc5Hb4YfPC40ukNKwoN/3979xMSVb/Hcfyjjn/SZsZHwxFvRl3oEt7+kWYNLQoSXbiJXLSIsGgVx9CEdqHQxmhTBCWtqk0ULiKSCAaLgcjIqwQW5eryjM+N0ZJGJ++j45/fXUzOfYbi0n0yz/zs/YIDzu/8kO/56uIzh9/5nTXzyWVDG2PSgcjqCvBScvvFwnlp61jyiOdJv/mkiD/5ZexTrvTvXK3YRecuJHeV+etHaVNc+kss+fKsbLO6+g4AANxBiP+KLCXvkv79vfRLQvpHILnEJpEjexLY57BYPJN8aPVvE8k705WTyS8qq9XSn8eXkKo+JPeaT+RIv3ukX4uTQf7NOuljwfItvckyyXBe/knyziW3xCz9PfmirPz51bu/OwAAcI+Vy2kmJydVXFysUS3/cpqvMZKiRdJwWfLu/PfsirIiTHKtdc2/pMAnqWgF1lzbYumffSpPeueVfv3DhjSRX6SJb3jTc+mMtOHjfz9vmJQmCj9/6ZtJjmVav6ckVUqKxWLy+1duByUAAPBjWHknfmJiQlIylKyYaUn//HzAfglJE5+P5bBcv+cHi8fjhHgAAFYBK0N8SUmJJCkSiRBI/oSpqSlVVlZqdHSUhxz/JNt6aIxRPB5XRUWF26UAAIBlYGWIX3qzpt/vtyJAZSqfz0f/vpNNPeQLLwAAqwfP3AEAAACWIcQDAAAAlrEyxOfn56uzs1P5+flul2Il+vf96CEAAHCTlVtMAgAAAD8zK+/EAwAAAD8zQjwAAABgGUI8AAAAYBlCPAAAAGAZK0P81atXtXHjRhUUFGjPnj168eKF2yW5rqurS7t375bX61VZWZkOHTqkkZGRtDkzMzNyHEelpaVau3atmpqaNDY2ljYnEomosbFRhYWFKisr09mzZzU/P7+Sl5IRLly4oKysLLW1taXG6B8AAMgU1oX4u3fvqr29XZ2dnRoaGtKOHTvU0NCg8fFxt0tzVTgcluM4ev78uUKhkObm5lRfX6/p6enUnDNnzujBgwfq6elROBzWu3fvdPjw4dT5hYUFNTY2KpFI6NmzZ7p165Zu3rypjo4ONy7JNQMDA7p+/bq2b9+eNk7/AABAxjCWqa2tNY7jpD4vLCyYiooK09XV5WJVmWd8fNxIMuFw2BhjTCwWM7m5uaanpyc1582bN0aS6e/vN8YY8/DhQ5OdnW2i0WhqTnd3t/H5fGZ2dnZlL8Al8XjcbN682YRCIbN//37T2tpqjKF/AAAgs1h1Jz6RSGhwcFB1dXWpsezsbNXV1am/v9/FyjLP5OSkJKmkpESSNDg4qLm5ubTebdmyRRs2bEj1rr+/X9u2bVMgEEjNaWho0NTUlF6/fr2C1bvHcRw1Njam9UmifwAAILN43C7g//HhwwctLCykhSRJCgQCevv2rUtVZZ7FxUW1tbVp37592rp1qyQpGo0qLy9PxcXFaXMDgYCi0Whqztd6u3Rutbtz546GhoY0MDDwxTn6BwAAMolVIR7fxnEcvXr1Sk+fPnW7FGuMjo6qtbVVoVBIBQUFbpcDAADwP1m1nGbdunXKycn5YkeQsbExlZeXu1RVZmlpaVFvb6+ePHmi9evXp8bLy8uVSCQUi8XS5v+xd+Xl5V/t7dK51WxwcFDj4+PatWuXPB6PPB6PwuGwrly5Io/Ho0AgQP8AAEDGsCrE5+Xlqbq6Wn19famxxcVF9fX1KRgMuliZ+4wxamlp0b179/T48WNt2rQp7Xx1dbVyc3PTejcyMqJIJJLqXTAY1PDwcNpOP6FQSD6fT1VVVStzIS45ePCghoeH9fLly9RRU1Ojo0ePpn6mfwAAIFNYt5ymvb1dzc3NqqmpUW1trS5fvqzp6WmdOHHC7dJc5TiObt++rfv378vr9abWYPv9fq1Zs0Z+v18nT55Ue3u7SkpK5PP5dPr0aQWDQe3du1eSVF9fr6qqKh07dkwXL15UNBrVuXPn5DiO8vPz3by8H87r9aaeH1hSVFSk0tLS1Dj9AwAAmcK6EH/kyBG9f/9eHR0dikaj2rlzpx49evTFA4U/m+7ubknSgQMH0sZv3Lih48ePS5IuXbqk7OxsNTU1aXZ2Vg0NDbp27Vpqbk5Ojnp7e3Xq1CkFg0EVFRWpublZ58+fX6nLyGj0DwAAZIosY4xxuwgAAAAA386qNfEAAAAACPEAAACAdQjxAAAAgGUI8QAAAIBlCPEAAACAZQjxAAAAgGUI8QAAAIBlCPEAAACAZQjxAAAAgGUI8QAAAIBlCPEAAACAZQjxAAAAgGX+AwDOhS5Okuu9AAAAAElFTkSuQmCC", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "## Now run the code in the known grid.\n", + "\n", + "# Compute the inflation radius (in grid units) and apply\n", + "inflation_radius = args.inflation_radius_m / args.base_resolution\n", + "inflated_known_grid = gridmap.utils.inflate_grid(\n", + " known_map, inflation_radius=inflation_radius)\n", + "\n", + "robot = lsp.robot.Turtlebot_Robot(\n", + " pose,\n", + " primitive_length=args.step_size,\n", + " num_primitives=args.num_primitives,\n", + " map_data=map_data)\n", + "\n", + "counter = 0\n", + "\n", + "# Planning loop\n", + "with builder(args.unity_path) as unity_bridge:\n", + " # Populate the simulated world with objects (once)\n", + " unity_bridge.make_world(world)\n", + "\n", + " # Iteratively move the robot and replan\n", + " while (math.fabs(robot.pose.x - goal.x) >= 3 * args.step_size\n", + " or math.fabs(robot.pose.y - goal.y) >= 3 * args.step_size):\n", + " # Compute the cost grid for the current robot pose\n", + " cost_grid, get_path = gridmap.planning.compute_cost_grid_from_position(\n", + " inflated_known_grid, [goal.x, goal.y], use_soft_cost=True)\n", + " did_plan, path = get_path([robot.pose.x, robot.pose.y],\n", + " do_sparsify=True, do_flip=True)\n", + "\n", + " # Plotting\n", + " if counter % 10 == 0:\n", + " plt.ion()\n", + " plt.figure(1, figsize=(9, 3))\n", + " plt.clf()\n", + " \n", + " # Update the simulation environment\n", + " unity_bridge.move_object_to_pose(\"robot\", robot.pose_m)\n", + " pano_image = unity_bridge.get_image(\"robot/pano_camera\")\n", + " pano_depth = environments.utils.convert.depths_from_depth_image(\n", + " unity_bridge.get_image(\"robot/pano_depth_camera\"))\n", + " pano_seg = unity_bridge.get_image(\"robot/pano_segmentation_camera\")\n", + "\n", + " # Plot the images (cropping the top and bottom)\n", + " sh = pano_image.shape\n", + " ax = plt.subplot(331)\n", + " plt.imshow(pano_image[sh[0]//4:3*sh[0]//4])\n", + " ax = plt.subplot(334)\n", + " plt.imshow(pano_depth[sh[0]//4:3*sh[0]//4], \n", + " cmap='gray_r', vmin=0, vmax=64)\n", + " ax = plt.subplot(337)\n", + " plt.imshow(pano_seg[sh[0]//4:3*sh[0]//4])\n", + " \n", + " ax = plt.subplot(132)\n", + " lsp.utils.plotting.plot_navigation_data(\n", + " ax, known_map, map_data=map_data, \n", + " robot_pose=robot.pose_m, \n", + " goal_pose=args.base_resolution*goal,\n", + " planned_path=path,\n", + " robot_poses=robot.all_poses)\n", + " \n", + " if 'semantic_grid' in map_data.keys():\n", + " ax = plt.subplot(133)\n", + " lsp.utils.plotting.plot_grid_to_scale(ax, map_data['semantic_grid'], map_data)\n", + " \n", + " plt.show()\n", + "\n", + " # Get the motion primitives, pick one (min cost), and execute it\n", + " motion_primitives = robot.get_motion_primitives()\n", + " costs, _ = lsp.primitive.get_motion_primitive_costs(\n", + " inflated_known_grid, cost_grid, robot.pose, path,\n", + " motion_primitives, do_use_path=True)\n", + " robot.move(motion_primitives, np.argmin(costs))\n", + " \n", + " # Counter\n", + " counter += 1\n", + "\n", + "None" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "45f5e97c", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/resources/notebooks/environments-playground.ipynb b/resources/notebooks/environments-playground.ipynb new file mode 100644 index 0000000..702249f --- /dev/null +++ b/resources/notebooks/environments-playground.ipynb @@ -0,0 +1,247 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "id": "4ec786b1", + "metadata": {}, + "source": [ + "# Environments Playground\n", + "\n", + "This notebook is for visual inspection of the various environments provided by the RAIL Group `environments` package." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "id": "761c46e8", + "metadata": {}, + "outputs": [], + "source": [ + "# Define a function to generate an environment from arguments,\n", + "# visualize the map and some images from the simulator\n", + "\n", + "def gen_and_visualize_environment(args):\n", + " known_map, map_data, pose, goal = environments.generate.map_and_poses(args)\n", + "\n", + " builder = environments.simulated.WorldBuildingUnityBridge\n", + "\n", + " # A helper object for passing map data to the simulator\n", + " world = environments.simulated.OccupancyGridWorld(\n", + " known_map, map_data, \n", + " num_breadcrumb_elements=args.num_breadcrumb_elements,\n", + " min_breadcrumb_signed_distance=4.0 * args.base_resolution)\n", + "\n", + " # Open the simulator and generate an image\n", + " with builder(args.unity_path) as unity_bridge:\n", + " # Populate the simulated world with objects via the 'world'\n", + " # helper object.\n", + " unity_bridge.make_world(world)\n", + "\n", + " plt.figure(figsize=(9, 3))\n", + "\n", + " # Get+plot simulated images at the start\n", + " unity_bridge.move_object_to_pose(\"robot\", args.base_resolution * pose)\n", + " pano_image = unity_bridge.get_image(\"robot/pano_camera\")\n", + " pano_depth = environments.utils.convert.depths_from_depth_image(\n", + " unity_bridge.get_image(\"robot/pano_depth_camera\"))\n", + " pano_seg = unity_bridge.get_image(\"robot/pano_segmentation_camera\")\n", + " sh = pano_image.shape\n", + " ax = plt.subplot(341)\n", + " plt.imshow(pano_image[sh[0]//4:3*sh[0]//4])\n", + " plt.title(\"Start (blue)\")\n", + " ax = plt.subplot(345)\n", + " plt.imshow(pano_depth[sh[0]//4:3*sh[0]//4], \n", + " cmap='gray_r', vmin=0, vmax=64)\n", + " ax = plt.subplot(349)\n", + " plt.imshow(pano_seg[sh[0]//4:3*sh[0]//4])\n", + " \n", + " # Get+plot simulated images at the goal\n", + " unity_bridge.move_object_to_pose(\"robot\", args.base_resolution * goal)\n", + " pano_image = unity_bridge.get_image(\"robot/pano_camera\")\n", + " pano_depth = environments.utils.convert.depths_from_depth_image(\n", + " unity_bridge.get_image(\"robot/pano_depth_camera\"))\n", + " pano_seg = unity_bridge.get_image(\"robot/pano_segmentation_camera\")\n", + " sh = pano_image.shape\n", + " ax = plt.subplot(342)\n", + " plt.imshow(pano_image[sh[0]//4:3*sh[0]//4])\n", + " plt.title(\"Goal (green)\")\n", + " ax = plt.subplot(346)\n", + " plt.imshow(pano_depth[sh[0]//4:3*sh[0]//4], \n", + " cmap='gray_r', vmin=0, vmax=64)\n", + " ax = plt.subplot(3,4,10)\n", + " plt.imshow(pano_seg[sh[0]//4:3*sh[0]//4])\n", + "\n", + " ax = plt.subplot(143)\n", + " lsp.utils.plotting.plot_navigation_data(\n", + " ax, known_map, map_data=map_data, \n", + " robot_pose=args.base_resolution*pose,\n", + " goal_pose=args.base_resolution*goal)\n", + " plt.title(f\"env: {args.map_type}, seed: {args.current_seed}\")\n", + " \n", + " if 'semantic_grid' in map_data.keys():\n", + " ax = plt.subplot(144)\n", + " lsp.utils.plotting.plot_grid_to_scale(ax, map_data['semantic_grid'], map_data)\n", + " \n", + " plt.show()\n", + "\n", + "None" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "id": "277b3fac", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Python Version and System Information\n", + "3.8.10 (default, May 26 2023, 14:05:08) \n", + "[GCC 9.4.0]\n" + ] + } + ], + "source": [ + "import environments\n", + "import lsp\n", + "import matplotlib.pyplot as plt\n", + "import numpy as np\n", + "import os\n", + "import math\n", + "import gridmap\n", + "import sys\n", + "\n", + "print(\"Python Version and System Information\")\n", + "print(sys.version)\n", + "\n", + "def get_args():\n", + " # Set the arguments (usually done via the command line)\n", + " args = lambda: None\n", + " args.current_seed = 2005\n", + " args.unity_path = '/unity/rail_sim.x86_64'\n", + " args.save_dir = './'\n", + "\n", + " # Robot Arguments\n", + " args.step_size = 1.8\n", + " args.num_primitives = 32\n", + " args.laser_scanner_num_points = 1024\n", + " args.field_of_view_deg = 360\n", + " \n", + " return args\n" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "id": "63a0c940", + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "ENVIRONMENTS = ['maze', 'office2']\n", + "NUM_SEEDS_PER_ENV = 3\n", + "\n", + "\n", + "for env in ENVIRONMENTS:\n", + " for seed in range(NUM_SEEDS_PER_ENV):\n", + " args = get_args()\n", + " args.map_type = env\n", + " args.current_seed = seed\n", + " gen_and_visualize_environment(args)\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "id": "2efba0c5", + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/resources/testing/lsp_xai_maze_0SG.ExpNavVisLSP.pt b/resources/testing/lsp_xai_maze_0SG.ExpNavVisLSP.pt new file mode 100644 index 0000000000000000000000000000000000000000..406433186e070787651c35388dea2cc60582066d GIT binary patch literal 484274 zcmc$`2V4_N_XZ4tQf!D_QBV=FVG;rava?IEBZ{$M7ZDW;m~pXJ1T0_yMHDM`?7fhk z1r>Ymz4vSHUB5F)h#PNw@Atp&_xs*^f1WdE_St=&nVmDUjf98V*jicH+gttZKPM|^ zt4JKxKW12Tqdt**q}PyvgPI1Hvg%^?--IGjQE`I?MMv>5aj`=k+u%OYIJ!^cm?+*+ zYgJdHwf2mt42O=6jp`})ii(ZxIVf^uG#=_D^BNu<)2~0TEfU4Y0gG49cs^#(P{*D) zx_5lcpgukM=-8ogxaTm1qt?dLGr|rIG8B-J{i3zDhFu(+4vLH9+ZieywM8Qw03%l@ z{Cs`mitiH{Ak*4~ZMNpM_H9G0JVTvAZRr2J*1Z361h{N+6E#IURy__^^BPdO(Q=SG!o`#gi%fQo!*UB_nd4z{$p4j-oJ$py;QT?Nb_T+J7 z)WGOIT7`knI8a)}#r89e6K}&wQ>c^*nNp=yN+tNvq2LP=>ee+-`|(@4%X)^+Djb2FfiaNR25GdxmKl|Wj3Iw# zl=~~RjiroDXn!^}_GdHNpUn*vEqHB9jW*Qs2vizIU@J2MKb1-)_g5*kVN!zDl%S1~ zAe<7kH4tccZ99#&z2y<8^fDWP9sWk7kf~(aj#8pdlqkYT)R_`>F%Wg-wcRw@?v_X3 zFCsbudzkU4WO9|SH>6ZgDNirT6KUk>O?jdWJbid=v_{+4@(5IVSsH=;jC|e^jxcN$ zG8hv+-oB7q{iTdCbifS&#=-$Nkk<~0XNjpHlEkUYqY~GGn%Hn;bx2~xk?TrT&5i%WgJPnZjdF^D4c8Y1h{YGFm;HH`r$^2xn zTFA81q(mu{DAhEli|Bw`42*>XZV9hls?la!KK-T{ zZkbtQ{Crg2Duqg=T`oQJ3jKgv3CETUxK)w?x7yIQHM}-Qqg`v6(KN%YGcg+SN9m)4 z|KLQemvU~P9k|ihftzRtZZ?o?;k8>e+HIDHoN@rg9 zrWAV&6uG=sr_lp9N59Szi&W4WQA(9Zsq&3fdnwgE1J!)3g|iQAt}#c%5%iXbCmKNGw>YewI?*%la_~_<$3Oukj=*5>DhTUl? z;~6^a&H`iMusg?V&ug?7OoPDN;yicJyfHGRLgnkH&|Z=r`f}KW3cU6T9NRP0Ewr5B z((bBf==Q>e^_rn=*Lm#?jrOKxM$`p9cPX|$hBBkm7Gbi{oz=kb@z z zD6uU))~_1?Tohs$gSZ%YkYOB#*bYJ-+k@3$2e6h$N8vPx9Rc!NYn9$ImTwhRe~tC34C`45t8B0B<-8xFW5xPQsPI8|W)TiN{sIYH(GsmWQ!n^29CxFp(QZ zvaia|TcN_$=&lm(>JU?ISMWw|H(CYUHNYFVYeI>~wZLkyJ6Ovj{MS@RXH{GqfaV%x zzA(tW71)CwLZYD##8iVPc%z28vk!A4)uK09Jz=g0(#Oe`$chkG%kACczK7 z-``KJz>Vk;Bobs0QwehLMhOa91rof$8zd;9#A6?@8te*(PK%(_(M$7ApksxDNF}7ggj=zYA^z88h}bm(=%oPV%~U}j}mTG6_}$tOZWmI z)~7=d6o62Y4#7|(O@|PO4V}>#N<3}?R)d>@wXCLa>c-6gVp3C>4*oKK7?RED-V!-2 zAg1S{C3xex2&GkUE?R*%(1$^Z$F0F?a2v3ubTI1-!>o?O0bn98oY-L^lHs;=R|&TU zV#?hPypg*-tpe^2;0@dzp~T}(U^O@btSKFSfHz9<);}6jKvpVca-|XvqKA@b84NMa zhFI{Rr7#=fAms57uo|odYkB;c76%Lv^R~0;f5K6LP7}Q9! zVK~Hwz8C=|9*+d8!K1)hR%2QmMg!zGHISQdr-R4Poh53-oTfrO8#Wq?6=VCi}1N{yt@pva#4c-OTln-W| zVO$(`1Hb|~JXFJb=)My2T!<;T4!n_EpjALlz#GU#DDgNCtOn?qFjx&f0@joef6zb^;wa$E zCCI(ueom>v$LJ9x5{^SmC7b|nlyH((frL}w4H8a6iN|NaYVcXGrhNEKf~D2r9N>*o zO!**(t4F2W7oVrcl8CtgG0lgI;6Y4bK3sy3$Ctrs@D;F@N1$nWxC#)n#=}E>n2umV zzD9SJ@Lh*kpAR>n0ECi!xCu4Ve7FU%p)+nniN|-qYVcjKmerV+hkF1qQv+9u-o9|} zfbY|tC2Af(Oi#r_@WxZ|h*rU=cnsda{sc-q{tK)IKLu+!9gNGvGXR)z!%dr9=?iyl z&*`ob?iUbK?w8<=+^=XAaK8p`;C=%o9=`>v!SBFY&W2x8vwnGa4?r^waGmV$?+a)D z13iR9!$*jzhEL#)8a~r1(C`JkLBm%l@%S594gL<+ayIuo_$ptmSO5ygJwc-YCVC4c-bleL{}y>9HhY z93ZCI;0PYX6lOzl2zgurtOl0^s~>-TqW|#P50?UndE@1Na(F%}!=>rY5|Wwl>rSpt%MR;0uK5!%LO^+avpoEx8@Bwd>;7hAO zf**K;1QnEc>?TbU`&Jw=H5bJZH2^4@(k_%0tMw$!FAU1SG zb13n+1y~Jk3D&Y2)5;JE5HmF@dYzzxhbpb;&Js0Y5YrRU8ocpDw4qgSBErEN*xN#h z#~QF2+zzbeTrjQ-?EzrUE%SwbfL!Q6ca?B=gqU)70&nDwpjE)#8N7kJ3zT@=6|4q# z18X@Ke$C4Im7zNTf79Tt@`sn7xCcFiL_<%AsfJ$QjT$0p6=>)U-k>20N<8iZR)eF# zTF!-E8fY%`1)P}#KYv&u6>tjr(IZGC^oN*AhyibuFo0Hpgn{4<5(Ytu$AiIYa4cBM zxnOx^hy%P)iXj*1TJ7rx>%tIvB#9I)#55N$c#u+<3qv8~F%MRQCO_q5fF!2Im0b66o8PvbTU3+9R)SgTo?_pp)1BfiN|BXYVbI) zmerWnh4BC}Q$uq>PH!S7(48e}CPEBvRd51$dLo>X@FZFVCn6ENfjtRIJWd9y!IQz7 za>1-GjO)S_0GM(6`FZ>M!W}%GN_UlTPlK3pr+_zdr_w6mo(|r?Jp)QSo(WciXMr{4 z!f)JW>p~g;%{1uSPj6t;=^-QYi!g9bH zr5M)*_$EUCNM!{*l0?c%h-ogY0uNFOb73`vJYEAFee|RhmdGE z1Tocc7`#!#5n2Trj)FI6I0hvi9|xLjU<>!c zPyj;DPg&snp;VZ;c z!#D6o4c}=MX!rr%py4N!cx+`uHCTf+CBq*y&}1kAxZfne!y6U6aIv9BkVvqFm`W%L z-YB6MtpW*l;0+S&p~Pbcuo~csZMv_7+yi1tUI)C9+>=%T zd0p@Z@_JC>aec5F+yJcQWcW2J>sN+`0JI>2P6uA}7!nbUAf_T@;Ef{Wvhgdi0}5kVsHLOeOe(H%bVgRUknP-XMX2 z5|0sB4Q9bw&IZd%0|$7c6yqI(j|?6x!gK#XdL)UIAc$!)1cL`Dg~<>CA&(n_)!-&z zBT7SiqT*tQ^^A+>jUT|`rm(@h!7u|tlYMbBx{HLRImDrr;072xuz14gw-2?Zye*-I zCIkdD4296p{8munaTr()ZVfh~q*MX@LL0Y%YBPS7489(tuM@)Q4if&h5X0BzSOcDR zxJ?pnN2{R2+k-bSc7PI(JA&2VPGBQS0b{?o$U!}O#}+m@0_sharopaM!eH-Acad;* zfjAVhzAJdjStJQ}qgBA!9lU|F2b6f+6RZaJ0vl06!l`d$B-EN1^`lA!xeZ_8;ocN4 zA&i2U67~UaB#fq2K-d?&fv_Kxc-$YX2FHMnC?_E_TVDpiRx@IF7zD2mVL}~9_mdD0 zf|wEy25%&erBy&22i`zD1WG*Cg4JLQHlnNrVwy%nVWSzZpRYGuWWdb^Pj{2>#zRbb zhk-Zp4yRSXI|96ccO;Z}JPND^j|Ll2Rl;j&B^d)CBfs$u10G5%=~dNOy1Rsb9K>|c zjt39?g}E~ULLN^9tHB9i^>a7LQFMegEwke zMyo)>a_|NXE1<;Vm0&e^6emqq5-jDyX22Vz6y^eaSPEYj;w|(@5-D3Drn#^UJV+_b zh3ydXcn4Sw-U-(7=rdhZ?E;8-)8V@nUwR$0o9-;(+XJya7jmHhgpyp)L5(yQ1c(h? zL7>EA5v&I1fwip0bXAoPkl)mJ!y*dfaWCCjqGlh&^hE3jZ#)qNvJ7_8-7FkV$10f33yw9xp{>GvqzS3-UaVoH7-ypj9_tpf6s;0@%bpv2?TU^Vy* zSj)-q>w-pqRdp7C7DUiHzH{^#5)tPirXntYH;TAOt3bph@CFf=p~T}WU^VzESj*Y) zO9ah^Yk)Ippz9xe&*SF{pSR-c^av6OHz1}GZh|*TxJ9c#!fo&d33s5xOSC&QjBlt^iP7k;f@DCpvRJkc?dDhhezN+OkqAehLFckz-sVcV1Hd#$w!#x z;HR*`tjT@~cn3r8?4HqGBrMM%4xIq^t>A&hGt?Fyzv?ffUP2Ac3FCFuD+mo8@ES@y zegjs6--3;Bf;9|DbzFD1SmsDXrkICXJNVP^6Sa zz#Ay(pH%YL7OVyr1shSptes|)elghocWU_R9NW=7CDis1Q)&nBMrub|1=PjC8>mY_ z2|hXotHGtfMwGWmO-FZW*!*{9xV*zobVmtu8Hg#fGk7C&Sy~0m<-i-5%R>o1Fb1o^ z6~RVSGh?01u<=9CIwcyj=sHYn&G5=w7~DWwv;k^Dk;Tm_uOm z-ir44TX~_mAJ`7I{Jp9E@VKEp-A6*x z0pc(#xJ&5>1=?14Lzav?K|p8cWE=q{Lwh?ziN{^QYH(MuX3Tzt%-vv%8M7b#On^RR z=uY>MF!z9%K7j5CUQe8ad(kTBFVJ$HI0qYCnItzo!=< zadb}!^$>_DwHCaQ8q+GE9tz$-%|nUD@nAK07+ABx{EM0n=Hal}j9K4k`ga{8=#CQR zkq}enQQ(ctqiGc|j{$FB9t$P-ycetnj|XcunEfpM^(vkKFrxy~VD^LOYVhX-cp^Q7 zL_-3^bTCf>4;l&wb0UO1P6DgJ$zaWflz-unnhaaan@T_XfWPy@Q|LYtnyChL`J+EB+BF$1C;7RVHMSp%E63slcoC$TcP;G{GX$8|UbeYyT0c z#Ow6P^(N$>*nRK@J#wQ7`6qT?yh)GTEJYS}wE}O^Z`>-~SlHFlx5Rjx9=BbJD{QP3 z2VK2GkKFl>NIBl6NA5NuC5<&ZrULKLBXdniNn_2B-dLwc3jc^yVxmWiCgh*keQ=&0 znQub=iQO0P)g$*wk%e9DjrZ#}7DzW1cD3}y3qGL79hBk_=FyL@*j~(d`gczZ9@Ku-3Oo1BhQ+Ue`5E==k&<) zQekGm|z6?U~02VH$dkG%SiNIAZyM_xA}C5<&ZrUKv4 zBX63JlE#`Lz40wQ^7cO>mH3VxdDn#e6T1(-r$^p5A^*hgiy!Eb52eV$uJ*x?^cx>b zHx_oa^wV_wM34JRiYx4DDGs{&sUG?4ACYqWT#tNVLP{EIc1#6+sYkvtAtjA9Lwe)a zdgPmbL@M!HJ@TCi`6qTC{9cdzU_$NX z$9O^px@{y-B{Rx(q#k}*W*e^afKZy#X$#_)FVs% zBT|k_>yb_-q@)RE$5h}ldZe=nDd|8nq&F_BN0$3Xq!O3cBP*DYe`5E+74^tUCZwbT zy>Vsz#wyZ{g&ine9B@@V&P9qV>_90FIg)en+UH$fY((UwW*!Thz*Vk`u zVA>2sP}X1j`r?NAjb5gWaO}d#R{GKlH`3!|Qe5F=E5$+o%k@abKO*JWTaQ$lkj5VP z+ZzrA_R%AKO-N(^{|)Jl{q#uHKO&XbUylqhA^*hggVlN@V?zFk-4`Q0l9eJ&X9^w@ zV@|(4P`aI-DdY209HieIEZt0BAebJv;t)Ncu?Ya0r2si@q6aiJ0YIu0puo-afaZS! zc;gm&K+8V?lsHrmXk`NYrojh?=>e@xfZsIu;x>9f_@4lNxUC+bF#&#~P~moZKzkG5 zHwu5;K@aFC0mKjO?G+wsXFt2mbvCYzl@Pv1t6){q?C1L$nSL3sX|ThuAMwi! z%|owB9!Brml@e!M_Z2fyNAY^C(P&?IN%p&tDBj-`Og;|nD$W^rm^>{REcTx{Ui1^v z#mnuwh!6TJMAfZK(k!u4wU0F*@BJ7OT+2$d zkrx#mu6AdK9?+ni+h@_51q^%a>pGqK@@jHn`xi8N;BnM-Yf*7)k3_LSU@h@x?JnZ; zw58&c+!bPlZz@rDt0n5u>ofUwsF~uqP+nL%uFY*p+uzvUS?Hu&v$|Blq}Y%z&+5NQ)ya zNRg0fq(aXdNTJIijTY7tkGakhK5Z)^%9KmdlB7Q9((R*U>Yd8s*iDB?ojnc2g6z`l zg!w5*qu9%yKm3^OcXQm zOC1yJ0%o#L`_5$Z+pRz$jvL5}@vYJ4okh6#gC|%kmrOS5{sFdHlX9F#xg%@=UdFy} zG?$HU5a==*p94Jx}Xw8(@EuH zyBXCED|YJl8se@_hscN%G3d#J{^E+_3<}@6meP}nCy)b1E8~bw&o1NO3{aP@V&5pXoPFrz-EwR^;YuQN0jyU&(?fU5~ z>!dx*#&j;jJ@q)v7CW88cD*{8eLuewdm?nY~*w7kN82;#56RJIjIn>`_B>e3!=r?S7BezdeIeM})EKf}GL7Qmt60fCzS( z!Ws>^bcBsu*NcrknZ<7HnJKV6Hjs|CJZaIjiP(MIEaCmKS!l~@78UK1fvUG~6X%X> zL-zRHB7<)>V*a}OgS@r&U_Gb!iy>1TNQ&oW@@3m1tGdAQVLRCoA6BxHhnz&pC-=~^T{^bW)&(qY(;oGm@*Hin&tX$jb6MGj z6Rc0oj_k6PrkY+?7iE6l03!_>>>*|JYYDAdqKkL+a9_pw(goZrM5N=+dF34((Mqg^P!r6Y$gw2Nn$Y|?3Wd64RmNfHb zPvXVG#Vh^Ay7fwkQ%bEPZ4Mj`xEo(o#PRLL_Gf>pd*4q)S=El9r5_IpDIb!=EX_2b z#QMQvcF0(9LFy90woOHH{4Gb^H~%E1gWt3AX}&C3ID_4*{K5AAt1Nr1rWN-ncOQGV ztS4KSyTdwe^kcV?m#C_%i#TcQYBF+beY9f5N|an_9lC5CD1Lo>MOZs-16yhO2sYED zD7U8AQ?}2Zne6r&rMYn}igWUSVqBe^Pi%$wZ(_-$ry^=tEHAUheR12&(_+5g5An&+ zW8(c!O~fBP9rC`mvd+tybWVIV_NV9cK1^c8eg9m4r98^V1ZR*UN~stPAp)aB|t z4CO+CnsDJig1K%j-ML%qLb<6~r`aFvU$YIfJ-Ep53f!&PUff}MCCX|U?of@t>Zw*MT!#f|lP(tvy69KTO@k}_Q5PIi|KESxe)<{Xzia;l&dO?nejLndTkOKW?SJ}p z%fI1&d@~3&7(bnD!}=rJhcdQBr8MT)#8af+roQ5#9tErm*B;e>r4(jlu;TiV6kY2v zHQA?WYEg_jgJv8q%AQZ#jUIYyIWX^R+ZZ#;xriT zU)V>GpQ^~95zEE9tVS3Y_KqYxld-hlx8C^c;{-Sh^xuCvzm~?oFTBtCZ^pmFpbvRI zrxxdrd$l!iQI&M^D5Y9{nr#6$yTbOoHtQn;i=GMOCTf?UQK2pKUhAH-&NKVvUr8ty z_^rt@(ao+*{)>&LIlfEDye0(>`Pu`c^YdOX?7D)GKs=>WpuATCiu)+%N=;jkH}YAh zz@Qy9180=-Bq!c(&Kom*aNeC$cKY+~Qupwlf7^cgt@wY_e(3W5_}_n4gfcNoUyZ_w(`{|^7&>nA`5(0~8O@lSu- z5$4^0KmX@+p1>WrI+^oT4dLSFH{;f2PvWe*hH@>t4&^fU=5s&o61c|WCUO&}4&k=! zAI-g8GJ_izv4(SAw1nGop#|5$HjNwJK8}kRGKsrUaz3~ANgK|k&Im4$8_)HEfBRr= zJ9Ks$x1iowZf?cVT>GC%T<4TH?%>lw94Ql}Z-02Zx+ni-`}IGM_TRL>*5iR(!-NEG z&@fNVdQmYh#B(l}6jy}{jg94=s`I(~)gN&Odo1Ec zHp<{iaRuDq?*q8M3Uax?-lw?56V7th53aM-gW}mmW%uYf#NmddM{Q{Gg(}?l(?Z zT%)mD>C%l~>}?V<yTn2(t|wh*EgQs^;6KkHisKO&z=$#bSNO`etXwo&!OvrT2yuqN>@$`X>_h_ z(3OVkf^}5}2GRWHltnxJ>-NJZ4gXF1FT>c}R56bWS&F$K7rSsyjgq-$VT(A&*l}FD zOYvOY_$bb*UkbPPR5Z6VE`b}BHIRF|x;=N`dIC3M*dT7h_lexT@rm5}9VuK(ujyRM z{x00~7o#}akV#y_-aL2foQ8Y3b}%>T(HO4E_6eMGWGYu|bziQweJVG+_!Ry5A93RO zh=1LF_z|Z6rv3S+gV=|MPO{m(D~qod6wAvH>al-?9wd&=b&;;i2hq>IDf6M>XCxLY zuHG~=4<*$YgKWY(ka2#On5d~one#o0v#}5EpwBjbtj`|Aj<)M3c6rnfmAdc32JWrG z2E^Xogfv@`yu za?@bHKVIPd!zFO3>NB`IMH0D~Ha1*x_-M|d;yli({y^^Wg;8Ajdy}{oqsMT&j_+mH zg=KRti<3FKjPjh5M<1@>^aO5dPs4TFJ=c*31FfvA=)XVD-xl=4AArISHp^fF|JV9M zN-iWe=Tq1Vi}r90kF?6WxWqs2i_4z8m23CqWjW0gf2Q5e%R5#sKhbR>>$j$6UWb;) zx%m$o1-|QeR@^mYW**JIW=%&F{1^KDVFLQs`p5R1iaPD;B~*zYK(0HlAzRBWKw+D& zlM_jGbUQ!JWt?nVlf!M+l5)CacJ2v(qzkAZ)G0EIY5MFPW6cy3sQ$%Ey!`&1e&cW2 z{}=l2`oK#x_>bzC>r?H(KVQFBwDSIa9QznQO==q4=>Iy7-&U0HH}GosFZm6>I{YvA z|G#O!@n>HDcl?I$9RFAR@RJ<+UvB%K@f&|D>wm{@_^JQ@8NczDB>!jp#^0R(AMwiz zKU)7^@zdV~p??YT{|kQwtKXhqnSNLI-#kD0zt4Z=t$fVq|H9u8zs~+$y7b=H zNSHt5D6?JB4`tj=MR6m`qh=FS$j^B?+PWoMcpg;+T^m0`xLUIq+Oeb*`M7lq=`p31 z@b%d~Vd%YPq>Squ#_v!vxv{<)>GD@9St%bFI~2rqk(mqfqHUwF}_F;MtJ;y9re?W)6d#GcaIh5etmfS2ENh)la!^kRz z3iCRy(nUBwXO0J6)ZwDznD-|;lV`PU&^6suwB4yDN|Z6=Uhg>cI5HTyq@5DV@(qRC zF|E+@p|Om2NE+I;H5qN}ZbeSVEnylI{mPt+pPD=Ccq5cK?ujn*ZN8ve@I!sK*c`@o zMGl!(`7^Vw!6dS4*%tM}kSjuw1#_9F<36k39kC-N&c~n$p+m@t!Ie?9xAlcHJL{0~ zsqScFzzXJk-5bnD=Z@%P%_vms^dP2l_dTe3+f!)0U2){S{4i?yb~GB2w*@t}TZ)D+ zpQJ8#B?0wytcX7Mwq>TfyAsFX?~LmsFEV4%Y2n2H!pyBdinwJBB0b`IlTBIaq;a*T zYK6}xwau)rf?Y$7cx>N?y2R~e3UNBS@vQvCv zS~{P}^?tfU_z~xWisR#`(WvRd^b3Pf^#w_&cYOymX4GY7=d}_jGh!?viiyapd^sj7 z@UgHpZ7FKD>L?mJ)D3N4To3KBcSCR0EK{ZKRrQx`htZU5J9MnzC~E(}1C_l}o=iE~ z0mW56&Yb+%o|(C>D-+?r7A3Kq5H`IZdhIe0^{u8Rb*s)4TGY)XpI_M!*AJ_RO>!`4 z88ubsVcUw-DL;eE502MGGzmpLb|YrOdRyWC?yJn`>v2N%qXww$riN(H)5*-UAC-h6 zy=J0Q74uM^YwkprxI##Klh3>vuvq9*B}YBuYb4sWCsnwypaB{BwHbLFaYgt#KAg-< zb4OmobIH|$^XfIv7pj-lP?6=&moW}DVZ<$WrS3w=ZYJ%S3t1X`R6WKnh^*+dn@KL; zn&e+7LFS$>!+d5}3uCPcgwqp_s?%};gbL`9uxH^mCa?Hz-E5C5OvTOaXsK*Z?v0}F zg@F&Vn3S|UU5Ob=ly-XsS|-aOUJqU}UI~jx-uM(|=eP*r(7`Zr`9(Rx+C~XS@ABkh zt13+HrZK40zLqF6`L()dTnb8UeFdHTJYDFyZ8BOPdKJBLiXiqK15k-|Maj#8c1-v8 zrJ3v2MFnQG8Xfs@P@P|43N!HKGGWdVFJXCdMS*wsWhUqEA~XGZk{ha{!Vt$CX3mUx zLhS={(6-l8)XU4QMVf7|goE~T)ixD&sSjE2W~S6mLi-zjRA*M$hvrV%hVDf!M)iiJ zA$(6j^%qn|M~8(Vubb}7lf`d^g%67%zg=qdrEU_r{iZqNY}b->?hz`iT2z(1JAaSK zS$stB@()H+zXg({w>5~9Ri1jeYi%^>WL1)Qz9>3SzXozns!SC9Y|y$&F9er;?r4A5 zVa9sbPR6lB8nepIljMA#L^{NeWo{1$L@DDMGNS4R6VkR06TEk&aL_pcEk9+2h*w?a z$VNAG=DZauI93i#Y1jkBxmL~H>{S#ED;>(5xgwx-yaPI5w^n_=X9g1*Fo#LkM57W; zThX2NK|24vDJTKvDw{cuq;}a9;Yg*DBrPyoc&(~LLe69hq4u78ZiiMxhc?e6;~FIj zQwDnpwksQ{px+F=l)34 zc3uTk32)3DnX#WaeY7G9xzI>Zmz^aPsl_stqH2b`G}I)8Xy-Q5lfl$aHaer^j^A9PI< zoJMccH5pc%bV;yRx6bATey$^_9_Wfbj9DjK8y+Dj`^_V>CglnzYb+(fQ`6CA=Lg}|{^rc~*b;~=d&B%((N8yj=X8|6X_?MnwieauybYbd zb4}Q7`$qWkIaM8={yZT0lMT}K&13dQJW?6$?()>tAWwOr;ov$oqMxvFB zW!#ARXmB7$O9Iyro+(q%|s7{8~_tudH5}sU}`;OQXYC ztI&ooPlZ^QY^HbicBbygAHu!pS*XsdOrerfC)6)9m(eO7F$srs$hq~N+_V*P=FPTX z)MR;aVZq)+rmoNfBadg#wQpODCGO1s18E?TK` z5>>=EGLVp|YT@vl4Ql_<*O-oX59f~PkSjQzI3aX*i$ZJm?+}77f7gA9jweNx+l8Q4 zrAZUbIi_noCab5+RFAs)O!wkxPHywwTh&w19CYPSQ`9DKiV(ByxbA4N55mK~?NQuN zXLQ#8i?Hd%4Z+>k8!c<%f-W}A7G9j`M&3+&$9(d;rQ1~dxVqVi3^cNQC^LH5c+~mp zE@8u=vFJxBB{QajkC2dgRkyj)RzW%KDf7N@JSzV6hOl##LTz1bpP(cah#0n5$U51W z*^K>B$kN&BC3^$V;_9C0(Rn*YR%%ATG5Km{eQIwq!r?S?HBcvXs5?;@b~-Mg{EZkU zVNG-Nrt=zIb0N|JRYFObI@%90m7rXVKd7#bd4kCpX!h31rYW|xg$jKZvah1Sd( z^s;1o#;1gww5Z`u?8n9mkLvpf(_e%L)ru?^2EVI^wmo_*R6lcD=xcuzh1LIxwkR*5 z(Ay2!ckjQTbKOJP0Y46+lI+ys?{VKVl&aG=4I`wHUDYLgelQd;Ade&YOt;vnzQyt{A-Tsth=C!BSUJYFg`^h)#LlrK%btp6W+ECA?psF z6y{yqE&SEUR_xN3zhlT#VqhZa=v*DVsQG<;2b_k*UzSEt>rJ9dq?cQM;mI}A(pFvX58K?#K;rLy5h*tLlW?kDDp~72k14CM zB^~o$2w@LaF*=uA;o9OA%!ghT$%jo=q;G{)Xg{)UIw{nHH6*kc^Mx{9oMGs7n`5)U{hsoM^ucgyV8Gp9!^M-z5zQ8#SSL{J`7F!+5eY3AC5=wdJ< zpS@g|TkE{19Q-3VYN9uSV@Y9%JSY$Y$bG z29o!8x(Ovzgmiz`h&1fgjNFtZ5U~pMbI@So@p3P*$}J9EU2FuZl*dmt>lx%@F2YT*kyN+lwyy?O=` z!sIlXO62>eF-;y1AWN)I3ZW>B>D<%?HE!Kg_~f7?cRYrY4=wiR*19v6Y(B7@%qSrf zPHwm?+;F)i3~;PPlBZWAmG8tbH%gR24voE#{{j!xWZwW{HOwM9|0d{Moe9JHtW0(Dvg zA2fG#hA@CxkNp116^iC8Vs>PAMD;2+Vbl%_kyE#G=$RG6Y;IVG+_*Fa?Yo$c>^=LU zTU(M*_{eI^@PjOJy!8Sd>$6Vq&96)v7k5Twx-2D!VgpGyH(4Ei-CB1#_Kq;<;aYW= zT{ZG-$T~9Z&Y|7Hi)E(`>3JBv`qgQ+Ot=r{Ey>k~pw){opeelo`SK92@} zD2n11zGE(3&SGXRnSoNj-b5|SHe}ZSSjK#R*cb7;TC4M` zZ{^lLJDmKO>P515Y)0QYToBxwhLhx{(WFKqL&j@%3mVmaGPiO8xjbMAnfhWksavZR z+Ejcf<7qt`d33LhntFsW^@8p*-tSU{)z!Z;M|LhirRw;S8&lU4@!%GrhTS-Fq1iNY z@kjyr{_T_CJ#-QgKlLP&?i58eHcupVde|{l^Bx5piatnUE=(sca?X?DiT6ovcnvbZ zevr`DPRTgbUya^QuqP`^S3)gjIG|<8k!0fX#>l($J~Tqro++5MLMUJI0@_)=B{Q__ zC1#XOE~@gbBl3K^1)Xfa7H#|yNV;w9Nd|XXD3l0pLzd;QB;@c?A*hZGahZFF94(qn zoL0;x?lWyj#fOQc;fG7YT}3H!>Ck8atL{pH(6NFAdF;eC@BQajz=XI<)a!qtVyNA-G#+{Y}t)rrx@SYGnn$O zOPLt^i72s0dxUE`GPWlYbqQ0B2+>(ZnTQQV$%fXObrCRjK5p|8J~eqHysq63jffe5 zQY%IZy*#!v?HavjItDjnhCgqHj(;0UJ}Fbkn#}`+xGb#OnADZ%ScX~EwKHk;VK=$d zE+m(kIg^}>DNEisEZ04A_`!I_+LE%7ZBg5E2h?9i4?)fiW}uVBqjXz+5GmNS2rX+G zgB*nfbn12*GjjPp-NS1sXnWmLD5&mjX4&{jP|bk3FEPwxS<#b$Q7=?Xi#CDOQUF&0kI$mGD-tKevp0uo^~QWHe=tX(}+^+YA@x zHSr{$4}4bZwoO8g#nuXk23AGanK?rFCK+l{ZZp$tPy}+6`IF=ARtw9WlhqSDycbp+ zPa)1%M+m3v`U_*MyqWc(g1W}$A!K^pG-1axOdQ=4$%nVAgtiwi6X&cDl%4ZI*mq;0 zkXT%U;<(kw$6YDh-06zO6_i4s$JP@z9PPigqFUQ7=o-A&BEK0j)MMr_bnl)DHTp6Yacf%YnlxJ~uoYIK zlC#P&3tN^#-)8L4xqc5r8>V(ab`vk4V@`{iyOWo~+PVOtyB&lYU2dvd2)HE+1u?VnsWOzGivAnls(`l>T@Mu zcx4xaUId>-MPW@%pPLtOeQOqZH)jgjK6W|@%*qyyoLfvD9A2a<7}Se2KVF^;aLmiS zJi7$ym{AEG-KZip*C?TH_IiFIMCEGfdaJ6eO?_rZs49+QYx<%fvD zqbiAqbk#+dURA`L+o#9}?LxS|^c2JI)e-CTeL~h;AI;WWw1nM}8PBFW&tfYS&tj*q zoXxJEJ(pcsc^B({Z35fZZ@jqqQ+IKg?-g=PnIJ}f3KAX1Js~A-%o3lZt3-LH6J+A_ zwrs$_Y3%G1h{ZW$Vd&3d$DNB~_kY*2&BOYzFGhv2&CZq<6-D=uc48|MQM0j_+{H%R zn^_H>2iu8*9u^Z{hh>qK+v|y6;rsbMZSzR0%n4$XbHQRyUu*H;u0CS%Pqt!0);p5! zpdeOn?vM|!%ZkVDuO>g25whyyYm(gEi%AZhA_VkXK-#-5U>+@6u1kD%3AG>jO}#{! zrc-<8qmv!)>TG(Zq7Pekq0ilCh*mech+DE%V)K2Y#39pqi0d!&;;7)MqHSE5IA}vT z@!L#0wsZe%lsx7lvKPN1-x&wc$tH*`_a+AA96f@*Su<>Qi;lXo%FAeHvnl9mWj ztWn1@%d?Sh7a`~C#nIwb?a`=LJ&4QLRg9|PeE*xb50bXIi%H_E255Y}nWRD10U>N- z2I~8$rP$l|I(ZVp5HH?V9Q4LpJbB1V=q+`ootGVHgj&0CyknlNuIaJ9lwWU%&-h*F*=M2uG+Dq2iYT= zr47&v&06Ns^f@TP?LN9(yb4Mvn~TQUd_oaV%CN4to1jUHnzH?uMX=q}2hrBe_H6rU zCDCX_UsN{Yqm(qttg>%Yt(Xg7t}y-V24EJk)D_H$dX2w921e~ z@$dzCSmKm$vZG40YkrHI89s;XSiX?mem$A}*7h^{wr?Aoem$LSGpjM%BYZJi{8}a( z(cg(JVLM4w#9t<7hh8MecbfQo+8c7Ps)tx>RC{rQcSX@--D2``O>5yp#;M#r*FU4@ z?@OWvR&P+LV`bPM34X$ql8;aiQj*=+Z7RF0(QI~8rz1#JZX@gTZ6)iO8p3LO_F!eR zQ`zyA`?B}@C5XryiQXmc#7Y~ch@0KIiCLBEiQ6$2`4QG4xp|&2WwMykn|6_vo0ke# z@|Ke!VLyd{uJ=hN)hNMb?jZHsyZ1@QpB}91+_G%efN>~hmM7a_Y7R=heOl-ePz_C; z<&Eqz3DLan%5=3}#B6xpP1y6j0y^G%u}(QI2(=47gKn+6g+6bKLS4GA7w)*$C(B(j z$!zzV!j(>W#I{$Ig)rUDk+e%zB(zu>v3~l5h^i^V zi85N!bBl-Q8oZo*OFbYI&sa(3X{!*|W`{{tH$G+YDa3WeBIN z1yWYCSm0~kAuEeHiQUKSB#YX3=xoPEk>p{2p@Q$TQJ-*E6ym%B$$eilk7~NI2ja$~ zodG3<$ea6_)V40jEutNI0{2nAH|L|+W7E;xLj%zB?hdR&?Y$`d@)<_vwUP{LHIj@e zTTXOY*o%q0ZYz##GLP(ebA+sps!C8%XK@X?OIP`LjIes~9MWXXZFS|_TZGp;DwAfd z5Q-eSmU;TJ7HSz*4}JbApyM%rF(l6#k(H~_fao8(A8!*;zwH@}ZQ^yowQ5mvya18F zs-4uO`(}{1=<#H#@&M^SF$V6{jxberofVd6B$5EfzNFDdC(`0oXR@nP4`Q>|m(*T0 zOZX63nRGv_6e`v`N>)yLPtMG<5gGewf~~_%a!dG0tgk&0Le|=o1$&%G{h6Z)yL%Y9 z`En&Wt4JZrpSI$f%M*!TW(L!>{X^0}Z8mwAu$eS>enF~zv=+m2N5FiP@c%G$9{yN< zVHmeZl##tlQ6!sq&i!bhNs+dah6bXgMM+j9l%0`Pl!#C~=YA1MN*N_eNvVDf6-r6! z_x=g*^ZC5z-1l{Tuj^pWUtctC{7jSV&(cwy19(H*0$;@Vp{IBl=8Vn66oBL%fq$l@mDDq?!=H+e9BDcWuyuqm+2#0kSa;Agf6>YvWT$){UUbvNHH zGMB;txeTj`f0vWb<-6&+HO?UI zp9Wqvg6I&qk_rU0^Yyu0++}4&-Of)ZZEPR?yu6Ye@7e>20UyaFg8>LNxJ@*wBf))i z44$-HgYon7@ZQoG_MO#&*Kw)nn4Ez-oU3q8?P3%@=!&*wA-G7o759!Up^kq%(B*M7 zRn$qr8n*xpR=Z9ed7Rmk7n)`3x5D&9YF4CA02C9h1yYNJS;9X7&+C<^gP zM3-WF{X$d`9jIR37>D1t6_P_A=78YNi z#zTA09(3pXAWeb~$nusOU|!Y$-+TSZT!Aa_;LBuIo!w2J*j3uPI`qL7@vD5@^%&hP zJDFYzct;Gs02H*<;uP@`B3LX4XVzArf%7cdAW@9-vuY{SF=X2Gqp02#g~pY>xaib0 zcy#RPoL>ik>er4_Yqwj-yFX4p-20A-dFi-bx|>-O{g@N`Y>DDMv%%Hj7pO1OU=_qZ zledM=ps1k3+I8u`h1HGF)z%9k_k`(@Nv*_ezchX?JWte&++g9cdH79qGb0M?K<__M z`0`>E{&^t}E|TtKNmLS^xu}k>qJ+pypVb&*_nB@>N`XG%1nhRmM8_LK=u+sydDQum zjYV59Wk(QxHY?yRd@96~TlDdsTn>cig~RjW05l03pi_QTk;|LaFzS#7l@Tuias6D!cVHN(SV`IA*mF3T1&8(FeQ>p-_*)L%Jt~=zq=OOr1a{)RN z1*vhI5YIwakeA=yf-WMGyyxMjcqe`qjS~~+EfTqfGU3x{MWh+%(sKkv{eU|s#);M$=Y>O3Sc6V%nYpec)KFb!mN>B!D?}@StbQV+n-3`$4%m^NI7-0MP zc6#Ba8Ro<`&`lNhFvX^Xu4*`hzvp}7(F0j1vHt=SG{B+UfEqnLVJ%j-g`)bbQbweG zGTzi!h{^7?WI<;;6|K*}Ws`HTR`4`&s2?B#A0x1y*-0ngjo==tIrIIclb|G<1s6Lj zL5^G^(!155euV@ZKk*i^zSTqxq$SzGCpS^yY%nT{Y{Bha(WFhhj#+T`24?e~P|Il| zcxku;|GK=UBVy5D{fa;Hol=8@-vMB|d?lon?Lr&8#6>O=Wnoe=vGu)zr}iphfQ%O6 zL0udbx<+0ayW(icGD=_1g2h@XL{j%G=e=_c7AJ1UKkYm5g<=Ut4+daZ#d@5u>NZA< zN-(Nj%2*@4AEref!kn6q%qo*y*sX3yU#|E{=X)&$^?|44gM|@%s2nACR%Sr%t|Bln zt%psPrXXg21e`Xu5d3`vT^bJ~^(ev0$C1EuS42C%tEjX>68_xzLSlZW(Fbxx#81f* zT@)@r>BY5ZE6_oBlXk(kV`=n_-8f0Q@54OoTMhqW)giV_l*HXWjSVJqa7jrLLGNZx zJ|v9u;XjCEcwme)Y4gwA2az!KOD=cLmV)gIU z*p~Z=ll)yrgS3^f@KH5YQ3{54-hZi<$x7&(5C-;%e;Ah%H6m^Blv8=AK{7{nU`tRc z{M$Z2LzhfK+cjHg%Q7n(A#RVSQ3Sk0qKLh?5SqJ3Qwg7!wA91{PA)g#Zn<_sY(^PL zdHsf@*qAWhyY^#(u0BLwokfDhwm_ZX`8i!rP2j^Ker7Aa5Smt7124+}dzBv2Rl|8? z#!3Mq_hu0a9yG;5^Dt({LR0Rk{u0by{T%yETQSgLE_Z7|88iByCx-GhARi~Rpa>lvd9dPwDlJKQ4N84;(6Y^sTvuHI?yfgs z)%##rzWypnC{-j8;s)r#*xhepn z?mus$Y!ZY!e+1%(DSMfrf1BW%+#7Pjbvk$qoFSWB3jtbGIj5h`xkm!a;akxe@Hw}W zbDiP_M;tS0W@SWmDpy2;ANG;D{T6hx>r)aLE(F#Y`mk5z2Bi79fwt%q=xyvLKfeO* zoZ!f0*apI>Ez6ns7ZI>#q!H3Q3?Qo92Xw2;V6v4JSSu=%r>5zUA5%m`_uhqTN|bzh zoeV}p4}ocW0^;|V&frZP58SBS+sYuqhYY93h-Jks_-`ItMZI*Kcy>v&4uKFW_n}#8S?bNV-i=g0Mbk!bM@(` zXfdB3TJz~MS*3A@cICfjL_+y<_nSk&9N7bEZ;E@T4i6@hdU%x=LZyxy?eF%oitzbjTe5^n2 z1yMqa$&=LSVBZi)<;0ueZ_O516Wk4Y!x6B@OOq~qcM5cqK9MS|f7I|$G~?HxM=#o( z2EmX<&>MOLvX2T#)5k{GwWk=U{s-;p(9fbnOx2{c`$(iUlRO zZ`6Y4X2AcB`a-82W)~-*_o%l&U#l%9^ zkPUcFeFCQcMA^x|G9fE55MJ8;hN{*9IQ+*P>aW+55+(x*L|ow6x`zxqxrvJDAEAzX zPdIB#82p0b=^L9xwqFGEsZr}WdbLd(<0~5Im5gTQ$R8<)DV88I8{Tjye5ycpbvD#I z-V95BD^Q7&2-`RBcY=JvX_D%zK{DP-fjtv~Z~!P63c4x082K>nT}z`2DMJIm4fBR&^srcAp4UE1(i( zHMV1cr>Hf#RCT!Nxb+eo-S+xA9XxmgUoq17WIsTXPZ$&&-U*wUjNwG% zT=3qc1u^N(@MOsm{yDrHdR3dq0CSm+Kiml-H`HO%6i2kU-@yE^QldRJj%1OL5!EZ0 z0)07g1P?xg^FtEsV9G?$znB9bwRPD2&KF^5?nREZ=6~ydadfZ23vScdZqg+^1zNHR z9Qrg;6&3uB@t~Jrm#h^;_$a{V6(@=Ml9Ld=U>nT)u0)Q8gpj%P2k8;$qM6Py(DgHq zT(92*avxqp_QLZZAn8UVmkP4B8?KP$PB(xPUjW~Cy<>(HPB8u93G{QgD5-z5mJ!WQ zM8an>rIiokQCk;U)~wII=n`Q^#v38>tUYV^%AMVpsm*>|mccH{2Uh3FEY?`0orFir z<4CL$5xbeeoXwIVrhfkLZ-oiodik_E`053?uyYsMS0`dM0lfXif_UCJimFM{=ygYh z;D{h@IHyRG*;yoTuMvO|zTMa5#Zyu8N_*i~^pn z%fQ(yrg9R!FUSe!GOGG}FDaA*6bszNEtxnE&WI^t?xApy4cmnNGx+@LpIo|Mz#gmL zNTXbGC~mWM0skfGxKA;bG#yLC<1ORVNGt=xzG>6o$2V}pj5suV6^C`ZlkjK%W>jC5 z12c}lfPC3IFtWc9)`btjYgr+fDW%5_iIjoxH+i;IjDLUIZJ-*Ob1`zG9Q{(?M+XXf z=q>9Rj zM69k9(J_e_d>q8*XTJr4{{40Q{C)`?mS!qnFcil-lhH$}nNIJHrH(nVn73yy4Yuo| zEv=^be1kdXxgs9t)RfR7gJ2p{UVxRyobd9DSr{W`!~|RnBqf^mxXM2k{b4Rj^1Waq zl>+YT>Ka^hYX^3%rZhi02Ipzp!WkO|AuAmh?)S#J7t!1~K>z{ozG{KNNl4G@lIFXU zNPF~kj0tY1lMg*3mBM@RPhd6f6ZE7(HJ@oFca$FB_TlC{Hyl)s!4Wer)VF^tuK zo1Hu0hcdD*Px%@#gx!%>KLIN#i6}?5b#H zB&^~g)Y6g8-#v@8e(9n=&n$tgmBz%cJRQq+CE}d4avU1lfU`Vm>1hEY{M1#%neTkV z)rjjLj2|QMAN;Gwj4u$+x)Ug5@`=0{{7k{{;(v6KHsBL2lit_O$c@>%){>;Co$^S84NxsgS9PJ zFlI!D2+9kB(cD6tXEu7!XBbocNG1d7`kf*FZ2<&bwgMTm)%e+V9p@G}1;krC>DiuH zq+H|-x@S(N@}2wX-=uJ+Fe1x#evdCF&i4;$wD-XJl~Ek-FQP~LH$sJCEm?f7o%&h^ z19R>TXM8vYj?XZq2Z}^cMPeIKQJ+uRd{^RsZ5OG@Yz@qv^obZwxB+*@8!6GLBI`>} z+OEB~01^yKNpIr?Q1sYNh8yGH)gv+N`NO|6COT7(tAk|0)^ehDZavZ3#GgYuAJVNa zH&RFOa1geh3YO`2sb{|#qy|i(hJi7l@hJv=^a?||?JU^vOdq#JM$oo7PJ?0NuEc!Nn3u?aWxhqCf}x-b9AsiDvkDQE`==xF<^7)J4rd& z3U3B?(s|Bi@b6nK=%s7I%0&wx$o^^7ilG_E{%oUaZ)7=1!8zb1Z4QSo3&4RkE%aIk|RB2%Z+HfUIR38N76v ziB3<$dtN%!+;bLrdr+10(TqUFi>BD)eHv2@2C2{aNPN4#3S7^XfY9qwP?V^rH(us* zu4{iXp9QWEgQVT?W4az}+?515chAD27Yo6@ua#&8io^NLH)NVwC-~T zT47t8?dQq6tS%5t$poe1HPCw~25xO&VfvwbIJWBuJi40<3gWjQR4NU;RemxxT0&T; zJ^{Wx^u3J4d$Keajf@K?&Y!CV`A+FZ7#3QqoEGmzLWl#LzTH7(~o3;kE4Qz0) z&Ly1rDIAUedTBx)3gYimut~&0WcVO_Fwr(Z!_S)MWU?^rqp!gUG z>A4ISPfn&={_28S>LmE~VIh4NtPK5EyqJ=0EySWEubKJ$=`RS;qZp9oc-QvhF&p-f$YO{H%s@k9TJ57kF_aTQ{89ZM-8_pZl&|?<+sGzS5b`P9{ z__!P}x)4P^x5pA6wN{vAer*7) zX$~Xv>`p?oa}XTkys3K4TQX6T)q->I##gm^ znsgHE-dGI1ev{y$%~jg^qLk!DTY_?PBm7pghfE7IST>=p>cNeCaz)S)FNT`qcNtk6 zdp;ed*6yJ*uf=jw?@UR`Az?DMGKaje+QB%5iQxVh#&~$V4V7#!aJK6=pn(5H+Fs*D zTcefHZA70QJQ&7#T1qh+*X@O5ng&=lY=@1?cHC?=XZok2 ziSfNx4s&H=;eekJw0yY(u~Q9T*l;BsF;KvP?pN?~B7e2))&+~u^+1;2C9A%kg*z+w zY(ak>>~B|v2iDopBew!>d_M%+`7GVEm0!r%?l0Vy$N<~RWiP3)kp>LrKV)R)ZH4sM zKioFs6o8Y;)V(O3D7&nordnrU-m$wR@RAwmcc?(jv08BH;<(<|(ePfep9n7LCnaYe zQmcMbyXzgad7oy1u=*U-OA4fYLV{|eqbnh0eU2y zh*8RQklP*x8S1g{DK`dU%ah^$zp2y@Oz5$5&$(M|+vqC~3$lLZMGDsvG2_pB&QI|? zGgm&I$|ss&vwt>aTLS1VX>Ytf5YNRH?x6h{PMGJTfUkQqXyWKc;{U@P?VrZcpwq9I zJO3s^<$<>z}Ip{i`8Zn%3v)p`f({Mu$&F0ZhZZr_R)5kp*&Dv#Iff z!%&{q#Mntsf}($Oxagmvs1a<5`*$4$#b4QQCQY3r>#9@1FSAIdmlmuGo)1ReVNjL( zn+Q&Oz-{V14Eq{nKvC~Dh=g7Nda@dV2W#P%#%bI9lL^qdZ8IuMPbcs;(IX9+)Ti(k1UT-88?$^N z=r&udS%MoHsz|f17*2a6i(cc&ME=5Dx;DlN&ecW1BWM8Rn&lU%z!8ycoRXRaUoM(R&1z?r;JPTJTJ zk7!!qM>qmoYL{SU-%p#VHYy~)C=<%(ekJd;-@)6vBCLmw28c2Dp&(xbWaCu8PQ8Xs zJ0VL%NjufDlmYLOw~&8oItnlOLbQZR!0+({Tx`PcjLnV24;Lb7o7r_-rdCB>l!oAr z=1`(t=}xXMpFo6`ucrQ2KTtMbo;=jcCeg0RRlUAKc=YE=PRk}3^;SgU=Wi21=V1VK zzp#pCOy5nTy44_1CX3#hy^#Deo(_kN6rjXH67ic8k7R{(U)z< zGfd#UNhKs4iHFTMuETHfTyTE(k0@U$C*jE&-1F6XR8!6nzGjawM_*Nvyv^xQcp(l- zTmsLWEii95I zd1k}VK?}&dQUEH4+8|_|JI3$a2A8ya;e~1}QCTa^_sgPTc2h8n$W%eAI zh*@8-kz}4&jPKNvxM|rU|6{s?roM3Kx|apdw& zqid2KX}TDWg;!(o!d5pXe$O*xraR+wpDa!)>Hs(Y`o$%d!nUSw@V{RMETb z2hi!K7E1g`t6n_QlY4AbiHl-&F+*An6`g+ZyZT-bq0tz!NWg-ekZWYzyV5!HGzKhX zt#H@6PFQR31Fm^R(4dW1NSM|oP&|E{nR}^-EDH<8=t?E1G1p^8OMA%Kt$^*1S0Ob3 zytyuw9`!jyca=zj-M&lYTEYtWAtMi~EY_0^3vPpt`~+6BQWkCU2FbKe6?pM^2?Tq) z({cN3qB)PCu#y34Zq7cZal8_(a;Cyoh6cS%-^R%WT(@Uwjq8VOwGbHMUQ4rNv z3g1TsU<3a=J4^VyynP0AANxrhB9=ng;cn9M+=P5sxfGwL#zFd?lVGBugKJ)A(Nww9 zG(F=UV`h3AgJJ~e&NIE_irg)9xg?2g*@Qmficw={F89`kpDVZ=4Lf7E(N#%F^iYBT zNF3S)k;=bFyOSd{oT(sBXG>sx+zU*z%cR8)(HP54;gJHs( z#rQ{*pHmoIj4ysfqto_qbhvYyoX;LX$xF2~^s+TKy6OxnJqgDT8sU&GsYo|h1d)^4 zQt-p~DbcG@#G=6vh&jWN^WSA)_~oPO8~f8~Ot%HzRO{f@O;>@f{jcaTLmO^|<^p_` z!9Z$x0?PLF5MzlhGMcd#By!rB5l1F7=%Vk=aWNCxA2}# zF!gHPiyCEjZ8ru_gzn8t$x+n-Mny-~_HB?m7KR6r=SK_h&D1D*YRy%+Y-UC!!*pP) z3I80HkU`~iO83cTLPC)fKRbShx%e=MEN%ZsXW4}VW`x0p?eUy+gCR23j&zId9}<3{ zg$bw@!WoWAXwb&;?ZaB~*bqsClNn`Z1(UIfy^MNp6B9P;0;uXeB1h_9!Scm{Q1rK) zq)r=VUip?VI^|2qWF7-QmQ{gO$tVq5-bmMUM8F)yN2n~emUMCoRGT{r&$EJIn|T7` zZ=L~_Q?7y?bD50fgfWpHW$B6$9&LX36J-Z&$SU(q@MuFZK05c2IdCnTuS@bdH|Jb_ z-su@Q|McYNwfX1ti3;w>y1&GIK_HB2EMiVHKOyhJilMPR96lcS0xuS9f<@<#l0~a; zfy%aGc<|sS*u2^dz8>S$Uv3|XDiYvbyU?CYTlc_lV8C z`J3G)TFClTDcT)5AZ?eMSHP;jTF(=o@f8Q!1bM61Zs$o<&f-1$GmIK-io6-?S}|gC zI{rF6iB}WsgoCqPaX`qNM<0Y?@D3fE6#oEuj>Tv-DGIemQ$RXd8*4>uF|w_IR0y^) zieKl^Xa6+t%p_lEo+gd#6=!&)^baPhO=Nx8jqL3tPu5#^9jmlxC+n+mh;{PwVZFT> zpvhTuJ)f0OTcibUyKmC0o@f}#JOh~?&SZRP3H3QEh=(3l;e)i9_)yLmzdb0Ui$^4I z%H4W8*|88!91_r_E0Vy6BOtR}5w;sifyvhixUbxV-V+bO-l}Zdtke?1IP&$ukr|lB z*MU#Jab~`Lm<#V4wdi!$Y}B1FhpTi;Ak8Dsq2Y}_`_S_xygIU$O-l%8HO_KyHhT|y zy?Q14)wvyp`~!H~%oKTtHwy5+?Apc~HW20c^_ucTKP}`fV3+X%M0a7!hNM2BBykniAy06E; zw^BIywc@QU*WZ)hVrp0s+D_MYeIPobQW)qU3O9PxQDpXa8nJH^x$vzRNBaA@$NrgA zhF6JS&EDdc1>gAZ6olbdewMa&!B-5gX~8FzL%2RW8yi#_P-jaAHU?h7#$zi{FKmD@ zezOj9H!R0}^CR&7jtLm$w+HHab>YJ#9d7bde;_{&6M_GBL+`BE?O3aZ^856cApQ)kGe%Qk|FC#rJS_svw+|<}J{ChC{*M=^5)&y!;LUo_>@j z@1*!L-j)i6r?}%AjlUNuIy{8%!FELyysg__s}o z_iKX!FSqgs;!!2SlrP4@tktmKhb24+t0vx~E6J9>Z)p(IK|hqtCJlDIpsMx{c7K|~ zK5DmT>k)};lb4B>r?jwQfz+V zb$BtM8g{3ZV9_f+Ar_qr|13F1Gye|wl|_Q*$v9Fc7X^PjHUg8Tj2f?GL0b1asreWT za(r(6b4W4ld|L_0`2y@uOMg(8{{&^{MA(@k)nH-K49mh6vKhBJ;31z2Fb^vOudnLt z8tBB>wPDDs-N8LcS4G`CiV*^zkyY;CXM$w0bMZII7`}keYeQf<^aDnt@4`$`L3X*G zJX`u!gk6%z!h_Hi5W)?>uV;VYXWliq`CbB=Zl-`uLNhcSoej<@(ro5uTTpSYh0EO| zaMRrv3?%i~bzy&i)t$qtxm*L`Jv^|~=mzBt6WNl28LXrI1L$4Hus5|k;Tm#aP$R+$ z$QrP354M4$8sgXwc}$IbfCC=kn0Vte9X;fa_r+ckUU?qL;P;Z;4GN;&5&Q8^1p{&a zt%a+Dcj>o6C#XKV06M!f!6?5FNMkR&oWKLeYe(USbOV&m`48rl)WeRm3nA|j63gjR zVCn~Tc7{#~{GHnZuCqHqW4kOnd6_zE>h%}0BpYBwNd*+LOQ0gKo9s;Gk84}3Q7pue z{L9XQ{Z;vNXz@k<8ygC+_{k@bj(W-G?{i^Qk0mR{F>Kf^O?Cy(l3n6z!~Rr}WSvF6 z!Li2q>{Po}SP?m$)sj$RgPNRJ$z&OJ@evO;;ra|#q-p}Yr7QG5YMe z3^i7$TZx_do(Dw5f^GYB5f1livs2EeL4K4f>y<7{SA^D~-wa`%vrR8K8*-X_))M4~ zcO-$^VZKl7#?OIH5nyGzqk-c(!F`)7JGQtKbO)|OsKXy}>c>w==Lxb6sY85S_bMDU zH(_3m*J6hr%!C8^ad09`jeS4E5&~W3u*-i)W>cIN&fkewyX4zHWcI%giPmPzOPes}trIR5@?w%{>IE1U+^t(CNtI{`D_%0R?~ zG5j#+Fb>P}^~znEyeoqIcRG%z;hW_jaas5r-pH&6xKegC?nyj??;Cw_wgRmRuvv&T z#){~(J_eP_5751R+2|Lfi4FsNzb7l;jB8{0*?xL8`6TYY zu7Y{DT(RZODOfTVMGU9?B;UTLz`JF8L3F_sRG-hG(z#e{e-?ocqGRyyx-1M>7=Z(Q zCoo&o0Zr$8r`N|kaaH6yG8P=n1!tUsMdL>3^4Yig@5eA$W4{&@-YkaSZt}R@)`^@D zIEekULno%B9@iV+V-)^FWv__uD2OwIF}eTe8HJ`e<2L-a z1bFhGcO#ybwvOFe_)nd_Ib_C(1TMz|i%jT(`o;KZw+e{xCSdG`Pjsa13_L8eCkI~? z!1HtJVBI&wly_y(`Qz%eGZ@f#&Km%(cxK8vFjOWhxL za~sX}Vb@v;gTvR!ysaCV7%ye6d$52uhsHqfGBv!(%fN7#7EY}~2|_ILNl|hNrv9rX zbC{L%fY(C!c6B$7X>Ne4%pUkVu1wOG9>ITRN63qoAuPIQO74FxBTG;1goS2yl5Blev)ZM>G1Car4R9M?G~)C;o-*|Rg7Ebim6eP@B_c|$3Q3*&+&V1 z7HrAG)1C*=>-`*Z`=1|%%;!;str=YO$$XkR8UooOQ#j9@a5$CP&rCd=L;Ag1$=2sL znbb)f3{ALZ8#8DRdRIq@g!p+#s4#@TFT=REi#9^Xt|Pd-X)Vf}ok+JmHbJk=C+V&k zr@&Nb9@-8*;heiJQL{I-PtMY6e7#t+qnnDXC~s&F4N;M8Ng?RuG?~j^X*?G%BHk?oG}EzrI*7 z5LyTU8#}q(Dg3UP2eG6z+Zhf|o67;^ zZ$PB@WjJS0Pa~8QVc{KLC{XKUYEv%3@pBhI?dx6&+b5CqW1g7&@i@#7y-p>hbcmdQ zEhNgiQ&S}wm@YRPnZ1j^@pUQFzE_7N-g1NFh%^`+d`c6Hj)0cyO8BiL&g@nxCc^A5 zI=YyF?O8oA>=?`x&h90T_~)Wx*cWbc<#Bj#m6+Pp^=LsxvH@uZ4~%T_W|R&F5q2@7!R`FSuFt3`i&aizE3O{GMviYk5407~m&0HEV&Y*E z3qqUHp^u+?9ciBnaR)Af#oIJ!eyjtHOE>~A|RigPrMV>!|Wd;WOCG6 z(9~Q^l}l>KPjMj-n&$}h?wUA!z1Jqn!3QT@HXt*#47f+Mmu$743mfYTDD#EymFBOb zS1Vf}Y@`Nq#Vw%h@ftXqlL|w&^Rd0;5|v#Ri*Ho&@YQG~id~Mx9joN%;E}6n6(@qq zQ^ue>@f^f?N#o_OU!g5QfPEml87=;kWice1j98tfnbSAGo{X)Kw&Wc-qjMR`52e8A z6k%|Fod+CsA?;n=o6+7O>4@GiVJ*2~1=ODzJ`6m}?KM!?zD{xXn0V5=IgLK44 z<65C5)Jr3t)*UnDtt5mJa$fNV5*YmqBq!0%+|? zf(iVy)VYxd+x;KIobf+kX~*{*C;S4>byBRSxhEv-dJMxKbKuFBDDZkYl`YhM2D2+{ zh^3tfZ?3r_FKSvRUaPu6rR*-_aDOq%%{-0!6*!z2AjnIz{6u~|UkchApOSs%G4y+# zHw2V#!JqcsL^gFART!8DVe^z&dG${Cy4?{@y*apNn>)9s6%k=^e>9TV*!A_1F!6zb(a&<()L^_&+K#(~sVD zPvLWAGW1(wGJWhlMlZ*_#@0RVST37}SE|P`*I^P585v%hL@O6`{51+^OY=M(9MH;c z7>`a8;2p_XjXI0@{AR-~6mq#mwI%-Is1re{^LNnqy8`~?&s)M40eJkyOf0CX<=?p$ z)O^u*Yz7`?cJcdUhwgF;iG05MtQJna^O+oas)EBSGpV!HEP`39xZVL(ID2~|sG2K+ zgzzp{pm3?W_31_Od21Rx8PtF(Q5}$fWlt22uEAfXKk=8u6qFzTh)YdkFqqF*I>vmb zH*3A<=el*!SF#6QpRfW+87;QFCIOB;QM6>yJ)tn!PpjT%#?9*_7KU?0BEk{zR z+?ejI&@I=PKkl03Y2-vWwq1uN-u;DDN~pZHPMQ8B4tT>bSl zR$Etc17CyZEIpouYo%LolJ6Nr-wC`?*+g8@BE`#n9fniyH(+||eta{|;;p+k==Fi8 zKj-NX>sZ82sW zc;zZwEy#uEbQ@tU<3X_a6-dP|z$9sR>c7AW)@oT(@s4Vy{*(du9Fynt5+;I4*J((5 zqJx$tk&GyRXE1qm8DDGdhLq~F;QrJBjSwrmp|%~t|4{D!ojRbzAc+HRBVDk%HD z1wv}h)1|X#P&?hngh{qTpNczpe|@EvMfh>4G_LJm zkE#zPIT2T9I&I+<>f@q7cc;JOw(Zx)jrke0=lEap;L#PE^bU1+7_lCW?NeZzhZ*q7 zzmlJOIA*9gk&xErjB3baL&z2?%?HLq;kvwc210f!a7N`Oka-GFv@*aU5qoD zr5Udu)zq?G5uVLrVNs$xG@b6Ea~dtk{wj44TXF<9*2mG!7K^A{%0g&0{0e#n(rlF8 zU2dlPbMUd3W^LIP+k-delaDPoLF}O^-1c1x9`ai3V7(7t-@XD81F_(nG6nNm{}PQW zVes^bEG!I4hv$dvVeSrbod2&Hn9+9F^J@oYar)qT*$+;5-LQ2(r4Po{-nMcNx8!X7DbO($hW)XpAp81r@P=n3NpKYz6AFQZs9gHAb2WNPO~R%=en*>+7K-R9 zV9`z|I&Y&8hI%@Xlkl*NBE7uO1eONsq1~){ zGVeq$eg8rV4ykRXZ+xFo?;v>`HmjhSJ3LXMdkXO`mIS5PLa@oWirMe@y=2GDK*y;N zx367;wl_v;a*3y{+yxn`;rwvU@O*0&KDh{Y>|X-TJs1_qNCWZSe0uV#K+IRnsl z5vo$B;n>#q~t*PswG6#HIIfRSm5yo=c(rM-JIqR2MnmT#Pe(Vpj`P16!b2n z6_?KN8Q>N;=rf0E#S*mFuZ8H2dfc$*K4&U(9iy*1e)<)HSJicZ{Bc9`MHb}k;dtiz7f<4O zd>#f4#gn`0J}@Jrmk3XAqHY55_vWQTU$EzrX)}-|y>oJAd@&)w#|!p3leQ{;;VtuBfkDdMA$IR^P01y1ju+xW{vd z>SD<88?N~La}}MjLKy#A%%owvsxb4Kmtcx+G;TMPg=<0;sH9|$r+99IUYIMM>RX5( zf1k#$k7DqJ#yg&2FrI5V#&aAjyzs)5Tz+1^z~3j-P;6NsUb_DU-Me}JzI6=#cqPCp z-zj8k%yFt%(}8!6wP4G{eY8eIiiWO?B**u3&~Kr}XukZFz-{_={A_d?-8WX#J6;d5 zVpJIow^yU<&R%R^^4wU~*QR!py;FXukB3{@k!0 zQy)pw&Ks}jyQ~b7_edFOSva&6ilE=*Z$zsk)uwUsT%H3FO#_YgjxJ;rkS2A#OnL1Gk2}REL0(u>!m?P4KZ6YGf zovkPEu)hxWs@S33&c|r<0P&893}!9ShHch-_V(a8T%>Y|R8@~b>1sQYVXg#`l5ql& z4az96ks=dlFJ?4lV6*O-I#0gd*wV_O&ap^ruX0D%W9Kk;{{%2RrvlR)-&3E0U1aS~ zB|7D50%^@y2t~nL$bsVPHsX83QEQj2AguH_eX>fCnwnD5$)w@hDRc0Puo~+8lfj3s zd%<({DdL`bi7LBnq+Vruz7F6UE;BDhH3a^@RT9X79?{bFDPXbKI^R2Tw=8BE%0W{yOK@#;mX}y0qhShje zBR4nPET4|$@7z$)sv9Rgnoa#gkK@4Yhm2mSFTI^KnYNS(LBgC0DjbqR1e496Cu#vK zRuO=9dnehcAjwTVWQ9f(`|zk%1qO5)qGv}e8G<++BD%)ZBs>f6$(jSih zDFNC43OTJH0T=o8Jl8F9o~y5W%{{Ly-vqq z?tJ96Y>5~jwj76_|Y&rl&mQ@$Tm`GEvc;Sfu%*-;Gc@)aQa5 zdk$mWk~~^8Q%lfZA5GW2>ZHGYccR%=1q^+<6oNanV62oTS{(LAw%wDCYrBoD<@Ve= zeQ~bLD4A1ou;VUOPT}?jd2y@K!nt9~aa^wUI+!Qw1cj3En9))ITiyI&3x946sW1UQ zyZ`8ZT{&tpd>{E5D1DN&6eG*-Q;TQ=Jhb6BW`4ebsisdzrFstkK3n6H7MblfuqvXnHsnG7KJ&Z+<@TV9`IKzllG4*-sV>UhN}Qvi`_De}YQq z%4^3fJfbH45vYDm3_EqQ=(^8x+}`uLnEKC`M2bprn;qwp+?J*A;m96*_@;; z{gj|vRTl7gpdgrSP>wB*OCjfFCtdh#GPc#N#0Z}d=zP|RA7Z`frcYn!TZI!;?fP*t zW|x3&EDAm4ozZZG zB^bTfgMmh&ppdNyJ|pX?|F?yt{{ct;J(hp>&Zxl@fvp1D|a^Oi@Dp-xGLU`wx2g=^kS6!U+zl%|P3p z@faq*h@ZPIbn_$$X!6p8{jD1C&P|M*)cZuNo>kCJuW=}_UJ9dAqab02F?GA`c+ufg0Gy#?djQ#c+6GJkfh-K`h;ukkWg8#IJk~Bsay- z8_qlNvDi8CETV~Lr2i&;@160^raAa`@mSR5eIxgH582b+C-6-rfC_>JA@WfXtlD&k z{56Y&v-z2Iqv0Fyl5++bXPN|-`PuM(&2xscb0&_32f=gY7H~c&#t#`a-uxJl6A^>m z#r(TjQwqa8zv!;!6u$SB#Ps^{+zejZi7l65p6qQ}@Z+6-_O3Fx3^kw&L@@8HwxpknGctqCFp^=m1`8IpP1lLlBh=*k6F-58}W>DaEx`fE5{3aXJ z`$@csCYi@;5)KTkfLn1F;kH){v@&N%>kB^5!!I2~-`RjZyN*XB_AqnKAA%Jksx z-Qbz14@Up2>6hs{LG|i3D$G@p`|UfR@kb2Vbg+%a?6!w7j!W=pQ7?^p`;%1EYr*Zk za@4!&3b~VlAZ=g@e-x~kWxiE#jQ8jjOB=v^)01$5Uym%DOzHD6Hehw6n@E-0f_mLX z^03GOqRwUE;Dd!^({^XUEB%GA`J6Et$V%Xcw?>#}8pU)*8=<^=H0iu@i&2Z0hedIQ zuqOc^*O-4l3Jm(0Sm0-Y87v=~3|0qA$d21rNKz=zoonBSeZ_gqe|ibnP~&ccm7A>h zR~D1T%AMetF$N=VmBG-hL^z*c09p_W`g?_e9}(m~ydY@FmdE55(pYkg;F#+ke0IuO z9Ol2qUNPuIj9!wUO!q9tfNcGV+ zBKp=GMfsZI@p^60SddE>-@iqs?Knc_@!pK!>&ft^qlD0Jry$uh1rq!u!F~E(vSQU{ z5c=SY8`ebejHJ0R|Ktx^p1y$GjV*)c^ep*RrU05kB~T6r1cFKx!7SOAbP~VL{ITHs zdZM{>Li7~4oPHF`XUYS2)DTMjEz$UyF^PDUM{AYE@$HBQJipUV`j1^Cek*1{GZj{eC!@wC{;3|hQu*nypkazC&fFJ;t~1=QY;hDRUpNb= z%cPT#jEf-r_92BeN2n9!89sBmmjyDDFt`6T%IZc26orba=V)R*^ zEC?L`2<}a&XKpTlpzm8Tg#FEdy^iJZ?L!BXz2}~w zFyu8gi)x~NStpo1&a|nZ*v0gx3a=DRWF$T>`O3U zrWDq`?yN!{g^J+QKs_P*U<$Y9A zoq_MOuM*j%rC3S4>9~RO7;j#R1`Geg?W-39zT*9ro_w!hax5Hv$^VaLJb-s!4nbGp z4nFrRT=1?Y9tPUmnIFT6^!|i&!N-qL)G$E~#5bjZ%lz|XN5~(6sfaLEzF!#O7Z1}8&-}LCKBTU1k&GfbA7Pu*_ip75e1Rl?);)Hu0MA+`9!2f0kbHaWln!PTy z5%<1=tCPLStl4g4?1H6CZA>zpZghdh1l=otJZxe0gcu-veYV;y3Dg4<;7gV~X=?vi z_jHaBk$t$A4(iC#UosQn+R!{O3J3(h;sEr#C{Au3eMn0}#OapN)y$>B4WvirCZqW^ z1RERHk?O?FM0U>*f!A@kW412Q>T_WNHB&HALL2LD$m0D8*U9CI*}yKUCyS?*fl_Y* zIBh%)RqrC9D=!}EbIwBlv;uN){w=B#*CF^777xn=*Gc7p3Yx5_K|@!&;K!+nB=X9? zx{lznG}!nboo!o%!hxc+Ix+)iiiTsRNk4H|{lKPwYZ4^znkVt$IH;2-rPsW3srYlA zIePLp6LvU_$XfQ3&2Qx)!R`Zjaj$}O{mFzWS;OS_f2}b0Q!yoP7XqM4wIC3fl9(rwsE>lr#yAe&h!pHM|Zb|exeHV_N z_l3{Q6=LYRfvV0lfD;GL!aoBG2;F*{m=>P2NxrlL4!r6We0_ZqTqbUY;i5;xp~(YZ zn?9x^6Y>}X%^2Dy`(jr|H}f z3Nm^w^z&S0x;wE7bazdH+a@W3dv-i?K--R7Kk!g+bxt+pC{~bYlRyktFvqJprick! z8Ph+n$${t6*lYHOv^Oi^R)fV@y@?_B1qCEo{fS_`pC3*i)+Qnm>QFac0uEj5VyZNy z=!S*-on@G%FB>wbjQCHI9jpKvQ?}Sl^}S5`CyC*TRy#VnZzHsZ%EK?GJStLBN5jJo zL*BSCM5oKtX48Y;WLL#Ln3AgnRf)ZHG_Qg_l8|H~3%8MFpJ$@9en0i(^F1F8rjoPj z8{orUMHu!nqqDsmAx?BY%wHZ0YEpJ}Gaep-+NOQbzPf^T=!Y_D7xZxct5I?we;rsZ zP9hm@e6B$BX}U!sl{|lC46?b=lSIYN-YIGb26mX+7ki}t3k!n zvvssw3I@$2$%Qk1IFfaeoUd`hw;5uL!;4=6rgnT8H-Cuey##1*T@Tk(Rrs~03ts#!gc=O5sm}t@e+d3>wG>) zUJW$~%*LfdcgTFNbY}T7{*GyV1~hkG0Noog3(dGPeM&yrDo$i`6TzNQ{ z+RJ&<=8^aGzQi_i#&`)hC51o-D8p5mVlsMC9;o*y#4FDg)E{mmle%A%z$HDif6m_k zI&xB!?3zQog_|gBs-#+r{K>R_T@>H?h-yuL#T=M*m@MgPA-Zzs=!#EM@ogZlDf6zQ zd$0L1-use?NxTv>XC7km;oweT zW^-r@G3;Cizta3*o|7_rYityZh}wd2^(ed*a>8_%t3=2m8f-#3K=@4^sPue-lsn~M z&)2q0^e;izhC_8O^Qy?=dGYX~jn8(Qa)(5ln~`&0d7q}}6l{|d!85WAjKrrT6d|X1 zZ^kmX^|=rds!x)FL1pSY_?ujve%^)&m86%RXY&5$ddBk=fhTL;0W>#2|=txyHF((^&BU5H=lEQiyUe5}Uox&=29IVP zLWfC5@TqJo3E1t+^f|>~*tZmvzIholGOm!VVT*~&0ehIw*W~3b?cr`lH)-@4Lz`PC zlO8E6IIFF~UD~n*4W$*ipLcog!lyJ;xYk1}7ft2*Wn?&~&Sm&kr5i7fdxdYVj^dA{ zVw`mBN!|WPZvpRH+`#hQ zGc5JKk2iE0(b1p?7k7r>wd*@DV#iukzRTCc$#$MOO3C*JCD@?fU!6!Sb@ae>4 zEZRiTq5C4LRV_mAFadrvZA90Un;2#`mTTB>5(jfc@%L9zPPpkY3a36nTaizwwq+uh zenX1RYn9{v^FD{4j!uKu={K>XumN4apP@Iem*Z0VDtvwU7+&kVi((?)*cp6_j`97A zdz+=Xp*02g@BJ<6H}^d?+s$X$-hYbvY$duhC~;-2Q!(>=96B%kh|4~F!>h#?F{D49 zR2KZjy8>sTb6OmQ%@sKIV+Ne*ZilVq8}Qp$io2MXxc;gb_k8M0tXVe&orkXD?F+f6 zFnt<67QI6hCW)dwuOC_{z5|1FZ5vi{nJ=es?D9-( zbG(6G4+pVLyqA$&;EoZIdF0>Qw1kP+F(DGmR=vz%UPEINTXBDYq-|D8i z2aeTrH1|4=dN(jI=Q2F-Z- z_pimcfvv`<{rwx>*sag)f7pTF-HR|gbv-UANTeiJK)lE9$F#Imd|7axG6xEAAn7Px z^nHfW=tV1ri*W15J#=5%Hf%cn3Ma-(aV>GD(Y-MTH@zIiEUm40Z|_IGkN+E+?~8J7 z#ap=x0b1Ng#~zG4GJ{)__8PBUtHFs9pNX4ZKRtS552`iK!=3Waczs3~ewwMtjpf%o zA+3Y--wfbf-Zr2}iYmTUO+y*}doOwt%N(?k zD_kvh1|2L{tKIkUC zvATta(iJ$DUJ>qD?oGVyD9s+E;q1~hGj{2Yc(yO-96R#;5c@_mksWTk!un2G!FuOZ z2oBk1gXY-+K4;DaIt!Pq^Vkmq2U*MQ zH=r!enw5RLfL(vfjg|Ro!Ijn4@LmdGu5N}M*Aq8~TM~W;)y9wKel&OCzJqNTsePO+ z6FJSwJv_`Vn01ofcejd#SBY$?K?3`7b_6TwxQ-RJO61;n9p=ugU%^RVaN@Q&cycPT zK3so{6_+)V#=V-ihg;yViIwb6Ve4h1*^sJu)*?Td&AzyZeaZ&1Mi)=8LUn7|1$k_FoW#~0r@7j-JX1&IcH?o*1T7aJ~OK^e(op`M25!NW=W8vlPMEvV( znkk(KD`rj;XzhMQH7*#|`k0)fOP(i?8qF@){34P&>k-2FiD+mQ36pdL(qm4MvHitN;Lup`Hk9YujY9FW@l~R=iN*L-QT%V>NxXb(0Sf)O z$^^-Np|RIk?!a~*E^~(>XE;}w3u#@zz22wKospZ$t;#Us76r&*-qdJrTF-{SLks|irl%-+Kt>f>suK4Fq+dmWY48}DRO6yn{jcD zHry6IgQu-`7q{i~EN;=|(|CE|7A`b|U*iJJIg#=sT;B|1ZtjUL)ZHk|hP#bn#db+U zX)!;}oF+IY6iLb>ce9$e#o1+LKVY4u1GxPZ1>KMttj7cc_;0v_*;P7`jor!j=#u90 z`H17$ND~dtH)tmJN__?Xvrp#k&IcP`x2)%x7GW8=BZnn>8c)seoe6oWA* zi+E;j5k&AhrDw&@h>%$q=?jX7fA88LnbBqMZS!Z37>r>L2{hPk9*%54VkBh1XPEk3 zp3PbGQ(&Z=0i)&)@YKCrKnzP^hhaG6ZYqc7#aBSEy9`2_g*lnHMilkgjbjo*IQb4^ zE@jC_9P&88of$Wld#_@^WzkG_3zN5F7ftq5d;)g0NChFe)(Gk=zUk1UOkXMe^!vmbt) z=2kro;sUg^IK>YqxX%I&o!i(med?xTg z@^46<%IfD5QfbL#Nlj-rNh-6_Vp6Qhy5A6WU7qzgF2R1B8wXm$!fX%UUyKXAN6viX zvnAB*@mOdSii{t?uBX`;@GuHLupX$B+=V|sZ2-%!aj-u@o~8VqVf2HLQPuwz(Jh^I!*-PfbVl%o)r`!~k9)`4F&=pzz!Q`rKL$S3VyQXf;;}X4OZ7 zYTHpdV_6!As}54FjqWg1J(auyIo6%`SE;TjA**iAhB$j=wrJKz2vI%5*I{JX+N?@Q z`y$UO|Mwkc_WyvWryF3F^-HKvr~=PRXJLrvq@}HthMbMl$o=>XxbWc^T=2LB=WTM~ z>ezVjx)Wd5Jo6&2xfWxGH0QFe5nZ5nb_ZNMD$nW#5_agO47+FjIS8D69R7|sWgRz; zVGUcSvp@6(AmzI{`%KP@bub^p@)#5LzcoXk_DYr&nY#+4YDPfw+bfuIaTAQ4xg1I& zkHUtW5%AUe4wK#{Kt<9NwkPZi&-Mz0$IVwk@wOVPH2){8KR65qj}t+Ok!7!(&4;-0 z%It3LK4h*_VGW_5$}_G>J5U)BV<8|7)exk zz;m$2;7tC+__a|I`i&J>yQ=dbI4;G0z7Y>^G=jRbVDIk> zaA{l#qz{L~zWHO=Ow&$i&=j6h@`bav!`>&QB=o)!QJ$&;Z` zaxGXK7{{(r?*(!1Rd9W%9H!VwvS#n6uqpTEv-evp*=%(u)>hY;EfF5aev179MUxfT zo)1dQU9;15-;O^c%z-{|5<3cStSs3hGJWu31_e8Bzg>aj%N9V{_!rQ$RG5{2k`9716(FrMh8_OFGlt!xVCecNRQH;) z*4~O>E;Wh0a%&v>x8fW;c|8ao8-75{oqe#0=k|y?o54$uIPhX>pvUw*_`ZsSSAp-y z(<(h`Qd|V4N440af5yRAlWy?JHfEz_V__hBIa;oIi>?tz=+XH-G&emH%V(6*!kn$B z{Vz^%;+zZ)9sNL)-Kt@GtpOCs0BF6n04NED`NvubGd&rcM7O|tjaTGTR5vu<*MWc1 z4Um0a1$LAjfz^5eq_n&ZqJKCD3^F9ZZi4~q#@El7XF|{tVZp9;Vc6UR1$L2(341($ z4!h(;5cKFirYk2>a&&qqQ|Ee(oH?|Y&sXT6bA7zA!%vA`y&=i2P`(Ao)AkBgB%uAp&c!3G1wgx4( zn0DSVz~j0B^u~)ausa(9Lsco{xNRJL6Q&J{#@lJ{92@#rRD=BTF$2}v1EgAMl$KBH z6C9ei1H9GE;aALZVlyfZze~li0N-&HyHPD*dLT zC~&J12EFny+;vY3);v88&1x5j;K(ruoIaWA*#?qU&rjt1g-lqL;Q|J=n`v83AXL5h zPNx2PNVb+3;a~%2$oYB}o zn$w-0i}9*s(7AIwK8oW#m$m$P`RiAF^0-h?9JK>uv_3Ppb+qBlxlk0YnuEUUYr$yY z6_gm>0GwJIjoWbtJ*17ql!sL*haDMH5 z2*7y=zn>OsZexV{uDl1YT_cD6nJM{2s(BWaC~(#eDTf%)5-FjsHPz|o;`}<+i&1I zme1N&RYEz@28>Va#u&wRRP;GZkKQha?dw;-!q;K~{}^|eARi0an;NNh&rvw5vk4X~ zSqs)TZW3m+85CTn!cS2(dRsLLlC^B{fWkepeQ^wUW<}79<{aJ&*bKKWTR>6&X*$cG zkwh(Mg8POJ;Cspv%4%E5^&jRuFLM@dZyd)Y`nl3MhnIoiODfjpBSET9hL|AI} zhjv8SLqUTU5%DV_M}H>4_u)rG`s@>%JfeqDQnB!dxlWT$?FWT7>13_D6cqD&-}&+) zM)!#)7M~j+d-OEv+FjR3ZmBI*7u139hFY-IY8D(^HXpPtYj_`QDbHWoNd7)&Xvy(> zvN+g`c7c=Sqgs-Y0v@-f(vVEscAqF-F?`Fv@GUXSstBae1Q=W z-#Q2Ed0vd{#}(ivP{V28pOV{;J`2unaRiUwD`~scIcVl{jPCxc1yirRaQmGxY~8va z)VJRhC{*4g12x7VHPlU_RF`4H{)OnacOvYtK1Td?roqiDMbNvnlsOP~iDWqN>y!zD z^9YO@XyUsX zFg_znPM3F6eH=^HN@vmM5hs~j>+)gXo;}no3K7&Rek6Jud8YkF3*_3D(HFf+_~>>V z8ryl`%XBd^99u~*5AT7fV`t#x%EMrNFCSD(@&w~npM=;cMIg3nC9P8sl zrg48R&zy?~#fG2ciu4S4Z&D8Ge+>l}2AjwfUu#mmOqXt+CkO3=g|Kwzee1`~pXeuT zQ7ZJ}7qOpm8It$iAO-9CiJ4CrDEIe~8&kq*!u3#Uad#X9`|)Cqnqum_H4>J!XkzZf z8F2N>O)_Vd6#n{|N!`0QfcNYRG;U!d$*j0d2b^ml{=N@fHYeoLv}Hur?h4f{(2(u~B7*@J#5%-@;u+O=lTo-pDW+n=7-)u29jady7JkNl-ToVbnph&sv zBDCz!Ot^kt9&Sq3($u?gp!9M9Y>!#Q)Gl2PgKLFQD^3|JJIr}D)HZl}d==J8|DtBM zYw3fRUzpw->W~i-5Y-wFhr;zSujd*G;Wa{={AJMN!&q>T45XuPZ<7&SD_p(nETc4Y zKAN~30mq9XV5;&$@XkV<9@*gxW&HkKQLm3*+xv*f{9nYC(?kD!SqN^@0O#s8ps8pn z5U*baQ@`+B?YBep)8+~gb#s7dlcKtJQakB^-|0kiwLLV&or5R`8QObUmgyK%LN5kN z!EWUtIz05A=SLP(fA+kqIzIw~0A+YLQ@V%oZkuo51@n z@<5c_CG^i^A*0>&qGh6!TpL3faGB*#j|E+=_J~>bTMdZQvb5zp* zprC!151AdJ1FlXIlKV|9y@XPPg#P!qI*E=E5|WhU|N8&@l!ZWOZP5D7{=t4THmu#X zc7~O;^(?EIGtC_Bt%bb)Z+~+PvTaopr0lnKesl=mA8p_8EyDJr>!|IvDowl6yFGTl zwNvfRXqwnMEq1lF*=J*?RZMN4mEN#h@xsvV;KxIDCzr_Dfz=(`kX~!M)Nv+udrJ1$ z8;?)7^LlW~-hQ8^o%J1AJLQd*c2S3)+0Hi-ckq2|V&7>p)^2N_uboPXhu#0i-(IM` zG@Kvp|DOLJamGg5QxWf0aPs>ZPHax3n#St;~yj(QwQ{4?&u|J8qn?7_7 zoPd(2VSL727^rJGk`>pd!4pd#Sa$Cu%{Y7nTE9(#5I)b9^?E}^%y*-GNFE+mKZPN4 zmQusC9)ae^dOWsN7we7F;nmDZRMyFmlH_2x``{z-4?IB&9y-E__$d6zXP>31$lxR$ zUHrYY2y6c?M+2qhROOop*~A$0*$U(7qYMGl=cR&yk}H^5=s;&kbkK;JShTgb!;#}1 zjD3VN&gk2R{rArjKmB+hHBxNntV*a69)hawJ3K%42*iJS&-bW5!Ze8wn72LxGmUSc zkp!_Bye{us8Vs#)0tM@N@H=27%$QV4q9=uecHuTCoqh`n zJ{`7+idacC>on+_v z$AJg);mL)vI{TxUeCEPY;xID{>IUzUS$<`VyTb>PHH$#jggMkX?h;vWdOR4VnBZ=E zFQ)$bd8#@-in2kwQN|~Q+|^r3>t$o>UKzOw@{LR|w5KM4UE+N%8-|-^;>KY#ReNm!v@TqnA(+o&hsY?4`BNqon6SHbk6aF*Rs8 zS-UIHdacb{L4%|pnjbb5`0<3FGNDzlzspdt>98fb^cOHWIE``q`<^cEo`F*=gwXt` z7??SpAnPKR!kfbf(Y!qqJ8gH-^n0NwcF38Yez$?ONCy8#KVZj{qJdbn50HsqNGlu)K z(cMrL)HeD-(TY<5VqKZRxKA&E18r%L!+W#)@=}P@K}Xm>D;z!3uhZhFG`u|HgWx~kUF1*t z?$aC)Y~69b=dZSG7zY{1N*8qK=g>bUr0}aZbi4j{C;QP2m@b|1cbnBiXB8z&d*=sS{ z(>B283{}x(&AAx1eHMsbOreMWjzK>|EgYGviJ$7m;FGbl$v(Y<#B1X^(2nRL3l=@5 z9{ikf-usWfEh=K1=h%?uzGlY1H;GxRq>c-NFETs4s>sIq1Wb1;&q{PIz0Kfy;OG!C1o=4t{@W zJ(a&dhJ}ffO`ch>FEftMbsM2c7xc((;pq_C5NV@->^FKeKE>6M&A4*Z3maEuqSz$^ z#@Du(uHAhMSG$Me-dXxMcr*mdF4tpBB*9Z3FimtsV z8=H+=j+o)vx4~2-iVy6kx8HTp!Li|R zc2YdaEL{MV+E$Ri;3Cv-v;{$kDlyhx4}NO@n7u(FH1c8%yf`4kScMzn(H-h2H01&= z^-aci{xfh%8jEW}B8c`|ag@A&3IamU!n&2m=)kWgsF~%>w9E@8-`2>&;OOhwO%67= z><7<&@Uq9FnUhi1Wg7qehv2OV?*yYn2}2F6@#~rfGWo=1JdMdr&Tj|Y()*Zh*Rf_4 z1czw)V@LE~t^{#0FX`xtv*emx8FXEK0nZz*fLq~lsNWGs{FfEOjUZE!a|n7IdP&3N3oP0m4oPK<5Q{Xxg7Ixcf;3YI^gh4wW6bQK+fAlz1cL2$n(7a8L^LCAl6 zCbs=6T6rp*8miS1;pG`rdE^hh8axlorpjUC-o0QkFf90Izk)RA3$caiTHP>J6i1;q7gU0(rGz^j5F?} zJ9Z%A)KZ(s<#NCo0Cu@s;f0`=jJ@_Hq9m6_`fDCA9)&9Cwf`bs=`f{1N=f+o?{rSS z(4MPto5GonljgEEi*s}ST5%;|8r;>(LHK~z9OVw_!}87m;ym<)X^l6*8&+cEa(gn4 zKiFyGadwMMPo*Xv$X*PoYU0qiKofLa?4aY?WIK57KK-X2a{Zu22}g0U8P@UGr28ax04Io|7-h(|5~j<(x-|;O7KzZCeT|)%(bi zWtpTi(1*xm&!#cwLgCvoRiHIW@Ycs3eI8cf!^6Ai{C+FCL!=Dm)#+XHpp7oeh@)>B75CXq z&R-4yovsuzP^(299eK{aRuVnbWKTDD@jTiigQUIK7|wZ?L%@-XJUFqFz7G_G3a3N# z`OqHnJG2x;dnMp@ur(Q|uqMu)_lc@s4oT_{rWJjcp)V(wT;CeS>^?8eXWHbzLZwwS zT}cHTm9|0H)hPOYjtI_u7)xTxP0;doGaWsdfzuZ0qe$aoj1x6Ndsi`BXtNQQ4ZD&L z5AyiT*AATUIvXe7)WYzhU$m!xJ$2Z06j#=E(G4&C@olFAc1j%(OxX2VaBR;X>hsQw znX@Jp|0Wzmy|YI!T-z6J9cM9a)e=FEiYKHd?g8?H<5 zOTXhK0 zY6Mo)<BRdYho*AS!mD{E!u-3qwFFhdzFYNWt`_em6S@+ zl1eHXBHsoLME%b1ul{j$UFGvR=YF31{eHa)@#eM+E>=dEgA&SX(vIffbh$G6qBfD{ zY*(Z&p6-J6fgNOT;V7o8(gM?DXJDUg7)ER=MadRX2)px>VQTB)^}a!vB$)@F4xIqY zg;#`(eGV*fuY-M`MiQ+%9#C?|0md4gCtClCz+jv#IjWTj_QmDkzd+cjUn>BQ;uGW+ zuMf(d58%GAQ&Y3j6YjHLLHF1f(0s5G6gIk^c2B)0~!^)>;xc(z*xLkQJ8Z>+2{UteQ{Kx})NdS6mNx;3;uBd4+ zSKt695Q{rWwCNs)tH%4|HN`o&f6i|zZRvwadH3j@W+Rw(anNcZUubo4cs06iI7|1n zjDQK>QbD^z6}C4?v8uhzP%A1DY?NS3>}#@a>2k8?@n*>7=79Ry5?G!&8zdQI80mv#%7zp4o^~XO z9oa!D#35*TR`$AE~W$BeO8^W5+?M*E2J3K_WC6;9q9orOv>Z!mjaI%0@|INv+#I67ZQMv3DB zTXwGjcFj=1kaZb2+3+qVls^`F5Q*5g_a(hJS%doRPC_N0Jb~x6fZRC}jN+x2@k3_@ z>VD6_iW^~cj`1VZyj@7fsIDXL#y3$;R1J^sPNuid6mt4MZlRd*AM{jygy(Dp2glcD zbWy&Ie?6mce5f=(^I<&(^DnEG4pnn{Cq`rJR)A0bD;p8O?5%uWkVIfRo{V$VTjr8JxG-UodzikO3Q zoFK+S8}i>J;)eH9c)He{@iI7o>-C38!>#M|-8c_oC(Oa}Nva?dI}yiQwlhmjcVL_L zF;W&YA3y$Bj1L0tFtw8kP-^l^>gBx)UwRIccOS-}gxFXbao-))AKxHcyeig7hhlbg zIo|W?fW-ZJuqw3&q~~S;vrnD%k^4msxvD~R?J`(oDXUJ`HDn7K5>zl)&vC!y2#I13}gvpsm*fL-T^5z3Vu1?pR0I z#on}VbO6-ky@az{uEWqLp>Nzc9qRf&lWhOP5cRndWBQC~v{gEObxy^GusbNREfCww zcVYI}qf~*NK?Ozy+ywsy<6o8hMPy>!JZ@9Q%uU+*(VXGS%;+n81 z9kM3S5~s~Fpc%<^OsT5yr*tK~dwT+B*X{$2o2Fn+#vx{fUOruJ=tTQ97vr?$*GTD` zsrdVq1{ldylLJ1KQPE!qaw+jx{rD}?%fD#o`8KLQpVF^$d#PbwH%8}8LD$k5CLI$xf36g5Fc6r#VUBd3web7hsD>%yRzleJ09rJg!G8h=J29S8Im>6{s!j`M z^5+PB=b;C?G-jjZ22q$NVuB;OH_&p)kM#4WVfy=59+{)alex0jiTp_mkiG24y1Tfs zQjMZ)x55#YOPImBI5i0_7k~B^+OS06RXkg!#8x{@U|;pW0o~d%cq;z^rb`Q6nS|HS zDK7ZHYh~HMpz$zua|l>}y+=HzEP*4A6{Ph@3%S1eBAgy}hwm?*fQU>8cBd=w4u=LX z>*G_jeD?%zt{+0BOXqRV9xHsGuEIY%+e;clZ_vI1j_&qspugC|#3nWwOboOj;EgGO z;~R2m5FoZ-3%DL?C5Jn|QbyS2zVZoSO6?M$kY5RrQIoj~VgJB5TZVldHkb7fMz@J~ z71+9?a%{GZ4r_hejm?s6A)ZPQ@U zk-(b!+BtM=%&ghY-!ib~hX@Qy$rA$=;Tf=d3jWgem29VB6?44$`-;Nsk;;V-LH>c2dP^i121 z?|Y}wEzREOzQlumeYcNk_~nL5rAHuf!8_6-vkfP_zYB%y+Jr0=LtZ-1z1x_A zN3|!D+&Umpk*VZ7WKi=ES(s_uN!6;{F#ehxtdFwdOg8&rtN#*e`+E{=ZOs6PpMmf@ z#%x=-HY@dVFT_~33mo{lEE=AJA*;36>NSy$j*@@{Oo32z5yx>x9ysV6&vbQ-$ED}= z>8zMa+$ea_oG-6OW#%(=UtY^d48NxXRTS+uOArU*NlfLh5F3n!wgV!NGJF&?&m3l= zmzKbhztzw+e3k52b4l3$+d}n>0eJZJAT*qghHWdiz!9-^(7w-r)q7?MRlgrdi<0|5<#X^=QC7%S5*5jU?;Xgf6vhZQHHyWUZH|F#C&)-5FU z^}LV=h@>`&+O)tXf|>DxCmCOjaQRDPIAS0Mr}PQl+89e#dimn-rwic60a3D4$_hW& zsbk-74YZ){R!0ttfU2iGDKhZ}-P|DXDC>lMA-UYcSU=Em-$3`ib*VWg>RLVbS0PmE zD3b|OuXE#X=|k|U2pEwe@OYh0fT+)JviaZ^_%V1Nx|&D8?DB79M|LON3Tp)2pc=@~ zP-f3GM5EG!Ni@P}o4}^kq(*O^k*6c{P^;r84hp@5bqjei#&R_bD_nycYm{MMelD5& zOA*#hIYs1-L<@OgcPeffMd1~P&h0Avg0{W*eCPz4*EnHhW;@=WrHLAwz42Q|3XZt! zijneXscMoAS||Ub-NL+cQrnN3dNffc@G*MqKTAX05&9P11+D3)Vdu+sa{YS{SYCSq zc}}IIJS>}eu2TmKFXRfHi2o42kHTL^i|}yQM}|!+B8*?eE+(w)Ir%|;V z*}}7-08W1MfN9Ff5Ylj$oO?SPLT~th_OWwhLU|lna^@s#Ed5INShi42aamYaDRg2* z#$c9`urpmL0@rwJXxrh4r9GQrp}^b{P3|TSyy8e`mm9H5nT!e7J`u;kT%tC?kL0z^ z#*@$QqQ%MxbPjQ#G6gsA;Pg-EQ(;SoHt#|wk#K79G#A%APpdICT1tiODxDiR8B5j- zk@nRB1Mry$qhYE79|ng|=H-2C@RY`&hr>9}TloLEI0-W9Xjn7 zkOR8!Xr+M#5Yj@=sP_}UItAE${5CnDSdI$U|1uW#9uP>bk>YUcqZ}RN#f$3Ma7?8 zraoJZ8Lf%BU?b#JJN{)d20zD;n!^MFZi~R=Vk?M|Gb0K5#Z2W(UA!z4j%OenQ%09z zgVh7vpVw;~#f zT|}@h>lTgG{6%J6KL}@H;~{NpF%gqJPv*B=;BMN;f#Rl?ng_QwfqIe>ya>Ale`i#~ zO;bZKIB&)LEgl6=4Ng*V%?4(piv;|={(vyTuJTif1n3?MMK8B-DmN?vWz1cs&3hS~ z&KQq_2@BD?&=#Mq`%2Wej7RB5Gf3Vl7ZNeikKCy5L9Z!0@WMA)tnHB@kJM+{0ak8~z?HkCdDxSJ)!(jTtNk!q z?=xrG{jvlvNCLh%uow?~zb_Pq!GZB>gT|tJk zJ4w>Gy_mCbq19=-UXt$dgw`fqBeQ;O!|~J#&~Y!s-+x7=WJ<}L!3}JX+G6(l4Fz^M z$$@Q|x{q}%^JG6fh-OK8IBRghiOsNWfO}IV*#!Z0aKUs4)Vp1w|D!N}FE?NtJ2hE{ zk;?3}xvm(hWsD+jIaKY@M!{XQ8%iR^fYz1qjLao(NN9Wj-?jDm56l>T!)0-P!kfkX z;dg}B-l@;`RD4A@+1I#iV=SgcnNjf)AN*WpgM6DNOzZf}HP+995AIFeZy|SjC$l+w*Rd6Xr#B-vJ_u-3`CD`sA1^#z9Xnh|I3sq|A zn{(}!+h2sCX&B;^&A*w^%iM`k{9Vj33rFwF0|f3jz>@QIFeX!-ZPxw*X-`eyzlo;o zbahLx3TcBc+N;3I*BS7;3XI7+#`q|O;C(#{ES{yz{q&oH?+$cZElqhy+$V`EiFdW)J2h?)u=%8w%=j(+XYz+P8kO-CXSMhgR9qv^? zoG@=PzrZpFbB_(9++KO!W4sx^{Zkb#I4S}^#2Iws))A9GHe~vi)wpbw35F?}V&&Zw zbj(>zE?tu&O`37I@>2g+e+o-GeQf7F{9^4sHg+W(a=;Wao zJmT1ZWk+T4u0|s93_M7;p3STIzdLeI+9$duKnE&4a*5k0b29w10uHEthXl6=;F`Az zwly>G-?9QQp5F?#8Llu5rn62BI&Af&kKjS&S>xmz5UUal=R}>@-)kqZug87_uPR*} zQ2374&o|=|lQ#Ss*GyBDzR|HGPSbeLTFFAW^*fNE`IsPoiaV3~rlskqMo)9#_Aq=Bf+Ca1EPHE7DZa#!#Nxo%?DfvAvzH za^$h$#S*LuG{+HNwqmJtD$TEag69q*Dvr}cM%fV!IW1fxQ^G}m7Itb&D3`e+9PNcE z)tdLC6Zgx)Bu^=r@#8ue$-WriO_R;ZJfO(t+{oG;W(HHVnwN^l=?hVqgKcwZ^W&NqGnGt=*btOD|awdxG11u!yF_TZ5nZG_H1jHMgMD43`KT+~H#nX_R&dZj7AHnDm<9 z)2|Ph!~2Y@*N%*(Q6Uv{+_XyEBX$;xvKHZa%}y$=kco?T1dwak#SAZ6NgL*xq4$g= ztB9o=$)NOeMrpqa&i|tgu12eI)l z7F^kOhI4&xNG*(m;op-CP`Ue_HU<{cF^_h@e5)(u{jVzW`*;$ySvG}Ahl%5R)w5jX zh>i4OX(ReAv%{L);+hTf+^FN(Q+QK+Hx9FJmtsuZAtJC2xy-0I2X~eJ z)zHK7&3DP~y&iaMav-&Q6+u<5*y4fo*}&L`lZeg>6q40ZY*-$ALoHxL)G}&4>l3N% zEn!~lT8E#`YGYM+I%7Zi7gfD^0rj)1Fd=dRQI>ba-*urVrx#-N_Dc=@&%BB|d~UbZ z;jOON@bWm$$ht<)BrV48LnqN7Z8>%iiQuIL;;7q~jPv`>VVI{WDv#es*BsZOon!=T zGQEsH%<8ahT@(@NYQgbI=g~{$1GNh~ic8(x>HfoSA!$_|j*&38X4KH)9pN}Ot`7g6j>6v& z@9EA$ck&9ROBf02z0OuSlU3*|gCuw&aAzFaM^WFdXeQOMj-Cl! z%_tf7(I*Q8zVw|bblO@Ag8CgbmNUQ6dv7jtE52But8O)Ceo+{v_>oJRaA0Tr&L2@eeFv-%pw%Qy|2zW@j@U_ah1sF&@p-zxbu#U#5YAEAd&$y!YFKk*B@~p#;%1FQ=o~8a z*k4}4BWsheJid^+1U1u{HWirAxd(4lB$DHQ+-lMfWn;B*0&PnlPneraaj@$XakFy8 z)IJgLE&YK73a9YYUR%68fcSpiCV_`L3FkiAfJe*~aK_*3m~-2l-acMTr|&Jmz@BA9 za+(r7dSL=icXr2BOPZ+SKn?bbbVE*w66^0I!iN9)4bw8RU|3P`+bvcEn<-nFv%>yd z^j|iP`*aHJ_9voW*LUuZdnm$+QhIpR3&9oRK;$%8;_Y$@gKr7qz`~%oSA5dm(L|3+}crL1TI)%s&$fA0l2eIsOr_ec(G$?U@NX{d7Pn_Z)fl z!yQ`7_mbJ4#Gw0c7qzYIBF7#l)4?mbu>bQhvVNBtww0YFnkE}i*V7rNXH3Ke9~N_J zwi0l7g(5x_`OIwFY#^|+o#+>jXdL&&9sdnSAooNDP9H0;DPQM69%`Q=RgxR1XzLO* z86QkkYM;_!-DMbQbd1=qJ5zJyWen-_X7Rn}JSw{P4R>f^3;di_4$k#r)z+8&!0W~7 znxI3sNw9f5$WPx)oApn_P4xgMw3tZuJq?AU0<$=7sw&i+8^yTLX3}v^U_zh*95uR6 zXDLmB#}mF0y;pHCeQ6}rv%i@7>1o`thGWFyq#T^M^cBv(-wLHP7u4Ajuvj5lJwtvk z3D(pg2V&OXz2`;vCr<$v)^*{?(E)<9>J<%WNu=&-S(y3g1iG7LbCt&{Ya(`ir40u< znf3MBjM>e9MESlsj(K`Z$O=9q1qZ&+D=Cj@CgVZ3gqnkjvo;8=M)x z7H@}NMx7pKRQ8#K8XFSP)ZZJ+53a|JvM=%V98vz^@HA}FOT-i*{}*C?5oabdbjz9R zIM~WDDncLdz3W-rSt!R|+tL8v<R9hCL9g%xdR) z3ml`7?4z55pl2&^m9AWbB~4@4s_(|^-G5SSo@fU=TqVbDoxL8k%6VvOI|pYMgn<3D zX{`J9L@2d>2H)2hW1B=VN)}VvXW@xAyxyUM&rvK|RY&)~RpM8hF2e`-iqi-RqxJ6n zbd|;h0#QGx+_M<`9dd_;KU4+O7g$1mw=i~rEbsSLhPOUEmKSGK`Bs53VcT;MPiKqq z_u8IfkjrQ69Lk_N)t%goI(M2E@q_!kEDcwbap=F}0qrxpMXokprOh_isBK^>T&gOA zwL&LFVY3lf=OhyKia02bt|FJm7_w^W6WQT!ub{a}kF5=!#G023!o=%C@Lq2$+v6g^ z+Lv8}s=Qjb+ua9_^)tbD=NDM@Pv9SqXoaea6+*8366_O^2PfA;&ep~d3od)3Zsjs$ z3#>6~dKve+WDdseC?nS)VTK;o!Vshyh)v?+wee``3(83 z&4#@3)kM^*8Oz(N&EnhLA7R8JW&XqydH!~zGCwrAiEPy!sxezz05)CmWJ32<7?(OA zoI|fciu7aQE@BCMSXNCZt@uqYm820nM(7enq(ZFVaJjqf95ZG4Ay_jejghkH!Qy~- zC?;2e_M9RgH>DCU%5~wN1HqWG_##eCEyDKNSM=pQVfPuGPD8(BGuP{H(DpM0_~oTF zWE~EnpPvYhzKTy6DJ|?_+>c^yP&t})G@;hgOUUj@#*fd-&~L$Q-21HnT$dWcbFq4| zc2fx#Zs84Ebe@35qj)$=|APfFg)ld80{dr*4r|yfJby2AftrRa8@giyShl=?meT~* z{Z?kTrzd0j7%Q~!bw}r|c~})2K`k9yaclod^!T!e1f4EM$BaU>xHbommj&0xAu9Kv1Y5&9@u|EGU3M%8?@+LD*Ur%Af-z31< z_^GUf;3t`?Z^D-RJWA$!bd&!&c7gTsUg&w-LS9TrBZua`f(NTMg2wJgFz)^r*km%6 ztqK)kef_RM`(`;dyjG9(7UuoyKGv)m_Zuc%oyH_i6x?AOg1PN7roi^O(tslx%==BV zAj4uN+U~E$8%k}Q)w+kw*vp~RDkBm^ckKcN!9UiYTg(Luds@laiR770D6AK9n`bsZ zCLj8Lz_tTIcXQ88Sb2CmnBI(qZtpm<=*C^R<#-!TxbFtKsT8b|iea35Bv{6ZvNIZ` z!FgOLI8VudMw?p@AncZmPj|zFH-qH($rN~apq}^#h_aPEE)aRQ3a3_XA|*GXEW)?@ze)etlX2zG9QBq6&oV~Y{a5`0%`y=LeuEyE4A3!l$X zVcaW8X*^IaWbM8SSsud$#Mx^-{wr47r4 z{B0U_6gr$nu+d+cwpOH)#NH-QpEDWecM9IZ>BZ2bT>=RsS1?)zJc(&=1lxJ$xY@b_ z6%LnR!I>Bw5yCMS59yHC+jB5$CQqaIqa^J-&&(CNs3SKCJ;Mw4pm)_t;8$rw)Z7+W zub2-B(LX>@V9Zs%e+=md^jX6fS#UR4M_^BF0Hs3@Nb;R;kaDn^cVIZwV3379=%m?rtJq>*D9X;0=kRI9S5(^X@c%nNZSG1>w9 zC)DF>^H*?HAsvo9Jp<02BOx=bm`N>&p!U!Vx~r^(S?>|N`f!zLKKp?jyYE2EC0R&Q z94q*Fw4r^|O|n{{45Sop!V0TxXdIe?XCCC>?5LYGeY`3T49MUCT}50oav3v}%5x7Y zlOXN7kn5CLfo-oF$^27WA?#u%IizO~RW&YnMm&zXMb*-~@oMnj@)B(Lqzltj67ghk z5j~augc~OzhBt@$n26^LZMpr9n7wRaMyluHWBEnYOl%YUS-qP!1>PZ2D_Y634ri>& z@4%)KXY`pe8%+hTNzUzAIIcv38W*0&Ek&cy(IEv&{+UseX>W-0XQVT@I>J^&a~HGrKJim;ay0w}cm^wg}BiiZ7w_MASl?3GhQWr`2^*35G|UnoG)hMw!U?TH^Sk><&He+kRan2CYDLg}T*cXB-6jGlGEH245t5*!Thu)+2-d2+th`<;F1EEeQzUd+9(5GGb|xE zvk`8*t|JM`{|Kpy1^k>la2!=jfB_>E-00t>6)u*;4&F z!3yqpq=SmU7LU}n2mkfb@GLNZI%T~i8h?lIYWzYh34M%jACz+zrpu|<)W_&@vY2Eq zoQn4I6;WraB&2iisj%-Q^+AP2OvVj}LWGiScQ4_O|i#*#dt| z-{{30I6WWZRHtC%(VCi&{XO+7pTI7ZzdglL*vm>%d?km*@W?6>qpSVoa(suQvDs%R|%fyZu?* zEvn4ExL6GiKQy5|>`9MNcWeqpe?EaOBsMG;*OlOyqx1qdm82WAPA~U6cZ& zjx2$bh1@px1_-6|9p{LWy~OW z&q7G{UQK@7^#sTMdYZi)(e?6vx?=SM&Y`}Rj*2*g`3qEptmiQ*@gxtO_(bN`K{Xhi z?Mshm+fdhhS>mhsk4SHsLqrW=ySBNs4yL?34NA8KH?z=f{4vnRWzSTirj_oHdUOF@eQPGpH=c*TcE17%Z584o z=OaAVDq;Oo12$*oSazi9O`vo-qMJ?!R{!NYToC`o41%isZJD zL;j^`7k`@2H^{@{yq*2L3knTIj*`7E3;fvZXNS;>@{`=HI_9W<&xlQe7;p}R&k z)8L>vTy2Ffd33gttG@M_vIEO7=+R5M`HCC<=-njb12ov-fdsH#BhES`+=B2IFTu4> z$WvVIg@s)YVeQ^I?9qBx*4V+CmGP8hx2^mQANwY-8$Gqy7)3+YWkEA&6kMb$*Q9_YcMA4>3Z-~vcC{)KK?F*Z0Q4W{V67T!mR@Z@zrgl3OnSLzqR zD_)78(>0aHdD47g(`)=_R)nWFD)Z^_`nc)QLv+&h#jeC#cth(w7WOBi=;~;)WXvoa z|Mn-H^KU0n+a$Qz&kA|^`fK>Kb`6SD$CA}EA7Efq8d`Zx#i{!DaPrr;jKkp+TxNS4 zzxPqp>nujC%ZpJ*akSuzJ&J8VSDT2D1W&B0RabqT|L-&)YjjB>Ld zE7QGqgwKh%x#)o+0!&Mo0XytPBi zK8WA-&fyukZ@9cm8}YaVfAnNO>iKWOz{A&Z+rba`HK7Tf`>3;LtR>hlqWv&bn+C>L z{zALcJQkPU05!fGvTl9>w?I2KljyMd;i+(M)NIzESJ*4LzkujQU>947v%3smLDK$I zm~~(@@$-KHX{X+ikKaAv-DU-Lbx=CQ9}Xac-;`MKvC8a1J!v-gUI&zX(_y_uHn5{- z>a*M%H#V-f5yp3~qxmLNL1p_0NE+ctjlBZU&F}>={$Pm*0}OFVo)!AO_CSB4gW+xa z@LlC(?$Aw(*%pe*n5o@>B2JcQGP)9F<#I9eyd*FAvj-Ig4_-v2E|wJB!>SZ<8fo(% zro&3q))3)+`YKU1Aq!h6k3TgsQNw#I`nEfuCnKJy1x_@}5^B{isLeOGr z2o`?#!ZPVIc(vvPYOj~$!_0RuTM8y%x#)RRoz2wTMnw|RXN9KO#;E9$K#Ywy;EH3} zptDXH{=Tw-cY&3#x91$y?Wv$G0q@;;ry*&vC-366;aBOI&!aY2c~URuWL;Lx;BMlR~jv8fy`T{olgS z$^9Dc8atbY3eVwi-HE8C?24Y3tnr_laPMfSAoL0Z-b+~)eQhmNMXJ3pV7(p2<#}Lm zdkUWPKaEd561qpYd&pM^qLcjn(7om!eSadJs~R|h&HWx!|JMhi6I4%B&&R?KvrAMp zsEAy+evj;(pg|2c>p}i%BpD(H;jV!^xlwfpIL-o={>f&%AAjch>b@~{F*;x=8U?MJ@ z=s`VBUgdsX(*%dKojAGZ8ayt^0zSzYO6@?q9A)dJn9cyA)DP zl<`riEL9W}@)_B#WGmUo9Cf=*=50_B99E5Va@{Np-M@y!e7j5!{*Z;u3NkS5o;8@} zUL}DEvh?EzMcCge_yva+LR#1*^84j7kTK5!*;sEnQLPYs&#s0N@$*pFBucIh5vJ8W zo|zh{1m_J3K&fOAwTRCKfgDlTH_&TbSrp}Ck*}H_Zrn)k0dTK{shb$1dTWXNBJr%xO ze@v?5Z@T|oS|k=h3X95;X2)>g3rAj!u|dT-1okMiT97hQ3>BUr?DHbyugdRd9necRvR)h zuQ$rwp@)u6de|oj>;C(}Tfy@>M#1te%7->tiv=rGt|4 zkIco*YVa=C9&z9#+IQWi$8GlD2y;1R;fm8VUdWp2@Lz~Zj4Pg(tfPNYjqu&S3z#eP z@9Kp8`R&o6oU4$li&@`5XV3JeyI0ge1kN*lY%R|WOzPlvZsv0~Nzkza$s;ECyGY zPrli%ON?e9Eb1R&$#x)$CK?@LFwn5!4KGer*75zAs!-k%V>6vf$0&6|gAT z4z-sHLEBW3&D<3Yi>gkMF-gauVxSq?h3u8(S9vt!0_Y(vZ7`ivPU`W*9F5N10&n5AC8bubnB{enYzgofaRnpg;z1lH>uGJ>tmz7CE)2CV8lH(20M4|j@Q z!U?f#dhx0Oem3EVhfxYzj?c%H>yP5k`b_#Od@ON0DELLMYvPrCa%9O7n|gRe2JIXZ;78`_Dk-t#I&kdk<{zAb8qqLhHTx zaMtr6Jnkrk|5Q^*XDkOkFFwJP+d}^dQIsE)eqi&CS@xwYwjf|vR!m3WwiS31(TNnI2hKXS~L`RQ1+GZKGG>Z0p{pUk33 zH;7l>PjV_b78GVbCoRHvVD&b6BGtc{#9eZQwfB#}##L!>?Bgs*|C$efYK3k|tP6x^ ze4g0B%uP&{b?9M3o zf2Y?g#$a3e0vMj?3%2_miNUTl5HV7Ro9S_zER!@Rb&EdJqQwF5W@jo?h^_>!b2TLA zYjVxO3{7ILstlgGNT(KRkqhj75}p%Lb0{;G{Cl>A&T?a|BA=9zqgEzxDgGYGv|CQb zlr17>(^|QaGsVfsdFP`FR~) z^u0;nsNQBIDl%w@QXH{vxj~vjWnfHTFp_P`urqlv7H!%WrPQ&R-vDi=J}bd99uUMIUlJb$LDN1q|U7 z@7E~yu?o$cy6Ltt33N$EFgogc!RBuVxkuk+;dV+A=uf^@6L*pmW}q@MBl$3BERkd# z^H0G3&{oJ95e=(_p294*ckpZeODG(90HQbsRGBiYb}hq6$(xzE8{W}x*QPUH9xcSK zMYB*oIEArVDZE48zu_8$f7ASX&9q!^9Bf>(oAGGbLHd%d;ex0kzTa3&wa33C-)ir| zT4OB;soM*u44PoNOfYCgzJ> zdJ6bmOQEqR)SyrI1vw=%38$5hB9n(Bgbcteyu0N-m+Bags^-<$>zakTj_07s!~U8Z z+XJ|OD|%$bMH`%N4>ViqIG#$rM*QxkVRgVODrRbj?Hh&NP0ul`zB3zht8LI1z3IdF z99nfuR=CGA!jRaVxHe4*k}i5clEB$rd`5}i_GBtABQ=-LyKclcWy$i#FZ=S9{&u`r z>P$X0b2ES8oHf62w=u76KZ-Y7-PxeL6@y8^zqp z_`G$kuZQh;V}0=baX%Q=Yy{`ZGw^cO zSk_26QP@YEfx<=qKmevgX!R)0#6|{H;-cX?uK+7w2(J4VNa&Ax;w;9)hCPHe+&G6# zzh}VC^0tG{85(S*$S|xNe;gjDw~|34FQ#7Y8kj5elL3>7SoL}m+_?FG=}MAA6;7Nm zvAbcHTO8TZuYtSuOX${Be%$U2%iz$$c(Aof0`a!(ev#k?dL+-z zVrw9H(`fKldje7KqcE)TWlinuR+=Ga$-D1f!RKwihlQ@Te2|VgU;q0FUOBy(k9e%Y zxA^|XOjRk2a^D6bOUB_Y<_%}Du$5ezFdpw+YGO2%_Cs=l7=G?6g~MhFbm<#2Tr2Pu z*1pJxf>Ww6;&~0+{C~!_(~fM^@43V44LVaMzC?+h@-Yn9k+DPch-&O}FB6N1dWB?~h_lu?^(se8cKc zTb%r*1gCtR$A@22;pN9BqdsYX|0LwuwPq)vSK0?AC&|Gky>U$L$jcz(sskgpyaA8P zIj|>pI(uTfG23!NAClsY+1j{95PwoaA?d6YVuH^e1)%e0_AAXd> zY<@|EDPPg^9djcX{_&4%^kBLL(`TQu38>n+eT zVG2C@Apx~@kKnfTHKLg*3nq1z_*E*Bs#+XiD%&f_808GBZoMQf=&d@)9Z_J*KOcwk zU2AB?&mE9!umX0Z_0_CYo(>9`Qc!hB6ci&o2wPJz?@h4mgJq~kj|^*s%o`-5T6 z5hFVOQWLrOFIwo|=7aMrQT9nR!oHtBpk7IVmC~KW>K`{}z1|qI)u)DGgq|5|RPW9D zf+1_*Wy9VZ>;|QgQ`yV2B-rMK!!U5O9J>u4qQWA5445m*n?yfAOP}u;>v0R&{f8ezw0LHX8vp6<=w;Z%lco`V)icdJ5h%T zSCj?!L_Bt%y@hk8itq>Xp3#o~{z2kMUl=~{4CV}o63>n+P}NcfV6%=sp2Vy%29v+@V0(%nv}*f;++j@KFkV?*sR z@>Ce!j5*Et4$Z}r34orDa&S}GW&Gumj;`%VHQ9mL$lYE}Kdfq^&^^S6>O8JQ@D_g*D$(QVmvL$938H=c7+q7h0H+K`(ZG+D_&V+-^}W!JQelTs+u$=@#~sCE z^gW*V9fyN|8}RND6go)OB*m(T+R8tnKU?Ft+Btz3l=A{FH~yuDYo+jtnG^o`A8~&g zmD3ykf8))i2}P4635f`4y3S*lD3MB}C{sv-3Wdy?(5QiCO;RW{DCxS+V>i&82$>>7 zWXP0MD7yFO|M2%;_iwH5{kzw?_gd$Jdb0Om=$d&0)K2UpnT5{8XN>~W zkm}Ds))FRph8<&D#&P|_+?Y~j4`$hI2gdXMCT6XU30nUQ!uS0V)P8&x4RYn-ko+?m zY~n^{9A8G)Pf;b`mRq5R2to5rxkP>06QX}FgEWVq#9cGfaVoe8OiXUkS0~;;XVe$) z2{&czGv9%j%y9``u4m8y8`=Zo6P0WhJh8R}R~?c2d3QHeQLWIxce5$F7Z+ zZa(JS!tlW`RJT8YDIE-oX_ny6Bz=xG^q8wdMhhZ1ovePKE_!+Sp?p;#O7{OHf41b{ zJ#qoNCyz6J=E=!Hd=|9R2#fi-vw_NQks8$bPkrYj4X)Rqdkq2<1 z4zFRvQ>QR{_J}ece?5nf`?fHa8Rm?y!+e%?zYHlH)ic;8E>*AUc{_)TSf zg>cgxaqRV0!|OL@QNv?T1$Rzr;J1U~P;u1>Pan933xB-8$P3OW+p`RtO0Uu!3&f*q z-eTqmr$_lyhfh6>@bIx5Jo>_zv>^fQK7PYzU0ZP4o+8|pn?W7x zp5d+^#VF$Q0!=3N(!v!kG_Y+AhTFbCOL?w8Fb|1P$5MJhhhy7GQt)!-814@3ypIM` zpsgl~)SP_6+a$XR?j2tNAuHNo!<=a#_d^0&a+bnX!)W4Q>P?b8&%@3?08H-;cu^Wf z)`cpN)9p2a1L_4tyXYUWTltFg9U4RQ{@o|R3BJUucsEXsIfHuzF{rUj87q?tiB|s< zY*}|2*^KkFQq&#q?KC5aTwdR|B2mmu>!)_(wwk!>_wj0zWr?LiJNYvP0B4xd+|ycQ zMqMCo7~Ba@-b%o}N*j8b&O}wW)3D4}26mpB4H?j@gFyA91IA^;LJk!oq4lFuO zk0_4PZv*YvXnPB1Rq3JX<^$MeZh#ww-O=T<21;m5p$}wuSU)sE3~ct`C3MyiCz z!CmL4f^0cabiC9~^|KMR9-YU;sUw)S*8tUG>T!Z=ICdteW9~>EMokjnW;I28_bv=| zt*!8`|0!PdjJLe)H}&zTj|$#@F&Xnb^HDoJ4Jum~L;jF5#0y5@&6`J1yn@U4R=p34 zY&OB`ZLMG^oq$@f5q}s7Xy&B~+A=hetPcN5eptzZ&#Y8D;&l{V@6D#$V^YYWUSSwB z-Hl3ru*6CG)`80UF=%&J8=IcJrlk$V&=B~|G->xgUX=7LqOO|;1)WIdZA zH9yX`YK9&;4Cy?eOkR8|z>Rrt=p~1%#4LWDX zj+_Bq$0xMi;v8JxQ$^(ppOL)*2|yAQ$?_^4APYXhPAeHEJ2n-fRy^BZ1?ibTvX`WaV^pm9T>*m;X=5T1vCHm`j1hIY`2aQFI9G`P5u&ZO>^Q=7j zh(3e<%ikbJqX?4HxL!~7UC;;(f|H!)ElZ&kq*p#5+g?X=x{a@pb}JPQb#uM;1Wz)= zPX@c%3i8)2n4ECwBY%7=X>|NwGEdc(>PxATQ)0iVXR;oqs0ygj4{h`bNk&6QM|$hy zeT+NMYAU&<5Kq~q3K$D%nxC-%wd3yK80{Y1n;nEwuC68}W4iq$LAjCqRV*W-DG~5;$4tT0kPq}r={mB? zoMS2~UK2>|(1&~L)8PYG*>JuR0u34|@NaVn8jfE;HjB-{MwJ)D`cn<@U4a zZ9G{QWlf(9yd{#-OEB)ZA}rJC7bMvLo;Z4l%-P>W&mFaZXW3)O+rUkD`eP66^Rgnt zYhO~+u%7~XtJi{_6LIu=S_)bzXkm?XkAQSLf@qj9XdT~*RniuCK}DN*-5;T9Em?GX z(0yM0L|)Q zdOL9zBj7mB&+y6xG4|qXdG<}>8VGUW{Ot*Ahwce>8>2QM@Q(8Kiop8JSDw(S%3~rLmAo6Pw?D6Y>Ngkge)~OK|r6fQ@)+LDB(?OJ8E0Iox zyWo@60$tzAUPzuElSoA+ta0O(qxksC5eWKy5+;n5 zf}_q-So+ft#CER6sdk~fr@v!BqjjTT&FD&+bvFv>@fcz^Bufnbb@DR)*}wzi8NBoT zqjXZ@F}!#t4RSSqz}f3(;QbPLIbu6>+jvWZ;pM%8_4lq+)gqiCS0PEnHq z7Vu`?dQK-7H1Z5Mmbq2MQ*w7{Fi|^|DR7(ii0;=th)dr!k-w|8z^|sCmKiRDwqOxd z+INnWx_GWlTt6vkO|T-3w?Zf|Z5BYs}6y1WS-gMWj` zLs2GN=P5)MS%bkAJx*^plW49_B#{A&Ve|G0Fy)N~u0G%n!NreBkG~Q7+CzyQele33 z+wc}ITwTWMDC@D#jTY>#CqHpk?PHvXF6_r|@vQm$H!Agjo9Ng%;gplt#$mRM6%c0KoZwC`%-ewV89(UsD-4`iv=H;_H$c?AI?kua=dF5f zK_kWGn#yOQ%m$(CCt>EM+=LZh#F$qB zOBuB)6~?=45dLi7vd6^rn8!h)xXz`QcEx34P2mY@=$}Yu^VQ)|+;yB{*G41nJtptG zQ(4vdv8=CL7@KSq!{(ei#(MpUWBpfpv2Ic!tdx%tE4eHNEmqt?t)E}%(C0|xzYRgl z$!3_5C5i_;uA;-#bX>E}ftX8*Gx;mHtou94@F<-R&)%vq?_R%#T>lx2^EM;qo?#v% z>Ke|BQTJw|%+E37dGSo4SR8XLqn25+H;L)FT)+$sKLBfiCR1=%li8i8#i+XIF#5eC zuscYXLDXi7l|MmWhzh$&XB4}F1$g^V7~0&EVyDbjz);^)DAQGnf?rz&mYqppy+54G zhI$Q>UXS5!lp!ou*##xeZ$OR9oy@iqXI5mq2XUVuDCWF_{*C2=&g1cd{tHF$Mr012 zDKiKANz*|}Zv^gjSCb5R&bQ*t2d@e@m@J?`M6bX}{R2c;UJvFCIx^E-Lzo9ow=&~G z;+Tp%B}|YP0W)*Sf-seJYUmU_H7@t;Wx5hiL$(Ls1=T4ECbR@GI>AHrX$L zqe{`tk>Z_9CNGqkP@lzg4Q*sbl0BKl7U@jXlR{?1EruzSyvuw4ek)nvFqOLMTH~Fp zu{d(Anl7^JB%A_)$R(E2-ZcX>VEkfKta*xt&qFaw<`DjMuEe`K{dnW+Fgk=Q;L>i%z*J~W{$86V>lGcI3C}|C^@fNeKM(A~q09%{QwHvUtA<7>vjPbq&)Hj{yv?0NK*Uo#ETNhSO8HlQw}hn>lO z)crTdBwBsRWTBrKU6=ixws{^#Gw=JRv6@yD3BS_G#MgFEf8h{4tKCH+>k%ICHd0IA zSn(^X;mL+-oSzzrW%K{ieNS#;4P@a%x2H7LI|kijT1ostM~s&B#`ZJ`6uFm3En`(t zB;N-rJlsI+Of=tkV-G2rSpsqIa}gAB=<@NURB~G;_AVnt+faxsFS=sRCr13e-XqI5;CR-+J*nyE6 zY=UXB!A#aA!hE}^!Dyu}XM%UjFnr+)@Y1slTIV7(d4@u<*Be+9J&tj#FNKV(Y#PO} ze4Lt<1+xNM;Fwzud{^T3OL`xOP*@6_>^%lL$(u1eHwYc~&Ba4or?MSagxQi);kbU$ z8GNFjgXPaE@Z`1-5Rdkwrv%bip%zUSQ&1Q@OrThy?8UA;YL0NrFYQ z#xP~_rD)=!4A~>&i14d&d~$6bYE4zZbVVE5*WyDBTC&k-r8e5-y%c!8F6SMYkxAV= zR`53MDy5UA@4>67+8C89PK0-jVeY6U!Y}_W=-XBV-)6ml2L&3;<0lK4_~s|DDlrqL zzZIsz_Avq%e?K_9=M_I{rZv1#uZDY58sV#U3goJN1-qxU$UmEddpqW`XD=a^f7Hjq z@^)OJc?I{kkD$wmc6|6^HVUiX;tgFMgD-o@b`V zsoaGo8pQ&122HrjDK}tV=uo~3dz&8e`nKFBD^xfitLJxe zOfMNyYg%CIi5OVeTMH&LrZ62B&cp1iV_@;E8@zeC%(K9;jPRHr;5-n7ytxjTYh?%X zEI;w2=auqqW@dqO+yJSb&b?QSI&j>^8PFM%Ls#Ax1&1Zq$&ob?;9a^JHoGU&Fry53 z=N|^mJND6WE2KgEnI`PZ(4bp#Px3aeG=RS^W|GYf3xV;s<2UB5#b&-ZJ9AG18cez? z$a?<`6`tGR>sL#uw%cdU2 zwi8OQ=J``@KmQi=$1{BMYX+cNF2}5ze3G|J@e0U#*FxRk7*bRlMrWSgN<5l&K>s{Z zkWD=gYX&N5+nr)qy2}=f)Jov+ry{uNWX_CheE^9?Ty1ZL9^<~gkp#Yf3iB&kL2C0_ z43X2}FYw8v$Atvg$vTi_de3>Y+{RF!gSoslLm8;5JCl?r%i>G(SQPwJ!wI75=yTVK znm1+e6&Bl&d12x^%&a#J~j zNHmqhK)o;gO8N(7vrEXxuO=8(w1-9wRe1P&gqQF)0s=XYqmorN7=J)uE(^fqRU){z zHo&ex3Fti?jvF#gkf{NBa8Xs6GB-*oul5E#`Jx9;>u_q$)KjRT{*~O-)q_iwg`ilk z%j4zmCE_-zu%1&leLWZlQzwRjbe}rNtE_-&3ph?^nHrP3M3>8`du2^_oSP{X$Xm6wF$%(tevqtXNe+APt1vNGPkyMc_~oU|&FxAloj=RSYnQsrlc*Pzl>p22HvroVTjXKh*9RgE2BT3(r5i)4` zlO`ExkiE(7uw`sIb#vmQQqy#z(A9>K?S@c0^%04^Oz`^tcIvRcnaD{LV^x6>+SPo( zbq|i=ZksMVm|=(qJ36Vw{d{T>TZJ#Pnz1kF8)mmP(>de0oP%j5*n8U&bHBlqF z50+*Zyh+Dx81h`s4IbS;4SJU@@cnyUaJ(yB{QD_WFnN9~ z8QC(E7a+Ehc+C`{a@;-YztD}yKbwcwSI5F(*`1&=Y7f)qt8o0LmGE2tGc1rk2m0+- zp>t+8i0Vax<4zf-LTw_Wn(&#lFZ2aP!w>M>ww8uYcYwC!LJ*Nw2Sw3r=!h+a@{qYO zwz-muK8uGXRePZ>Q;oMrr3g-#je!PsJ>71X0}oyu%E zFLC@MmFGbJ8iAU2c%_;Uk7mS8Ml7N5UG;PEf_FRhNKi(vuKh%^ z(5sc(gZ`Wrw^t6>5Whn&Jk(7C4tj@E0#{3A_R>~RSlCYRz;_in5>mVp0ky)kNH zKK_1ihsJ8?bAAn5Xsm33DT9N&;okS~eQp!1e>j#o<2{C%?6D9Ace}wJvv{y7mSvXg zsD*py=0lBZ6pY3^2EO1VXnu%-OX@$sZc-io*>?r?-rm4lx@zp5yN@s-n(OauIE`y7 zlyIJ>3_Gba8|AfJ(O26ArK4i7<%b6ze0mY3+d1Z!O&ZRaXn-dg-VyuXL$q#lprB_> zJqdW##f!fr3e~adAVc_&U3?mLXI_Q#O@R>oArA^~tYy@s<(Xsil3;a<9@Aa&8H^{S zLe0(^eq2zdAW>A4yuK<4(Rw=6QznjgxrxjFOAI%))Ue0TB6=JHWi!n)J&Ds#7SahH zukcO_IEMbuL~I$SjPtxIX|?`&j;r$>Wp`#{#^@bP-l4-TttiE~lLOc?k>bvW!)V=U z#ar*R5jMQIOPaUr;zhc@B6a_6Lf;z|FdO#(%9lR_VX}n%X}FwyI^`R#k6Od}+ZeO9 zZ#r-)r^~<1vtsAp`h*rPIRabd~B9EGKh*VY*&WldRMG59OWEG5g7Zp%pl_51= zDhzLf0&)7y+r0BS|7dkxA^9Hmoz`%91STPVSkTyryqBC`OCZ9!uX%?@YM-L*o@_KZ zAdOY~&!bZG2WnNHP1dcPOq(^PRUZ83Mi;fl3o1E3tkNz|{Ht&SUDl7qbKM`{*SI>U zeP98*Mq@bM+*;UbBF20;7!I|TYE1OJam%y zk39!RN*{sLwQRCU=QYVWR6-SxZ=xka?KHlK%k>j>B}VHnVukfl{LPC3ePcfCZ8if% z{uWrtI)aL8285ac)b&s2_Q!XD_vZm$bbBsLOW#SlISk#SmzJ={R+%|ta~kSgzHs{r zVP@g%%`g*G$fDJu@Wj>-yn>R5=r&jQ_0R&2k8<9KriC=tG79e9zXspKOo84Mq6vQ| zfTdY6tjg~sT28Ixv4uT^3su94LLQx4G>LYXhCHFZvgf(z}oIHGZ$N54k1o+P_Sg=_85^dZ=_?>Z8 zWYAO!H>?k)BX6?k^RHF3X?qhXi*Q5sgQ=kUPaWUq*EBq9-$=GzTZ!+<2+{m?k!~8~ zVUNxN-o8m!&`14_spFdqbXVpnyy1MF{^_mey_XQ7+eOZkuDBX9RH%xV$BoBN!Lb72 zm?Kcz5KQ&XohG&!`b=YpE)#4tpOG-w#7Hmy2%5Jq!eKiJM)imbD4l&so~oKb&Y{21 z9~=s2UWqX0D=&c2aqew;Zvq?=mnN&C9O3h@3g+cY@P5@)V)WZ9D1PfMl{~l^Loi#g z;6ww*R=&Zr87qaKD^8OsldlUhJ`_>Dix2L-Qcl-8IMJuG*P6Z^nTF|m`vpHvUchgu*ZvI8`HBa-lJJr*okwp0TNR=e)^QMPe z%puSslh!QTz?{^TW16Mvz*o+IiTpN}DK|4>pD3Sr){U)UHA0N&k^}Fe>9tqOiAWh&qda;63}&@Jr>!i!i4TYPzHMNf>77r(*EJEwdVdG^_uY`9bqXKO^Mi+}=9n|}Do^wGM%wIZ zj&c<|q7fp-Wz8jnE`gvaMvv9sw27mn1I_&o%OO;eox55hU6EARk|O!mj(VFve>#O#dK4 zVke4_)%vHwQhgMzo{WaUTbp6YKqW|f$HRmrIZzwX43!+SKJMiu=!%|!k-Y#d?Ke$@ z=5jfL+#Wbz$^@5ngh9XtS%`2u40k$?QPnq(d1dWp^h$jbCS9TEA#szex*CM+(L&rE zx0oua?84of528Yn9V!io#X{fpnzCr+2?+NBaqW@!t2l!*m{)5qXV zcNTPMN<%>F6D~uehw!wIfnmZbyxaPRmMzI5e~cHSWAPy@PaTiz-!)V5WCd7VDn*ND zBoe<_DHuMR^O62hrmOqb(N3XhF#1=LtMj&#a|#!L{5i$TB6D!w=8aT3E)r7)=8{XD z$8r6=+w`hlyTC3-os7hu!RT%2_;Qskx@&T*jTs6=xppizXzJ$I# z?1Wz`4Kd-0ys30!5xID_n=CK?K~oC24Cb&Wf@m8xyvlJL+JX|WMvTkRERbf$R;6Hl zi4dC}_!rwPIShGc62=ZGlEb1J=zJ)NHjVaR1LwsQ(UwLVj#n%j%iz9=iC8nT82>qb z=bjZZ>`rw__Oo0W&9PTPpSD;$nDhxXSBRk+dCx!mh09_nxde}vNSl-eMA9rTDSElF z44h0opfN~or^T!@b zCztN4(Ju1}nsVQt99n#mOqY*?pyJKY>7hZsywiX*-|K?IqjnH4+D22dT_92q-!IP?o9FERZ2cOHzIQ8FK!Nd9^)Ffg%s`Xkyo77+WbecIGcW)Oh zP)w(vI+C&bXbI|Wn~u54uh4P$Jw_FK(uc_lFl-@g zSgfO)B+)Z||IJ-N&uRFo-FQ=ZHfqVv!w546>_{D?83nzjW3ijg+#LaXrigOcPlm96 zl^9m0uJpzZVM2IA)*c%w>EJ+mixj zCif2DSi@JnIR|wTuAi0qjCm?`0d^`6J@ z;}Z`o(MqJx6|-3|BBH9RL*UrJE3TvfQ5KbEg z6grJ3T|XlfRA6@43tTgzz?M9Fg#-^*KAcCHJnzIEYMIqd8x-U?)~7M9b~{ZA+yn8$Xbe8R^_yH6y1^6btl)Cf zcjLfT9%{&Q`6<a=P=hx$v30)(+^#|YaM`hMxyxU1QdvA!>XK)o1T<^ev_kbgW$uY^Tbuz44d{Z1b@{y>~*Oo^Gx1Qsd7V8r>G-1 zQ;xwU?^UrULk7o8Jd0ob<1swo6rSqIptVmg3XWUy=xBa5jeOlj1Kr#4RnHte9db=@ zLrw@cemP5`IDh?d=>Xhv$lN$GcoWSX|ZvabB0 z+tyBiEB)%|GC|B#YXP^nj+}!p9|;R|Eu_implm$*u$}s6og%KD6w0IK!no60;o7nS zQmv2x5!OgFN1s9F7+YA!u{bgx)kC|KE0-|2?w$s||mr`QU0oM+_5m}_)#xCPWrdI_G#tZ3NvLcu621Rjht@f*-3+t=Tt zF|$kY^`ZOp^_L}}b*F-K$MCQw`mEr3AjjJ|8c3%dI*w|pzv$4oC#dJ+M-@5!q_tHZ zeBM(A(Z;Eezt0mcn|HvR6}^IY21|(6kD2iI$t(ERZViDW0#LtF1x;C6#G$K?2r`dD z=)WxZX!ik})xHzgYJZ5A%N2m07N>){ zb@&~W(nS!qtP|o!4wK`bQ()_~cu?7}9gZ(iBF$X?Dy5-9kX){axdX-gaUDe_eo1_? zzvDi6bu0pWd)C1oht;U~CkInKq~Tyy0eLn&5uV!EgZ7{mBu~*tz2q`1)mw}Mf^4jx z(8X)l@}q|v4Ys+a$$ti|!0^e9a7cTzm(a zeU8EJVuASb`c&lUG@u6O(G+Ptg^!j3lE0qleBd?Ry?2Nn98!hK_t&YULkQWOy_;Ig z8v~WiB%vKs;KBMf>g(=;Q%q0cqSs%@==D>azD*T9oW=0X%_jOU?Xe*1v?cHNxs@Oy z8;LEe)|)mh7o!fFM8LAg6EuvX;IX_q@GpmOeT}>H(9`Q&{&F4tRq%$&v)3?xK`DL} zDnqT|OZbalh1NB~Xwk72^SEruiN*?S!wDrkrG)gHE0>w|p#?u*e1)RX4{=)DD*P~0 zfct!2<2w66JhwIsv%W{-*?;OR&wUcBbMGm7I@;2+n}TS(XtH3fa~`PnKBjt~Z0L}} zA$T_F8u67pNAx|<5D~rux}5q=)~`{3FCyMB*c<|-4&~(GgBqGC!lQD|UQ{W+gs5t% z;4SsB^f+$`sLyq#D}Fr{7;fO|BD%pO_;n(&za@bSzC9yD5jpf=eGl~+A4L+KgyEw_ zu0Vgbx}e<358>xx40`K{ev1!aYI7WK+}0-o6Ae)as=0{p zCg#Z(=~~_@z@3@&+^lc(Ia5wYHQtda&UtvNuLOOkmykZy2r}`YA6{Q?K#%Xs#}hBg zP;b8g{XCx1pR?`JpQmVg^5S^hsC*Yqho*9j!He{<#8y;V(ZxHYc@Ad{b<(-6iR4^w zpCCggo{pFCq=$M2>CZ_Q(9g{iZ)%L;tqPZ>)1JwJr{Zh6ZDgA9shP5PGIRmmr7%cD zYua$X(1q^_RwiFCj z3gE%#yL3lSF{E|N5zllPGTGOauDG=dYN8`C?7b;3;AK2~=R6$Cv(J;Pav2lXEt;6S zOAPuy7D2(3Fnn|W1ZlVBvfVzm66MlJlJRv3N~-2lCSw8Y9StV29xRQ0GzNszm!VR` zW|(aClvdX8V5(v*8SLmGqF=^gQg68+&ucM&rY}|Ndm`B9HX8#|Y>Ca*#Z<;~E0x_+ zNIow~!J-ksY^CM!u5<+&b)Dm~WdTAwrh%W&38FQ+45nyx)61b=pgor1edIj(`wg?n zzS|#&$)l;@Y2Qlt^M?sa%E8@-9NP=F(L>!nFg2@?IGL34N@wariAWh0pYx0;ZuKFZ zU#DR;$2tj&sHO4;Q?N059qs6_LEk%k!S$j=FvIl%Pn_CG^o5dN&l+$3mB^hq{4uj0bFsNEx0NtY- zLGGX|)aPC$5B+RNz5hDgD6xYcEfj+B-5=@wo&u_z8jYe(OX=HA5uBtDN!{ZX(uCnk z+;76ISt9k+_qre22Z&ICPAraJDNnr?DR5bemr3QTRzdar>!eNZCTWd#L#Kv^Wc_eF z&wjob*&b{Q?b=HP>p~O3XX{oFRkwvjrjG@luQTXSXPD`TmnWxp_JEfYbK&0a$z-|b zR}!b`4coZ>R*GS-Lq>F$LSDUU>;k1uAhtTx-G6-qc06&c$ zS{x`%drsV@zVqMEAL8;T9D9e(zU~OcrhM#>l%luyS7O7*dt9bZEG>NuxaYkcdc2Z> zISye|rTPesnXntu>%P&kejDK1s5DNTV2+`8-qC`l8|anu6{i8S;u(bvIT?9Di;AC8<_!1SDRnixKgRx|(7bZrsxa8y3oEj&aO`tW=uTV@+q(9GTumc{93D%W zZ@FR6*kHOk(H)l#t*0@&-O%do6kK1I$ZM-VMRs^QV6FE#a^xqM{adF3XHPkhVBZYb zpMI3OZcm`wx5mTavJ#S*eIB*Lk=&7wg&wZvqfvbnZ*rMfo#UqCznzA3U9}JD9&e`> z_UG}y(X;gN&|WN6cvh*r__@hXuBLI|#1mRMA<48^&IiU^b%x+~7T~a&;#`Asd|THL z{L=ag6S?P|$~_)x8){*9WDlBOI)}2HZ?{n;La_Xz9u^Gc;{jn$R4Uh}d+!&~tAQM^ z!*Bw}mGcyMM1@hk40$3LfPsL8?&% z9NQfO;ul@0o_!0Yt%Cy5-m%~}W(*YUPvy-sIYjDmgg{Q;6$+=9LSFt~QW!i+G&x zh5jYs@DC|=g4aW?kNE)ioO+7OelBBUx0|r__KVrtwVLdlM2atLF5=bi4R|fth`n%c z5j#w7pys1SJT!eWdwxSd?$cCa+f#3#IIF>uClc%evK}CCvS2lT7O}IvLk0>bL1`6Z9(&ZP&K1>YAi^DZ+? zjnzTs!>1U=X_E}IdJ&^^Y^y2Zwc3ArGqux(Iifg^ znLBO)Q@Z{H;~y!-_-vPC#%5U4;kXe$7EiF1+rJWF9^I^*dP{9EDzg zcc8OLC|({@kJ%wyj`wmzyGdu!=VTljZnH<16=H1I(+*IavIvs4xI+4Ce@OY@0?wBk zAv}B#bf$bF=YHOxQcz3vlk#cSglM|($|lyNLu%ghgzVzkcAXKvqF%M1=_Fqck#g^iUSJcWr||NcxIHQ#$02Bx@yA%72K zIt|eAcIP0zA{6c>YqI+S2JmiV8zzfLve(zI#^6t9C}Xk)?G!vP)wTyG_E?gJEGw|u z)I}U~mcZn}2zWisnd{pW+@q zA1~etuSB)tGL1F=oq6O>WOS*F@f+6gy0Q(9gYrXyCG1 ziBI3APJw?_vM{)S$4fB0O7m{MA-!_b(MU9iuD!2^T}@WJiSh4w_rfPZiGw&k^&F)e zr--6kKq&Oy^Mseq=LN3Zv;XBG1#l^df_$fb;yo(@X0EwJDveU%#IO+OE7b*!T}dF4 zo=tY?G?0IrlA(W0JMh0Dd^&3fsrfDtemESuBjmuy>n{n@e#Uc9(}3T%gGkPiezNZH z71(F93%(kb!jmPhU{2;N7{5b=*|ydDCIW6%TpSPy#_bou z<&}=$wKL@{S(eS)kRAdH77p+Zp4dz5g}jNP!!;-~%!k(L^^jIk3uQA?;gj7P-mR8O z_;88KQhocFh>V|&f5y#6AOC)8OwN-`zXroED#MHqWn9K z{_u80=`9^(uY@%O%S00oZm)&?p@NrX7pV1EAM9&Xqt0*2ImVC!d@8?4+AeC+S?|(d z!b4w}D>03no+*NXD_qEwBx}B6j5>Cn3WGQ2B|wGELjATbL0!9=sh^D$jh5EIv-jtt z_w(bp?1}@d6>a4gP$OIz;fOz#cA|600^X!Y^U1{if3$uPYx*%P1ly*+!zEBoZ^+4@ zjYm7N#z`pqSOuq{HIX{@kc?z3M6pl7blZMUa;e}Fe)zQ#_l;2n{e`+HC@bO1uRlSC z4;Uc?tOPF&08?Hjitadwvi_X6nA@M7pU_OZf3oNuw~co_?J|HhnxBnQ(!9fff4lk}8+J^rTzn1>wdX zB@jJqiibUKaaoGaP&v;K%mLbVSNBF3&GUft8JR@)sJiYe2&)e>{*KMBBf<^Ne7%nojvM>>H`G0!Ew`(#gD`zueoc?&I z(t~&$sbOBsIL7Y$^N;P#7d*@YEdrLD;TJ1EMbh6H}AHZhrEw=2#307prW>%o+t#jK^~1e{J?53iOr0Qt4gJsX2ls%uX?(P5R__pdcydaW-+QU58SSBr;*$(k zcjd&Yh4as_o{wj+E1IWObuH^g!*lKI1sOB516v*8O`l>_^|eK8^Og;?782OD)lDq* z+05S9yoEV+WI5|`%$D)>azwvH582SXP{!MOfZe6D7h5kVRQ2u~VzLuT826{hyi{0F z^+n8}dXDIE+PwZJV-nvAQR6hLYUG(JuYjLb??M&f&)VnASP^?Od0#Cvxs@W-?g1|u z?+|lbY}Zs(zB{PO?~b?GGP(Qg%PmUPYlY;hzc7_FgjFyLxX@d5dcfLj*2$=m{@>5b{dBz9 znVNVrq2F<4Ij` zvn{71&CaQuGyCuQKKDf4GUu-Czwy7jzW;UoU9`YpA@|w;zw-Tar~d!s_;3Che=gMq zacBQ;{Ey~uIDf%{|HJ3cNwW}AUl|Fz=@i_(_aR+!SrZ1ov{Rw=e@$oi?iA>5&cI?z z8L+z}j81bsXknW=UtZY;(p$?&NXup5C6tr0;S_wdZwKaXltDkvJ1ryO7B8!$#D6(oSLpTt7ZLo_w7pfnU{QASD67seJ-; zF0==s$&rG=#{DqGF$(WDhvSZd7sSS_n!ef@32ov8r@1Uf$(5(M+@y4PRLSK#cF3Sa za0z9K*TL4*Z0!0Og`TO)q0Q4D|1Z+c{I90(4f}@%l#(J8Ns*x>qS9XXktq?$bjl|Z zk%(lkV^HF=$Q(7?RELHu~N+Z5aMD@-+5N0bvW!4K( z^EidtIjG^(*i7_vTu;Vd+ybxeE`u4B%m-iBLafJ*!?+_tZ%}Z_Jp*!Tq7dE zQQq|L8K}>9K$9IoTyV1qc;;_H{mV1JWJU(35FQ5nR5=VBrUm-?BQUPY6I%Me(qNq^ zddFfL%l~gBV%D#wzGN6XPewx0!8tfsRY>CIg@SbGKN=mf3%i#4iId(PhclAWvG$V*x-iaVt+NY6y-LQ0(=2;-SqBC0J{k}Ai@^c00#5AA zL$_{4lz8e3<_=b<-UWH zhvuQlq#~}sWIM^8VFscZHI=Td`9w8zF>E*z2iCsMIR4^!tor9ldRMnntCM~xB3k4~ zQU>&n97;}W`J?7@FUG@>gJI5LATU|WRePPs!G_7;aPBxvl<>yhH_oK0CX`y9*2aOS z=ZN~BBT(>2zzyAb9#57=yi zp@uY6^$(>c2WDW%i7c>KJO%HmM=`%t53y5mC(f_8qMQ0CC^#{kxFpO#iHPy=sXH9i z*9q!!A86_g?^yR2JH$%TIQ=o)%h&?7maYy z$#j^}IUMK9zJ5dhy2$uv}D z^o&a9NK+u#^c;r3_At<59@&OkTj-$Q|j`$dx>xTKAgC^nW>^OO#Q$g|Sll z{2{6PDiI%x!*Zo#AZ?LJ^r;G}>K}u@>;2H17ewPT{FRBQBQOLR!#B3n(NbG+bb{hcbEp&9l2nWXMw>vee^hL z!-}!qP{m*7Mf%GK^UQ(SB3INKoP(lcU0nM*Klsb3;P8PJAll>4DZV|A=C)Q~m7D_) zxE!zyw8f@%r+{~y1BYw%(Lk<*1m(oTohlCboh5WIIvC;)q=9MiOQJn)D%W7cdXWwu zM3EMU6JztRgQ`){3pI4<52DiR4@2$cexjW=h8R5CPk0CdL#KQ&DYl?C)6Rk0;Z8bZ z9f6Kj7pZAk2psm6fbJgxRDUl^B`edhL&Jr{PxEGs#FgxK<>`gaETrc`fu}F%$BUjQ zoo<4>Xa@#&Skkh6+rea*4^%NG;n(Ro*xp4jd&?j-Fo>WnKkTr7iZ57hiiI-AKVxIUe3g*8%=<(JBHPHv5i4+Dl{Rfv%7g;$Fn-Kjfd(Eyw5Qbr3$mPz z+wYp9{Rek&n!(nZT~oj)aRu;2vv6&F76|?bID>JK%&jPP0rw zPb$;!C(^;+<`A6VLV0y57#vI@CK;^fZ@o9WHbYSKh+LIE>IJ8pa^Se`Ry@3R8JPdR zLi-jm?t%CJZ|Hpkcny`7Ia&*(1FvS}&bKE|7<XX=((b-?UQUPdxQl!TPN=N1=l#3YL7!L)m&t>~3rYyM2?Pz20fG|HV(LFYU@I4-*$qvK6cYwS^3y%$eAj_d@_1h&?tMqxo;6sZ~%Kxt|)4wYhF;O0FL z?6ZriE{q}$Q|btD55_~n5NL?YB|dAk{`Vcx-&uj!H?*D>IgLPxy+fEEcnj#POahUk z0atZ(4t4tZlqC5w2Amvw-*G=lg8d3?a9x68qd>Hbt)^x#wXnVZI$8S15>iyyvw2@4 zbsb_vc5I2m{^f3<)qRJ!1eOqsHz^>oYb)HGlmcZlkJF9rsh}&*dK7nr(U!$)!8~** z3`T|$PoXARRd@z!5~D#~>M**URs@6RDzwQ`0-SOgd#-s0@r+rG*|%1KO=KfA^+3>KNe}9j_?YNg9l$Z(Y!+%_i7i)nzIR;%Uo~$h@tmtp3m!GGj$k{Xlz~3C%YMz=7l=VEW`H>E1FIyG-*z+wDHDn&^)$FC}SP zo+cQjs6*3?ZJ6e+13!MQ2X!?=ma#hzZc(Q}b$J#xJ(GvBUrT6v3|ku|*MSk635n{OjfCvPRro+I6rJk)xq(%x zEFa_pKKik6@~byAyg9?NV>3|HAjg}?Od;Ikd04P>rLm{@3*QnY!Tq|-*cm7Hf{)%z zunEqmFKy3Z;GZ4f$`7R``lG=qyOgVu8Vg1DbfC4}8#CPeq5u9|D0_bp?IKlal71Ko z`Vs|I%9=1d*ASHFlyUh<`Pet>C#ik51V~v1I+a#%P8%bsAmActNzMj!%kj`&nGRv| z?9nJD26+oMTdrQPcHsrmg2r04i_%rMAU zO791)W%D6!&l|oV+?4wGCw}yO2UNxs#Axnnp!3jl^wpDQ#0qgX}M#h^0z4zR-$- z@4tLt+<9*hNb{Vl@gAc7yqG+nZiQ9%D@g<&14hReph3wV9A0?}G+z(F@hUD5y>J<} z2zH|a^T@SW=8$T3omC08qWXXeBn`VsS0DF-YStU)d2<gXoK+^GNoR~Le*54Z!wE1vbTfRK=Z`6Bi$Fv@Vf}pO zVXasL*=%MtvFi-#Ca(hy`>Vdc2ILMigJzDsJ}`B6*S%>YN4Sl7d0K@oc7ROaU3yiH^an=AT&@u zLKN175!v!Os=R&=HA<5Pm)-85!2hP^I)fxZSmeM^hzjQoSxek+e!WUoNG*lcRD<{L*e zl0dM9?Qs%%c#{%mI+*o>Yzxo9s)Er>_xQ5Vpud6qHV8!jXlFFrD1n1E9H^?ska#W( ze*9wDfn+y)Bbf?r%8n?CkLKThMVV1B$0rIb z+wRfcOA17FP9v?Um&7~oq@X__2lc#7V0=&rC{*-N+4_B??Sur#c7_py`!7gbQXbWK z8U@PV0(TYUMv^vd8`ghe9A*C?DDYZHf5*o|;E?6$ z62AkxCA)|y^|*0K&mk=H7Laj=BhfZo3DTVWpyupND#$VdRpxW=P70x%XAriuXH$c1 z>wx}Xnv$gnaa%qT3%+&o5wmyUhPEhFn{5GKr~0Dw_Y7fKiOL4gk9YaFVf$d`lMIO45=n&WidnRmC^}!CeA@r5d83&e$ zNZDj<=+WPa5s#)r!|i0WdDcnzxmzLbi#D3Czd#GR?2S{Kyg>Q+WfE7JNF4_iVL*2q z9XBV8G2HC1tu_XeAUs-hVUVuNL9mph9N&iBL1NipF1@i4ZhE1Nl&XG(*S*N%;N+spmOy1 zYg4?`8x95f^Ps?O7CA0E4fu)>;t&u`hBqCAUqd1wP+lIDrG3HrlOz;m1fs#!`$Xx< zD(tPhOVVUtP*DZz$hjN=1(%~LYf7Gw2)&&!Jf3MxKNUdNDiH5nP(+b`JTZuArfOgG zpsdxC<}NV8nrfyKja4V*bOd_dyGGmPZqPWLa;~i|6YMTl(Hh5gB5ytuJt{VWZIC5$ z+q;NKjX$rhSw#AdtOn13GrZmFEV9EmnXw(uQRVh#E-lOuHXb+!b|?3sa7zN1R(z!e zE6R)uxSO2Yp7kL36-nJ5yQAK_H^g*&82AizMl0(WkX>m`MfWQzsxHLx|7{7trlB$5 zv^9`A#r5&W^aGH0I}MJ*($KtDfUA|yf^N1q*wk2o^<7z1-v5#J@0$$D-@AC_tUXLK zNMTIBGw8!QoraE0M%B&$ta`i{rQKP+QHe2t72;`d-w{+;aGWti6zSUQOc%*xdyD+} z;OXPfn?6#<-c8eKyVGb8ny8^DCXkeKn{aUC2O5@n6qM?ZBIkOWw8zTfo$%?Xn%+%B z*+bB_#}fR<7(lpA8nmq5%?%hCkv^@TG{VLY^g7c(_;)6b)Qbe8txIrt@pg#+7YzQf zme}N}1KR4N=pfsZ+a2&li(k6fYdsH5k5-aj*1jOI?iiR241>78#nkP2F8Me#2U;ZW zb9xbV)Z?xe4&TMr6oXdUUL``;r=_Iek{0%xpF+oj+GrJ$&%FPM*x@vj+&dEjvZ9Oh z_$4C@w@<{H|12TkiyxYO@CB!t!>MkxBt+P61M|KVRIvC?(hBs5a+MZI4oqO|x9@Zy zIf7mq$OHp-8?2o^NIg%AIL&Qd*v)vz0}r*qUu=t(bMKR$eNmwQzjaTriSIo+9b78_ zFYk;7UZaHwQf0Yby>@P}dM>6a`LW#Lc~o}ma3)|ybTnehYG1kt|ZI#6)-X=U2<0qXj37HQdWl2_?XMOUMT^mb+lYL6U-*{BAF zQLK|b!I^j%pTGg`JX!yY`OmLDr-Ij8_%h*g$lbOWio)$sc3}?HS`&uKCncdb@GSJH zvVPtfsbG0K8_bI~(g9f?7@sYH5doQKWAudH*mMvJmJC$L7EU3Dy;4D;`x5Q{Z3Q1E zkH!}1;WTk|HW&zFN%p`=R2}XLx;i7k^I{d(q9wr<C(q>H{rqhmrOQa0e*vH}Ro6#uy%o#)~CR|BC9}!j0g#(wP z@zSvr5OHb7Hx5W(T2>#GUhIU9(tua5jJRVhMM23Bl@Q;TSK*3KWsD+4JqStywcG!_%2cR{6~i8 zjevspNi>*wKMQik@vdKIqRqyi#AN*uB6@VOT)W~r(O_9LmtB=~Z+sebukojPOT0l< z>I}O5*o=Km3xKb2M7t=aDZJUh?Qmn-pZOvP2#Z1OMBwATt|OwzTNMSP-RW(+Wcc`e zI(97HO=M0+!*Sc$OzmZzc#Yr5hP7T$8>3DH4=-_^gNv9)#{*U*`GCVuCDz5X7`61g zak70lIOr=u!z??f+{^f>3%?VQ?LLfaZsmR}c|n7!H&rN~4uTyv?0eAxx1VY_uRaX5 z0|L03{S!f3FcTCE*P-Q2FVKB67MJ=h1;YcWc=d=Mlu`${Y35G0pZ!B2rj^S^UK-*6T z-9AnLwFkL)jqMl33NdKVZjCXW?94Yr6SWJniRf`ApS}AB?RyuCZGVK=`Y{zuo~DzO zz!WS?oQ*BRg1H*oP3$+#H$D`XgC=`Ad9yMLlWg(@2qFKJ}29! zNY+CX{OGVp%h2H%C!s(~4T8XD%~aN9l83G%gGpS+8Z7zEJl?(m^odO-%9x!+mt&bU zEf)Ai?hK~`UW3f>xW@2OHivV3{*e=qoOfaiGuun(tcG51tskyZumiJJ7gpj z)iEB1jSZ$H8WH7x6R1M_6sDst1a-MKDtP;zYvRX1oZ=f^;C+|~!p0MwVF|F}aS*EB z-HWy3KG5<`8%WVN1m{O)Q1y2{`N8(F(uF;Yad8I9+^lJB!enAQ?F_d0JA(LaD98%q zh~AMr3{Eto=FRh{`iWUo-9Z)`6uZe%Za8H2GD;?IkLw%ntYJFyFlc603e;Q64 z@5f6lg&p+*gqrGWUQQo zt%lGNvH?u(CShN*HyPZq234xV&}3jM_#O#C+m1t+8kz)-Hi|fh3xxSz0bu5^3hj+H zLh{dKDDa=ot>2gcrEZ>3P~E>UOZg1+e^-Qpu>1;tmo)P5pcjf1dx^=*M!qaAhyE=c zi^^|~(G{g<(Sgl7yA7l19obndds543nQeuFy-5}QTMV$lql5~sFfHf!9_U>xqPsh? zpl<`~QWr2y=z@QxLFQqab|R6e%9+4NMP>94JqKkQDoB889vW%}W7k90Bc`4TefG}a zpqN41Qr%J6`Vjuw9*-jzp21*;A~HB@ESQ`qBzK4pIJ>%`$(%|qY2q^?YJJ3;94jPY zoAuyiybsn|F$OX&CM8NGw3%_~YY)0G|FIRGP7K4$Pj*nHxD;KiLrCwW?|hZaC$7q8 zGzLF^MVyxWC0)aFu_ZTv6ZO<^jxh=_ym1MnBl-kA6&0h3-F1%KxZFp1{L zJgG2rblQa`VXIL-*8&sfI^dWi`H+&o2Gw7;QKz&1{M3Va*i&>Ia+MFG!=IbPWcXC7 ziP@mMDHBtLLGZ(BJjQjl@pk3$P(Q%fR97OwY{X2E{r8m2(8&YQ5e;aSZ0(VoeueZL^v8~EktAWN9lF|E zg3rcd%yaObs;*<_Pk|KY8YKY*Hx43iewLcQT1N(#=Ml%)eJHpX$j4psMW<19+!JR% zj9!od52ks-)NkHQ_oJjfaWR(7+K8qVSyVP^60x<3Lno~%&>``Y*v-->xoc?q!3^xdo^#wVQgr z$lwEy&xaqoSAd7P9*jz7*VT}GbTF+UvZ*@AIs7CYYr@f_o$>vate`KKM}VtEEKPW| z5k&*ukU4^}fF7~D@jhE@xo(AR8d@OGIlz~@9mO%7UQm<%A0CHbv1L>uu}uC! z&Gt$`Z(0p+w{aOQ;BRwP;jBA%(irdz7jxPQzFb=m%X^zh!$+%eSYTjB*9I^?s)`b* z>laY#C^kzo)~65BQ-Lqt4NJQvq0WM7Oq~%6we4PV{;Re#&2AM4rY|M(%?6BU*J) z?X@h*>uZ2Z<9U3Zco<6Vo`K%vMPzsCSv1Yepo^ZJg#x4RB=Ej6m=8?AcM9iV@Tx1; z&L4uN%Q~p<>s)xXaU1&VI|Z^EcY^i?4?fMHl;~G`V#lsERKYL|Jz*2b?)Xgv{}Rc- z>Zwq$u9dedIt7)oYz^0ZN%=jdV5jH+(`9pT;Olre_UJrDd|e36n!eCACkr}KXVW`% ziXhR+x>QqRFj^)H-|73~jGe~dEISl6yYoQcImT#^v7wxFOS!nyb<`!Gjf#$B5%ZwA zkjzKooGl4x;44cu%J^dKsfVORJOO*O=0WCLRWLQNfYL*A(eBhsQuf^sYbUJ-m#cdq z?T8Dl|L6&~hexA{&3{xdPn|0WeML>HjG%0o0f??lB%}T$qiyy!C~%0T5o~|xDc-@i z>{>}5WM@EA&?$WJz!S1(WDtA79{ivGXsY%(5KLua9((=Y`j40a>;Kb#<++GCpZ=d; z|NH#2vIO5v*vJ3h>;LNW8|fR(Gy4DY4`zRFCVL`0@k6~gwrh^X5obo@!1$M3pPmTD zT@HbxW~}S+81t>nZ$;C^86^J4A^OBH46c99$KT}vG|yxV34I=ps?{}U6*Q4`!Hmbg zDYuEW#Wh|*MHba}InyFkhT84T7?M*@&at!le9hBz@q-hP9kvv9NnIk{8FRrSMv2CW zuY*c?9;};N2IJ;S3Lh*gA+EZ!!EF3Hs1BW05&Bd?=yx^?wzg){wRv|*x_>eT$j9Jj zspnYxAOXLar{e<2Tj=sNa^bmoDcDfQ_)6)EF)eZ~UffqkcAr+m+bWebX+kmtaii%s z*A3vc{1@$fq(VQt%^(l|9-tde%))u8Nhod|f-95lF~wsizIi*E9A=$h^Fyv+$ek{n z;r$FXw$88ou)YnY&j>4n&S?uJe4fI!lhVRhK6z}N*-h+@Y@`K?SP$F^Q|c^t3+71& zpn!jlnb)((*4jo4Ir)bU9M8h-nM|Kr8A_M$+kwaat%gx1ui$Z59qB2rf+uag5MXzb z^`oxf%B!vuxtx3OdV~lZ`$h=6Rf@r+_CK;jF&=zY>*?yd5ujx^ zLO3qJjMAA^uzKVT$b9Gl!pVVfX{QH1yKsq^y{&{fme*kGcahJnrZ5aQr>gNR<1I_kBoKyg5$0X6F+TDz*+3^{#5G|eoy~Pv=mOlpWmC|b>Jrw zH4*Xremyd?9b%TyfYBgK3aHVn2u19&0ew(IzrZw2v}sb2()h`f^2pVJAWU8|3vHP zjwpd}-yGHzlj=-fcb#6iu6QMCTpY?*ovlQAejX-F_Q6+<)9}}l5o5HLTxo;#IhK?I*vWzX7IsOvl47hj8;lFSGMuJX|wdjn5M{keIX<#%h~@2fgKm zc~>gn)9y~Psc|A)Rk%w2&5MBWJ#}!W?KGUtPzR5~I>=`{)-ty)@R`#Kj~$-Cq|FAf zukI8699U0R^_?e8#xJl)=MUc5+DBK|2%z#_GJgI33?F>@4Li+3$eDu`WS3P8OjDUo zzI7aa{Sxx@=yek{Uj^+n{}Y(S5xZcwTClfTHaNsjrqc^fAl?pkbs#cgH4y?F{< zY8T)_$Y&B!w}#kiCF1A;4|Mt`jn1IQ{rxkJu4F~s+G06uF8WILl?1~l{deT|kS}fiE7gfeSq`H;4RL*fTUizTG7#yR>t(&7U@_|0yY%Jg| z*{b2tES5Ej(8h6lA}g1;-J|hW#I!q41A2~+1e+l$*qpopZ&kfQ-$OOHedZaYf>yL? zeZ&}v8(}{j2l?;oxP`as=;sad$zGulboPalqYM9#J8MQ^MuGx-5~zdVk%RG(#^p3; z=LM>^Sq1LivL^OXLxi=v8sR$A^vuWKrFC&E-#)67^s7zBgSIQ_rkF>#aMA}fui6nZaC+?0qOQh}^W7`N%sMxg@ibu}I@juP+!Q>Dkaq=sU^ESohDY5u{ z?qkxpJc^wCI~1nAZA87Q6)@(j4(xoi7Ou6o5>cfIXr4MwOTPNTw4|f-MR))-M4l(3 zMF!zEzR%!jtw2 zE^$FOFVYL+Uh!c@>2NY49mZ~UhY1=1aB1rhVbIT?^fRANcD}SCPoGa92NIE*ygXDLj{ z4x}=UCuoyz4gGiUFpSi#rMZ{qkVB@-Z(Q$+Z{OVna`7$QW8_J%NR8k$bpCK-orb`; zLR+kxDGT%7x#9Q;cla-jPN07)fz7lsNY`h^NPD~!Lvrt9{vQkC(VR<$jbDM~KTo2j zNes^3?M(B`w{zC1o|t@fD{*<_gpzd+$S0 z*8PCuP(8ncS+=rRN6E8xQ2}Alq&{!Sylucq1hm^>b5EDJ{LC z(_kzOP8C4d=q{q4?1B9Ub-Av@0gQ5egFmK(V<6+BYM6f~iBHDBskhyR6t&Z?;(Db}A|hG=;6-dmuI?0~CT|NRs9_;moD# z!oh>i#A>7vYntY`KA_%ZtcDtR{}~!JL`dT5`A26G955$hre_V6^NH zuyB3LsU+uu)_McdD*0g{C_kWK7Tt95z2C%dbQET$t76L~)&+X#HLZLW4@Y+u(SQZb zT;y9HylmqM3tLUe+M;}njJSiR29ofB%?PaTl@!1B&_Rc#orIykjxE?rgn z66_u@?fBLmI68SB_Fx)2#N`0L1@rXM(LPipEPZnYQl37G^S|a}PJB~8?v$6jB8rA{x6+dVd z(TYr2G-~mnjm1Oo^p5iI)`GPhSBOKcsRCJrsn7_KoCR>^SJe+(WlnCxXrP>EbJrw)lL)cFx7<2sWCAVZF{u95-Z~c-b;%Y?k&a7>l<-!g#kWe9{XXBvMb{xu4Ay`2(i(IW6b9! zB5rSDVdK&Vyk^0D@-HR^Hl3VLeUFxd`O%e7F{U40-m@l~t+nv)4T1P#loQ%q6Npzd z-=dnq{oH@PH;8do3Vr9RMDq+ULC4OqbT^ELf7TZvc-2FwURGfoc|8M8_gw#Q;2nt2hMa^!L2yXyh(b22xb~^+H(xP>Y9ax8`7wHrxYn#W{(d{%h;aI zkdhHRmWWT`MmkB@d|-5CN9s3N_bmu&PfvoKwh=H7m4q=5g5kPG2?_gf7O!S)hp933 z^x^b>wDevy4hu=a^G3>$)AE6SUV4{|3~#3IPo!cXJJV;T?%Px1ppg(tEv3?$H^AXZzlZ!a#71Fvg;g zEW7iaMp{I`(mA!<`DO<+RubZx!M~VscM+cG)utcL{Uwrm(s(N=0r#rP&_f$K>CUPa ztlJt!H}&5{oco;fOD@BEb}m@9lFi=MoRG~l{lXLH`dpYEbqO4|uY~ROYiI&SLG~#naP(>7q6$@@JN`Kx`t=*$KO#ld zX4mmY%=Y5!svLA@dXe;rli0C*8+zsl(V}uPTG}PT1m9Z_-hP`@&U!^VYZKslS1kAq zxzE>}HO1+FZy^fws4&SCrK^=tGKtV@W=n8ebPOzPsw3;eonha@EL^&!9Z%oT!>Xvo zC^e6r``B|NMsE?`Sbmv2Jr;=xe@k&wWdR?(bt?`F^#jd2C3LI)N=%E_2CJbW)S0{$ z<{v=ZT(<>wO|BuaGyPJl||A^EI4{Q0vJ`=@%M)rAnG zA9up_r0=E}-J7nIz)GC{i7?1yz}sMb$Zh z$OISB;cKsQzVD}Djdl-xV>=zsxEE2KqbEREQp(@{)j$vCCV{5%He3?J!CtT3;Ce5N zkKCNfGWu^|(yghW7J`gV=na1Nzw#}255mdPkH*doJE8UE0-9u}Lkd=phwUCAD1YNW zez&R`%+)=DO|r!(EpeSoaoq)d^GaX>(~gFyj6#);yEJgac)nI{8GK`2mHI7)a7=s{ zKMB9nbm_NLaPkqKdHV=0_sXR+w=0vyHXQHth zfn#BXWSCbyKHa+j*X!!Th)1kbd-iC2s!@nTSx>?#Y1YBsY>gRz9)j$R+pt=Pc?5G` zfd3)Zb>J`?YsSe!u+$KeKKCu%ea3{I9#uf!c&~yF9oNA^_cKr5PJvqmY9M6>q@MX-e?ID2?1s3t=6^v9Nx`TyWTy3?n3N zklAh?xcjLbM3yYWr6&%7){FC$_ps(4_^hDor}|*k<_pmLyaJZ8j@d^B2O;#zVZ5X2 zhc~l&P%eEoF42m@S$rnWF?derkMKh4f@Hq0Yzj7>oQ5M;#NnnlAF+R#3|^{~5C_@Z zrdAOfP%^fS3;igG396Cg=Fw0Lot}zrS^jk8yd`MQNr|;z+LGm6!6azqAsV9NiW4gKAYwWt0w6XwI8{lHzEw$<9Ke!R!g*dVhKUg!Qfo|fE?wI!q+@y+&{V) zk^)lb$~`IIQ<;zFhCZiX8i$F0PiC4^@<{QrMsGaezX;z;eMKij#!sKXxVd^@9@8*2)tD7j|)=U@!~DUc~eTqm+9l^w}MD~x4#e86f!16@e{H_ z5Jl|$2B1hzfCv5b8q9TS|uEJU!HrmIuFk!?x08I z>Ugz<%s)249-UN=LN?=PAVGpalt?nF7dj`8$KL^V-IZtO_NyKot=#)ZfBYE@DbVDm{%#W=`UxV^Kr)bwUG5| zBFr&)O#;>C(1ZFnsP>Zx?rC;68j6RK)=e zp#GKb_^plK;}fa1l`1ujzs)N;o@X7T#n|*G7)$O;pxa$-@$afqk`g8{0&J&|DyIU3DHAIr8a1%R9Wo}jyV5~)Q_DA-z%rmmpB4mEpj0OxvS)j|8|-!;e$g;WkKnQhPXHF5++{1 zjtje^(Czb7v9`@aH=Z^o_Ac{+Z-Bpwu4U$ zT1V2_7sDjYXT)J{I(VNb#q|LS@b~8^EV=%h-tPTNGW~g0T4MNlPeMr6NC;;XH^P$Z8zDwLkCWfA44kY_!_K7VRQ_!+x~r;_ zwFw#g(>h8H*UbgF)ccHYnt-aK4x?Q07jkv`S=RY=f&LVDVH)kl(O7~PW-LZoSsTol zl|waUm8Be3rngpS@*USh&J``ouL=moJ@}OPz1p--9gZiRT1tn8X@d=UJe_LmUG61 zr8GJ%8T!trV95bry!WaQ%nk+d!V}D~7qbnQ(`lt>L}sE&O+`)UI6Uc>%#WRJbdsff$rs!LU$)$ zYB0G2ay6L0>xvb(Vf-*`NKYqbD~DiCWevIIomBDOKoW9g?$b4YPhzRR7%lgV0ZES} zJd+Xz79sOtOcw+8+iihaPaDZJBw~fMAE#E7OLp&9!(gecxaQUdTCcMh z>uw!o&lfegW;qv~2A1QVQI>czI)*X0Sf0WC67K%H2luPZg;eI7h?SwRt*wN9ew+=9 zb|_==M1tWaY*xoFqhodxxUW%2t{+NoLf_Itx>s{b+V| zB+gni1T@cQ;5)7Da7A$~5@;rOS2p3Lk2To!dImh-sey&<@vQrcL#b0j{%zL>ZvNFO zJfIj2*`EzKnJ-@SkQGHGLm7A?P4F>n!-3B(P^BY{-75#k=_{=FP&EU0M)_mq%Juj< z;0i8X;D)mf6fl322X+{EBD&88nb9NQhR<)3x+n{hmwknGAvW+ddner^QNJ+XObXY? zKH+VC93k8s8!Uc&6Z^L~aT+hQ&4j7aY?c~%2nzF3_NM zJ??NVj|-{RkY(Us_>6SSKZY@vBl#X8gbc}IShnRF3E!#@J0k;)s|4%tU&wI!--tPM zjlLn>+{&^vbD96~T_6-&(!MLP6xYjH{naVq$;*iW3 z-A%MgT_3NM^@E*$D9z}zCs8sZA+}c$CWOV%IMr*wIoyWgU_B6S41zmRPw9%w|8Qog zKkha5$2}2WXmOwl*)~r?yk?#0hE5r3%&1Ns4S~up43)NaQD9s>iKcd zw)rn1g=}vcp8=6>DRkS+E_nO>B3z#!hCb$hclmb{R=)FPJmyq5z2yUl1Equ?1Vg#+ z?EEWyvJQezKY)}S_hIxwDahS44?0`!!?5k6xHCG;U6mdTyTq$7Mr${b@U0*QMusqJ zUIzY|{Df>7s)AEYWMJ?##lp)ypsOMfwynv90MkogY5bE!zn0}%?8Y&_Lm~wIV)Ob7 zo9OcBV0_&gK;wr#H2z$%9*wq3qmAV=oFzAdbZKN#wZNBTW`6>XiS)!HDSmj?F95c- z9YULgJ*YLO04roND&oeEhRYf_b&h)})K9lx7Sck5f zN8#f=R|sfc0=M5xh9!&MlY;IGP_Nq#!6W?WF*7;gW36_2I8h6%vsH!CD{?^i>^YcB zdIXAvQP7TO$fJxyAp3AK7)y9@5}Ovmg;g0CH^vM%KT5&@6_(T29!-uk$N(cu6LufS`lHwd8Oh`?l0jrn5 zRFyUS^#(t%>RAP&*O;M;gO2dV>rq01%|2NErV(V^|083az2V!C)1>=}GIdlQOubz(wl*3`jfs4@bGyoPIJ_D&& z5vlXIfRYMCGOgKhpVjp705o zExi0`uF&y^8siysLUU^#pfls?xz7^5ouD9G@;jVMXY+Nv5d|0-ew9XgHsa;?H7o-X zKxUmT=Hk*1z=x62kpBJwW`Em9_jxZNul06etsWcBN4Js5F(`X2lS(Ev5Ut3B^gEUDrAQeqYMRR9=&v|wp{Qv9xzUQoCt^LSa z_HFNb@B7}@^?twJ{8OU0aGL5bW{zwqD6lP<1&quX#Y=hY|iO*c<2;>5BIj=8|ErKM5Nf+C23S$;5CMy;XH+#OzE;U z%IxU12!~V78ayw-0}!+z6wbX%hLiQCyksc>*!5MGS7_V{wU=9Qyjc&)h-)J;@?~5$ zMox(BKt%5ok&PSg0qtAS{q(Z!Dr zD#WHz1SW4i#$|QK@S9aO5{311V9K=~nDI@ESO3@xZgaY;@WxB%TB}T(mbWqsrd_~^ zlf~J}<2Uhrni8wnc?#P!hG@C%MOffl168m6A?fWr*f#!mL%qlX$k_Ipc<1@!>O1)` z`c&0nVZs6!GEb)GPo0C9%Y9_>!nyThP7czEuNOnV-UYlEwvr~9#qkHSgrMY%9VABX zgOoPJeK)%Jm(9$`J?5H58-_30J@~n=p^tOmBe2|Yj>P~}9&PnW>C&BJ_ z7Gf15_Tv=0-S#O{4q|cc7!(!ZV_3f|`?5fSwE;CU&$|GwU=d6YX#x33I|$A>4(}>` zF><>CF<&vZRZEvTrF zhQoHpksVS-#_JZXcy|(=OP|o*qs916W+l}OuEm=ivm#c~jI_tz$9S^`;ZD*yxson%>LJ_dNv@VzjK$8gvFSoT_Wx!0kHf~2886S^ z!@`+FXM#QqOwFTtx_V8x78M8 z6%V55?kbcsucNu8WAVNO$9OL`pd03IB8}QY?9)T-eDknC@USz&mtW2BsB0tKU2qT* zzm>t!b>;Y}c0cCKmBNEj6!xoTfU%D=c2ul}f@8h3?N}yOa{Si9!FgOJ(-LqRbOg!q zq^``dm$~s~J++ %^nE;<*=1SpA>}r)(2}cRjXn>0mtgay}pLPw}8A`jJj3(Wiro z8%h3obBBOBMNkPBh1YEt98SHz0}qV$(@I%YEU;dMlNEL`uJ;6SQ^{HKkN&94_0QA) zL_cL~X=Pz=_3!wBoaE_W{roe2+rc6;?{)?Y~HGV5| zOLO~wd;R~HcI}^Wq|Fw4_@D6OY_094+FDxwNBp?|PCNI{xSEDfj_7jN_@Cpyy1)NB z|IOCg-tNESzx_Wwzm2uIy#+VF{tN!xe|P@>?)U#(pZ`=pXlG?_Yj6Aimp}J!=D(e- zxxL*#*Y{uWOJ|Q9b&eI)a^{Hzy3A;GbBPvqbm3e1JB6&ucKWbzt@GiZeC>SaPn>g#m8tX9F^$fnVdI?r_SHCl)X8<~(hhU>Q(EBcd(OvsyM&nY((X6T zmqMmH?>g)2a<$OZxn+)xbEHs)Q^ZDD=kSm6E)F>YE`Fx{&j0-Xlj?29?BeG3KgWMH zzyEiB;8gCxv$p=fbN~Js$A8L?oN8-t!+|{iqvyX*U>tUxi{rhP*ua}%zJxbVZUIl$ z;1UL#&*Yt|i{z*H{e_VIEZjP_A1pg2;gP0gJbgpi#&ms6(2z{${WER@!A=lcd#ZfKB|2c=kvy<<@za1I8I;o*6!1LVfsQJct$liJaqHkux@@t&#J0JuWDaOJ&soj{Sz8YhHcjC+gOK8CK60}^j6?a{1 zM43&wr19DTyl(iM(MStsT%6{EyUr3OvonZvG5%y9muEVe{|6>1c0$KF&f8i35kl4; zhL3*|puD;dbS96b-9ly1m&@hN`(B~%bBkb`tN=_CAA<75Pa*Af8y)dE2)Oekc%S%2 zutot^ZWQMQFFykplfHstEvISK{R_s@1>iO627Arl!;FCiuuPPPy$btadqXi_c$pz_ zJh~f%c3EQG^BkD4)3^Ro=?UdCYsa zzcAXwWz6&x(H%Kscujt#(8kKKu?l)D8^B=Us{6EZumC%s%CY{@RkSp|3!7|JZunMQ znH{_7Ev~e;L`5@kwqMg4MKZZ;wHY5#wC*sGi*CcRopt2*86n2){8RFN=Q%Q3cosF& zwxIn`Cn*zMM}vQyr~S6BRMt;`XzvNY`l)R=^;;%a<15Eo5(fCuPn%tMDvUoqrV6c2 z|G;I>Uwbc?37w!Rgee8{pvKxEDNi0>qtPN5j=mC z3rlw8!1bvfwBnN={LwnW$3Y}(FAji{zC5qxn-JXaYKCX#^FXHk16lTK7|w(!^8Ctm zdG;SGF?pXFSb8+$vPmq}a(s;R1a4;wo{z9#Bm0U+oS;Fum+CQs`1vUtOd6$ZQf4vUdUO~4^~{i^wOB|%&Q-S zKaH0S#?O3d;P?aZtnv(}73c&}@PQ>l)v!-7pX$fzzmz1nAZVr?qUaEZtHniE+3H6GVhQ~bFupN?H5fNr>M)%;1I3XNrc*!4Uo`7dZOJIvBh3T`0;CdLB zITLOPZeqT$BVC@GD+$bN?%sSpq7Q;+z7ntK3uGw!7bE6k2OsVf!lZCP_%gPZ6u(Oa ze)kJV+R*X^jhcM_tW@0GNMS^=>xbVb{uHUe1_eIm+;tfb4*xJiP6WO@ufw-l5Jder}pDw2)FJA z?JRfvWD*4#I~`&9!KYAt{wZA9xgXpeqhapRad={TDD(yEofsMy1cprCye8ug9=sOiGH z=T_v|4IRASf-sxQ$+)kzkH5OM7RMIvg)f$On3pT#=ydN$a2`9An96YVg2Rd6`C1l+ z>!;GCvgUX;beP$0oK4lZ?_{$fLA+@7i7tInLcM{!Ddj{bP)C*6k^PqUO>GP=k*>Vi@R5AW1pifTIu@p^X}g# zmRmw#QVmzHDm(zfr4D#%QZuM69wZJEG)d65G^iOegwBoGaPiV!v~{@-QcXwcoD6&P ziT%asd##7-WxHtYSt$@VJWgNlJ_9*>hru@#!Hl^Mw)+~$+=*wHEjHtE+hijUI#UNW zZ+LV(9;WF{Tj{$3SqLt)f(dgnXz8K1aB#jN?B8U^FLJVG%>4QpL&wMPyP_V}<>Z0; z)sygEO&)44L_n!VDu%_YgHrWb{B-33T`3|CzJ0Tx7|u||^>KJU(*ahFnqzNDCXwSG zh26Oq;K$T`bj`tLevnfI9azEX=EA1a&)i<4>rNI|=NeCIV;&L9i(W7}B8Xm5$b_7a zK2$$^JUm~;(mN|Ov2PKB)1*Hz&U405DbC00z;TAw1a2n#PIvGJIFIJQkQ!ON{TV#m z=>%@9DAV>$5kxrdg1JgF_9VUK-`944KnKplyZ9n56J86&k@`@Qvk;_;t57+)ge=`7 zPyB1IVgctv8J(1dr9aRK(eS~<; zy?=?UlNh>}t;RR@$$Yi5=FqKKhKd?ZbbEFOR=YG}wuTZuQ7(j47ozZY@fxyqr!i9L zCg$0`6oz+R47Y`!gvC5>80U}#LaT3)@Wd>f!PV`^>||(oqecTf4ncZyGUMmI5 zc$&8qJf|C?;Fmg5)~XG{*H+_J@tOR43l?$A3>MXPZecq1mXZ-{!r$@nsA?s}+Iv61 z=9oFyBw$N*ZJt6;Q!9->d>SlMyWtJ@{L}Ndh)DGZ5dQKMdKbIF8Sx`HW7!DK)@Wre zp2;QgepS@1c@)394s+g>8Z6mhO&YFV|tqaTNJIxwysiVpJq?T7ak*wYfvW1J?)3#UHxDqF2y)j z`@-LZc#!+?6=F(EIp&Ep7gcQoGfEt2W^pXczH%Ch3`Fsg(je4rwt%E4ak9)S5@s1M zr5>wV!Or+Boj3J8*mw!j{v)rz`S4u`S!4u1m3-0tNHz{QH&gj_&6xFEp8dK)E2gzUwGNa^(`e{o@3BwO+@m)?D7QLp7GXGh@kWHTKq`CS0<^6Z@u0vcG)>=~iwo zsgx8_wX77n=@`LmAD;Vr$&aSSRl!=IA2Bq3!K zFP1;H?@xY!OBWucPMlxq>)IZsuh5A%aC$SSukVIw8E(9vvKqY1Q^PRlqdv^bP~^QY zli>ZOKT$EO7tv)RBz`}RfjaN0%uiV;-E)D<<9&{G7iKciOEY2c?J&&T@CveWw0Ysv zO?aOc?tse2NcPOt<;j^Aax6auURq28d6?o3qG<(;ag7qMRFaY}F&bb~%jGqzPl4a! ze%$;r1ryHSKjX|0bl=zuEi#|T4kZ@SLTaG&kO)3sBgAW5v<1$(yYTEQzr%4}EtsyI z#ItfPBVaI09u6z>ru^36)+A+YQsw*(h9)5QffD6@J-+&&IZgkaK&9ymlv$GsTX8(t zUYiMlwFbOA303I6FTgWtJOO22w}G_LUAQBr%!{}v$;&hB0uh75u<@4&@8x}ap8ALR zAnqu_8$0k0cG`}TE{{~mu$Ti4hvj(-GnW(c_z4)BkL6vFt$;a-dOY@+8^-BRV0YOR zp?!=BYa4$ISA6S5DfgVc%@M$c6eXM|vl*-7 zagt9Xr`ghH`3vtMvD!n=P5wyrg7n$hD|h3(SP}M>b16UhZ5sH!B)p65M!Y~h4c@qp zWiYy8GB46cou?Dg09Yu=OMM`Na;-M(^C9l}745)owc{A6n}V%Msc2uPgAd{)5#`-@ zt`6&Y@4ld+cc?GvP&zo1J5HEK3B;KDQ zK3P)N45C{yVNT~=^0Y6KXmEbBRpsM&0bG`QucHvJ|M_CR?xh=ar&=p$j$D9o^~Yg` z=~&*b(}cGx(h3BXieTWeAAGs?8S*Z;!>2pbAeSA_=9S*Y>RU=|jO$xWbl~He3Cis5 zgDn_WWyHQww_*!(Kf~x`b)NjAHc&b24UXKiB7fGLm)@cZ{s&uOptRZgGQp0ZOpSemI@PH)!>4EEkyPw(U8y1yw8z)q1D-)7s2_CM&|pGz4OQLMkm|> z0f%syfnM--@*MWuZyviOMvCp)xtc8sjbv-?%w_||+T+lHt*C9ru-|$rAjeDz&-`X8OyCF3j+^8pG*dgQN4hSTriEOi=y&SKzE)J!{@_-Y>@hQJai-n zPsNnu964>)X-J65txCfN;e%lFjLSrDm;=Y39YS@}za+t90oaUH1do6+;&S95wtueR zyqn25Np=Y~+3R8@e=NS4WCWM)?8e6$56A-fR7@{!qOrr44vAj(`Mdt6lP-m+G<(@| zR9>KprxGY0jyix4Ed;hvXNmde5?md+xSn6CWp;`H>?#qjg#X2An1!YYhE@N z*WL4Fd%~kpw_cO|)#b_#-|E0UR~NI#Ac&p#^d0%4xE{Aws#D<^^GQL}HTr$3JG@fb zkGl?bp;0bNZXQ|;PqsIZ;OJ=r>|jxFqj+9b@uWVtZk`gb~p`$oXrgjZC4&kd9|hoTXBs~WJT{0lfuNeBmLShE4$f$T?S z5O+Q4MUJ4wN;sd!(@JAlhs3Xbf^}DP;p~DU zns;Oxc>8d<@QdD%xpw}{_zQ=zcBG7ybw8y|v)4jdaxy(ppNp!&_Vn_-XJmy34BNh*pgj^4P`Ir!WsMdZW0wZx>OwNgjHC_yaE(cdP-`eHF4JFxuA6}9v>dtN#@91 zK-J_ZkZN4Zm%N>VVq<04w~v~U)_%leS=o%)_H(Giu_~Tj7RUH3OLW%SgUw^J=+~_` zh=24%tZ=`L-@D$S!}3`qM{az~kLvc5aOcng&{|PNT;6>F zGm~zpC~bto!Y5$jf2zUZ!xa+11fw9wP83}}36AML!L$fL5*=nt_L#@u#P1>~V%3P! zksWmWb3Ll8m;n#vbYbRw1m@6HCNd4_#4U|rs=b};(@aL)#}c3*dJd->^y7!-eB3na zF8wS!0V6WiVE*T$P`l(8lUS}mWt>IWPDdeT(T75EbtDP}>U809oDo?w^BCXhn*`GQ z1{@|m^sUP&G)umYeiOs6!EqukF%HI!>K5#kKhGiK+7u#ftIQjm`;_BAM?n_9glNis zhNKET-ogNR-evWNXjmtRQbP*tGm{@wypH=WQ*mYY?Q&s7-u}e9vm|lEcP39cSAn;* z_A8i-2=OLQ^5ON~w1QzZ6Q1sivAkm;V|gAnO|a2)A((zU4NGIrLuySwBi-)`ml(+g z(PTLup38*r#|NOuv>tjj_dz}PEfLo*LXKXaO4XSC#Hm4)x4GLFvcHbNd8)(Hp11=B z*F=I-nmI4%L@wC3DFAuJl8mh%An$G-j#f+IvH>0Tfwva-?wO0{r>U{WF5g5?&O2mj zX3pLneFZs=e_?At6|BhB;6+tf0+~0+DSxK$a-K_p9It~hTV(+j&c)DU(+t%gWq7`| zozN-x72f1MA`v0&u)JQC{CURZvu9ZI4)|_{i99vlaH#|@{bvSzmlJ`Z$b8VBF3+pH zZOHBrYR7rq`|(Sv3oB%G7ekIJu|j1{c)2@0F?3qI!H$~q(VN%BWD=~QDs zh_~Pjfvaffn~WMG>a3ou9vh%ChJEvFl=CXI;n&O=tUHh3kzaXOQ#_0rQ+DC2H)qgo zzAalXJdT}u&V{w_orG7T=aGZn>rj7DCYM{d4|q#biO-}O*!ESA>qkVR>-tf0ui_55 zrKy4+f5~Ch9!tCs`waKrc))QYtug6y2#t+az!Q#joo~YNXd@?(2Zyg= ziqj-`ad#`G(i&`>lZpd_YS6x?1Pw=yk%mtM`mS`~l$w|HYkpCK#Nbno@m`7U@}KF~ zqb=z4eH_Ori^4voX>fC1DO&061dFZ^AZeRXe#J$a+gOW7J#s;B`%-v$&5T<4@$jDO zdf0ltgLd96#p_kCn9Ny<5W2RC`s}}sU0aLr>iQ@vB)CS#T!1cxOF*vnwW$^E23~wpNxIC`wVJy( zK}f>hOky=Y7Y8GiNpge}Ebq6)ekK-G8$6GD1ef8DA}Uh1FeS#@Lgax zs+Ld0V-=^ce)u@b-@8Tz7Cs}VeH!TZfZLe+k<|0I9NhG_t#j`NpU=c*UfH=~q>d z2`K?n=TegNWCKR_CD0Xhf-s!D6SU5p1$w@7Q0`e&ia6_S(Vz zwieo`7!IyBQgGLZ%ezbqhu(Sj_|vxOLjms?-(*;c%d%NQ{Dj3Ia#s||=ZK%eLn62K1nKzOLw0|;jAJ<(;?`YRsM4km>mOgIW1TkRLdiP5 z>%0%7@X>LMKW+r2y{2$G=^Y7=5yRQ9$D@we9opM)%At{w!#1%T+-ANHHvGB)O708s zY+wqmsM*cwK+hAC*%llhxSKh$|1z%rvx3$c{UP-wDrA9mB3vvu2k&mRVfnjiROhmR zj)qUbx#xLg(u)?d{-7Lgmv3g$T4!;3`;DOf!xsg9R-+L=!C~e_X?(}k-GdWuGBGz- z(CL%MFnX*4>{yV6V>{}hZAJo=HO+-y8xt@|>?A*aaBL+*VV>#28$hPD6FToL$u+qH zDn$g=o~p+0{)HgxwHK7y?dSk08@ujrKFI?T7^JQ(_6c3a=r!{-1eOnPw)O>(cowokF}qokQi?$`kjk3Dy| zSknPH8|PtQYoUXcm@($;yv;G9?-A#VpGjq)Gg%im3&srQg2t#8evrt4G-eN7@V6eu zybXmJ#uB_&@3@SbF-IBJDp2`qrj~j-=jV&dx!*CaEIPxT$^(U;u7YZqjY0emE#P6D5qk@>g(m_#CBN zTtX^1Uj&0zY5llGq>SD?90`d!x5x~i45ECWJO6B7<{igsd!I24KG_C9ev&3QJDtI0 z%X(V*uNV~WX4P$3P zO}z(EDz|k8&n3!rIzTuKXxZ>4ulobfZV@qz~Gp;|K9+HhdzFeK$^aF}~ zZosCtJ>>O*L_E9Q4YkUHutoX-rf%^h6AubwdB!yUyQ^k!#vupep5MgaNzG)|(qy`S z0oTA?_KVz&6{oh`dvOm}YYS-OIKoj15UTo)>^;xG&!auqUw;KBjy9rcksp?DtYtqg zkNE7qemafK1EV{c;1^#E?5`$jXIx8qiXSjNRvKL1)m!{@{$Rs2&r%|qJOPuBPr~Kl z);Le$Fd5x>07K`NlW(GGu=L6|YMUmCKBJ4tvYtiY-0qHj3p3~=?PHKO*#(lyXTbBL z%c!}K3#6^70?qo5^!Oenq3njl$Ra*u#PbsmcB}ei8T13Gmd3ddDJ3aAaGs#X%0cEadcp$ce z@K2aRU5`6VxWRW=p<)gXZI(jR1u0%}LOj~t-pZ`I;tltI??NxxEi^)74u)0FqTMm) zupl>{+6`}zaQzhL*)8@a?x!svq%9f_-918r+fvEj37JgXs(QX~nGi2v_7C_x`w8{VZ>IB` zDdlG;!sat_ymcXqVUBtcr|mcZ{nbq*nmmCCS}%x+Z8{7tuOY7l){|S)2H?Pi4WJ=7 z6U6RUfrykaJ{_q*QDsR8D}N2i&ubxz;p#MIo0-kVsl>@wkvBc!H4IBVASZUTLdSN7 zH0=q3Dq$6J-L)4UZQevo0u6aJOC(`bq0O>-u)c%DRDu=iZZqSJ!Cqg<{;GFabKuRdHYN3nuqUDp}QyysZKWA+?jnI7W<&blMP%j_ zu1CII77Bm3(o@`;<=$S7zlU4VL+s-J)XyFqFtz+o^s`g#?9J`|rG7R}eK%benM9=2 zLP5n!0{^~NL=91Ca=EC3#5I@D0m&S?!dwBXs31m|YvN`@DV$LHi;9Jwr#+dH*!^K4 z1Wr*$_rqZ@<%AIkOn*YgzH`Jf^->z)l1XB_=R?~paVS<;i=I*W)ID_^S5pXw6(?Nz z!t>qe^67CTW<8giDpAbWi1&t~?N90Fdy;T6GlL&ED~Z2-+Cxr9W6gZnEeyq3lz+fm z0Al?;K*ZdFnAO_B>1oT+M_~-CzW0<|t?_~-M?COLhX^j4^M?On#E?pTT!fDrOtD)0 zClxtvfKjr4`PcodIX>JHSe`Qx8hxhY-nU$D#J^|i&I9*pv%Cx*f00SA-1|a(_4Mf8 z(xos%#|*Y*ib1BL3FP1CAmrV0*p!>Yx1PTiFD_L@E3@N-ClCQ?$_6;O&IY`kCxMBW zKixlkkqD)`;G1PU5EUE`HTRa|-Vjgh)X@aLbZb{M4n@RHjL=Zre;FxR?Eyi1{C(uA9qgwznJxT5;U{yB<@owzz=MTRU7+x}WJ( zTuOokrc-<6JhH(`4L{BegI6Q(`O0w&dg-Wu?_WLsyWe6EQ(eIvy}t;@tq?@TA$|N6 zb&&af#uZDd$H4k6=jfr=uSlc8DjIk`g)AWqtlW8rtbSk#Yi(q3g6UZP2Nx-vrr`*0 zmZ)QF8w0kN|Ij!~8yGD1$FbA|>{s|R)~|zLqZ`LxThvPR%S)(EF_*2iYz#gQk;m12 z5fHlg5EJe_nFxMThN@ySl$AR`s;i9gz{CO)tk>62SFs44BupUQgOJyWv%vYCI^148 z5e>eX;5u1%C?45Q5`$-AsJ$D$ubhN0{kVSFz5tMSHl^qfaM{zI*gai|P0kW<`e+RQ z{(J*?akH4b=>0~xNH{Q@kxPX8}7-E=4KX9v+vu*dKSBiQ@$85tWM46zdVWcNM|c=YK7Ie6F$ zWi`Da@$Ld#ZxxRAaTodFYuECB8O%omS#8F8{!gOx(;C*y^?;k3bm3k_0k!OO21)Y< zD)Tjkj&t^bwM*Raq~~H3&({MtWqU~IT1C>2d?LKt)8Glm4Qbe@k8UWBzVTYXzo~}H z7i2JBl${}F$`11PML0}XSH^;NZ){cLvSOoMK>d?6s=pZ~ABMg#cl&pf;B~^#>pO=C zp7ccMRpM%JdgwpjnF{;2)6HDXZ2NalOy97C-hcrT>tlgJE%%6ypfx@kT@KR^S5l>U zt&C|SrQ>^}=^PU?bltH472Kwi$?a{_?&u_3@8!dnoMnSw<9#ss$W++7>j3}KXjOfg zxIYJCe+E|B+~BG~5X%UJxD!S`_=>9J%rl)n0g%+QpCT3H*|GW!EnvjXt3Zlqm) zt8gnu^iJp7yiZ{=`rfa+3(>v<3Y2OYJ&=5C!t#AQo&5o zgCMZwbhA$+`smDsQobM=Q$vXxmmd(wFguoK5T{7q00+x%7Oz?v%sr!3bC?c!2tn#rzrH z!!i5XT$rJ1j+07ek^b>@G`z%+>a==cvd2Y|;wFiPXC}hv;8L(!5XX1_Z30^LqA+pF zSQJu`!L3g`;VJ~9t9Aj|WEoF&FIZynZVw#3907hY4@u+(1Kc>U4FB|`Q@)KIRJjk4 z{_H?3dlm#?mX>JXw~M;PUF7r`bMfpQL7a23oVK|4F$ZIF=oXtNWMruxRcOCVCdkhx zZ!gUPQPcUjUQ!yTuXaS$=K$kaJ4i(Y>rWvXtvd@}Eb$}! zpOj3xIS2h?I6cJjt&DzGIPmy-`0X5*nH&0pOkEjGchm-O?6+Wu_p(E^`d_qNQwh$$ zRK*~E6e+pbLAnDv$$QR&6!7h^gMGzyPFLxSn`^0yHntC6eSiS z3DoSg0R$abhCA!qY4D*+BJ)g%u1yoi3(HJko~H;*vTC8jweI}92##U>_YM8E$^v&J zjM zFwxQ&p^3x-Y+ftlmYR=@liGGN$kluPo|%q&{3p>dO8u})Y2+ci&RL>;? zM>IK>p%@k@>Y=nJpxL}j^xfZ7dcsZ#uRHgW=M9hR7g%I7Th{;L^c72C+3yGB@s1aK zi&M66G{GFd9MeWMekIv4%<_vsqwP1dbG4vD$D#n7d36Ses*lnfF8?z0z)t!^Ka6U0W$+br_wci4 zF2cCb0_IvoPJL@{6FK`*oMV~`VQ8`^JQp@21K*nYlkV+h^mup3lVAP(f!AGBqS*$N zpLmn*O>^Mq2ZDcgiNQ%m9J=Fu(R9Ecw}sf^)d#kaDD{KfwG^jp$01UqZALySN5Nv# zjr>+cRa7btf`JZ>zdWU!pBed=nplXDLpF0kdKd&a<@oJVB#8Edlt*(6|AaoN=c zpNQrb9b%g}6NBccK;pq6y4XI8NnI;X3pBSf=GVtl#}8#hPTT}Gp1e!7zq}+&@H|w% zV+mjEqUp#DJM?}n22BFWxXPZ>LdaH;YD)cxf{F93T*PT^-8x00TBIWjdwP z$-bJWB@nlEDGat6;ftmO zGW~a6Lq6A^xzv=*WR%$xw;UBJa9JB}8P5c{qdbhc&8JZJggg%JCvWAaFys0#-~i1~HklRB@pOCTts^dS!~F{q#lReBg$| z=No^>2FnRJ?Yb~E+IyG$IjRm(0n4$)sEAI|2m|w(#$yK-k;C(4Fwi@e{^r(B zyZZ{*I5Udq<|ojizhmh-)*Gx|adp2PVGSF0Hqo8hBjllG0@Eetg^ectbbk}a8qx8G z3C*^sv-2*AJ^O^j2P)(1Xf<#RwZ#t|pNVY2RQ!0i)!t^>XX1Cp8_btv5L@v`s_XlO z|M1};KO@ndhTr1T2+p6H=)Vj+lkSt%xvMdBqbUUFH_~%19pt0@G_-0ILA%t4G<~f$ z_yuP&>qA5^=~^&lLY!db$8)63U6vZYk%T9Aj?wkc2gubSTVgk&iNZE(QCRIB-Nfo) zqstxovs;Kr_o%>Ncmc^L<+LQk4{itCBYT!q@VOER6JYKEtD>Y~r<5ZeF!@7FZ%!bA z?ydY3BMB%i5JwXm5j1-KnkG+oMzzHc8alTxZqT%#)L>&XvsvyfeI#Z~<$cf4H#JY_ z3h!R>M^*(3$8ijR0}1@XLK~#l1mRHoYUsT?9palp@Qb_(Y8Z!*p@vW#TD}0Um^osj z&{Re)OavV~q|n&bAEZAEp)mK%OgnsvYCUPAqaTE^<;^YHGgcoqmEL4Le@3ARod6;y z7h{M(5QZwW)A||H@Y;z?QtoL+gHtWh-~AmU(Bp;-F^}4WPKKPhe`(h- z2C`lVV{DHe>Ilq$&*2NOGoq0(KVgIVwmoFa2~k+a)mX00cuAXPTqFC|{A3P}a6WCZ zM^x(!pT^#|C2~_lfs>;G^Jgx|oGc`!^93-*FPdbFOva}xi+I@X7Rk?MTnec5c{PH!1$s62ppJ5RCpI(IPwUCr*-65_=LrAms8?J970oSvZ z)4Ifqv~jl!`g|MY>;2qBk~goyw+$)8bzvM8$J@lo(+#^q9LTt>%3MuL6Dy7?;>t=x z@?BL00`mu`)Oi88s<#4fRxt27Jp`rpIDx?A#r!q8Mf`%22vm1UXB0yI(3rq5_}aD@ zmn@qAx2-0i4wN&u{t~?PL55me-C^9;#}enp#aLG6fU~XCIgVuk37;AlWhl)&JSh&66=D<_L@ErMkhQ;>ZcjUw%J)G*E+_6@uu9-}X5v^ztN=7b^d zR|li&?Ll1DYmhB-zY~R*K6KzyC)sf_j;gbhQTX$Fa{KjMc+d5))Y{)TL~T4lf38sm z8JBtJ^Ry{sVUA6;-Ja%+_76TlS&kY!<&oO6zErsaDFqHl34_DTR zV6~eo6?nn1sjoGY_^qBeD{3ZGHGiT@ZY@Vs<2q`3j>`+vv%xX5a_KaS>HMW8S154b zrsLy3Gn-CD!pR&v^g0m)W(qdM;fD)O-hYxlkaL6ztvKdSs4Ugn8U{~vIY#uXWFqo* zGhrucVfIl2%*7)lYxzRhKf#D3pNwU4xH=B+av;{`xzM}ky)nl9B0V<}Lu4m$nPFNk zFv3K`Z)9-B{5*d4K#hG$l`rW0wS(>Z@*DE|yy4h)ACA{zPaaS4B{9KMi2Wl2Ty{wt zN^U+S9a7zNbCEiZsvRK-zn>FNFvO8S2B&T_gH>0LP>I=}`05T8_#%OaKX!d3axa|V z?qV6p%l%7Mh}y!nN5;UDu!afOGRV-zHm2yI7@pGpLQV{-V$rc_&~w)sKfdiGkAJOT z^fZ5vd6hYIzVj;R&ep`x8``)cR-aokm&3bX8T{Xh^Y|`fwa99RRbX^$Hr|9({)Iei zaFyrbZR6<}9HNePS7bOw-%70f#w8f_io<)YQmRpKo@AANq#r!W_%_WqXpCVbQJvjG z_Wm5D7u6TyoSlDZ@vVjUM_n2Rw`Veed~PovxdL6v^>7214;{2&HGXSNV%B|Br}J+~ z@jDN4*_@GIXkvjh1_^i3({hWUb-EV#+>xU(%N)^n-5&DokT_O0gf&!}h{E)tTV(O? zUUHv%*B=q_Cc*xJkavC;HR1XrCtcl1%gUeRs+>LCO6{dlCoHgXqaFWo^ceg;se{Cd z2$FRQi{N~_4Q|k#hi8xMAhnnGGr21MQ295Bq}_Ie=e>hu`D+InHT;A*kmLtjUF@Mn zaWR=Fzmi6b^}(qVrs34?9{pt>gn!@Fmaw6ey`HPSK}H9a{Y4s zbQ4CnX9sz&UBH-sFeTmn#@J<0$TZgG6Tb2!ob%opG$J3+Jx2pDr8tj@znX~&xlvI5 zWh$H>qqprAV3<)G*|(*Vkx5CQc|Ju%pwJDbuQdY&yDQXxiz}^6(nO_2{wQ9i zi3ar?hn#Of1s1*}zeJ|e7c=VVH1#b0O=U+K>=+3zO%&jMiX_}Gu)y9SPCr*SK+b+T zN%}qK;>7LC7;eELn?H)vH&49q^ZA7^vH2-oPC7`Jped}6o`)k1D*V0WUZ8rig5y0` zlE*TD4@$f+QsoPA`oU%% zCQTHDuD?ed-uQ=+?P*Cg^K1bL5`Ri8-eyy#XAU}@ucr6R>gY_LJ>;3l8b}jQ;7i`J z!d)^c)Od>!ZF%#UiR~GWTP=3dyCaL}!>u;7{pb=1<7)Rh84mo9f$?PNtZ`VBU;v8J z*>wAkFZA5Dh2VS~uvz~J^T+`}THY0NU7fJizktbD+CqGlE0|KfV)FLGoQ6LM-dH}( z749ReCv6>C?Q!%6r;s(qRAe9`eS31^v|Zbs&*)mVGX*`({Xo)8HCrS z64^>F2Y&o`l4$6O6^2W=Y?ifT__HmP1V^IZ`bB6lemM*&@Nj;|GJLz_0uB8m0IiaC z^m0fRO};OMj*qS2`|`1nM??9`Ma}8=VR2j+#^C(Y&vaExFbEotfm??sK!%VCEH|@< zHFqNUhiZ***2ItWo6RWscIObc_Gmy*pmJT!uCeH=oX&h3S_;|IjquX2BX*_ zRIz%1Cc3zh<4=mnsfWVgI-&x1pO*d)j?OZws`hE)Gy(#Gq=3>T3Q7oP&yWgANQZ!c zbV&Hv-Cd}N*oCN=*s^EDZow7{1-k-!>{lJ0yV!+x zq+h3Q-!8*V`zmVwyi!V~1kxm%YNu%N-;+peUd$9OZf@uvu#fyB_X}pLbOX z=Z^++FW=(YMNX-#n7vVy(|!ONJzhiQu}fg{(MI@uwU#`jxzM~;iS?tRdBN`oLh)xk zemK^c`{l>7?U}B0yy_Sz-s_FUKB<(wRtM50UwfOYCf_tPzy;E~G+4eIe0{7i;8hq7 zRqjUjVqU^@S^-1Pyo0qF0l10M=+^^l+%qf;cV>2#I?wlr)AgUjPW5t{SY9l7Qyut} z#xUNfuZFW~qxj^FWTr{9P+3nQ(jJ4I%mMKvWZIgz1t#v}{=o&(I)k%EZ#;Ha1NYpOhZ{|6$)(W-eHKSj-o^yHct;(a zVoyTb#yo0JjKCRMt-><<`H&KrDR%qb88ib-`QDE{NU#1;+0QGqAkCYyt$PXczTBZT z2OEUc@ylSxw*rh@oru|G$$X?E8lMi3ybLva=*!yzj{9CAoVmM8I4*s58F@{xq&}0w zMg(9>d*lJI-yO?W#QG;90>k67&p&*cKmL@ZsFI009H6VmqsV2g4UZjysh(;)Qg-kaegu= zKTP4kk3M+dz?nC^8p`1{z43fqI@`H-#vO{O;97k^C?Btd zFKd{_`>Au_+D~NV(iQc`d!xqjeNfRg5}J*=a7OhoLGPEBlmQ9H4X;x1aPMFoH*Y45 zZ!Y1iYz3UzQOJ)30jqyrqM0jIsN%o7vTe8J(5^&=C)5-r_SFJG-A0ou&(ERGxy!-5 zu?0NkDya1RFg|+lJmKYsR5|!6IYfEm#~)q!ZN_5ZYY^f=wLtj!FNAMoT>$e@2Wj`1 zZFDZ|3QRCf<^Bs?*}=h-&+JnYg8ftQ?D3uAv&$v)`a%p(QT<2$P2S>=g;(L)$=@(- z)hntq+5igQyz%qn4mcSbjqN{L;L_)K+IFp!_O@PwJN*h_fQJTjdZ~pAjJrxYatVrR z7f7|-gRYk8@x3K7zM#29bkr^r(nh)R#2=bCP0@m1Nj+M66?Nn_p^B~*gkVm%J{Q)X zf?qxF2pSJYQ_Lz;w0tHfw&VriyD$$tw>%Or?;b;%OU-drvleEpapvnq1zcb8iyHf> zprWe-zxZ~E-bMLIU1oZmtJqHOPg>#BXd^Io`3C!?9OSYGgJ?j2Cw6^W$ak$Q*hk8F z-d+<0RdSa=L9QH{w~PQi9ftCyE(ndr*jfDs4be8_>=9Mq6*LUD&c6w=VTZ*zftG^* zjbdCs-<{jfj)8?2T=?+?7ba5CY-G2eQ zw`s$}<>^?xO6vdKzOz(BhR|J?OrjBHNtriKX|W_)JO{(hx=XkX?Ywu6`DKoXv(4 zjh!%3<^8fyOyd(NI>7blWBp%O;#nV~&eDFplE6-Eo2}yqVsNyHw_mAerU9*L*qXuB7 z=wT8|w^egsK?c$1W*J{Sq(eQDB5>J`<76PEZ=!EY_pr7%LcCfk zUbE5Xq+~6e`ZWXF@(ZBnm`ZBuRKk}F3|Kd>02@pij!7$6XldR`olYe}%1>Le{aOy+ z9+g7gM3>{6J~oRJhr98b&#_|N4__E_IswZ%?WFA$K6p^YhT&Q=9h9mnrM zV#^cM$LHKI7F`W|fT zo`8e9<}hSVYVCD#PWlA$FdiecjtyniRyBT6V$T`!t0ALr zG)Eoyk0!ng!^;~4N?x;A_#5brS%vCUyX3rtMO_aAFYAl8+PB0l&4oDqdS4tjAwbGD zTL=}CT-bJOXB;2C3QYGEVWy)8{_byz#?w9dg;f`EnAH&cr6u)Qrd$&z_fo{(OOoiB zb|jlU?#YqwRB%JECU=**KzEK;#zDshgLa!c?y-FhD`z<1GVKJ;mh`gzkK_6M(t5GI ziy6UdW6b^Mg%4lpP_K~=Xg2fJEVN*LqmMNC>M`y z3xy9oUE%R{1zfK*2l~mz!*Iu;v|#FSO6|FV@;+6H_Z}bJE+Ykbu?JNMNYvT$J zGwLw+jXx!3pfzvb|Arbo^01rCUi@sY#2(=SAKR&q(N0+$ zYvsfL9oj7Zu<3^Ze^Vj4+>yN?pgOSp{=r8;+ZGl&=$!OcNiN^0K<{Nnkz=WyAJnioNz?F1%Eyt#aYIF^h0w#ja+qHxTIPw z?wxr-c-+~Bd$ot*-#|U=n)wQ1Jq&T{hs7}LdYSNN$OC$)Tn-k~jzjP|8JCrXqQMzS z_v$;N*5XY+)N`zX$TbeU@l6~ZzMPM3>o-trupG)C13o&{0{g7$%o{y_)oS(bfl(^m z_*cU~-0U5J^D?ClfZNxoT4GK6{W2!GYo|yqQI7+(<8e>UHo@QfJ4L)RXLY$ssvIZX zKUrJc{G%I|rV8XXE`dK*j)S6q#Vmi%on6285_)+jU#;eqHgqM zFgR|3Ml<(-hpr)aQJW+CV6Dc>j$fp!i==&N=x=ebs~4@G@|B#-)(ZOu$#CD_pJZG# zUmP~HR-AjxLtOaX8i#nrQMc*gRM5)|f97nVm(73SX_+}` z+2P@#o59yVmD66VqnbK5JfxihgHz*C_1s<9U13N|pXzeuSAw0ZZCRsRFO1x*h3~$r zqU+^E*8aGcQWPC=%hd`}d7Mw(+@hqW9#x6Mqsd#I_Jnd}1-$1qjA~OPpUB)NwTib^ z*Y=Y5Wg3ZVYY(N>LH)#mY^1V_mc4Mpq2WgXFrP@$a1&BO?o?O8(a^8-(X*S>M|bW)O%1!-|eKMP=LXge9-yg zav@*79du>ET$=5G)7{f?NQ5ijSTBeBGMf#-KzplF@TaAd_LVS`H)o5*F;ScmygEguZ$!uP;#hd6>M zQm1&h7gi6rC)hlSK!Ch)pI2?{^{2OYhR z(&e2B*nOKhR-TH(Tk;D;?TP0>n4=C_g#xedeuKQv)(L}qpCi4rLojt8K;%^&eE%X9 zop<^1$%pB@z@$$6*dgtMC&#iypFI*E$$;@tZ|rAg&0_`!(CLaSd^oWyS4^8N>#;}1 zKb}<3+BeqVXE+#3J6zFjvnOV}R>YRcA0c5@xY$vog6mdBu;Ny08nk5~Hq^G$b~!cN zHeZ@y<}ITM8+zd7!dUU>p{sCrgcZByWN~HUB~m|QLyn+}^3uNWs;e=)yQv12iXCv^ z-CHX6Yo}L-!>}wikvzSa+6;2|~ElhF_MtlV!Oo zrKV}&A^R0De#BS0^YI*C=TH1#v?F&RX<1w2_oMmli&o& z&}Al4)w%1W_GGniYehX6PM2or)ENA(JCNp?DAvv}djhfRrSIRfRWQDMD_nT75&pd2 zMCZ26fEzlu$YG-g4V3mB7W16>|8aQYky?JSkt=~1Uw0;@Av$3Q1cj|;v`=4|q zCXr9uf2|F>&`LAodvg9BMZDEZhH`!ml3z9(PwN`-W)o>=Rr-)l9F4{^<;HOO%5*q2 zdoX-HQN;RhB?-uIJIqq)hlhV{fZg-u`D)-sdN9F?nv=4)_c>+Rirvn*;hht{a?}z( z6b{0X*Oox_rPspPk4k7iCzSm%KEqo}4=h`#B{7n6xyfd!aJgG2uKI5Tr1(OxAm}48>G$^rVFWYx(7#eZW8W( zoGCt*I`%sEwdIv9_n>`=4+pMngvjhApjaJ_3BESCubUPZ8OL$w+YYp@P0B2UtKgS7 zIX)WQk0Z-h!LzBG;iaR*#!=i%UMEX%p7L;Zu}>xIPUR5n62bLZ7wL+XFDF`7(7;tz z+%o(ebd?$6_dY8?dH8POdN+b|?jPvix+;#n&(Q{Y9S9kTS)BV78k7Rp$u=V=8M}_02>FDL7i!!w5zayUcH9k zs9xu3)Su-t8-oyGuD33~SzpX&q@8YKL<*(P`YhhXwI0u>kf;lunN=Of~W$!J~eE(iPmRvLEriG^X;^hSx(HOy2f1G$hoi^I_y#)#% z3K=(_fF6lz^yfw>{yTkMm||2;gAMLO?1g=@2EP;H$D$Py54KQZW0eaH!*`Nl56SbC zGK~A0HPO5qbrLgoiQumF8g41;A1^zu!=^TeY2ar89koL}8#003wVtG*Ln5)$YUC3K z!my)Qo(3EUtxXGf1h>n&P=K~S^iujnH?>uHi$CIzbpvU|AwzWD@EDdSC1CmZWV*EK z7{%6j@E7-!;CXr$EZc90cc<9$H>!iK63=ZUeG>L0O8U&9^Khuk1bQ+zNXmY{q(}RV z;G#_WyFYHh(w>UqVqYKrUg3*PEBf=7se?#u_kB`T>(7@1qq%v+5;_}{#?iMoLsR2e z+M6%YT&AaBFR7<6OqzH0h!LcHHGoYuzERPf6p4vkL1PR$;1YUa$ck#Rxt+`Qio?Xo z8Yx2boAWdwbO{{$V-6?08Xz?H9jx@PC&Qm@@Sk-ahu%`)6Vje@g`EqJ_%9FJCUwA* z{hs)Dbr`-~c3J5BFdAP@w}rB@ZM1Z(I(Ky&NxO@+@!Hq%(D5!3qLueUb{8jps-(e> z3hTtpdU0r!F|~H)8kTmrs?ac`g zZuM~BPy0;xV6T0ktUOTIquQA#yIi2{9&XrtEFRCL_~A$2o;WCe?CfQXnr!k$dTt|b*VVyjWQb?_QH<-hLp2f558UROxM7H z-(HDi)!zNY9$T_G<@RCmOV5EgYNHk!*!l9z1qYyg_ft4t9}m{vD)?aUIndhZi;t%d z!`lxo2&-rAgNrR%98sY!UVNvHN~0Ofy?27sk=YbHzZ{09N_u}^9k{(x@}&IqG9Tm0JddBYmLpv>VzF3Be0VYhdH>6JYyo8;zRqiMM}JHWbz;}B0hnMil)KOC#}Qcr*f!pX z%X1|~^3*~IID8)55A?-FPO3Oc^0_YZm@0bE5qQ<^gq=5r;kw&W$Bd*e%+}dY7f;IJ z%>|txyCo18oYUgUMFHsI^aYl-UKN|1PC|XRt?(k!gq7uQ!l*$-oMUbU$IfmbdxJA{ zHhKkh3>qZ$B2K2N;9TC3aZl9vsDkdz?)=!}98{fuN8RVU@x?xC=n}RI7Jd9VX0j)* z@wrBx=a<5keFA=T_s7dE**s~h3iq1n$Qx6h!1@klE_fD+W&!g_>0x*LZ@(MB0t&WN-{K=1(n7SSc}8+YK}MVz1-0XPFH; zelnJLYI=OQz*{tvkK(3{`B*WfPV8UljISH4@z_pD+dQ$Ee4RWvNIP5dbBSQqeIMjK zUoK=w@5hQ?9y|#u#7HTBvOFUgx=Q)RgAT6PvM3POhDOr73KNW)7|P?to?f+X^m=!?TsebcgJmT-V%d)@9W@6pYOHWY16^-sf_Ke^ua4L zdh>?SALy1+9~$W5BfPquiD4uCB=*#DviMX=hE92$**%q~?~volP*WbXNusVtxpIC| zxWqWs;waNBJbb?xO`GCSZSyqxbvcRueHU<$TNjD5TqK)i;>VlQ`iSQr7ejZKo8tPp znXG0n@&wpyPr}oRvQpo^1Z()!5I7NA>Gpdn-a)c=crg42ZPlP&C4AyDyNY zvLjpF&cZprCCzSQA>KUnSGaGUi@SSE&;D%^SL*w6nqnh4_WVGDy5{r4^nX-YB4CPD z9G~zkkj*RU!$Glopk{6|F5e!=-K(|PFwz*aW&7cCp#vJ6vY`0i`M9&cA|8D7Q0y_F zki-6Fh#|7ef|q>(Z;mg)D`(=w>L3ejs_ltmZfj!n?qs;uR=`h}cGQme`j5U&42Qvg zktS-;|914fzFY%Z6~TeyaSz zy}y)CjbuH?2>$(Y6a0F5g0{T!Mzv}B*erDv2Cg*aW$$)FJkFE~m{HjNv`8A3e5^d|!N9R6gU#iRwLZ+v@=Kn>rMu&-Z2PPDS{3%#PZs!$G9z zZYJgJgV^O^3`aC)V%z0GXfaIc0ZucKxbLmv;z~QIw^t44{{~t*LfUg&4d!b~MidyL zCb9Kq2--U*z)}0*$c=h@xl4b{&6oxHjju@KZ~~V~%1H0p_s%w<;B9x6@FM`(X+K2pvCaq8m*1wXue~woST}q%TTS-ix2kaRv?o`ull09E z_nE=;~ma@v87yrO}3;`!@4`NVFx2|+KnQuBJK>zF6fB#p ziq@W0()^#s$5&coRD2z&cI4umYj1>-D}KV>K`pRYx`#X{aKh64{`|mkB)xyHg*H#$ zzz3T!Tv4yW{$GyJOzXd}O!p6r?DB<{J}eXlT|Wr!Qa|vL+$4DD@Coi$O5dBYd2Fhz z$a5@vV@Y2dm?WJ$36Xl3cxI+JP}`fPy)Bk9;}chBqSxicG=Kj_V`-dB=&p#qP3GKke~=5x}IVER(u z;5G5vObWN$NOK2CxzwH)KL4w;|IBYvhmziV#6-ALoUs?h3-O*ALQ ziPyJ?G-`nt+W`BkHVcxV{RKs!WYRDI7(1xIRjG6ixR@6z1^@ZbUDx~8zS}Xb0 zHk0O2BR=<3759(3BY6$_K+3(7LQG9O9^6q59@;HX`|2#|?leJhr9B@uvE?bBywUS} zyHNRWJsiw^N=$#A`Y#vwdAzlAP7yY@6nPmPMl=F4*ci)abL|Zkkv5^%{;7V?8fJy zw0t=A9i7eFZfpnBzdwbu_muJGBxQaj-%fMBsDQ!nHE{g24K|h=!j|pcpm_EU{PlL_ z`WhRdXnsB~>^2U9KCL2!WHm}XH&Ohax*HZlIBv92E2Vne z>L%kQ>cw2XApk%2QsJ#RNy6td9`&TWrZGI}cmszvN$}fV&qy)}zIs@;2AB7r|!E|=pZ5UGQ11$ld+3tORWH0b?I-1Z^TjFVu8?Y@0|mQexc0Rl-$`@jPxps=9d3F-#!|j* zsj~~tG}6bbk$2#1dZ284%zirKr7J#d+e>B7wo<)<8x~}0u&%r_dfhbT@x6xdonTi| zIDCZU)HaEmK1Q>8yugP})QPP{&2UA#8>ndXlRb1a#@}P?sCj#eVE04DpTZVPeU3If zPw%&IgC*T#Lnz;#)*06}T2pfMVyb>Es4roVr))ggh~e`tc-sw&DJ>}nBzn-_!gw4Xv(+Zgh_9?3f*S5wzLcVvnowyZt; zHN;6fGNa$RkdQT(jQqR6&7i9kvsm(oYW@;b`^NLp$Tlc;kL8f?^PuHkF38ln;FPwB z)ac;JUOkOzi=+`fKAntb9(&;Aao@y$t(m;8OBkqhb>arGg5HOpfNJj$j#ZR)E0ev^ zU*$2F+xlQm>jh!6&;@govZzJsk(u}8u~+*!O|}oVlNmlwr0R7ltQb@xF zDDL?K(&OWBbh!_GQLrYv7)RdJ`x1=R?~Q{JJ=j({TlN;bC7+u&;I+aDFbK}3gURm9 zdy9D4nqipn-3OPge?dmFzWDku!%(Fs6k>Uogzrr>^-+VEfN3<`RvYg%^+2QHA^dGc zC|LTB7J83Nz}0?^JWr`FYMu$efSbLUZ7n!*{4lJV6e_f>7jRSc05a>cktY7VE5`M^ zCAdA49QekG;Nl&_=C$4UqKhuSUZsgPZz8byz6E=}?~9wOhQOl^>74nsQZ`Acg!(ue zV4L?hx?VGx{B&)w+e15k6jy{TerMsxJa67Cb)xipk&Sz+PEuy{ZlS233vV2kg>8=| zPG_Ythq|@b8XvhY+_g6rHMjHw(~KeLTs@Z(idNFeFe6M>x8Vg#9PnY#BS<41TpXRl zmF}77c`StVniOzh%T;REY@>o&Q}Nw)ZOWVb1ZrGY)4xupT$;0x#;HVccUv92`(6~= z6Dw%fmxZ)T{jArim=MU1_2KHNPS}>JOng6GD4BbREG1oSuuTnZ{1S@wSESuxffe2D zVUJUddeGSN6xexFn+q;J7iY!2qc;jl_<7oTQU731{#QAHLLTR2+N~{9cvtgQOc!GWQ+*)bixV zPSc_0RtS!x+O7%T0RuCNuYDKW$N$^sgc{Rh;K_mP;k4qUQf6eQTV@eW6c+bf3Q*18cw z$+@0z=Ick=@FE_fxAwp^-`};7K7~+}X(fI??LobMC*Y-Jljz3gf5NQw>15(sMoqFN zy3u%D)_c|v^y(EMjQ^z0qXwyAd)RAuXM2h)RVAIWcC46pLJ>7acjj&}0=M9AFz@Tm zm+t1_%=~aPxo9m*z4H<}{c_{hvTPVAW$vGcw16<98SWN+g-!DQY&`HKEY7#(3-!Ao zVxc;3dTfcsv#yJaO`Q04{b{c~x3fscz6)<}9!eTAHJ+|o%*SdJ+2Gew@(SAo(;B_t zPrW=Ev9ycqG?dhS#9--lL%dM_okH>#)6R#hC9OpPr(GYwf4f|PkhkGHRr(*4*B^jC zKKkr6W)5lf^@k@LJSo~BiB7wELv%we+$R^XC^#!#PUrC*% zV(DjZvWz*+JcyesO3CtRt$1zkV;bMP5RLysVXxW^+H2GWVcvF#>#IXe@76-y{RD3K z^_;rD3qkGc?pX5n2$^p&<|Ud5Jf>qOc}m%`Cf{Z%elD@aO{ddc{mI7%4;YLIUqn)E z(}E|_S!_4tE4n2AS>OO@&939BRewI>ZwjFM6 z)xb1ORaQHD6js?dp=dPYcsC~p9C@&qP2Q$sSkMR2UQUTK1Cih6ZiBl<(YPb?3%Qot ziaANjI3q3^t~@vAr}M2E^sR8=(S8`cR*idv?SQu6Jn)!2 zpZ1&X2V?JBP_*_vbUR{>#nD4h@3$i-H6IYi=$659OBv{lNyV$}zi6mdZ%&9xV0HC} zLcIH9>hCW33VW5XO@SrN{OJewYaQ8OpeCn3z6W7B!}wWVcl`M&jLsBgvYE1T?Zj~@ zocQgV>}%ni+KawRXuQQ)c$;~G3Z!hQ<2i{jv-mg--{!VpE6*`c5 zSlGHZlm8to!q@kP@~{XQ2?|N-QYJo9 z%JV5;LTne-x~nYxel-5*x=DC2Lz{=+w1d>gzEXEnAg(u_0WA-T;Gph#IyvhTR6f+> zMQy*thU{G4V$&C|@7Lh*{faQ{pf0Q3O67=&9z45rfH+eO=d#jbUQ^`84L+*;e>>4o zm0~>lp_GJm&LnpM@xWYL?z8a(4V^O+x|eC=+;_6>nQ|U4=+)z(9?wH_>u4`!j zqAt=*Sd7J9I)cB@LI=8(L9_i0Fi^fK{__iAokJn)>F7=&GtLV$;%|vQ)BQ2_ni8)0 zEpg%Jb>|nBiriyLDDISI=5-^2&{;1MmP@&m4^jtNj`u{mId3p*jQc>VE(W4Kr1ONn zlZB!Co5U}fu^8(N)F7WBn2wCV728(AvA{Z7e$WtpD0_j|)QMEHT+;qzKS|q8kBd-WXRhx@^ek$ZnA$~$bu0FO4w~%OlRw`x;_PHE?kN32>LdH3XTAy6_prmYr^0ZI;}5!D zJ_`nHiznTVZn!PX3_1_nMn)e3F(Ia|R^5I$D-?x+dfFT@#bmzhY4kSHynPlWK2qZ9 z7e{F8{*&||@(9ITmy_6Vg;b$#&YfpF;@JNIq4(8qzwj?l701xJ0>}WKeh+{rJ@g4;9KELXnj2db{m+(TDLqN z^R@tP4v`pH+xF3*&BgG*LLIU#ig4-|IllQp!1XoVN&Ue~A#c@cSXS0ZHTKb{v&n!H zPuk$Gh%_9&bd}I@)eY_B)(OXI718qGa+8nfD; z5bkxQkoTnZ$59IxQ>VZ-l3!iG6Q2l}J1&}oA4K9UiC;EYV!3RyYM~3u2J-N+N&IvF zOnUx(KE3^R4*qlrk z+;}!h?Em1F&_`6FYc&QGYNXC5bx%QIm^wLlyn*E=R`@-X^+rKi6(<_xNjr4PLqQVOFV@7oioV5wd$CV zAcqV63)$pZBIk#jU{Hk)$VT)>Yuk}tIipunVMu3Ct;wdmH%Dp7f#)h6)wYuHDzhCtntnj6Vv*zO4hGq7vdX4jJY;w#PAqi6!eptZ<9jatSs+if z*d622YQ*rWGNG|gC2YCc2C)W#yuK=i(%dn$rKrV_eY)xx%POl$r-eBK#)ux_y5irl z?NA>T3|kf2;oh6U_-W^7ip!k}v$kHRx4LfJa&A5xS$~?2{(TOkzdPV^*KB-ya2Cxv z_ySa)go(X!Y(R0M3{BcQ@wiXnQ2k~siS6BR(lZ&?tQt+bL0dM#uv}0-cOI-JD#FiM zy?DzWADm3`=xC`-3!3DmzK11bUa}uL-q_Qujx3&TxC{O{55VtpGx)`Xb8xCCk?rfl z@#2J_+O-hFkDkf1aY`VXC>!&3QbRw7KA7C^kmzxJCJfAQ;Row#U~F<4$J_Q4lJ&FD zEy6+SyqjLzHDm=HK4F6?wX6U~;KO z99J}m=G|IE;gW7#*58CzU5MpHdM-Hr)kSgrpUZG-Kf~PBHlqAxcMh?zBagq5hp_hr z8ZxK~RzAIdT zQn^_H2hHz5x5x1muN4X#r5xz9O@AodAq0!Ajii5V8e+lnk6#XN&8bVW~K_}oH;5u1%^WRP3BPfUlP_E z0-lfUjTIA1NwK+@(@er~TH-mHDfK&0Fx zlW0j)06ZGm1vWm|MVlT;oZcybx!vvvR+R>5GRhQ3cFL#DXQI&1vvI&gNb8W`-lZ3Lnn*pMHmTx97ss4sUuAJ6oKq|?IIltlSI6C=jI5z-7IP6UYpkW9u2H!1QC~5yZLv7BHIjC8 z9Fv(e48kc3EyUkPy}VwXdqI~*{{*W^14-q%0+?;@%1y&`*+EH*#v}zw9{U_N_#A>) zqGcubwU7?k&R;k4gDoTNPol27GRVTmP1P8%kU_SNEd zF3OzemB7UYduYlMCm}&)Fg9%5A@uN-p{w^$G_iRh7Sjo7zjRBec;Q0dcV85?ZVl!S z^8dl}WyfgR1t0D;QciGD@Z!r0^r)ZZXW@%{0}Op-i|Kn@IXS}%2ClHF^{{*j;c=lH z*E0hTnFQlz3B1~WND!-hmb!WF%Hgi3H>lsk-;$p`mwyN02W$-Fn?LN)wDUqS%JClktK0{P((X(KT0))9 z461A$gsRWJ(Tmx8>Bo=_V6P+TSIs@}K~Xf~Yk|*hpG={Cp15F>4aAId$H$j6uv54p z8+ZE$XOAjzUZ^Fzse93Mxi!Zu=O2PM5wD@(;ApxQv|V=hSO~C5B6d3R1vYzxW5})E zpyv|-d3`*vaN1DZ__qccn~^_HN}%c+AKE9jE*yW@Quhf03O^Pu-H2LJnTA9fzI;R&agkZ|ZB zEnd+DTb{hFEqv35n<8`J&E7J2>tn%}4?KdmVH;_c#$Y_Tei%ZXCk{}oq7iLcyf~vT zC4IXlWF(!GwLYIOSSCuE?mEc>^|n>89W$7R*H0$5EAQasS83OI$%fZ#tC2KBCtP}3 z7aw^C@!1B+e>rpj>{=FwE<0Pj@?f`sx4VizJ1g;_sgL3HCJVgw;2p_Hx@+N1QP4hR z!O?4LX`K30VNmDB<$h z<8;AiD}}F~C1!e@C8_TSuFttm&eobB?=^xCOJJM*Wq zNQnL1MdGmj2FHbmNX|YUhdi!^AzfVXXWC%)II@TO41OmLl(M(yRyEUqsyf{E)Ey;5 z75p?)=HXI)bHalRHq#p-)GS#nL^yY4wb)D^m*CH%KKkLqS{3%Z=f&Ob#PiAg;rzhO zl~=6mid(zp@)xsXbnWDPxWB?1({D(gxa&`eTOU%l1C6x!SuI%>I8wvhc-&nS!f!4a z@SxOv6uL^CX>>lX+O3BJHe}-rqez~%NuJfNhM{hFIr&Q-yv4gO3ms|FteDVBQ*Lbq zt8t4#E};|EPW&p2=%}C)zazqibak}cai5CL`S2d4EWT2yji;I=R_~ucI&#j66?N_k z&5BZ&!9YLE8_|c)hL_Ts$63^ttc#-u^<$H9);MYD5!iCF1}2nivPM!kc1-&x-jk)$ zwQMVip<{)EPbTBR`w{qlc?7<)T1}%`8-Wk0veUL(LU$!Oetuu_Fr0b@@3K~sL*iB1 zR$nR3%F3Z73q!H)`ESxbC~1z}^0~S;pGi;zIzIv)uMOnwb{DB?>Ib^I)EPc?Q5C0^ zx%0)o0qikXpGUhSg04k8W#4e*%<4RzP`?P~#^hnEOD31v%?Ix}opHXxqFOhHnX;cN z{=n_$mT;rk2KzUpa%R&p>UT;};tW=Z`Ae*5SX2m}oz{m(6fY+?IgvWq48&E1i{N|T z3_ioTl&q0J&;OexT1xNuaJ?BYM&FMY#<_5QNe|3bucnVlp47Zp+5=pd^b$epIMCQB z7un-WlM#^&sS~Hpa*)@;GXlA#3j_z;2y-VB?fJx_M@U z^b)*B^S{4=LmEantvO7H?o%Z7z{c=3!w$L>*b`sx{(ihHxnC{DMj^WIh3&6`QN27B zN4%O*d#rSUC?{prE@&0;w)ew$?EX;1C5gEBZG{+oJ&oUV*oyT-g79X*kpGeP=FwQa zU)(>DkRggPXUtSGbDzBp8B&UpkU~NsL;5t&MRS@p&!uRRO2yf`S@WDG4JuTc2Thuu z>-+ETzu)uRYx%=k*6pzFbFS;!d%s^Vlp6HVFlHht58Vub|3%Pu^A?I+(@5^SD`8&W zC#3QL(MNn<{wy5|6a9WdVv-+gkNHXMOf04Qd)nhMr3*0JTNx*Xn{w-lci=qt5vW}m zLayT3ws^xfMbfHkG{2h)thpD*1!@E6<0~b8A8jvkvZ0u2-;tKyje|G!!MH$23Ae0$ zE+3Hlbe9iC9 zK$Bp9c>J>k^*|r$b3%)qOrA>H1%E#%)KGpq#Ebi`xKA4cf=N@uoL7o$!Pi7_zpr*? z^Q+<9JEX7R<%Zyo#CA}4tR2t&;{pETtLWL^&6MQTgTLnX;qr2G9JO)^yuUJvGdgzT zYdyZug8U#{b1R$|s02e@x*isL#lzfJ2VvP&2WnaAEKhD6!Jp3d;>hW3SWjQ{x9@uM zmWRbu>a&7gJvN|;-Uk)1Z#($#boh6zue9c(8`k}6$7Yw~v3*P$q%^;#xkX-dKDiw9 z^X)MHZ=Isqx2k?w!UOaJH_2iU-r^@VJrS zJn1som6-Fi<^=Iv&xA17a7sB-2K}{K==N_vUOC4Ge((DWIYHY<`+*}@sXeDAqkW1M zJwHmbOERPduT9xOQ?SCvzotn^VXWQd3!UT~w79WA@(k7HBl<_A-)^J9^Is3n^E|0o zdO4mqi45QKYG+>Tj(G9NU3hWg1ZDRYjMw|;#AJST~K@QLr=iM50^hkBZ&@6M-=#+uY{~F-t?{I7wEIgR^^;vmU4wp>u zqksr^ zj@4WXGxxPnyMdZ~>_9WTcZj08SzlT9=Fbb-ZxJUyPF86BF{0kB?a@AM&LxhHIy@G5U(At&UxoHL2;Zlxxf5F z>lgK8^|`+k{(i6EM~7GR`}QTe`s6bFjvuO6aYPGG{QLlO#hQG^Mw|zv0KQvq!_`SC zyrJo^?>kwN<6{qz7YxAx<7Haj+Yw!t61{wIio!HXV4(k3_}b2mrx~f>l_FCbFJFbL zcXIJ{sWaE_>Pf0yLa{dHB#b#H_%f5%Q}Q1>>fNW3`d2CAt0fBhZ;BnPQSG64BeH7u zCVz(+2SPZjQGs`!iyYy41BfDD{J3cto0$r~qeluhy|w1SL;sVOmRo_X-bh8#=r_>n zpg%m_DE4WU&D7?b1Ae@H2(FVQF1fCY|KbJr!KDWW9`?t{L)zi|tF5tb$6|TzQax#4 z%S}r8)B{UNLG5QIpdJbTYrlSY{rejEukBixR@Mq9E;qr|n-v`M%7`CtT1%hJmdY`^ z=fkwP2uv4wA-^IOSm9CsUw4xjXh5xtn%4bmXsE1~lno0YvvRhgjjftv$VrqV*g| zdHiuOubWTHht|@ihd-p)n)@_tZUz?Xt&#K7r-5s`6b}D6ogR87px4I~thrqz>palL ztqFEqrPr191{z^*SiW@q*#PpGVRuHalkc8o*O7?>#fYdO8HCG z=vI!X+V`|<79i%Mmjt6_j6(K{j-~_4l5oG`o22NWjMKdCQR&uu)b?}~^a(fT?arRm zWB5E+a7LV)3KiV2?IF~RJtpt`cOU-6*3v)=ZLSMi1hE?8|JlZns~ugS_4*Qca6O70 zR(a#-wq1FS+CJGn)|ow~%!U-WFSlx11gW)Qv}v5E*S?=k1A0}%{DY;!A>0Ai_E`#B z`wqu1L%Z>|T`rKdb~>o;55U`|t!Q@NU~0UUgk|@Gc#dqyDNpU-aLzvYUfb97Wo0(L zTzYx?GiJ&plq%Y5Wz^Q|*S^r+Z<=?2g>BWIVjQYz@I(uhZcJN?5pm z4Xrpd60iMnanW zJK%`j;k3@cosEBeCB@`kJaxA&4mcrko>CC(zfwW(!mZi&h8}`$IzhxFYZTtsX-ueif zymf>uny$moRjC-U=mjl2ZNR2ij{D9Jh=JD&d*dsgpOEL)qDT{GCHwxDsd`QljysXa zgB(_q{)#l-?0!>z(|RP1E;va`!hg}XK9QW_`jAYYAg%N?755 z-iM2d9Qn}NZhYvcs58CR;ykleP@r@Vmg}1F!6iEA8tlpY#jLsGwneh_|7LbwlksrN z42sa{3~L{1pqhyzZXd3}eTtIU>5?J#obN;(dSvk=#SAbKqKmBhzWmyFIQ(AkLw^ix zab1o9&fU@*zD*s5CVO5`Rs025zb$~hBHFWoMIRiSF8D;l*21cVR*-9~E&J=Orp-ae z>FW3HWP3!xH4}{C(4x-r57k(#5DwVNHTSDLl?uentrNG*&EUgvxxDj>KM!|BxUCq> z3w3NTu}=n%b#G1A_y4JypIbt=cipDjCVS=dZXI~Rb_1TFv03s`ZKU;!Yv`%S&K#S+ z5eioXQ>C;^+V5e^XCow-(ER~OhX&%swl=&<=Pa#{^}yc>YtC%0p|gX=(aFIgSAEZ* zGTfju4#_DO9+P5f?;6iatBu*|Tsxd{LNN0dMX>n+kqIl&!C3ET{Cpr5=U+KO>#jYA ztljN|C%HF{J!*%K+FzzI?=};}L_&uS`>EI5E1*2E6jlt&V(IKWaC9Gm^ZV3*o0T3; zf8~vD*AJBgtCMhA(-WH8ajQhDeuI+YDb0)pY)RV=v)q*7#@C@#|M3egthnlZt0G$7 zQIbjK6&jeI*A^%2-%jzj7c7mJ=l#*9n9eS8bI)YT{qa;bnw88$2h4&c zQ|458&H4}8e_a8;6V*h9ZYZ~3+gTA=V+Y-*^kla!f5D=s9qT(z6zkYfHp?8yISEss z(WD&yOzX(;iRLhM+akI%Dim$b9?td}$~Y**hcj~T$~Qw-z_o~B7-?}p zwp}t@(X6dTk$ZZP?M^LTROTp{Om-Yzu}87;mDrDripKcc?_l!sZ#4MVc`)>N0}r46 zBYDOi-&;+WVf@Qddc3A1e^cwlUwnhvZ+{|wc+v-YpQ$`n)@uNM*A2#njY{}yicG!H z6vl^|@}IjNvdZALkX$$z|CM*-rg`ES8*>ouJ@n?Y3lY86^yXnL%5d?L4b0BIB6?GH z_%drI1-0@gFRK}fz1x%J+qLVd@aI~3wB@syKJ}ctBF_*hX7xe_gBJ$l6@D(fxDJ7OKk86=7XFI&7zYLydM_~OuQB$54!Q1{g zvCXNjyvs%(?-;bfwd6pZ)ML3vULlN{9KugyS4ttd@w6e@047axWkWHqqI)bEr)?57 z%1u2vsQ(n%wr@wy>)amI%N01wzXDo6F~oPrn}D_a*xc#`_-3`i>(_+OV{slZJ5xc<+Yc39hI!FI2w6?|NpW_Kvd=F)e)k~?`)yAo@3!`MvG+hSeX$;1*4BgJz1?y_k5brh(Hu9# zX7g^-DDJfGsC>XTk-HSN5t+X2pgW~Waoh~wScl`Rj}8h4SK%hzHXAPXkyyX0 zI^Q3v$s4xxl#abJfHOU7r7@LX6o)VGC6oRCq@=nubi8v0y2l-pzAxJi_kxDYli$yS zKd8f_4Kgundj?n@1IcN{WeA!Pjt)0U$xv#8VV$1Bob$T;cR~rgU4Er%lVw{B__q+y zwu;nivhkmhs5^ffi8F-@>6+j`+`VK$v%MT}7^X=_{sr^sEN=!om}mGJaH2R3+h8`{;RgSuvK zIoSRHeQwg^Gbgu7%X?0h8j7_r+0qn;wQa>q58k4Uj;**+@@5zRZs4RdfgX2XE~gI2 zuXGDrC& zNtqX;NqW-@@BQpZ;ZKV|=g$^O4D;ljwG!qxsqot&#%OuO1od?bXxpE!a;?=3*{-iX z2PKb0sa{FUMMj|#O@fqr`sClLEjIcfk2BK*m7x#ipDROo(AXTDmfMCs>#OPFJ2jxF zckQ|VTg*&2e8v-ckSgJ6aX*Yzt^n@=pXq%B;EVe^!IB|;pg-o zCBNIfntbC1;J&kO#7(dl1}jU|;gOBRm)=#RQB^Wf|dPrTHi0#5&~$kT?a@zoAm(*DH{p=dPX zd+SgR+9CS0G@ii@$L?F(0p}VGFtsbp6A?#ljT%i zHr^Zk`zxbslr@|S4ew?K?N^sh>X$)TlliP z53Nu$#>Er*@&M06((Bu9!mafN?CnNir{3eG+gEZ~;pvQDdcC0u+fLHS>x;o{YP~e) zXEVjD^n-7AB7{@d7TgbJqWO`YP@r$X<-jsb=zC~jy04SSI)7|+A$LQb}H+%1|uoF0X(y#>EO zHILi5=g_Tf$~@8_5o^`$aKmR0Y-c=H@_DBROZr-%+P>Cu`;viTmd*eRuY7~iRky)4 zGZE812**R?AGll79lgyLQRa?(*uL_x+{1U7yyxK%dEyO!yglN&^z*==s;Q}0;ou{t zD;D$U{={f@3H?nc+CL{@z~QNlChRd)WISJv;EEA}bTkZbROV$Er`;XHBJ5~DYN34G zNR?mKb(SmAcaoZJKMG&riDy3OqGjI{p19>1kQ58*?-oJO83pC2UnaGy{Wxt}C$4-I zL3pS)Za6zbD!!P4jh2m2e63s>H&UHvCA7uerKlCW{2sh&yQXEc6SVlD~Ecmf@Z}52}xLkKc=2~RJ zntzdeK&)%?4-1a&n$hsYP)y%j3C@QpfOA+lG+G3(`j`PYp#3b+(ew`7$5KKj1B8@*epvQ9l!sQ=Zx+`THd2+aOrR9lgPKsn0Etix1RteGh3*e z;4W!o%A|cQ0u_C;IBM1(dGohOgs2kOQ2CHnx1LEMQ+G)3>Snp-^tg(BZD_Gf{VO8NB-G05xCi zao;i}G#FvWwqJ~STiaE##UtSX8jINQ{H>f^zY|s`f2SdF{eau+U}^uCp!t4@^wV_; z=$HMX)s{D<|1QQzQ!JHmSKD5Esn2j$+MmS+9UGzh!3EN=q0YPy^1=803tG8n7@nwD zPiZNaNm_LgjE#NJ+_atI;5%^^6&&=>7kqtJ|E;TBc2t(?>@6^HT?|#-bwP#BQcAm> zPqRdhD)8V3Y0&nEba_b&SglWmh9BQ#c~>$o))LIlEy}Wep9H*(I2_e%0eNP`JSdtjYGgH+s-$k~JbNU9SX;ZfB9&W@>< z4Q@4n(z`eeSy~9QufCKllQN+0L>FuluF#*Et~jY@e;#Bx67m-;fm_{zQE@VrtM~tq zPEPCz`xaD(PsEBhrfrlZi|`A~);2MD@j&%J{WLH*v-vSp7o^kUsl z=yv)<)&1f~9(AH44;?>`x~`kAxLdwcUJ|p9CWfbzSC~6)$Q_Eup9iCDtNyqmUJqYi zpMR|1R~>TbES}XK;u$-;4S)K|keOB@4R|t=(lUcdo@&DVZ<|xvsWb51%?W*GbmE2O zi{NQ{Ev(gB{wy{PDwLvQ>|zv4s*I+H;&tXCf!&^q0Pz>&Q`y z*TNOAPGC|me35^7gU_In|cmh6PDEmki)aLkZ1ynj>j1i&m`t za8&jPSSMM3Sppfh{c*w7YAV=2kB-Nfb4KD`X?w4K;Ihz=+nl-yUoG13*D@tk+nI^l zyLQ5zlF>B5g<;aXpRO0%0+keaN4^7=(R;+*?1ak zI@5*69}Q){>e+H|@7{@q1k zGe6T5?F20D6vFi(ZJ}tXBg9Nkpoa2+7^blt`smD%M_a#F+`M=Sg1WZBjR8sW*Zj_C znr6)FR;cm~A1ywcT>?Ef-Bx&vRB+ReAzb`%Fc&)3z)K5bJYHS|GhViX!4H-~-eC`R zk(%g#d%ve;QE0zY70-ygwR4R(TGRyNJm2G_rk2VEYX8xV_uY87-WZX6^Fm%$2bV-Y zc=*QQ!VP|gTFp98WutWlY$^uG$0`hARoscHBci{5`f#!wa(5xTrKwch*$B>13Yz3D zq}m%Jd9Iyc3;x>xhNkTu|f(NX^akGHPA!k z7UKRpOSZk7v8l9RXrBUYCf58E8-Z~Jzth)s{Zck}p(s1$jKxPY%j9dSQIP#g8PANL2=khz)||58hk1AD%B;Jxt)COQc4&>) z7YyR*t-FCn(Q2wz9)kA6TB8#Q2G#t2=;q+Z4ILj*(YTFJ;j98@`V2wc85Y>x*bSeQ zw3qgXRCig;OxW`>hX>ji;Pja_P%Vw6Egct-NnRr~4j9f&2Su$WKMB2{nx0M%2J6Dp#E(T zU5V`nzEORovqoEC$n1K!64j0WYc}WU-=|5_zvszKfs;wRJ8BQguNtEw9AJs7X`#6_ zmriit4B3Jgw@c;1e}1g9GnH#M4aJ9MW@Jz*7}kG{K+mL_UKtj^oSbZI5H7L;zijj! zvYu|K9*1KO%H$rAXC-~XPfT6@4Tf5;CzE{&?+#P@^O(c0C8aw?yjyxnF;2N0|NH~g z3ie0ovvB^kI1#NE7~$`3-`7;IT%yAzsMaOWUD$)$dX zH{?OnRwXXmI0+tKiQtdgc^orSgM9~ogFOd#gXPpl`o`VBXz?g+y($O?A3FhCnpZ(o z<1%vp0(9p(@QkCKIq88J1`X`aV_N*^=<_q+$v0rM{uWxgZcW*~?_ps56L5B$~`*X(+E!3|^FD%$| z0jf1xV=Ga2FqTBV@a`_^QTho?6PAEMfhlhqy<4F&E0G6m`U_?y`docu6XcFe<{4)y zpe6dRY&`Kb9Qk(z+y~#IlfzztbW4Sk8cxv2|I*NOJaDhxuc=GJI4}*$;P{?brJNb- zB*T*m)I1l1R*P-f=HNj2Z>J>QeO(PJDpIg+kGhy`(c$|d$5kzQ1J6f9a=JqJMz5M+ z^2+YKtF0%i#TUq<18ZdK<8AP4=t=0kdl;IT1HXz@aMy1{BZ@U)T1FX^HC?0`N2}qj z@EA-L4o#CvSN3x_2&^4)3yzS48E!uzuAY^sxAk^ zCl>^FRYl&lV2E&8q+z@4KlE_S0B~4yPa34W=LOgQ4rclJT5%P&+1*kM;iw z6IA8_E=B(I@w(jp#tzu6>4#I-Sb}hH(#Yo4{PFSxMfUX?8u?GZ>{bz*(%r;90b($J|y7lW-0*x7zKC2Nepv290iPQ`WTs*w-8-hV@6@9bT0;T7Adgnsi*WIL&8~E#=Poe zZ?sFZ=RWbfsfaqjS&Kq?`&@X*{erM{rUid<4dNNk((&{h1wXrXg`kxcc2b#47Qc;n zU%wFHFNtOQOPx?FJqY!^LeReAt8`I4ms>aNrs&~?(r-Bprrr)_-TM)EYjh!)mbi1@ zjgGu2M{t>3TA}~)Y#gkoMJ1!eCZyoi? z+eyzY2XfcK8IU_5fFI5gSs$g@nj2xE@z2bF!X9OU7GcUP)$?wapl>yV6FEf2%>{nfPG z#1K9oD3X_+%z&&nc35bBm*yT3ew9AyT>L4Evzk@;#QqNG^`N2Z&#pe;bE6g}?zN?X zA#=gJM~UxuaYnUE&!U*)-cT#;tNN2|k6xp7Fm?SE_>!h9JDo6M_3a_}V0R>SKzAa}(#*_5P;+80x!!J%(WCFl(kdgW zdR_9v|SHd2Z|vtR!5AO;?17faFZ zUfd;ETh3QfkkRTawAwd{N2?dY%(Fp!bMt6ga8(EL{zSq3!>%0mqQX~Nuz_Z0D4|iA zBTp=-q`9NJ<9~&_q$@euoJN8dY%m@Me>n)k=14)QYrtnk5`HW`LWh?2VzXp-KL6gB zI~!W@y{a-rsji#Ycg==rV*X2V(TGy;TO^KFOm}chdLa5`I>6;9X zC~`{UhcisMch^9+Ts{-lR<^<4fdTkceWBpISn-o7VSH8NJ(yO`qmxhXNZUq6;`(!^ z>HeI4+}!D{T;-_5wZ3IA#>s{z^_n10pIA#~L!V3Eoo-9>lit(caWmn^)q_+hTtVtP ztoYC|O&a)W4A{So!TmqygW9t#q&ZlRhxI!_@y-2ljoM(Gb2$Sh?CFThZ#bh*julSs z^Ozz^SA$_qD(L^Y0a0CUQO=6D@LVSqxBa?8U7y?GG{FnrJVlEwmv)rmavivH#zOGC zG=OR|)!_N{0F0ev#r#{BdgV01U_WsWJy}d9**X~4U<#4$1+*zq0XLee=xhFWsoE+K zLn6Cy(eK0b>uxESr@VwK`av}JzV`uJl!f zdA9D7i<8LZU3p5qVhP%mZIx6DHF=`1ADSOZ#NSHhe6Z%dtUkSr%y%h4k@7HnvdW5X zY;34{bK(Z5cH9Ofr9Gj@{ULpQSVoDh&XaG)TzFGElrIUt$CG+v9AePLN2$wm(zW?MLSX@nIop#L zU+e*&6{WB!I)TSkBy)G0wwzF@0yAe1;Za`)@Tquv_9~bqeLa7U;>x#^_u`2ZRvaK{ z-JefKhHZi(%ahPu`3JP!g7{Z`J0;hDfsr#FDBf)SK;!z_^CER;Uf=u*hBkKN4=;M* zEV~M*DKD2TcHW^KQ8y@Q^mPh2v;{JRYgofd6#>-nuz?=$YGsP?BB!lAU?XtOShD=5 z0K+#GP<>E?ZyD{RlkG=Cyxw3Qa<&iXhvZ2kJ~T@cBlV6>4BG@t!j;i0M-y|l3zsXT zLFYk9(zMcz@OXy{XZ4v^x#90T-^cHJ(m8cq?v=h3malb|-M5-n*<2jJZx`uuK=(BK zRvN}}g7bfKVkSej$ga8mmKTll;@)+Ec;J8!N2pq%#UCAhKi-C0YX8v&;~Yvi)UVp< z(oOVjK)RE<3DQ(HNbl4i!y9LXm>2Jf6Sdo8?6@)-H2tqU?3oc>8@d~Am^@0d>oj``t(E_q;tC{T)q@cc`Gl;j1Bhi3H--`RfoY@1%qYm-Rr&`X^a@ zOQ*oC-jvwe9Y>#^PlcZMVXlfQ-}@4Z*WMkXOw%;jq36ik|2?G^i|^Fl^B!$i^XHp| z18~8ie*9!)VWrh{Q#6004WI3=($#lL{6u75c-S=Xe0&Lp6fc9sd44!>+c{{X5YO{E zAKw0;wQx)H!%Nk@c%k5$-cWa-QTHM__@g`6_B6n@bcj|aX^FFFHl8efLK}LlQj9rs z2sl~h-`%8A$VB$wTxQjya~`Qprl(#zTE;BJ<|J*@2b(6ob4t=J8#WB1aeCt93Z zc#T8?+0MtaW^!&=!8L??n~yjtEF{YL|gau zc37T#lmhlv!79-cD|pr(%`TLYUP!1SXsfr#7`8%J^%wLiqAN};Z-th zLQuv-snyIPdY{z<^+uN9y+y$neqMk*NkN=fRzs^aHqq7^XPnvB68<`O;EDa>cxO!# z`h~2Q7T@ZGKWFX*JtctEhP8!eHhgx%Bu^pwao(K+_*Fov`N|?9e8qK?C0u{e>c@i^yTJ@gJ z|2Gh;+uLx0U?&_??~3zH%=pl22Uf|8W5Xpj7`fbCs#AXtTb>GTc1%nt@;zwoorNPh599C?MNs&m6Kd*zf{nwBIQKtI`q@K^Gz@e3 zQgax#|NRVNR{Qf08)YtgxL3-L&*1Uz1Ekg8&Qi}W!RUWKo_}7p<-vK&q%K`L;GqNO zscDNHx`tV^R;WLYneeG5+%#31)kO)vhgV7sy7kgL`Gz!TKtH_uER&BL?379> zym^nsYkA;kOP*G9j=qWC<1(uqx6HaI583>f&cEp<2Z%nmuUa>(Z@-*8-TTva7WCqm z#@HCLhc5QtDTQuxl^zUNhvq(-vRlPXxEEDU)%zO7UMQR+7j);2PrBiceYLdri5u9e z2|tbJU_5-rj$dfl;V3D;o7jg*)u;A$+>~;hCD) zGk)&JH|mzr0^JK#+cXzq)<1{%_Es^KOQdcJPvJ+AEd4#j~v|dAf3u+!$Z42A;&g3vU~d@ zpp(@spFa2j7Ae&DZwDE!g_J{OV+Bp~+a;gUNaC;yGodET7qf3xlY{PT=~U}cAUlsD z{rf9Hv#b#&d@Q0FePelAhi=s0_ciP+23~(O15Bg5FziSGRyThH^_U9ZhyDLjUT^_T zc~B17<-<8@V!4zo4dTVuU2y$d6RtU*jK@z2-k??pekqP4BYTPe$Ad2&B%$hk4NhC6 zg#E(XsJA(l)K6)tlG6Xa`h}~gDk-U}i|_tFF9Ri1N*H0SWcJ?n= zn0vDKJ_CQt0>#OG1!gA`vo@c2_xaL^y-8hrEiE}G-PPX0mz`w)u9VZ5U z-sZ0nJMQF(Tj}(_>(^4fHsk;1`hB~5c=`N4UVlx!8PD?(&riDX^^f#^Zz4aj+DT@%i|K{>V62E{(vsg%lT{R7^<7ORog!df zdL%x2)E$q#>%;c;{RAVz6gBE?sAcChQV&TNc>@*Nd{Rf`XCITQyU0^sT`RQ}+(fMn zn`PaTD=XE{_moyI>q>*NNBbUVswVr=*HogGSoOHmQhH??j_Sp!{7h|`A~n+m4JRq{ zxl@|hD9&b@-;(g)>>+}A(h9${{!E=VG}7MxecmyVd#L5h<&PFZZ=EMJX0RK7%TL5J z+4^*_QDg#}W>bT|V2A2lrYjReSZ~~{sx2pDc)R9S+MF4~!%9kJ=kdLHoR|;FeXY$K z*L1{x0|O{&LVrx0q>qhVhH<4C;xy+%T0Kd@fy9jeY~rWNa)F`@fH`cLGa^dH(_=h7j3Fe($Ps;(+lJt>x+vN4Yz z9)JgRMGe&~8q3B1{I~T#IMvjLcbb1Ex7=Vn@2kqu8V>lXNu4#?4r0d$O_KI)1?LsX zn3hpp^?It{J0-htP52z?*`LRx)5;eW5n@&?K2)A^LIo$)HN)d)UhvX840|{&uJV?j zOINz(;F*n1s5Gyl@`P#`;c>$e2Tmge0eYv=I zYgp;O21*_JQHSN(Y;6+3{!#+QSKW}cFKG#Odox*yp8sym<*>}=0kv$YrWGjRF#BpS zTR4s~o?Md>S{!)9B{$eu@shfWJ>$TCJHYTmLe=>>_sMID$c7%i01GVp;N@Xa`1^`8 zsoWU}d#p{^?Y$LV(|issXv~XDvm^s+NB$B#lPvdI@TG*|IAW%!oOu@T)Rq|Dc`1aJ zjt{Q#+B1X~76?wqz9GEYSM0;)&8HZhAxNPSitiCoV7z@bMHan+a*YdcZBP=`>@=&& zpBjKM`Rk!N%&sc*;1aqX+*#`O_BoYIdkmlED9~-(Hj!aXVXYK>9MWPzlTG?!)MquQ zxt)gAceAUudG@4V-+n-JzJaK7>Y(f#4W%98v8--3Ep!t+kptf75M<3s|LuX2;NG0R zJ`fXcb!T03Q;6_O;|=a=a+6?N7nC$h!}e()XKUl?1*;+D)lE8cJQ6?K*H(?yya>G? ziT->+Yu*?%63g&w(71=k$iFB-u)|HU=bIAB4a&qgF_UeiX~rR)T;+K;45>WH0*}uxBsU*( zRGGD%7S5`t<{ihO$v%R|CY*sc=ep7i!3|m;-7Kq_&4#HHN6VKAHPLjnA?xHP3%9#A z=^WT6?Ju}PH-1ipt!s4!uSfW8f)xM?Zo?Z0J}1M&VKI9XP-IY!9Xpv*%yrN z4i~88#|)@NbHO(l%nQWKSh$`8CR_>Tu_jr#xIqu*91FqPt+wbhWEWg04~9m};+WN{ z9JR*{6SFUazHutH1leKG<#=9qbO1*u9EW~CFVg+jVSGVw$;y`eqZ4jJF-4=i@GeGWdjV7_GG{4xDy$%H7)5susQUrm^>jgy5ZMjuj z(R=>So|2Xu(W;}RG+$+b;*j@#7|$-O>-i5(i(OX0;##Oq?@#+ShjIE{AO02Thn_R@ z>9laPB=-9T`sMfO`xI@i&^ksuq&sYN*aym*B+s3Gfr89mLg%-J99wgw>UfLDZT?N- zrosb~#bpVXkBsKpm#^XB?q71nP4PFz6;N)66;f&U_R`|hjd0LmH&uz=fq}gV-+8uN ztbdDrhhHB}**W*fBREsCYYIe*{v&vbi|8X%g<|G^uVMBMI~u*!4=TC}HesYC>js>Y zCYR*m&^Q-J`kp!gdFZNh;IAsybgE%4C09^)v)oD9hTnc#m6sJ ziJESIDtmShYQEo>Tpo(7N$M2E6T1xFSl$2$o9ld3dTgQK)~;L*A>43Ghll=q27zz; z^Mv@D8U%bP(?t%9WUnq=dt;7%7tgK>N$pM9sxJL_9dgfr)Ckjvth!^X_tP^7ku268)oFiUU)j?RLKpX2!Qc|E-K)q?%3kJG6)>I&sk zncU#@>)76sCuH3@4cA&U$V$yCsCbxgwG9!zqNU&A>FG*1uwR=Gu`!Na*_+k7dSKl| z6*PA~4d3U7q2-o*h*W+<(S~N6{vd^S#a)CAo9;qrqXzFj^@?;_->2n8g59$62Cc|P zT%f%IoE&$9e}^_`wp5d!UDCvLXNO?%Aq_NA$wixUm%(~gUX{cKIO|3o-MSksha6Ypvj^jNYK6$JbkV|;fCT(7 zraL~Hmx2$b^v2q!o!QO3gw_rTz+p`(oShei4n={S`!5F9y9aZ>x&l~!cLSuR=Hh$* z`PBHJHM^fXLbFBhwkEp>E{qd7-7&x6@kJFba&%+&Q)}St>~9opVZ%CaTyU+(9lxIY zOIj7So{ngA#Cf$!{GIItNWdk~wwu7fKPi$S-5M;*l;97`@4vtudSB$-!*-(TM+U zIY|ZcgcHLjnV-gdm6y#cRk(c)$EP>1Ly!HEtbK7cOsE(IY76z)5k-D@#zAuPY@}fE z^Mx~SN$y+?PE&u7^8R}GY}!b3OxMf10s?VTpK>WED3Zp4HCmXZlG)W`P|&7MZf@I# zXFuF7TX!B$qjm@29%QJ_e*l6qNrnWkK{n>w!Hupq(m?dwz#L z9`nIoqP9ZX3Ji44W2;};xJ2|9+Fbqu1zw-P**%iaU)TosZz)S#mGY=+k}9~R1i*o> zrkI*HR&og)id&v0!S|c7bRlH9)EwHCCv*{<%%|OXN|~q;{!wS`#M|=8SYJ%GxJ;uA zSIF0bhtYxkw_wh?xfC-fii;{w$-B-ZV9PaQI`}}H6fd*ok|9Geb3nEHv-ft0a-Jvn z$UPL{!y~ISy#!yRtvSBKK<;(bgddz}iwC>guD3bpuxReF^qAGWg&3X>i1B9~jS=4;~Q%r8R3p$lNnQKAj)HQQGD>SNb8iqn$2qs#^lnV}{|2 zk0$Kotio5aAJE6@!Msk)FAZH{i+>KckaMOvKFf*X6;C(Pg1k1=XV^bjv-F%`d&jcT zQDxN3?aK#8T@-tvOmuX+1wlS#a?giGTr}@5v>aUk`d`n$rb#wvF+=cC)KukB7xqKN zALLEF=ZJY1efIBAOKVgrWapfGk}Q-kd#5$ji?uLFKNFml6M3w?5}BW>rVBM$xT%!%Ip2zWeJ)e85AUl6B zDqoo;-Z*mu`tcshxr3n?`6iXJJfm5z!&DLTSK-k7!8H5vaE#_>uea47 zB$gIU?D~W4O!uQb30`;D3d4B%&^cCA9oxw&u4vGstC1*%Ohyephuf4Jf`_X23&sy( zXvvU6LiTKa7u)V3KIOca#FUYUohCG32ZJ>$|1hu5a^$zm3-W&z@GhVgQ@oZy`k|bU z(P~X^zU#Lo5zW;**D_`O^LbvaX^Gj1hZ zoTdtcBe#pH7j$r*20tG(l(XZjBIz?f{|#97fz5PSAyiLXRTHUcf)BbaD`3xj=Zf73XLBCm$49qNPYH_Kqu4!z+q4=Xlq>gi_h0RgY#DlZuGPU2gz$M0*8dopmJ8i~2 z@{C<>Y+>`CZ(>_-o`q5wE3$VUKpRt@o$1Cj7HfD@*a*?I@3gJhF~Eaf+PoDmN1Ye1 z@I5S_-7$+V#<(Q(E&JzpP@F%{3nj-syLzwOA=HU~U6rRl5}u9M#CHe1>HC@p_f zM7&eLv<-GV+iC-|B;O%P(TT0JoFTbhq#|COa~j(J45cU*MTR`%bZf9Lj zQkvMZuTnTIE(`@9J^ZwF7PHe;AxoR((C4}(HRPQHgZYn`hmH@M_t6MP$tUvao;7{D z0dVQ~a#7QBBkVMpK!zG)vCw`sfQdmx>BoN8)*&r3&1Ujy}WUP;-tJst?%0o=goAX^|7@9o9atVXgQBd zwRLWUx^pUIq3tLe!P_(hT3~??G z#jRdIpYQVXq9}`QMwY0oxJPUb>=KMrtua*B6xO)`?OoPgQ+Z!XTq@TDZ$JHj?`u@Z zp!yv1agU*&$uXew&7KN2oDyHpPr~ED7ulPQ-OOieFu%ipWvQEW2+MV8>8IB)!LnBD zR_TPdT^e*sryb^Py&^iU3@0cy!`l-S@o+#s+t)OZmL494FGfVuYu!a)xK_fxZQvP% zQL;3y%mZC|@fq-1TO85&39jBs#C?B#=|^P<-R^Y{G%rO%fzC}x92P^j?DAODZ$oNZ z3cOF<;VRJ&qgmd2*oK>jS=sI`*7?x6M#(LbDX9 zY_N^9j0YBtLyZ|ebbe(w8=<5{r<=D3ilhB-=_&446~^Kg8BZJ^dW#i}mBo;oeW>;1 zWV)DMR-LgS5yMMN(4)Porns*mhUTmm%56CZSML^N9jkMFb6A!Z>{iSqA4re@axHWgZK>KnP`gYck+AsEp z@+?!DJmH<>s@7UIBgF(4{|Z8R11D^#^Te^U%sG4O0eEO8k@SX9wEa^y+6}x7?c6;+ zVMM2}X2bxdl=#rXUnH_4{vPZl&vT93SXM>0qGS7QDmYcb{A2(Udils@`;;->$~*!Tnc znaQ+8@N~K|eU4kpmW{Q*QyFJPqlki<)sAu0=W&8yoD`0`Zx?|2r$#{~+Y^>J6tJJe zUP6z|48bz&E$g>Qo2D7J3n^CNs98RW6waN5kCsxTWceck6Y6fkuoa%HcYYRCR?QY?9OVA}{xF%-o)F!JY z7l?6=!=^`W^iSIYr+g>&an}Zz=EV2a1;5!tTkdk0r-hlVk=*AO#`!ygiSNp=CtZtP z4|0Ww)@`u*P;dGoTwzIf{ph%<2maaXK#x-R9`V{CaZZs7rQX-Y8H-!k-$!8>@+A`O zm4k&N3MpuF)}6MW>4JF~Th3f>9*rWj3&+~NfRAh#6`!@iC!4w3szVumcAjTX?UsOg zx&ri32_oBJ{7h4xj0Q+af{oOplM%t0hp47woR%8n6oU54koG>9z!-x8K)iJXfx8aGw z9MHbGmPKilg0Jp)nCEMV^OgGG#DW+mQ3<27a~;{b9d3BQd>~d@at=aWF{FJ~VJ4x2 zsb!BM248y$j-ym@R`XeQE3aHUSjl;XF?N_UY9-X`&t>fB3g&FPUhL`W60I$4C1u|G zL>Yx-TUjy%`#7K9Pdu5A!c#GA=QFs~`4yN=JPSRShLito7uvdhK}3TC zYd`vs^;D?TY_Q6t!jgWN`KJoL+i{-!FFiUNbPa63=d%P8XG{qhj%SAyL*|5ZG&PRE zM*CCH&t)F`)LR2HB1+iNr+3-xBa`qzb|B~QM`Nb+RB~CAO|9u^%ynrN-84R2(`q%0 zl=@)@_FaL1RHqPM_Y+3I+#rW3st2me&4$BHldTi#ycD zP)S<8xQ%oEHdXw94L?(8p`Qgh&3goOUI8TYJ`F2mK=8h;2Wl6h(7tsy8ypzQ<~z!Q zMdBQ`Npl)2F1;xFTquIgFJ0lo8#N3p4TAjLKni<{;NG#9%zwEQ+j?~od{f>E6DD!T zMR>6IV$lSwWV*Q5+>Q>V_hP<&e5dYehEY-%Bo)DyOmBKCgOgP(>Pai?=?tXSf7Pr_ zhJpQ&04lq~ow$MN7}Bnc4GG_CZXQaYx0AL*K#86>ZrC>V?o<)$Wit*}9UVzU2QpCG zd>gxP)QOhOJjis%4-^*d-UIIxg2>CwkYxECNbVzl&Ci+yqlE|IlE*XF>qezmC#6m! zOUKf+3GT>#Pm=8ESu2$GmEecBoFSl5#lBmOp?+%iRJ0-q-3F_prpiZ{Sl-4omWNVS zDnGMkEoN)i$HPQH9`Am(VtXnc2+4M1Db6>NsVBXJw66osytGWAx}m1@YUo(p@Ngh~ znW6@-@{Tje`A}0Cd`CIw##GyYgQSBd?3)|ZZ~G!`c9<4*Cz&QSd3Gq7KGK#nsR%AVJ- z-O^Sx$%iw9ZoX#Wsn*Oocnt2>H=_7^8p8V%<*e63Rh+b&z^e_l_*QE@}yiNXgcI@g=ot6G!6e!x*JMQm4$I+iQ&dE&XEn)i-_QBkf#+y=%} z{G^i2x#&+a5}v>By&blC88YWf#NPbp$NLoq>^Q%J*CusI+{b9UI#&ndyxi@=jRD43 zmb4F<xna^HZ>SVu|S0lZDxxqiLvRC{3^)%3}V6Q$vh5gxN*m06uSx=&wNvQ|$3X zpG;hD;K%l@kQZxujltmKF&NHg*n>2pFlkX6EDq{}e;T83(Edn-Q`SO6e-lc7e4ee@ zEJr3+T43rAGrFx4MDf!s(PptAOntQ*I?Nfn<#G|`Rn-Z3a(>k0yogD^)4?Mqv1oEN zj#kf8gPr~SDS1y9Gure_*wxpcwK>Ss)YEsE;z{m)2xovRKEvU5d1|-N!$!#fntxzB z`^&%YKZcgGhFs2;Jsg7_Lt^Nmyb@-esbYoCi4&Q+X%4sv zYX;Rxax*ol_jF^Np5M;8wD~SNIY1D!yeP=anwA74(70Z!n1=U#cI0*(&Ew3 zdiJ(N{Oa|C-Tv_$ewMniTi1@U2S=>1q(FwOcGU`(%l&BbE;pKH84XR1FJO#97~V)z zrMi^|gu(Y~+2#xN;y!B${yQB=`73!>aYdYXIW(TNndO5_qdYb|p&G&ETo zQRQ$~v~pHPx3^a%YDdQ6?UksH^AM8)NxVsa9X>8yJFrZpz`T*cyd9WLR_3_t3q#a zaK=Y5{xr`E{tBqcI%Y_P7iKF(xjPrzB%60QQ@ImQX6DP)tBCimKoO~IWZqv@{Z zUorAR7Fvdc!|W}qg{bLDH1z8Y-W}!HI2MlUTwe=`ttRY2xe0owo@8@5lmAbmEIV)L zDXy0b#w`o{A*^O2i}nrX=X(=D;nXP5AEQlcFL}`zx3w(bKLs?<>xI|+xtru@B(39Y zvomXk(god0X0g+T{y86Ji{k!5*JFOZFxw=gBrDQ#^K7`m*|DBDhauh~qEC9!81+eXuB@0m0LaRykH21A9 zG@H3oR!I^oOm$-qw|!^&pR<{wHG|~(2x_$wq3-$5nvr*0=+)8zw8&<^7|`uW5zEy` zg`X)LeUi!9K7yLpdZFd5RAHu9ml$We0wUhVAZA??yBfTiTi>T*g^@97e^AAFT@!Io zmlIQ2YK5c2>|o(oZK5^fu-BbZ7_0F~Tu;Mk`FP&h&?%HiE*aqMKkp@qcc-&zLmQm% z*otZX(ZsZw>mh5)P;z-PSo~?d2X@7#)9smtn8&%L!!I_9=aLPD>`kUPL@|}0bNXTE z0duyI|NHUPJ4G8!M@f;41O1+%h70aBvOCtV;Ynr_yAUj)0sn3?Y8lEJ47d~MN(faS zl&&%I^{2K)(x5Wy6zE$1C;n5OjB%we#V<auv?Y(FdGtqv4IkLet?_J^`$e!c8AU@~ z`7XBJlPNFOriiBm`*z)7i38Tv#5<+Yi`WXVIoZRcZ#j{+-EzJ|N}-5uO-%VZ6h0P7 zsBqhJX0+_I=zevDcthnNlhz!Dzgo25%9{v$<8F^r-(CS-KW$hr`xlGiouSexbKzIs z2>jBXMuz2Q*}_8xD5yRaemACKcd!q7jWA^g^v}Srs)^#h-&$j z&%n%&tJ%d6KEvg5c?PrG4g5pHc^}YrEx;lZXi;Yo!+dvAt8-+iwkHOZ% zI#jx#4({sknMc+EA;K;O_8*k6wIA(-`I?I$>h>Xaxu^oBDrkXhRZmT|T$?y0#+=Si z$)F=C&T#l|Cf)opj(66w$nO>J+VeiPFY6X%THsLIBe?t%u2p@yzpYt(d$e7Ix=PLZP@2p6QPR@BH_|{YUO#_k0DbPC5@g zifO1;nTB-*Ozf#Jpb_ho>CKY)Fe$Vb2Alc`x0WiiyOKiob?#c15$l!M-H1Qn?P!8h zjXT(f$dznzY;TgNOk^&<{GmgkLfrD5XDK;9w@_^)nQe%M)EQ%i%bUC4#PUBd@8}P4 zGJD80<}GEdgI%#(?hMoDX@;TamNJdmk$9?Ww`5I|2W=a`xwdkF;P@pI4d&M}S;-#Q z|Hloz_C1F+sp`xy_LF$%oh98FZ9*zBgYeYg64rR&F0?ETh6%F|LDK~nCXV53x~6?F z@qK|<_R3B4I@iEB=L6*}Ye0X^9-a^>5`*KCig~W zlUk(zq*_`pAdy-;i$@%W4r-$RT&VkgTqJ$+^eeu-jP+T}~I+G;Y*CZHQ;8y!s z`g_8QPBtuNpIk(-Oh#2`%@4tyoDq~^GnLM*FNB0HGqPI}#1u7Ca8-~3Ee%`@I)Uqj zGyR;2oxu$=qn zM_-3Tuba#)NDBwf(M9d=RbU$8K<94tBlXAW;trcBc>Rw(-aOO~X8gyQ$lg=&{7x@; zvMCk1T7Sc)As%o&WV@i7d7qh`RAlpHM+tp6(`9D=tE{2g1OE-RVmH&BKsiel%Q&ye zZ7E}!+L`#R^|erNfoFhv`&0XV?po#NwVQ*svfigpf%l?lnhlQFaL;eziR@&*4Xz1cgy1Kp-s%a$ZA&QL6gCY78&q{3kBo+p%v(b~=!2WY1j7v-oGeh*-%vql+DAzSBrDPt9Yez4}qxs%LE9AqzZr z(G{o5TGq(Vh@lbr8Tj9SItYy`p=O8%UTTdZ+X=EL{bE0i{O|$>9AC!sA z!ZS_(SjvG=OyD_%QWabJ@xg-h!z5(jpvT|$T*(G~?K3HTU1?#2AIj9MV)aQ*m^#6n zKI#^*oC;Z55~&2cWXzafunnF#&$CytV`$nLWvqJOOze~zbsPHAihZ9TI^Pz1;z#4K z+hO?8IGRj`Y-KlpJ%B@hn}w5V&je}NJ`|PO6?6#_qqw?4JI@qbTxClmj#y^vY_XEA|0|j$6g$m58=1_ke;&|eccu( zm~DE);-%Ah=h>R7=KqA{k0#?KHdHE^U|B=*wNgv*8@SgU(lGPgor z=y2bWY_3nK5|Z4^$jLbCT7~HgepfeXi;|` z)~~>fg`D`!WC~;H;jx2ocIHCSI&lOP-*Dyb;b8C@>_{`cOlgBw2CUncK?9U~llhsW zu05y%n~x5lEB~VL@&{wesY;}Gsq4XJc{3a1Rlzy$u@rx+7p$6{N~N3u_T4mZ`xhzYi1)|^i|DB~bY*SX4m z9PPtiHCAyRXO5(Oaw0W;ehyv#jBx()DRgdbC}wMyfc*(s{8W3Kg`Y@+#}akgGFX`` zW~$&egWqDa`8&ZTRU7Y^aF^IyRh&{kki4p1!Rpo+3SXy+yZR=v5=5`*X|d$e z9XZK-gPX#pZVQ_6GM4=rF_scOhrp+)>J)j}3Bz{ug=2LJXreQWHBOCYN?p9ad%2W# ze^I5=+y(Bt-yWw;A1A!JQ7YNzY=}e755=GF!cq2%I+p(KshNFy6uqp{N6DXm?D$A$ ztaJRvcSZ4}qM1(1c*f~lRU7E_so-ptJ~-CB3oIJ#VBgDD?pc(HZkY z_lR%v{;QFMljzgE97c_B#|ds0q(0po3!8z4+eNY>{mIlK4nn^JmzjP|shA`;93FF) zORMe|7S!?`q8<;Y>-yoWdRH?4otT7D8>7(tp%%J_o`u`|yt_AL09O4*8{(?z=55f+4Ih@e+86CO(8|ErhviYgm?COsSSf{MP60C!$wILo|-E2r^D&qRt3AnVw7kmc4 zga7;*SR2pyrS_f%1~Fa~?_o~zH;UQZ_@@VC7D+d*6F@H{=W4^ITEWm^6Yj)iWv3MU7q-1NG9{4rdfTg3H^HHBKi*imf;;cm_qSY`%TvzA?ZVr~Tiu0ca z-Fgo%{cgFAPTm0{Lo(SR#YuQAVzVI6c|TeOSK#**75p6Ujh)s3ILjrLOt~A+>(OJD zW8Mev-WY-h9+k4$W5cNX>3FgBm>x4Oudn&FpSwE;PNZn3sWkJz3HY(RSoFR97_512 z&h&RbYzkdj)11cnJ;mq5QMtF6Pi{R(WHzyg8FyKVj1SgYhQiG8$!HPniNR&u3wH~} zW@7``zFMokuCah^JyKY| zNDc>S>fr+KWn%dbHSv1VR=D%0gUPRYCEU7WkE{9oEaFZ$(YwnM@E<{M9&6#-nntlZ zZ#*?_yDMmCso_0?J{Yms85|>r(JKS)pP#-2zJL6WsR!DKc2Sl>=()3k=}kB6by*tw z8jYsqazS)2s0*UUDWj`X3+q^)1g4?WS=+aj;I#QDcxVLRA~!Xbd`gGb>^>&oDnII7 z-VX79U$ME<1$=(hA5ZoFB>t&+2gZ2`G{nN3mdR)1$dA$RZPFLkvs;hN-WguA;M+dt z?;%SErB!iTr~#c{Gk|Vq_MyKoO2jy}u?_m$iHn0=dJ(%<0UNHZ$J!xN!!Z)6)pmxUf zn%qN56rV8^k7m4redm&C7H5Wib8dy#MgY(ZhC(CSHf)Fp5LMP9gC67ME@?ZF4 zhEyEATBL$f!~3Aqm~o(E;UM0)cmsr6OgJ6n&<`%FUY&F(0=_%cy zWw{Q1Pvtv(pJbSMNDa2kX=EmWF*NLb9Of)i2VsW_Hnbr1JuidG2F7?hTM-92^`h0o z_X(-51wnr87TEn;jXvM3V9Ayn*lguos4;TEGv%>Vc+M6d`r097yP#sgD?Sq&fp1|N zn{zXq!ixhaelE|v&hcX@*}K4e{b;gSJ_Sqn|7Od_j1XK}C!&M2E`=C1uzv&k;PYwf z!lv!XG^6&CxW{NZ{IZQka@mNte zP<-CHj7b-+XL=P$SU2zqyEN%V4YbZ>|19r8sl<+E*Sup-Ym;b^PcX3^IpUSY>(~OF zM-XBaPy3Za$Yt3KVRInwiQnyyL%!IGy?+<8bHk>BU4IuE!@2Y2_M>RZ$4FRX8;Lbp zh;znHAzyI_g@os^#V4Zh(x*IO(Sn!a)C$gD;b%}QoF&FxhUrCm4?nRT7q#*2fT8rp z|7u)?XOZSXkOlZK@*@ZB6o$}+~VqK_AKc)H-7c)nA9CX4y1YuJN` zec)?njGJ>)1jh~fc+5Hit6P_WWN8`fJLp7HlI^kYw4cmsYdF-;mSy3^S=2{w5OseZ zN6W&$u}>%dz@z@=IQ`-hs5dBLB`Y^^@0lK3AiG`+tklLL|0;IrP7`z4<%o(~O4z() ze&)H~z_uDZXUo21Bk1z{tDXs+56obFQcjBhroV!-J_E?+Oc1^f*&^CFcSxE(`C?b> zUZy`M8xnk@@xt&SxTY$DwpmRjlg<#bOlX8H|9yd2F%B0e&xRjs{=zh&KP>Eho2^Ss zMI;Fqf7bxcuQE z8^1Rm$3Gc`&F`{6Q|ANxxgSWieO80~kuBi+I)?1(%_RS#v+zv4I$f*@AZ6}vI(4aA z*n1$84eJ$&JFLu5eVq!q)vHmjQ$0fG#3^(@d=4o*TeZpVFMC)zi59Hg&z9d9PQg(X z?90KI@Wb0&;+N-*V=q2ndLhF}p<9;3`HHB%d_SxBFNp>Y7>05$*22RSdsyJtBfNC{ z=Q4O(98TVSza}@No$1Nmg8wlX+GIj0`?wP377xU8eHOAgi(j#I6-$Lf>G@FdJQ3UU zq_H_U0fm%nFfV8V%v;)<>@zok{6}pX6d1^=vy-q$EN3?90jPSl6W(7^#0KuiS!H#H z%}5)AAw840*X1uv32g3CLCXl#-a-uS#)*s5ynZyai7z#exj5@!Y*?V&&@uwon*}mroZ$b8J7n zI<|uuCQTsptrf-uU58i9hKd5+s4;dKn`7h(M{DzI{={jc=~M>{Z&9UV-%i7nP%V^g zse*?=GIT^K5{WbL+d6b%?(4&B+K~IuoU#kXStgRbn*#329YAmTzJ}TJ|1gE!N%(4d z09@TSfCciM^o8nCGG9@d{?ig?b{4YqSnhU-<4)AE1!7_7d~m8e&*J9q zgv7b=V4iCy&U`wJy?)%^weWJCuzAT@_V-3OW-CULOph~n89xTcH;%Zf_ zS}=|s+66^Qo5brA9*S(32@Sd&2o>gm=w|g+nD!`NbSyp&r;FCZ8oNM9dgKPzN3Ip0 z^BiGjqbh#g6eYeZjlk<^<~S(N1Wz8UVe{TCXYSg=g^_nvFf1&U-j`?75nnkxT+SUt z-czWl_&!@ynT2HzgN4QzC&4Q{kWJ(Mvk_N&q5ENP;iHifteYc23u!x2(v`*&2Sd>3 zSS!=np#btlhP3d>U&xkBgL63tSj@Oic=ZbKWBXYs(&Cv2%p}X}^Wo&srC>O)51iQ0 zBCh|G&iak)O*`vv!(g62Im;5LSAsKOkRGbr{DdK~OJK8It5`R6Cft6JOouxYY4RTa zJzH%9J6D;}o|o4p2UQJdv_~v1iRnxKGE8XX)O_)R_IozL&kY{fdNP}Zq13(TH;d08 zcD&Y?26mriw?z%Ia#x@bO$}5tE)f^xA7y>qxAOC%0#=YB%BwA9=M)aIOz#F3qZy4E zHA$pe;fM=fDdNAW`$Ug!F9`bPhQa1TpnKR?A<8HaEt)gP@YzomKT|^4?|eymh#Bi? z3&Hc>GTEQg1>m?_fg~EA+4zHj6d=43lI}T^2Y)}g1Mab3j^#|Q{36p1Tq3Nnm!g9G zwy@IhCR}mXC;JlK^RTJpdH)dla=0G;Ya&>!6_1tghT=IslihQN`_%*IFl7rvT>sGt z`^pM52}@XQ=OC1ADuK-{VXQfF01LS`3U4%TW=|70L1>II^UbwD|4?_F>@A^lJ$e*a zGZObVjG(RkjH&C|0$9t6;rgv?^3w(Sde})E{_&--)jN~oyUgK)T@uNZc#wIvB7c~C zgroKm{P$a(o`vrRS?@X!hw3v|n<3cil?6rXXkgzPK4kFq4I5wk5p)+E6}DZhX6Bz) zL%@^_7&ah=BHp{R`Txn{+T*9iN|{}v?L_Wj%k*a^t1mG5vO>6e$q-*&DrCt`(e&iA zJRU;+*))p7Nsb0&94AdzVjL+KO*jYOu~68;`!rAL;jRTip1wAE&kMu|>$5QZ?;vuJ zRIqu{Zy{;7Cf+idD|U@PCBA$if~vg*d--7*Q`fQ(-Q+gFA1B^jJDV>U-|bINFT94w zXXL4&O@JAee)N3UZti1|kdjOg4cgV0iX#oMYFL!G+uaehc$Q)9lQ-;DixQqz;IDnQ zJl+oIVu3YvOf7*s;W-y@rIbIdi9O7`7LLUSWi60drpiW*j%Mk4Cxk(B2U5h)Js_Q; zj5*-}Y{N($8sR#T6o$POemJL*?$Mp1(Pr-8ovH&u$vLs_8EM+`PX))cx5Ch^wm9!| zFlp``3Ui%}=xOs2w#vyL&&L^1spCZW*)1V9_={k=*be)QPKSyrIKuWTB$0b znD0uE#W^)Oi9PJ~%f-TLvoxCdIEj9%PG|FsXFz3~3%gqH$hKve)Aosj@%_mhXn3GU zhXz%%MQa|wsQz-~N9J`%P9BB_cn0p({ITG%R1YJij|!VhxI@X%1Wy}j z!LeX-dfxhk9p88x*6XOy#|9HD&^^Wi2OSp%|88dsf|IGPI);KjhM>XsXnb?K6CSCr zg;S>=!+gm_XnmVT`zv~po>c~((YB92lGcw)yr zFasNy!{PPfWV3~E@sB=Sa0w*ob0(;=O^ME2W1w=9KQHE77lOX$3T#pa^_4WUNV6X- zaJv&r$vFidbobT-*xKR(`#Ki-SR42E_rt^UJxP-cp*bxEEqWt8|Cxjr)LL2Pwj&~0 zDpK+6WA2s+&O?8(b3KjuuAF zmqLf*Ly&Xrq5auSVOi=k*ZeViL8mr>MwlD|&D(=1HO3Fb6f^FQRD_3zUqj^SVqr%5 zS9p|J3~MzwJ7Us*(7@zzMpH6cUVA24*BOKY$T2};vJ#Uz& z!!GgKnOIDD($4f1euK%g8c4f6gdF;&Q%tKXth@SwrM8%|ftxzm^v%BDUYgAJf?Ii1 zI+HdOmLQ?9w|H~iBvmPxYHJZbd_}BjnKgreJ-rm90`TvWbgvurE7Skts zDBN}O2%mA!eb0zi_vlW0_ZfZny7zR>bC)@FZG?4zf(MeN=Y`$w9u2XM?l<;m|pBY zVYsK~`So|*r#k-~VXU;@JwR=t=l}RiXDuIjF6M9le_#J^@88Le1El`H-v6wox2!5* zkEAU>gZQnIS@&PVlr6u4j)pX}cto(>&4qMsLp~);i>H8(%TVe=ExSK?5AD9MO5+ne zDPd|N2H)9(5fgH0yj3g!U#2AYWZgb@0Pq1 zM~|FNuWTN(s@Y3x=1sDow$1e*Xl|n1O|F!?*a;`pc~Q|wW&BaX`w3;U&@OT_3(A&5 z<=JlNeyvTAds9Tam#C24#V^dXUX|VNE+FT056E%30GhjZp`61CYRQ<0*C*sqm-rBAofXPIBjZDs)KjBJ6t zkz4Roem@qWvWuL1{3yg(4)euKOj|vj<^DGnHBKD{jlCsMxO6nlUA7M=ST-?#_x`w} zv;ea!#-mHp4(v%x#l^<9qJP3Ywj*FSWp?IZ*p*eN_fQVguB{NQhn)~huIECPq>NQd za~78LZ>U>!7OwHxZM6JG`dwYkCiVIN))(%zuB2Ftl#915dSbyVk zoYZF_mL+)Lx1Q}_y>KX1J(vV(@7lycUkpiuJAQV*-;LQ*-m{L%mAE?U0MA`9Rwcbt z@YcP>yk|dW1y7cd``0vZ?>CDQR(oK}hQ%Z``Lye)^(L74gU?ICcB0ly9a_G49iFq-&bDff;VbI-h-HJ@udX@Y-f9n!AWHS89->T?K|jD%0yH%Q2_i5@(%! z#OgOYqEy#viU^Cq#Y0XC*Hq=eT~?lSGB%5CUFIx%=Q}8Te}c7V*rDBuJe;>npu%e{ zLfN&SV4dbDG&2pHFs1??1@P=>qYRq*S~B;Ir8J)Br%#1iLVWdhtgZ{hftpg_*{tjff+dR+-B0b znu|Z#jjm zd;)csMx*(D>QAIEzci-n!9gxU#C?2VKYo}DOzRr|a_*<}d)?zE#xDk+#O ziKE|-{V88zG+N($EsUqf!l{FrAneqkS4T!*YCtXxI{`R;u@TBLJ8Y>e5ULK>iY<#~ zia`##RP}r(9J=C5!%a2tk^B^_^L~KL{0%Z^Da)>2xaPKlXHZCEfR1f|GU#(1MRdJ^$T!Q!x_@7q2C|tO{ydUO`gk zm)XVIGK%e9K~MXwK&c;-n4LogDL1FH1e(EJv@}zh9w^sVQtPyp=xzoja_98jDBWEE%SRs*^wdmEq@jax{!;?m3vsr z)2G5V=?bcvypJX+$ab!IApl{$k)s;SCPFFkQq;9hNae*nH+ly7T z{b7>BNtQHk0EG>(q*ntUuD`7>s_l*hcb^#icz-+3pXuP84_oN$t3G(ja}N4HYlo_(Gcm2{ zsVKESR@8C0F4lGwi`Kaw?49#Qaq;_G!mpT>^eBuoBl5Das%wi-)XxQku(7S3O^3Jc$F7s{4;K?x2-jr@L8abpGM8JFUo*7YQH_kcvowq0^1eCE7b~wE!oiLp@`dA=7zT_I7u6G7 zhQNyo$t6=2=~*;?S}-a9WKSCsqDk-AR50&P98U02c_{DPE z{uy9sn?*~`W?}}{cQ4=NP4|U5;@e#uGk(hqEO}T0GEybvRQ^`xs#_KeYRZzZHz{aX zEzdO7+LBM_^w4Z?A88sbr7FuAq~4NEuT-Md}HcENw>>B8M}e$3)ndxhBI83#fYqc%@|o+Dkl z+9WM$DZSqMnrIbSqODsIZhR|=rwsyRb}yu`D6@!noLyx z1Y=BN2NkmIy?B3LJWBppgh@eLAur?v%;Oiqlegb#R_G3Fx)u(>p<~R6RzKJuU4|Vq zQcz2opiqArO|x7M8f%0g{QZA4zicy|{caLEE^)$7Cklb590X0le|YET6o73}0hqd{ zpks(5PEPNGg-_keJ|qn({bUw-oblZl}Y8%TOcbFqF$!(--rlNX~?O zFl(Lx-_6Q#9;QHtj3V9mH3lbKyH1CY50L zR~I_AmHT^s$)%oO`$<}60=0b8O?=~nF>p;jNZhK##z7+(o?1!LY>RM<^IY__Xdq86 zi{kcQCD8Ud0N%RK1kbhGm{U`vdHeZV_$$X4>rzu<;Xl@^sF;pbnY6>2QA$Q9Q8~k!)XjH z={$%dN2;K^GYy_JHIuGX2j+h3F5oXKMAgg_IJ9{jHV<#b`*mSB#j1i5<5Y})7Y7Y0 z6|iMc8a@PPpirusKvc&MBl9FcMJt6i)~&(*NA^&-nvc$0$I$WOER;#)Tu?!_5K|!_ zpOzkgw`+$;e489h>N@}pSqe1LNeJip=Ys9=eN@Fyi0n&S3p>6{#@W6n@aUT5=>Lp! zspsb4E43W(*W(et>7~%L>o?UJT}#tCK9MJ$F|<5%K18Z612gC*yjUrmure6mE=eG% zX1OS-wG2nSw_~Hz26(cnhxE0r03ksdHcp&~r5meprdA+I7OaMFnFYA~!aTIvcmxE7 zN6^!A4an>b#1{tcl$o=i#%E^&uX>0&_-}?^L3S{-Rvwxv<@MOOUQSz3h))@I3Y`xlggDf^mJ1x4h~GGLZQw)-Bne~m%+IxXv^)~`sFsqGYm-1r zyb$|n42HvE?7I7l_K#_SZL%DT}!ss@Qe6*yr;PMd0MfuQ9{b`&LH^z`jFH{|qmwyL8TF?; zYZr9gum|hP2dPk>3gi20DO^{M#P0?faB4eaBcs0^9vB}7=K&ki)w-297o4PnTZ6G) z{W!i}9fw(JX=K$%AOws5Wi|?P=k{F2lo@U%{oZ!yRILCnqLzV{7&i?rw!-C;EJ4*d z3c60l@O<+YK-bl8)Qx*Ss;p0CDwoROklcJ2)5ry9uD89()fL6<7K8J~57bv$8!IMc4bDaFq;GaCOmm7xH`!ev z!y1!OuCEzBXExE@I~mU0hy$0-R2Vwx33o47fQGXvxQ&&e%2#iiv2Pal|MoM>=g&pM zb*mY-`-e$ivpK4`1i~bGnDb9&fh!w}UCnCrdXzQtY)fIUP(E&+nhiUgX5#QJU;Ll* zC(T9^4IxGD@QHi<|2==2ZT5f1U*}G}=KY^u|8sp;zLgJaahLZ$um98assAs0cxwxD z3(HyD^{M^u`S33OP2@`Z4%l{2l%MIfA1qvhV8Ht}fA$SakmvRnUn~9+`_X4)|F$%^ zQI`vkz8;2;)s^_`OCXxxlg2omlWbLr1&05vfgIgFP`vL2vRVzCwC&4;&D*J zF>}Z+TOyu%03C+I__Z0GtQ6+}ta!xnfw=d#^N8%N81B9O&+Gs6{{C0~J@@`B=UV>X zo&Rw^^8fw!Ki3iTTxY}ofcO9B^?$mKIsc#E^K7$OR@`-%|L=d#|2savg`F$UZtO5D z%QnT0d>h_{YnK_5Yi^*PbqKQ8^fT8b%piBeIutedN>0sOf=Bz7;BzMvGzb%lc7j%nG-CIfTl8_V701tbj$>DnaqF}zOkYn>P7V68&x)ujb(GT&$gEu^cT#DH~{ z8GSs|LvQU2g1?(A;MO@ExKpgkH?lD2@7Gr1ODx>Y-}-qoKl+0^f9tiC{CUkIAocDy zbVip$a^fk_%I$*HvS%QHmk0IgL*Umv3LfKIpxP`OL}KD_ZuKX$mG8xrHm=9uuZwq8 zkiIgjrk2M$aLw;DJUh1v;<^i9wZ#Q^`TirA%y5QYHDNfUrw^xQ{)IZ_N}}gjK#eB; zC0zS}(rRl=J|l&ZLPlu7b0U|DMIh8b6qH}wxa$W2n3-{wH86Eu8 zxRN~Ue@F|i6d~R@h9%|+C_7P^KOEl!Id|tNb}`~DcqhB zfR@>nsL-xMy+e0mN_#n48JglG69x}&^d&RWSzKGEfuhq?VAmCMj+yX`{tS~N8q&h} zJQ9gb_7iGcK0@$cE>3aQ#C?-O@Y}5tye6i_EGgAM?RCW{WgmydqqBH&ca&gxa|xln z&h*igrDU=A6f9qtfEFX;=zG;ve3|6JOxT|RBF|1T=LAoP_~Ii7)SU{%uOTyM|3D|Z^7=l8r(6Cz?&xJmtU$=9N65%eUEA}P%bx93m&1Qkm zhO@+CYcPmK$l^BrVXE(&Lh~j3i2KrXT<;l*LL4h3O3nyr$PF~NdyGf#AH`@dIW+Ej zh~H-`(;u{%wkuwtX8MWPUi_Q#EN@}n)#cP}TQuJP+lAHb^YHk(OH^Z;9ewBJLk<5e zCHPn25DK=sYl!4?S3$q+_P#M@B{Ycy!is8>7ALQ+7;ELyW_>bGC z?+JJWTv82w0`2kd)u0JQV1!LwyKv0G3J;`(o4v-}~r=yVX;mlwm` zdAYb_a|EOOOA6l%-6ZpuM`6+rOAIi}r#{#Hcq=;=<9ma}M0{&3eQlNjqa!vT_W1^R zyqwD-mFG}7>qP3V+aUP5`XPCrU1X!QyMvC%acgOLbt=84jo#`mBrmVMp#?|vaM@r3 zeG;aEG5?*yIf8CHzg`~q4iuvNbdJ;iCIJtIT*HW|XUUdMBm6J=3l%6-6Dy?wE{i$? z-GzH>g5xieRoq^u>OX&^9h|#Y_&rUx3!}Lz2`GPC16?@2$UEN@jGeKEHWU=WXov>n zeCwiHj=0hv$5%jB#Gy+fBXUre?F-MvBguMEW&V=4nZWu_hqUSP`~`O^;MYhCu~q5@ zo1^wHv4!JdMD3uCEv^{7<_vzl$io6haqfO`7Y$t-XvsEbo3Ls1ST`XBzS$*0_%&Jn zfeTTvN^%~Vzy3bVk@*Whquzq@+g8wZoQ_B4xs!hOA^l@!f|p~S(vNP}sCn25D^c&;Zs6Hlg=&9u?XX0IharD1TZ48imAAut6N$rBCvTgUjH-!g@lo zTB*)VD|qRjh`cu@D7Y#LquD()nZJ_GU&{xF`$aV5!gTy`m@vn7`jF3K|LBBStBGsL zQmWoZ;9W1JE7Jmr^t46@I`)TSJ;s2uP8sj|?0D$zzW`^m#{^oQHV`-D1!L|jsrz^d zxF~#;-pVwEDw#$m@cJ5zoK}Uc)85gVpsRSWMGh^rmy!Clf%v3v8%orlz{Eu=)W<9z zBRx_v#r7l*cv z^-?RDljFx|ua*H^<#Nchbr%yhT@pH4^N6hn!#O>Y1S=h$QcVdB{1E$&22ITC;ZL^$6LZuJd{{ z8oQ0}qwnEs<$3t*t1&I^=JMTZOVQZp25r5{`EX00;<91}OI&B;O@w0`3bXfm>eL9tr$ z_yEUH=#;{ny(?kSFK;La<$79YbivnpHjVf=NK;dafXNR5e>essXL^{^x0;}~t^)q* zABP^FNhnq=hq<%Pp#9Q#d@UM|TP#20B3C(-vwMn?3+r*k>ss6}-iVF6GnLJG^8tDD z8Zh(a9Xx!2MV(eDc3>eZngRr;!~}Vly^qvM&n0;K?VS@LK3N*7L>)F4-=@x)x7ov%Z{0Ju^$T zb4eM>cwEM1lYgSoqfhjcejrZywuKIpoNHBF&g}s{jF4k* zj!tAXcet{59F*Akksooltp*$Dq0QDes<3uCLhP;+>gMQmt335FR(G@7bs}(%kGNtyJG{W zg>)v$bvAJn!|pm)MCXRd9irMl&$UmgxP~T*{(gQxS=T? zq0S7e51L~1`vR)|?GXOkz6%#5M_`c_i#_8c@$-oo+|wY91F;*>aceP(+^?l8rds3e zJ5BgB<0?8?AF!IVxdtPR8gZYC3bE!mgdW55arVqTy6GeK-UgY4&E`bD9OE}2z{>f|z3fAnV-z*+3XqnKqO zLDPE{v3pekjPZHJ0}n4^9Ow=S8EXWCa%?WjnQNOL6idzX@Ti(k+s=e(JR z;icr_nnG|_$Y)HW%Za<_L|D3`mrT;_5)_DSfXnMPVkP=O3SS*V>y8Mn`*94YyE157 z|A>z3eol4ahhQLVEuN3hB7Z75;J{jz(mF9BukL|5A@yk18%LweLvi-03zR3h3O5K4 zhvF78)^;jbzrKn_!v!koh?sJl>!3XE=j|HXh8nLDQDM9kac-(XE%!*?mZ{0uSN9+3 zy3WU0nFd75HIwdnt_xq~?~(kY<=mn@0To4W(4&(kpyuf|s<=Re)i=t=3FaZVJAXEs z-l)dlGGDCJddwW>oClBPUnTYwB+~>k`3$-^;#?7K#)b(%)xiGSl?0C)1NP=qV#D+W)_bVSO{Df@pJ1>tWHQ@rkb+&d z11KT;2xG?T(C5QHe6UH5UAj#H4LQ!}aKlY3eW^_w9b9S9xFI}o@+Y3+&XD(3r_dFL zeL-(WJsp+!!#nWyA}wxl2Wt41w(U7YhbP6thAjqc_UdPNBUG9-KE&;#q;KMwVl++^ zm1p(SWZC!U8c_P$Omes2UrX~*T!7LlL+j0m4Jqa5@McK=HRaose z{Wuuq&Tbi5z$(vwjq@+vLH@+$?6K^Ncs-*F6CzfztFk26h2^u^IVV>0i#CnI1Roc^ zu(1ihyiH-ZgOy0_Xz#=B$f9oM-Sg`eNLOcxAXP|QKn?` zCFZZkRP=o6gY|E#(fXAxHpd;KMJ11!r=|_~bY2kdZt|zz?L|20pCIETG7)q-_YHDZ@pShCk+fvw=?w{}i3=q705)-c@KGgc0zR_0-QOe=F*D+Qfu zSEKN~yY$@X85HDtaXF4AI{nie9J^tO|9nbO?N1JUIOj5oeLjWDrtGJK50i24q2pLE za#gTdvkqCOJSv==!aRR#hh>Wwq54QNc2u3krIAsLiOd%o`qhQ`b-NlDiO)i(sc%TJ zVHP_2_u}@q@wm)pBi@`Sgyk*Q@xY}%ntU9vFU$((8^>T@-VLtLw;L-LJ;aZ^9_+7Q zkJ&pVal*Y}{ONQJc{dMYpMg0WGHB1f2)}_F9-Ky|{QD`!BQ@wHKv)%V@$3XIWyOrDNb5T&SoluZh$t-d>~9UtBOfn)>Wov)-Kq;V+s_E_W+f& zec1gyk4mR_n7`)*+w2Kqk1kz9Rt)2&XdE)`;5pPa>dJUxMCFL>zSlZvv7Yp`in zC!Sot1|Oun!n=zupzsk%cCyC>R63qcC11(Xoia%{eqkc9mhr*S$Elc+p=NWfKZPlp zXMu~J4w4l=bI5+VAWS$BOH8Zux#z)E+UJ``)Q)i9S>sjo^+7eUD!p|-@P$yW3tX5wQ?Kulbf!JQYDlZRFYM5IugKAhGI%egb`b?uwsQiBx##+-5d zJw-prVT~ogINgM0#*_K|L%VRE)jX2x62~lE;Y$qn7UIvsWXeg8@ch>Tln4^T;&2(( zBeD+Xo#j}3eb!iiW(Iz~(1Mn~4sx8z41DN5g&taz&D%d&8r=n(L2X|*owT{1p5z#< zKiaRtTh~DFi+o2OZ8k-p1w!mWT@m&{MGJ<$EaTiR73l37Kxf3XVDb5ref6B5*p~gJkPiq3N4tywJBb)c#O5ib^=vSCo< zE4<4og$r)A*n9atN}rNpBhxmZ_V2^EJ^Km9_6V^TWme+Df8*J6_GL)?vbp!%i4m3$ zXgYTm`tW#?Kzp47-pH_K);zMtf;&rDspMtshJ&`OyxpE1m}0{&5TD70 zTxi9J!E%mkcM@AxiD7iiSKQ+D65sf|$KvUPp50`@`8R^`LoV0lIX{T9YcsG>V+`pt z1)OSfovNB0qV`;VL_u7gE|PviPj!pIcKZ@;IXjEa<+__o&5a<%cP7uV(}XB=9p<<< z&#}^d0?Y2wXFquAu&-j$(Cd*B+g6>6=Pj)8lGjXJ5+XigtxX83c&qv33 z0&Z=g3O7X!u%lW7vaMu5QfxJvI}|VjKLTiuY#`&RmVg;wwo>W)J5lxvpTyrPfK9o6 zkg_U-+>0uNRxc;AeEcS6cvOev{j-PTf;y@&`7wSmQp4t?Y~0%EPT7mvbb*K{syPX> zA||4^lPljIpQ-{wegP1s`Ie-Qn+I6_o1Qlp;^nB?VbhsFo6Yre=u_8FG9}O&wH1mm z>){#{T+_g=BrdD1{Dz)W1iU=m0;!=2@A{T2Oi0o?yiu~wW|d_SCVswx-`k$gRhpPd z>e9GO=;wpHv)vJN?Sm_nIgHpm;UT?tnxWZtCK!L4J3m;Kj>J`pjH&LDH-?T?l7GF#W!Ug?@ zX8}jB(#B~cBsppN)f=LD0a6WVm3Hn?{NXJ6(+<%7t>X`tJ zdpZA}fda{Vznm_8qe#Pseo>!k+dzWbH|$7Xh0;GKLybeLO~;2rG)PAr0zNJRk7#9_&nd?*|D65F`_(P8^Q{L-0%-ajU?i7hYiZ|@n@oYsM3yHwcsB}d3kjbyU) zjxs$Hxf)J*H^J$^M0h^>nRe;8l1~TqX~)x2GLg3gdXBAvOWG45GIWGA)U{EbkpoId z=t0VGB%Ho8EC~3l2)_$7!QL#0=yV<=eun@mr@%5OT%?0d2hesB)F8%uzlUV)^Uir}Er z5+IB36N7C7WI)Fs_6(k-lMP;ycRIVkqJB0AChi2aTn%tjUq^o!IKb^Zj{OnfW8G%G z7sEUbquH5S`bDgnr+G&K3S7U_?dF!m%4!kM#xeui2Rdl?{N0d!?lM#wxWR&l>D+ho z64mi(5DeDHKy!@}_D#7@6SVV4o#F&sP$GvpUaJ|eq?>|mw>IEC)gx$m*BX6=HK6zk z=Z(A4$GhP0kt}zQMp4sVdc`h+EL0TGGP@iKBH<*=B7>)%u+?U%ml5$RtHtK=im-Mh zmafv7fvK~8kkKsx$SOXgx5{MDI!+CePsWiAJ-1N)djW5eSO_`IC=i*HGn_ZCkgVU< zhP8U-sG>yi+;MIEJ2immz;%L%92<1gP{xTQk^Z?CZF9)T99IY;Y~~EP(i2;_p5;l7 z)!NO?^(UXCNy@VH^{t+J;PaDVFqp+oW zF(X}92zN{7!xKFZ#y&B?=F+uFh`i7Ssxno)AKHF!D=rBRR(62MhlL>jW*KgcR>8^L z1=ONWj?0$j;J=e~v^}ep@oQ8>b@g>5f3H5*A$?B%cyrFC8J&w)UJU@$Wp z$9FXxrIXf8!^^L&ryuF>Zy(9piXc3;=N+x`NT9Qm?TDa0 z4tLypz*{%*8gnlDIqo+4Lw9&slC}x6@#c@)cqdYqrkC{4uXjgi*QVt(w`U=oJkIc< z?K)|Kz(Vk^vyI%c@`l~#ImX?H9J$mlOvl3RLf|b&__U-3Mi-t0VN+qA%AOp?xLXr{ zKDESj8v(v^pN)xu+c4APA(}K&Mj^wFV;&pfo6DXsRZf(@Ut9q358O$ORz26#Y=*Hn z&!By3Fzhm|BAYLNBcifb$WM;hXq`Qte4ZYJQ~q-N($PKSxcO}|kUg0g_CBCdd%67P zOdd`$osRnzeCT(Hw^aDIJpRf^qjQqKk$%$#YJm?({VsW|=zD6Dy;H#Z@#{8IwKAEW z0&!e@CzpBCI{|DCuyp0`-PEGk2xq^Ezz|6le5`7Y_XHZ$BK8)^)87D_d@eH%I*A!GleD~-85NYR>eX$c>}5Ub1B)^-G6wkDBv|7!8_Lsv{Y)P%PZ zHF#y(vq7r(1QQ!@hxz3j4q(D%#WpXcj%i}x%;n|d&3UlSItN?g|53?+5&Ee%1x<~8 zaGAsoobShVYaLn{Jm@Ox5hC_nh zDSVXPGXeiwrj7K(0sObT6f+EO)2(x^V&nZV2s9VtJSIiNY6TCfibNVe$;ATCBNjSE z>TK3alW3MH}9(MIDTTtZy1=l2lN}1V8JU1GU^{qe5WUYUN|Ks!*_TtZLI+BpYjxD zasBM9SvbSWo0iFkqRZGYS#)y}HJv4mB6GWm&0o$pxc53Yw|xR#hl62s$riZ%_Y_=u zcN)G6ZH4syIb3d1muKQ|ge+1z0jA5VAd_>v+bG_GrYFuen>Tz z@wf@vRb2mKmj-`8%@v%l=z)*-cgS1EK$+ezz`SE{w`d(YOsgQWTyC)2a3&~^jS#Cq z5a=Yop%dZ{Lig;Y;I#cEeKec}8DXBZQ7VqeaeZEI=Py(!Did}!NJ7=R@p$8wJ=i`~ z!Dk#kqPy1eZr|GqqklU|_|!<)d*>Xeh^dg12PElaRp=flg1tLbv2@In`SbN9YCOAuS1v}OrT$Vhmk{tmE|lW+s&JGlSK!Ys{SFI? zocP97Ui=4UPJ9>f0SKNvo!@oUnQweSnqPS~2%Y!0Fm~Q4)G2lu?*7roldtliLvo$W zrj`y8t9hJGv6}@o+j<%PAU8Xm(@&Pv#4*D@8!@D+fXR%W4A63&=dPs!h41G=_kkdI zz5N}rzSl`wc5Q;7phD7RGDv*;pU}ILy|AQ?;|7`z(!Z4+IMn-?4oy0WuB|3GYUe_| zq^F@qdnlc-NEzN7S0u^4reud$5Xm{vN<(sW!QQhLWXICs#OJvrx5U)bZvbjdv_ZdN!G zN9M+%=%yt&H`o>bOibckyvKPZ>TZ)cDh7BzWGQNwZ$iiDwvCo`=L#B zH5v4|N~I;Y;Ki%a_$5*2R^0IXaF!i(3svJM3|hHACbJcfnxj zR#-ih53_aCdFS_W-%+=Pa8HpX`;O+3CqE8Bo8?@(c;7olzU(c7FAHFebTl{n91pJx zQ=zp%l4#6PCgkrzc(=y@-)=tv=GOOM&f_ZP@EKZa^JuBZ z8+bWTE4crq0U}3r_!Hf}faa%*kdZi@e~>57ANQjj)X%8#XP=hlix_ut{gQ2T@yF*l z>N=a+nvCE^i%wMHSn>L+&S2&AgBU&BfzMl<@Z!`QBEEJpTn`K7^&7q6$#?hD$2T|N z{P_`Br6!6`bW|_(a_8T3J67<Jbr?%45}b5J9MG$`XOdyZZ)q>@EV%enZk#Q zQvBsYI{f~FxlnIr1X~V-L4eg{{v>T{XloLI4aZM{enkfCH5$)%8axBh6Q%hU=}%$t zehPX42Vm#i&%}6XrOkRXQMkY5353a>0zai{(z)p&xO21GJF=BLp5iP>6R_~NZ!!}& zw39rux({Y*wJ>#dGYpp(!i%t8IIOOXHv4MH-@75aU%QNmzJ(I(<1+9@MJJhvzE${P zMK-!UmE_mfarwZ-FTk)|nm_oa7qUETL3m3D)Mgwd6X&jh{~iQ$&zMA5|Dl1j{}J%g zD+?jONeo_{t0U`5-;>&;TXby73A#CNnmq91K*??LDBJWh!?p8KQhjen5)@zoP;Ep)Mw#($u&6BUzDCL48ZuT zDso_wDE_j&OJ+rIS)R^&@Y}rrR(h$E&;<)%rjIea{I(uehIT_o{Si2=Sj2ns<}tN! z$tMaII_WHS2Hur@KrSy!BuQKA>E1&o7-lub{F$uEe~@|w{%oGW@9aMdkFC`Bzt8^R z{MQD2zgz|WN!RaCk@Swnjl|<0hZDF@V}ME>PUkXVt5K+DfChbcqi@yYvBj<%_Q?xD zhTTt+Ci?&^;~e2nMlpP|t%o(Au0YmK36Q#{0a~Y5QP+zv=!ZQL*s-IRl2KV)93%}< z0u8vLQHb`_f{?>P;aD}-`zqGQ;5r^8b6&GpzBXDlt-1?rri=c7N`HRUO?JeMW@sW?!ND!4?#RjPZmfD?z5qdTcz9M}%G8 zk)FeIaHmWw$y9VCO|zu1Fd_vchh~Bl*V)nbZiL!^k1*!Y1e!+T{29|l_=iHCLw;Ze zSbe+*LAGrIkqH-x+MYsK*7yu|zj+1EH*wsM|F|B2)HU)@|M1*Cs|&~+lVt9^sU(YJ zHuL&UFGHWB>GZ;x3N+VQg@St}*rK_Nha6WZdes>D-mQRMe{Io7hH!r99H#ZwMs7xO z4s0hUaXptNxT_ZgT`uP2Ma@03Rci_7KGcN;uYI}CXfx+je*o3|e5m^Uh{%?=fFpN5 zycph0N={z{`<*4Q%-bFUHIzVI_#y~re1b%~hK;i*NJ}W;uv{Iw%pSn) z)iyiY-IgiG+Cj~ z?k(y^PO*jS%CDpOLj$(``FG3`yNTNr7O`iwU!Y#jUyiwDz~(x5kuwV8K)2ik%v3iK zaf9yyv!A1MVMhX_d<}zhvH{pQC4*||Ji}4z2)rVng5x~&@W{f4IAge-^JPlmvbl}8 zAn_sbvs{KQ^_Hl;eTVfvwe^g2&oVNull!hHj%T!XFN2@MicD&y7s|?-W6Ab<9NU&b zXNouA*Zp>=x3riyORWN*j_1SYATQb|kO1MHBGQ_tO!tmnB$<-NWW|EbFmHtOe80WH z&C8lFShE>N2QHy^v=n>U`#mZiNWztuJn(g{2-~q;lGROqj6-vd;{(-Ne4i-H<{c`< zuKuMM%e#z+5>}$2swHIA9^kDh6s5j~XW?kWP5LaJ>o~Su;hoyG4cu+Ma{PA!` zmgQU{a<4_!6S~N{s7iEdvX}kacEybl=PU5c~Z#(R}0py?v#S z;TZ)BB;#;%_B66jM2+`w(OsHno=Q%6>>vmCB{6iyEgDemNA69KV&7W*!@%HFd{>`} zbN!0Y)9N0oe(AuZEq$0#6@|+~R3IW!nXYYF3Q8Nt6LEM>e>`=9E8A4*`253UQRGxi zS2~TWR~2Hji9CB&>=u4)9>?~)n!|3`^9(J7Y5#ZTrz9{&95TnfE=&!&?I^%E`QMw~ZUmo3!I=VpJg%4uS%~NQMrv!l+ zo6v)KAh`P}5O=y&bO@*b?XO!ga^5!GF_@co@H3^w?J$D2ARrzKF~5CB!> z49wrP8sefvAm>&dVH>ka!7(9}s_=z{my@A+u`D)TktN;=$MB@bYMkdio!kf|{^eKSc^{q+;;TRSo=?KEOPz;r7jz$z-uj6oY!1 z@1r#tk5MBigw9*p4!lk2kXUsPm?hI7la~T39p-^|^#u~M@*D(-%Y){?86p|tiK{|W z$--_w8slz9Molk}kP#PbDVRaOtQ6)kCJ7M5%wkR@?q+_?6{6$9&cL;te8`o`p^J~K z)t8y{HIePdjYCURyt!92_H!-jNXxsFE3&m%r49LUY*(572 zmkj*aONUNfrNg;W6|bVl6~SjvESE?cP}4B3&$d|!?@TcW{{hEc=4HW-O+H$Ne4>a zKjxeSH{sp6rEq?_H>edoqH`7Q&~9^cIO2Mg?z$97A9&@##~;p&$>9oU9(zY8CA5*6 zC1Qjxz5t$T`~+|F_b@6S2c^qTfvipucx}E1uU@&K%E(ewJ0(XUdBGbp$;K6At@u%T0oR)G6nY9w^38TZfXxktL`AM@K^e`4& ztECTTP31kjeF~%Q?7$!t-J{p=J?|RbyZayWO{W^u+DC1M6!l<> zl_E_RE~cL&;xX`nFXp9|@>abT!=1#5;fbv0ZT&9BF;L&L!9{cx8k>gXhQH$tg(2nY*$pb(%PTsb8;;#c+VK%m&N`VLY?bJ*m21XeP zj_>!6Hi(X6m&nx6B;gy_*QG{$p;)d9^JGEKU7}D z7ri}LaOovAsTs${8E4|f;Bm0Qs|J5e$iw;J!=x_q3OO)vl$OzW();opQOMDwcGW*= zUL%(S9Yy-&r~*#>E6>g9y|HF2lU%Q;Md{{Scz(-#J;+WeG^@eQcC=NY`4v;f~|7h!sL9@-Vku==%axY{BW zJtU=hFHQc@{tNZ^Xoe_Wd!+@Nifeh@{N?oamZ_knx*K+y9;6O(yTEkR6gC`v0M64D zaieHIPAJaB3CqT@$q$5B-`v9}%gq=R#U%)Fy zvuYWhITwS+u6{>3-AKpRiQX3)T_!%gDl?R%UQ}~h(b@;Cr?*i&14_oVV;KsyU=2vV3-j;rd z3p^>l+{$rDC)~i=;!eCgb1`qW_Z@2g@B+=WH9<&;M%_K9asJ;a)|a>ap)>C15IL*2 zbn9F%To8R4w_Z<1^Q$&&WE_|Aw7rA9TFuB#o6c@{)P*5O)Y;6MI@}m|9p9=vzzd}Z z=%pE)S0vmCcL+}+Q#W0~n^P~^bgsCLT66;z8B3s};Tb%q{{nw=>xQ2TZs6EkPkQT^ z01JZx&~KUz`Inx6pCTp+q;yTOE#MP1?^J}AIhyo(+%$5nZ#i1a?xzJ^xcCgQ%89_;QBmkOWfcyW1mK6nI^zGs3V$t1z_OXA(BtVw z^5(M(de}tc+5sg@$^1)Cr#4~&t;3x=%W)3Op}`M5(D-2jN({ZCDdwtJsPzK9jYZh8 zGc&2Xh&t{W7U0*xVo1wKfKy_8dVNPFXtc#aYS9Z~m3)HComtDYeq9C|+h0)gR(FBI z=RaheNFQzGKF>PuXP~!(HrOt|Mb4j`fRQi$GE2@S(D7%}IX@uB-PltH@`JJvTjdBX zKfe%hW;*ZMKSk&@cuNHmezYl{p}eiX$X~tf)b1zuJg-EeItEa^Q;t9F@?`#7{W<)S zT`jOIH5(%5%;jf0-GOUvH(_087OW|HiW3Z+aNOH77?&l&CjH39?5P8IBf%W6=Gma5 z{ufkU)Pc2ebvPQHj8adl@#}CfZWw2W&$KeI{iQt42~0&1CX}plK1ntnF$BI`1U0xl z8Al47@nhs6R2tokv;IcndX)g2G-r@bm?+Ll1+JzgLkcu{U_2)6nufnef1-MvFnh-0 zIAt0?knRK0@HeTGXgjHcgvl;kw{bU5X1*={FxTch>F+S|iws*`F3+wTIgK_o?OX=y z0p4~j#s7z+GmWe1{n~hwMomhTN`^>@3~AW++LDxrpQuoXQY4v^5Y44YqcljRIhtuW z_d19M6-5*>MU;w!QpRWhpLe}GpZ3{j?{#16y1ti@R}rQwy~0WUM@XuxCzSc$Ai+j` zMDF4$aNn59Gdt=6ZCR&yIgx2mq3O5ejp`L5OlFFyb4bJMJd>PJAw1!>lYrw!afcMAzEprtcd0%Ij zlPI@sIP+i{F~T~gf7UCSQ8^XXLZK8L)5PWSstm^P?~vOY{d)fl)br zY>Ede)Q02ZjsX15WiURUon08d$!bzEZXdv(zZJHMF z&yBr8#e>uMm9r6hRW$kSKg!T>as+vIuaDNs*HYzeyI^+GLaZ8X=4s!Wi$<@O!=i8Q zkR5FSQn?QA)z4ZkVehU%UGat;ZS3~XrSJ1eOT&LX`T&JIax*>Jgre%nv zSPZ{ZZNQvSd4B24LEL*-jJ=hS%yAymVL?U%=`Lyo+thq+pU?|udfvda*epmmAO$yq zlL%k^FDafkNc3N~Qh7;ZxOvZ=rH z^8ed;J?((ToDnz}Xb<^wWm%28FL)Q5IG&c_dE%ev1}iGE8QG8G zX6phI#yMW^o*hi^n@E`RT@8NfoxpyJN7O#@0@nvi8C7zM%-pjCK0Y)e{5m<%HeCyE z-%W<1buW1vg?3kXL5yy-e96g%_Z`JrJn6 zC7U%Q&L&pRWCLHGL8JG&ytc$p6ce0)5z2}fp*uS} zF~o3l08E-W6Ps#(5EFZCxV5mBJl30v-kJ!Si9;mPEFPW-%E3P>0Z(S&D4cUww|zJgA9(} zYo-HP#LjkepSTCtTkL=h>oo(__p?Vw7YW@-wg}dO;2keASCtcIC+I?h+IdFcd4+LRS`rLZ zHbDKqY&f|56o_lfu~J8EVUJ=qyz-Q1O(L4XQ(KzcvI`+2cMF(Rac@YAa4%KgT}!qo z#=zf&?bNW%0-jon(YDJ+Yewyj=vCe&V3vk~yF?dZ>mq9|>Lw5+-$BOFGK^F&jX=A0We#0iv%XVBXRAw zVddTlU>F+>y^h@c+%!rmybQtRyfp}qq(J?jkC3w-0M7b>Oj8utbH0$m6-$WKqYU6B zRdW0|e|Z0?1{PhFVRu>$kPYKM$axSW;kUiHeSH;iJ*Wu>U5bhK181B&TNu}5h2!s@ z^O$lforX@;qd&NwwEXuEklmup%XHa}D#kI`!s_6+wnFAmeHAtrpWwQ;>TuGg9bAOe z5V!T6K|0hzpZqGJW0REVxotz#mGhUk9uS4?d9l3o6fc}0cLEfSaIw4~Zw!ckjJDGY zv3gDxZs)w{_w;6Bn8H^)7{&3(!CJB=7ET}uj#$LZ#)#^_LAj3Eb}<65<7{57)> zH+MWj9qEZowJG;H%9@I)hLt$cOcdjD_F_m{FM_!sG2!^|8p?fi{~i%MkU!hlvg8WB z-kwfYZ&HM1IVb5$qdE8sW?-6VF#t!MB_p&Fj*DY23b411_{3hasg2ix}?f{a@e=#h^hyt0a)RIyl} z#D{pnvx5^bW7|iX9(kJ#EQy9z&5amus*RK9^>cdsa$365i<^Hx(3bTdG1NW{E!O_# zvRqP-_WdZ#zP2Bdr_2D$_7I*+-<~3nA^W2_z2{&=k*SbmCVfRF@m2IxqHeOmhpg znZ$_?A`BXw(8Oy!NW zANN|a7r0W@{YrR2DH&%)Yp}tIa_qtK zv+QSeS9b9AEOsoymp!Iu!-njaWv%ptSUH8u_{nVrnv0iU_sn0Y=;Me+XVm%Tft_fe zdj(}OJCOfqK3laynHA!+;nx}B?AA}tATH#=buQ*XTlh?NB-9Iv$J|guhsC)IAK{+3 z5_~Fy_%Bfq-=)Rk*BO?tPm&G1#&JZif>g?bE_qkMcae#;NS z6KihMPe!hIW>F|U;254!EhV`0{x7WmlS0o=Hs!rnPr+m770|xY0jHm}!2>1XbR=+u zX8XP+IZZt@Y}tMK?gRsO<(H95T(9Wh&m=16tAI|sj`5!SyhXXw1o0XvFc$R<0TK7h zj9>69oL#V;v^-bBFV_LqpEH6wL3gTfOUNkebqMwSI|hH&YrxD|%B*qXHPCQ<4*JV| zpjo~GK8$_lxcqhCrP7R&do*zR8!q$SFagW@P4R@b7@l6`j5jj!(Q%tNKYZym)bZ}Y zCXU~8v%M0Zq}HL|lX%={whf_sBUP(Qz(?1;pl0edI5IDfyi<^eKJ9XH^z$R0!0s2^ zepG^nCHjL}vNnC~mP;zR2Kj{(TzOX_45@3TDNW}WVMll_uFeS~5<6UJOr8U$^Q(`27}_(OCHbKWyqkORoEK zjjlBrcW`!BwcDqzw88WbhlO)gHYVj}umNOvp!DdD7>7@mJX|Vo+X+ znkpe=pKd<+BeIqJNPUQ`awWa!6_0awarZv0#wF8#QQ6<8pt|BT6@GDtS88^Za|NG%(HP2yqI2Z~XJ6Cr^E;C*2t_yblV=k3#812yM%J!@ zX?OQS%s*i&s+0{a^S+YS$@*Y0-c8)*r{MD2@y4Fc6&RlGMZbUAMLj=7VWE5zHbyVQ z#Z~L^>h^5(54%QFWF_(Q!ENX(Q;)J2XX2R&6__0lY2Gp<^p-Hpva+zNX)IIf!9yGThyC3OtIk5-i#iM(?$J>)o$KoDIQ47ZSq^0x- z@bLcsG>_2+9No7X=L}ZTSIq>yyi@6d^j(ex zouQ7Qn(#BKosvsc3?lJ_?{ix5w*|k1#$yQP(Q}C}7!}JxGCp)2Joe2dWsl3jC)*X8 z)=meQa~qC?{)e&;v{8S>LOMLNfa?-0#?_*a$=_LAccal2+*m&ieZTv1_o4~%Elx7E zcd9szuK-`UzofGI7f_&mBMNU2#&I<-?3C%@xw?$gYt}#L`BXj9yMto__I}{)x-^yU z)2l|4I1O6;LyF9({7n}5aQ&DKB6#DjE@+l{;GQX>Ag26}2rV|@EmTQBH`zRD9Yp!l7SIL%D}r+>bQ#%ZBgbSDL~N3*f? zz7Q(BDnymJ2B`3JIcBM~lbt^=<1w!-SZ;L?#e~jt8fh!JHK>7N<6BXx+yNg32jIh$ zS6F%VH}&(+#-HofaUQIfSW_s&4|UDKj}Klm9_I4jIq3Oy4c!t8NYR$w zo}+_G`V-K7SdyGLSB*R4<5836Y1IB^GxiV6Kx;J(lF8|d|2|pQyzuAI#8-PzRpkgy z43Wom8*1pV?>XGP`X#MWl}FR1JGmUw1dN+wO-kHZ;`se0?Huc-n^xL!EXsV+YvxTC zT4=%YeQ&8#&Iah~o&r{-vmr-V7Tj!-c|N1tiGR8v+*#!SBH9!9i^Y9$Eypu-aXX6! zXU^j6)sL{m`!HTuAjDT~mE|v%<(Sc0#XR?0E9fnmHgxFUga@ZDqvv0Dph5$|`Erd^ z|4$Lwt`v)J9z|hR#2I?RS`*#k9O;f_QFtow3W{{T!O9t5$mt~?iQ=O&dfc|3IJ~go zx)K#g=+RVqZ^#gK%=11TvlRM~A=!T<5)9B@roAi^g3hr>v#EJ>pnDTfS|9y!k z7n+0V4^1sPOIHxK3pm0b+ZO8kZ7R5m9EI+jy>K#;pzqUa8W_F;u34K>6Gj$tyZ;$A z5A8vZO@+J+K>?7}4@4s;E&Sa1p0qX0!)<>u=$HCGBo5l>_nO6^cyfpy>+(T=|3s2M z#|eM@i=o+7D!6yoYhG#6WZWE}!#sEzfMJI?PQq9WUN6hX|NNEs_~H=91^kL%?LJ_@ zxl!D>y%|-6`OMyRqvY`avLajL$XEF-w8ff$-n;+6>VqM|sk89-tR#Oh{wjW69ggPp zF1WeB6rs}(PbR&_8mD z;Czdgm~yU(+THkp*&@^Vvg4unS5b+d3K>|e{sG0;WpnStW)u&c%oT3E$6%E~{Jbw8 z!a1Ju&B`3&>nFiBC*Ow2wgyE%)J=rmwfW*9)-X^m2Y@Qr0&j>=bnH=vWz=^<^4jD7D!{$Tfs4OXs(6<`( zm%pP=ue#!Nk=LlxFNaT0_>t$1RrD9f)O7adIGe$jspi}hn6uOgm6V1Mr&pnr2CpW^ zl=8ZA7jsb3F#K|68&Sv%N8N|LjJ*45XgfK>*z^2O{O?@={yibd{Oh`iKJ8M7MXz}Z zC;wp0t7vTV^T$f%TQt7t3dU${rvn_vY2C#~I8(tMw`DHEv#0Ljg1mir-Hu}&|9Fgv zkt%r8Cmy5BTkyY%Zj|`bjJYaRsLu-XAjsE{Ie~(8 z0{oK)UUKY4O{Q~l8MRyZmdsCHODeSq@~2#2cI2JKDGu}K^z{Z1F+UNclup2@v3umh zUOuQad?iv>FELA-%IPho_r&I9E0?!6=LzBzU<0Orbet2saa{oU2aTY&vVy)ny^OkF z`b^J%nMMbt_izkYTl71ugIkLPz-j46+R-b>ykMlUW#?2lzN{IwkLY1=QUhAljUsR2 zYZT1ej5`NL@w{sjJ~Pw93aMW-q&}J+Uj2n={ai~Hi$!DaYD4PjZUo6In;G_(8fI;} zj+)$TopCY&pB4FGshS`;GdB*O)Yww#yGdBFQWB@0R>9(8MGVW7{W}Yo{2#K>+GycM=SHUDwwF4}iqu@_P z1U%bRh)y~?$iMdw$I$*y)8KwF9&*J`IIW72uo89XP_BWi|P4 zaJ5V?Ci_39N#=66keh#Z9N~DO)obxx#X*|-sHmYdLVq71W<2k+##payH=a#WJ z%2d*O4>j;@u^$naiJ_Z{C|1Up(W=@8hCj{WLv#zYsOj z4xxeN0UTa%3ZHgWQt$f1^uswoh1A>%fNrp-@jq$eiIb7tTNiRJ*OvgB$)_>!I(D=fUIXpfK(}TC8 zsBAh0w?v~zLltdwiD8cAh7pIzB+??kkGu#l!~Pvc@a~Qf7(RDrHZ)(Pf%3k*<2!UP zW11?Ce*8;6`dr2pjVtl$F=f0ST7dfDqd4P!Iwo>n)ZIy^utCZSKZW_y=CA2!)7DI- zVq5U?VlVtFqmD5eUZ}h-8jh5_CX?kw*){8fAR$(O<;|{y#f58#xnTyO%ZgyO)_$C7 z6o|_L7c-d>j-+IQ08JeB!%4=5XtnJ&{gWSzJHDD>EK1|-X}2)q_!G49_Qsy|Vwhd# zjlZ)0(&Da9sI7Ao_4X2~do~Dj$vljGKb_8-;E9FBzPRFS6FqzqY{Ei5 zGUA+~!VUruujpMYn$`kG9-oyn)->~9j7gcW&;a>}@fL&JI@V4SP#1@P*QlG9s zH^&9&>%0Pa3tec+nF63GGNf&H z7_0P00UH1LpryqmoJHmE=z%;cbmcMjgEY3SY{xkQ9rRDh6#kP_KOkFJn-$Ny2JO!^ z*?-RZaABGzd-1d)8+Y&>+_(JKk9|dRYc?x+l2vst=%vfy?s*0`Nu0vs>+X#GwL+Sg z{F&FcIF6pWOSmq9EYfkB`=9og5nYvOkmNZ;z5MjB-Rv!IYta7cD&`nE=nA)8uhckC4#no8 zeVFpc5l^lCOS5w(<6?_@*gM&Xrq}h;L@6&+t@w>OBasN){yoK@7{^bmIU zV>ANWbTmi^`--gp+6o&V^+L)4WAb3CH~1{y06jgnDEQ(MNnc@tty6B0JDtmzo+~SH zWJJa&p==T6PwXK+iOuBb`$A${)W?Lq-a!46xvrzdUGzk*A@=S*2Wt}|;o%)A*zdFz z%(>mxmq!O6PBc zLn5FdAWD8lEhm0spJ2)K{V?a6D@r^qf$!-HA;Qsu{M!>}tZ(TIdw+1>`>iw*7OqB3 zC#mBxJrR`m-Af90xbZGV)^gboTc|!|gko>}VagX9GHw%!*=ZY~D^QiOHqJm@n`z|z z>PT8Yv=q{CG3vJ+L*M(x$Q2J^ywnb?dm;rJsS{Whk3qza0Qx;%2|GQW z(;F_2Y1idL^hVry8e>`q=hS@Q+s@=spmMndt^}vSz~**Pl8c2CyMKYYK`H#bJP%YJKLxMWJZkcJ2fTXF z4*sJeusLojFY$M$y|Yc*-Lfk84MPlbaSP_-6oqtx8Z37EE|e8lbiy96U~>L2%G}l46hw zTIOT$cojjzF_Q3f>nzxm{q*iPfit7Hg$c8Ci7 zwWG~BjtoutKnr?Tayo$oq)Ldx6zd&$cgU4I8~e`t`9>4<{@$lKQAXfgznwc9&&6?{ z*&x*%gLbn7q24r-)21x`zmsvPc`59@rpXe8=b)W#z{b80gwC_ZkUL$8?fdr*8tMmO z@AFmgS!w|dB$K!$EVeOorN|&%BKdro?!~S#SyDdbfV;V`i)jA-k%g zX-1(NDIMnW*ulA=**!`Zc6J-aEDI)QBlq*{HIjI9m+j$Ayq}FrHQp1!ccoM#?>;`= zdydXnR8`XkJ@mgS0s3{3GrB%($DMt$_(^CYo*LeY%+}3tHba$Mu#Tr&6vr7eDKU^X z{!NlE@R*l37Qo|;-{|&d7igm9XJ)f{Dv6PeBZ0=js423S<0R*j;66RvdSjTp^ZbQ% zZsoY>=_umLO&C>|j%t}f7&GG#F1hp;r^|oDxUu!<^$f60dKep4w{f#uA@{7G#^*h= z#Q6`t2 zrP@P`c8kJaO>fkjYsSQTa=C@0_C({O6yCUKMb>>38525Avs$?hGMyV+dg){Fj?&6T^0HN43Bf>lE~HT%r=Ml)u8B zz2+p(EdWzZ_u)wNQcN8z!y8`0{EW%*xa9FAw7ESOE6sBl^`<7?h|LY&=U>$%Z=w_E z7#7yd;dG?6PY;sg@{y3e!5H#7jQ_{(rlyh6M71y-kF3&0bKL}dD3(uaXK%r+XL{+b zLOe#OR+Ac&S63w+*|=Qe921r&t<) z_)Fmu{aC#9&K@nS^T4WHjkb8q!J{c1^dUEME4FXImaBzWoZpV)E3+_<^O)TH=#R&m ze&PN87EIClM`f4x;4;N%jLHhY54pB@{!J(IBxa13pH)YlZg;%(DG5*BRKZCDW^~4< zGUB)LJzaHcCdvlf!ue)Jyc;n}sCS&;E#qqZdMz4X%FV^bJgzT%CdH-=8F(}|A3e7z z;0S}bbDu4q2@&K6@;p)9Gz|}JdyDHYiSQ=|mE!d3$*e+|5G%rjz~P8CqF6l(4!GPT zmcF5|%cqANeD$&H`2`=g_t_$C+Z1g)51ALxcwe?&FbT*sb~ss$VLG-iEuv6$Cputal%P7 z4b##t;DXGlXfX9TeN^JkJbezRehu8awjN>&XTfg1Db#OS18b(fgjFA3 z!Y#EGaQj^f;GXZK-bb93+0FgN`gZAuPIjWo<31YRZ4b$EFJQvAc-W;J04DOeOq*6N)Kn)i2c$ptq zv|C))vKFkG*#=JyJ0bh}D(K&Q9j*=zfZ^C?u;$LRC)b5=9%e!IF*mn=j4X!zy01Y! zyc`^3H6Tr18+@9lP=}4ygo)uiYLzjtE-sg-%}XR!I(0Rx4WdAMf*!f({g1gWcZ9Ky zUPFVrW`o-@WpExj25%EqflZVjQ4m(fr7;7>3I2hgnymop%RUg7M@1xIf)uQNssySU zp1>^6M=|BznkhArIJy55HTE_pll8i&vycELrA8CA@8=k@<^;+Q%;G%fQ+e-R`k};@ zza*>g25-M;54CD2q;nn0m>8VG9yle#=2+f`5!*+w(efkMRK0^wjjFJ4KgWu`_a1&O z)m8zPYMd*FEb6y;qjT}JKAW)>KL-Nx0)&} zxyY!=4G@FnPN)&Ngj~xmg?oeF$nRr{#4I3_F#F!ZbAt)c;qFb7+m`e6EmL4D-yL^M zRzXIahkuKPX~kVt^i8kB+7el`?oGsDDOoDfrVH0yOUTNO6SV4bG+k*JMpQ0EliXHG zJT+IFy5?Sls)1>sB3S{d^ViU|9gVR1?m;r+MihuA*7DXnU7;3d{OF!etZJS1i!S}F zj#(o6P|Z>suZ|>;D49=8jH5H!g=(Qravq#9Tmt;64x;d=7&K6X^*EOX_1!n1VDTl` zRbdMKQHb?NkCW8qEBM7q0{6Xb=Vpa=`fK+v^>~C-qA&{OX03pYBazTO_a31s%8*&s z&*)#&g|+8yLj6jFpDAZxRxrVvzXRxfw+VFjs-3)}nNPYS$=)V8B zciDgtj5fHzz~N%za{DyAxUwBSqG}r|Zl4!{)X>8aJn=2p zvzH8O^+j2ccT*u>26 zd8+9Pd!}i@G5KuR)2R=Q508Q0@|`eTl?plfS0Uc!3i*BR0Ic@Xg+{vwW=Z~akl`2( zI)C%YqTVlzM71^SHaFRO=h@pmfq%?l2=#(h`R3w#QLjsopCzu&7g#!(FPb)m zZxUpT;`##oq1(#T&L;wYSyu@5JSt;3!ATqo71$5eJL&P5u z^xyfHraV!@7oz8x21j|=@Ft&U#&70*Ccdo6x{a*lO?&o~bTIq;&~bL=C5A=48LaK1 zh3tl_&a7Zu1FUS5f+yTLSfeorM*Z?gsr*y;W|9alO0$XLt9M{E-x>usS!3j^eaN-5 zqpDsBZg%;FB?2F@cF`Bil=R2qi6h|fMwy+RFU~HWOyP#R1iN>91V)ALgYowFux

Ul` z*_;jx|3xuy?nlfD>PLkHZ7BY;8wU6;kowmROm+&8h8}=ey?Y>ZE)R6oIzW6|GEth5 zgl=NH(P=8zRjU|=vro)KQ))+)w-X)Ov4omQwW|Z;uXJS0HSIco|=22YyJDRF` z?7#@Ah3HY~fppqmIFlgAesk@E(C_N(K=C}*blqasZv6r_#7&Jow(Jj-FBatcaaoVK z-WRbp)(ju6^}xi_-|$>_ELyq?^F3O$_%~N7vL>}pVHz5+a^8w;@-{=(yp?-@o)ut6 z#dX+M@yhIhf;!x>{3+e|Y=HM8a2KI-Jg9u)A9{?*!w+6bc>m{l{3CRa>{zz}HFoKN`PYtSP5%GmxFK3i=rC(V*>K>f9BGv zjq}*Tz4KTXpJ}Y7yd7Nf)Q7&|k5D(V8YZrAg9FnhvD@Ve(K7M{YMu4Q+23{W)v9%P z!NLWd&;G#LPnYp`b1fcu)QCe=hyQ8rE$scrvEHjjusrG-&eyNOfG6twU;1~^@TM(p zPm`wl%ha(j&w(VHnc#otmC$w9OQ!xqAgVU3z~rK6Fz`zPPqzjmt0+~d^mB&~n-N-e zajf$F2t}`w;81-Tde~o}6|z1U-cvx^$bMe%b8Tu9S%wXY`dB(o$yn)_Fk~KPp=rq+ zXg@3qH@0nocbfuvCVB*VIKTpUPv*$#HV{j1F#jsYw0PTw!}+A&suOM*k~zC&W-1h7W## zpw;nk#WfR7U3vgf!aqUnnF2d%5(n;w9>a#7w~*0%2~^UjgNVdgcz-$-*rHsR!Lx(k z(kigAG!W*=YJt=gcbrt0MlvEqQIAN_4NpYSw>AYY3k2i28UCnq=QjP1)0?L55Metk zT%jw#5tRHtz_cY?F7a9kc%OX$$Hl(F*6-iR>S#Y|lPHTB14_^yVn7yf%>TvXuTj3*ZWI|y?-G}B3>2nUapM?+s$d0p&u@l+=^L_T-MGz2aO)w zuYrI-7FG{UL$OaEnXiAp@K$(gQeF40IP7_Z z7i}^P2R=ShjEEdFT=Ro;v;vQ{0!kHJ+uBhwJdZ#asTg96x5F9w?NSE%Kq zc&aYC6Zw2mJnps#j-=1SDN5X2<0MXWmAt{PRs?&j#2`!j3iai;^6pscVU=wrnbcEB zWD@Kcp%gCv!`!4*Pq=LLg)m&bH3UVEI)l%(Utk+m4p}~bxGtGMh+p*zvQO$ls;bx4cNqQ@Rz#mEH%_;kTL8k8f1hZjroHPI8J4<5#= z*90&)+6WEa>Y;_=WKOr1LP`E8HL%;kq#7DwyTQyFjw(r{uTICuQmS~kK!kjHXbSny z1X<&X1|qcV4w%`lfVS0_Ai3ugsGj3PM)h`xs1Ra>}q!JxE`uDk3>ram!6K_?wlvyDfGb(e^V?GG|vZW7~Bb)7h_&*7Es(?+jYRn}MI zFgy9cW_HJ@54-w_6>HHb$6g9N%vMA$XSdAQ#s2p(hun_LAl;en#LX@R%pNpz83q@~ zNc1Jvg??Z=mD4JwiWxsU+z zr#OWHX+I{@={MDmb3luma`S8h@D8zF26|n5BxH|nH2;rmyMW5LO0myqqXe!;w(04-z~PY{R%txUICloSIsJ4 zY+@Ho;h0;}1*p~x;;0xy|{-L13ju}d`SuSeqjHg$i!iw{}#^v+U zt$aa8^&z=^;10?7cpVmFI54|>IYSlqZqJ<0c6L4IvI2`(rt%Hw^*w|y{`1*_Ty^$Y z`x3Tz(r4(fzXDX^9aw7Kg6t_ykQDL(=BRU>yhZQf>9H}mIB*L_KmCNi3!1^t_z(E| zEda^jmmqUZlpW60V8j2;Wk-KIvpYgXSg96KcA~H|yF1^KJ?Ur0*14ZxUkI*X&+kxT z&mO)D5#Rbq{P7DgQF1NZc{KnDE@JGLkb^K`hAP{4RUMl8p27|d1CliLJ6R?r#=cr% z51X_SV9o7D(CvQ;v9F$!O9v;i*Ts#&>XkfXPS#=ve>{UGNiUeWFdmw0<6!R*G4|Rc z70x^On^D){_%fX{A>Ydk_9}iLa{?vc!MA9TR4j*&J~LTstb?uk3)!K!)i5>Ofc;W` z1%{U=f!kOHl-Y=|J4Lm4i}QT3Nm3o#6Iw{Ymi4yH$%<180)S$V~c-MX( zJhbsn^{1JG#JP4cL}&DpH)l`tmbgTdKBIK9-gzhF1Zm*iI{-R2Z^5l1iz>k;BI?m3=`$yTgfvJUK?Gl zy9z+pd=u#3J4fwOA5syYbG%|+7+g)i3Xb(lAmZp&u#1X?{m&(C+Ncgu^K2mb%_Q>QIu*>l zFiLvwYQs=?HeEO&mn=3*BBImp^O|4Sqw#94t48?^N#M1UEgi?0Ixa_(aA+kjQ9Tuh zqc)J}$wl~s^9VV)1Y-QX5`3O8oA!K8z(_?te%qbP+&1QPvb9~r=-C-kE9FlgmzCm| zLPgZ^ZzmT6f@^GN1mI1JMfj1Mj~i^x)5tf|E~B{9IeIQ{HtyKE61?L=F@Ge&(CK&z@6DD!WW)A;WA&s)DCOpkt0QIb^LZJp zTsn(4HtQBR%$h^8)-5FPIi565J_#lUCujw882p6OsQ7`~Oo8P)@^h{!Y_3D*etH~O zY~a*C6@4NaT?t?7I+z?yF3%Zxj{K+!zzuq)bYzb>%{?iLgQnuRD&Z;-Hjn0fPhl9+ z8c4HGK8A3UbP(460}APfVea5jaL7IlVdZYj_?19nZ~X!~+jn6KyNjv3TStew9@2xB zMxg&RkL!0=$FRvJ*w8tbTo-@DM6JBX+px)(_V28#iSNEz^WnNIhAe!EKkbc(-1R23 zRjkAY2kDYX`B~p1G5?~P~}hD-)j%R^P+h)uw)|BlfM}q%mQg1KbN`2^UEsy8za(V96|I8XFzQm2aY-_zW0JLW!Wn6NV(|nQw`ZZm zss_}J^rh1VInU`MS$JBfgsXRs()@)&Flds4Bl^Fno?J2=%RT}r4@2QWPYLWfG>LX@ zDTHRn5NdSG74}u=F-6-iGmj?p(>TuGy!}KuJ+NpVtm)_=|J*i_|3=mm{sUNU1I#3b3k%sy7)4Iq=UP4zb(R1UNrEk=@b5sF{MqGv&i<6-H@)mN>XFZtM z1%b|_1z_#t2Dim`Kx_^V4{l~~f6{EUmuSJ?$=pu3@D@5}4B+hJ-duN5HHJP2Mcxx3 z&Leh`cG!MG=_loMIj7MHx=rAZeXGYKvCHwN!z?Pg*8z^C4w4U7X2FApL7;Z~7TI98 z4>YD*!OwwyGB)8n_kCC4{xdmvzG@s#T#T!J?r4oN{abKJYAKHWmd9o193cMS85;Rx zBUtUXgZoo<8PDl5gJM4_@kZ^=OgzuX;~G;lGSQ}l#}>8l9301(+bWmPu5TOtJLp@pZO>f{ ze{mNrgGZ^icqRQ6#CgQ{kI{b57|q?%O_}!X=pAzhpX~I*pVo0?{lpSl?o`2>7HI_! zUT*}WgNJG9IY;AzIbwMH%Mjg|AV$y2zMyIux5>^u?!2#+OVM`!Z~D0RE&bu)kJ|sX zVXVgh*9%>ZRrzI@S=WQz#y7FlMHN>{^kaEz7Z$|S;8WM9c=6aw{@#%vsB}+&UuE|S z<2+~ca~fs&->OEj5{J>GObM6)XLJaaq=qUrB!c_>cnLAEW}!Lg-jIf$l2J_d@-lpU zvjR0vp2yD(PSmb61LG3>=+onkNb;oVY=dMJ6BotPlPk#Z&~`Mo*h4=53m|HDqiA-P zBsfPMCK}KG&+%8pP{+ z$eyZL(0`c#S-U&Q&)fpiBPC7JoQ%OlRT&@jx6#VR_vpPc4Abo|;=cQQ4150@N6XC6 zt@;!ST{;Oj(qrhK1#@uFdI7ApQU&qS4RqGsB2v>L!Ep>@xy~O+ylAh8MF9yIz_c+6 z{ARop`Ga|%wTDcPHpGVgEhyQ%2#*=<;n)xaJ()6^x4MD0X?fsrVuPKM%2f1e5{j9g zhmp_70#=0JorIu@88#hnQE0KbVZ#uA~YZAmCX(Y=|Sc0>kHb!tB zXq&p$>ch>ZR99;~r5rP%sFw4A)kmY(o(p(#upgKFC`V!29_*R(8oQJes;P1q!aH%| zEnSGlTh`#amMXepl?lpvTVlkNMa1z_F0*gU7!_6+W7MmIbfvp1Bnf;V;-}X`zvwoY z{5=RtHfz9BslPbzUnh-8c|;wT^`m^{EIc$`i{%MVa6tACHQ1knn_?nxS*IvnenA|k zd^v|!Vi9x=a|e^_F46C&`q4=+pZawbqUZN#ydHZgTvnYynuDToePs*pjY=zXZ$UDu zs!=+A;3rxC(iq}C%|g}dKk1soGI*!khiN(P3Kz^1$dwZhNJr%w^nZ2%*Cg<%S^Rwx z92$mZb=R=bc{kbToz9z56hj}JazJI(3^L)K3ucs=Z?YH# z`R_#ZgC?3k5~t3G&2UPpG$!dw^ZiDU{=5)`7au&vno>^7Qy0LgGdeI!18_~+73{jK zz@Oaei1t?taEGTEZqyLrKY3M5^Iy%!4JnjH?U&-Oc=Z}9t+{84`U`9|nStd74{&qL zK3sBWh%WVgfw#T~F^BHUFsW8{80_?$H-DWXeWJRYY~NBtg?%EJe0?9nws8#eoWv3JcvB~Z7xY=oCDiYs=yKBr%_rxR(30~cZ93n$_)`LU_}ryIjvlyN#*k*op=C@82HFpDCJ0d%i>|J(16uj+Z9s{Kt>7tF6&J-t>>cVFjuoYgZFc_9xi zadyf@vfS=vwQ`>i#Ti^p@a`pRR}ptA8J2>UZ@{-=ryj+RTW8{UYmN<8 zCSA>&=udT(ZjqZ-+IYJ$hsts6s+7`gsQa~$-Z|_?+ReV|>-4B|5A9oPh6K0rE<`=%1sm)mH#Q1WHt#j%In~fX@ySpUHHB=D;XK-FY%y)G zKMq-DVh430 zt5=;T=jTUSx60{bvGfa4(U?mN+K~keAZ*36o}EWBg&At$AnxXvC+rcyCTBEnmY!-|S!fkSU=wae*KCaeo^gR#Qipb&~AN(pXM6;))@a z!fbQc5)}U{jVon_=pO-=UgQcog*&=vvo59a3c)y?V~;PbJXtfZF2p@YqCIk3vYCTGXINO0_|E9 zKq&V8YjQ{>;!n#CwY>JhT|&cW``> zU91K?HCv4a-aql~iixb0V=IQeX~uz~NNQSFW+i1+j}o`9;H!74_^w446T-!Df#y@v z8-?IX3}esr}B7xL}00jor$@peES2|T1h#Di9$NU|8ZaV$~&W5E=U zMbazAd6g=rQj}=(zbkO^~`r-w*GGU(ycXJpLRlG!dnznv{s>uOh0vGL(E& z8OLcLmvdR=p+rAx1(=+uw=R?6gZD}sh^;ybqxXDy{>^)+prt&~7z*Rf*mjV2A@RX6lFOYvp+dal;E0Gd69p^-cR zn{U@4f971U|2PW@>d(Q>pj0T|^OYas>H`V;1K_l@GB~=ehd%8~q|tx{62Fo@YpJEP zxcmo!)rTNTAP=6KnplTk6NJ#AX3+og)_POx7H~Kz3L}R0V4|hKPZN7jmWcJh^;Jfo zzL`SO`knA2-XGfB;%P9KU2Hu154_yvNLA~l@S6em{1k1Y9=+b6(0(2Cf@A5Qu6lSM zVaeO++(6}jNOG(^M=qDu1g<<1fx+j7{IkcdR^QSSfnE&b8w8bJ7wK1p1yM_AR(>Fy z_mIUKYc5hv?Jbb$^PVnQp9o*9lc7@I6w@EuP?-n;)H4=`eBMM{m&AEI9?ys5RvXy3 zF`c(#qY6C#IFYUi3nj)&%5Yiy6kHo!Pvo6G(tjRb;@=bw!XUmAHz!Hql4&96L+8T1 zby*NOxsgA#>K&QRt01Un2KiGdIpoq!Q9qE*e{>Da1J|Qtd<|E#563KvN-PWtM`o)8 zU2}6SnkPTU3%&IaFB)K7?(hZnWoTOJQrxO|<=6=z6og#-A+m_ble7A!EELL}D*)#A(ZMQrr9( zeymM_@5W8E?dD8!D`+kRRW|T1Toi$B<2S^10>==MccONOS3t{rN^2h!f-~o9IqT(4 z(km*#i^~y{7$_!PQ&ULauLtD8qjvJLbC_@QMwuuzPQ{(2_M8@_mRc26^4UvSSam6f zSQSNs;Wu@7dh{!=v>+J5Cv?KhnmpL`v=(*+H$%wWx3FGjIX={>rG6S#*wS@q9PzYXUzJTETI}oPY0SRSZ zWVRERY2dVvIQzGe0p(uU^0$P%{Wyr?>~(ZU8-7#uH@Y<^123rV$I;gpQDmvS^|`$a z>b*T!1V47OsY0_*xphV4#!i#vUF zS(p2=Z1_DLR%=lbDm9z13NO#m+hfhN@U$M9eALIfHG5$Dflze$BMSk8s<17~11l0s z(dpxST=H-;E>jD^CW}2N9-4q2R0ee=6X}k1`Y6bGNhXCHfuR{C{KA;0^q)<~(d3vZ zNxXcMZ_V*dM-wxNt^G5iH}Z$}i=V}w#LIYnTO5jPIDtAf*ZEa~`t;(<7+k|D;>PW6 zFnzH$6m-`Uy<8GZ&E+*+&B)^M`z*V&$UEe;28he zMSWD~YRtPdy~s*|MoJnV@>|)BsI1>cPmjFk?OxGA}veb-c9K zVK7nV8!?KthJXi;tv-0f!4+Bw=Y3BS+tTU8NztABt{TGMb2y&kpdZa{+`(l>bNkb` zdH8$QV(YY(H!#@r8mb%0;UzX1EjjP+!aXij+-(Z|8KDW?8#1x+&o-V|zXiE<){x7z zHHP~SE|WSJDbVY^Nen-wkQF0AoIW?4<1}n184X;1X@4GYGaPIqAiOj6%OLrgEml`(Lm~Y zu23Pzi~PsB5kx6VgjiV4$9b)%vHHvtvbf_3?(H~;t@l&VE$JF+`YMqQz}pmQ7};xEG#uTFq6 zzB7#*LBmwpj`?L0Tm8yQPqfd)P`J4PhTPoh}4 zHeXOj4xia<$G{7e+%KDjztVkBu=WW`WWL5FLv@Yv#?5BbFP=mWjo;GVVt+?jB=Z&*(j_KxGt-PKJ}svNLtgCG62 zz=!B(Y_R_9+K5+!ig0^w1#T_Qp&BkK*fQk~o*sKePk89#^1hAOcaQVHxR;`K*Z|ty zIfU0EC*Z>O5ojaYg0oa^5k-jy1Xuf_yF&oYtz1lhWfh=qq9C4mSx&sy6l3`+RSq$J z2v_~SfCuaY(fgDq+7^f7?b2QNFbZ%mJfF^9Qj3g!C5qnMgKkR0G)~tQVkk*VUXa3t&>SZ5govc4Xq;GbNOp?l!qu{_W} zaSf6;Z=j>Hfi&%R6rS6765}H+uzto?D&{IhmFz8X!?r;DdfWo-3lYuV*I?UQFPhBl zy<^l<@qu6}9$%i05?%TDalt8a(peH7Zr{Ln{`12ez1PFJ`$Glps$ zP+)%^a7O2Ee^7Mn22PoI8DBZS;XFta**U8#@ax|!)YHG)4+v%M|lx-C9XLY-_-mYg2I5&Z(^a zz(TH2a{#^U^w_04G+CR`0pvMe#HV*dagXQ-3cJpt^{%C;v*HdtcKRZk*hiw3l`dW# zCrsX-y}^q%EaQo*b-=g}yCLvS3cL==gs+{iVBHQ$=Fp4h#Al5<__uR9otay3s;v`l z(HCX^WWK{&f*ikc@jX<~zKOeX596$y5t=j{z#`KA}7d`1D$#0mxA_rAED4sOCj;?3( z(TyqPrA&}TIft#NSwk?h<~HVQuEZvDQ(%;j@=VS}^Bc-vV39=%8g>Y?kJ}GW=_Qxx z?G!8p8`77!q&Q7Nu*F)3=OMh!oav1>Tz8JBMRiPCdQMud)5|q zub3lyv{;p$bjzM40rS}HYZY1d2##-@d=r<%f5(@${ur>l7K4?v*^8OTd!ySUkd5FJ^5>f5g9eP}50IIQG3qK#cO=@yA@XL5P>f~y`tC+GA<|~U~qSYR_xa>3-%sK>{ z_9c)YPIKL<(7=l+j_1z}|3TL;o&<|mmT)z)VHBIvPYr#5Z*KeEI!&P;R~Vefo1Ihe zI(Ke$I>r|j6W@`Six;8l&%+o!eV8|`{u8l&I1hcx21&CorH2n{ppfMZ6nPzue>n1oW37rHpOC)U>FWoRnuIRGF)ySO(*3aqycZaJb@e4m>FY34@bM;hbU!w zt6~`*7Y{_TG=To(o>89p6!ac;1O=Db)O?BsUI+^2_P%Gx@n;Xn-oa?zTuE`QE3mTrv+!DipL*mB|{K8e1{U-rEp zHxthDaxMa++cI!j_)~=5v-oY76XtBbiY+tNU|ig9l>Dj6?&=B0l0`MBCcY2m#00`0 zjajg5aX38ajE0G^i}^-tz4&X6S3pUm2kp`f!6fxYl-~CUMMZ?M@URSPAKHV7Ti2oE zm800k6yn`~C@yRMgW?}O@Zq)bEHmc_4xN00Vf)3|&N&JwWIc?w5~d_@&1L$wv4w`d zJdT$dPt%#Z0;oH3euTXRczFFw+C5H&-Ps|_-q!5Lh?Cb)b>AQkn~h_mRX7HO+aJ#V zFb*qb*|TP5%Iu$>xoq5n@oYYqd;B76HM>D}Kl|+lSC-PYWH&!-hINudu;$@ixR^Gb z(Ni6Sstcl|du;cnsos{h<>h`#$IMYIoG z!+)=3qO{A4@!UB4+x|~uG3Wm~mslFjF)^BB%sop6|Jhuk&#kf_cD2~KpXs)9_>*K8 zsI6!h;wEALV@94`?wZ;5H&=w(31>{OFPUv)7oS4yQpLa7{bA1AB@SoV?f1N6tM+Fy z_YORyUj(-x3+7$ zuiN%lh}argo7nH3;%M7dCSn^mbB}GqfTrC*x~1*3MOn6Al}zn@$`{%GJ7#hd6GUve z@%p#@pT_Ke%>R}~##UD5bIkv%`)AqyOq=g(VB|1W?4ER9T!EzK?dyZK|){~HFEES5$8%tl_-UMabSGo@JeyNe&Ypi%` zVxD-L-sJZ^(!;HR5hyw+z%EOEN1uA7(#IbwQRlH6ZUI@=s2Q;Qlq^osRD%w~Q)n!r zj)fkQC|bkuy9C>KTeiFCcL?y zM2~*(gAc3IajMcGND#SB-8YM{yLN|=8gd<>UI6rqWI@AD9KZVNz@E6Pm?_qZ`dr;L z-?f}>ozLa_jUm>UxZ#UKi_t&b9G{Ckqnkqt>Cfsw+%Wzj)-64UtyP@HzBY=ggwKE) z&YQ8sEDh(b)_@ppv%K0b8IJm@lBG*6a4Hur`9Mq=91a~qGU$$4)ne>4B{OtUQQ%^i<|sk~FmS=HVqFPV3s^Np2=w!3$FsqoiOj8rhWd`(2#z zK+Aka&S4(2dDTx48vthdM;#_(x+dd%(UWO5(P!+_M3{1pC9pk92K7>wU_@mzc3m0I z%1Tz?&trn@UAt)1X(~engD3batlIj>nisfJvyby197Mwgd3Ll&1~*BIVb?(q`su6R z^}g(JkihYz$}Tk1;@juR$k)~Mc~viABlVyly&r0F_TrWg1+@G}62_)Qpx3%$Y<)nn zEK~%4trsVC6N|`tqextDLvhC|eJ*pb$2ve&1{GDq@W{-ylpXEm4-`H_+o*hW{5coX z-b>=u?fJaM>2;W;Cx?U1t8jnLd1B=kjz?dm@pHmrQD8zD=H3d&9|mPKKj;DGxTjF_ zH&3YL{x$Rk=MXw@=sjljd104tG=^@KX3w`7Qr!5KI{1FTzL;z*&NxxM8I(z04PNE<;oRCcpgi^)Y%N8Y{W^Np zM@@c{frL`Dj*({<_?<ouhOpwGI|#ovg6$f0@K0h2;kk#y*q|%b7n%;q#gaHN zZv^*6&1A>!OS7~1`RF@Ah@Gpa$KL#B04+}Gv8!a7@pq&Fp3DADHQKaU)tA?(*rpa- zvAzjA(q`ho_D<}%=Z~ev$>jQmcX(=HDV319k8!JB;JwWcQ7z#str97v&$)ed^zLl- z?8a=?XIUSseTdI8?^4)z?I~>d{X8~cM-IDtVkx^^Xe*of$DBQl?{VFXVeIQE$79;M z?E3S|*nXjD?1yp(c7xw~_N22VYt?DV{>f-U=Abz{u5}QFZoR{zUKzGkESKXSrZVYY zPcX77TbWtz>CDx8XPNT93Ct;)%=l*@zAG)=+EId5>? zAs$A5ZN~zCPYf6qWefeQlCKdoVEr}x?qz}B9ZFEac@`d9c9A;#-NHnbf#5w$4$|r_pud3>MhIxyv zFVV-%$M_R=Nm2La8$9uDQ*vr#7L5CtiGFY9p{GI)91T(;cRXeAd(K^6=Vui--k1u^ z#`T!GPnQjo&Bk^M9X8)56kWgA;?zy@?3a^%XtGO>-Q@TVE6g~4+rmS*_@oQ(v*1mB zuIP0dm3M)9%L)*r^)U8^U zcD^cyiu)EAJ%1WDZQF>`p54PQanDiE@iAu1>!oq_G5BLa6WW|A!esR^e0LUEvp+R# z&!%p6lHecqjd3~qN~nbmSX09qPkY2JGrY?#+B=oKR%C%=p9b){s}ZZ!JDFuKiJ*_9 zIy>o^F6$vI$~xWHLX#~8S;M-16nfE(YsJLa-lXxY#8Nf3@W3?uBCN!Y`7Z(Q#6 z+81^kr_eVRZser25WKJM;j0{e0Ec6oAbp?`YA(%(S1Xespuh*7c6vfb_+`>(+W_;* z-$Hwo0Dbaz2kaS9Lj5lxbnSdaxOifW_D=Byx3qi`-B!=()V*Nm=EvmJ!*P%)7fkCf zSx`-b7gX0|0lIV9J<`gf{4wtpc-VY0cs|<&1us2ew)|H*E?JGcr;p$j+Q%DZ!;uoOn9O8E&o_Iw5oY55V8tpIn!y&zd)HpI`Dfqk3Cq2(-fP=B!uBe#5} zWDeJd143Z7L>NEUcY(#83iwi)0=YYK!D;a-q8_moOgwIrn=h5|MZYX|Z3?%ZHvIyZ zuOo-CCl=9wYi_V?swl?@SdMc>w1|mG2c0%m9rcrZu{STAX6O2H{@0gON5%;0Zi{d`N?>3%E1OM9>Uw zqwCvjpnGv7IH(xHSEovl@A_>WF{Ko}tSN~K>LaC>i_v5{=VjWp6B4-^_t$%=cyx%% z*qfFJTdv4~fz4D{>nID4?PI~2?SscP>d?~S1P3aLL3rvd#%IYbCc%4v*`-&=K;;#t zUGgg9+!D#0=%{8Co|G{0J=>VsUdtFQ*Hz5l)Kkp(cMF;NdB+&&E@8?8{F$QhhnUdv zdeWcoi^lA8qTJ?-ZzPT(q=tjqs*QN~TP4pXv6w1+&}EKobzlVZ4H(~(Hq4U~YnZqh z>zJ?6vl%P9Rm={KCpKW*M*YrYq0P~E*yVSXR~#IKyD|=9!iE-Hw8RpZ{w~3|$-*G5 z9)WT)Ye;D2O4LnROg4Ld!A_N181P0GwPiK1W`;d93yCq;7sZf$t6qSi?q5hesKzAu zq;Y5bNzhut)##_|wG~+?YlWsLiG;w7AR&Izru)W?@-OF4@(8mVe`g47`=d zLX$#c{QWkFXSO{Yl}<#W@N-)nzc-yWSDnF!bF5M4b{oE6%t`0*26AYR9-Q4bMwXu2 z%q#kRh%`rvv(`|?-A~dy!>io_`HsJP3`2{ovJ84bSd>g!+~Xu+Q=^J`~O;>tD|$qMY-+beA#)O;5p- z*6~=96HSHO?qcudF5-FX7~EWF0JGP4VfNv>^aRI0yrr0e7bnlBk=pUq+CQ(*kU%SZ z{L_xsgq%Vt`)>Y*XR|T8yb+U*3$c?r-ePe7Fyh09_+wrfj>Jo_!x47u4U3Do*hrgg zal4K}iTU`sxCsnDzJ;1X1!!{F1K;xo!SJFCb5*&3%RBx9vi3>fHEtTP?fc=P<4P=A z`i=bD%keC-ykJ1c2qvs%(EXGK80$!q(xZXsEAocl!^@$C(((9t3YYnDDiwR12>z`5 z$$M1w8u~Uh5s}sX#OmfdqW{tda_u0DZl42lZ;9}%J-p!U>iJyWLVR_uix6gc zFCk`&t6;P&fIiC4fSx)bD0hehyF&~dZEb|}+Q;F-%(rAgDuQ$A7T!0u3np@Na)VSh zoqsD51ZK1lnjyjnDgGc|mQCbcxZ}n%UX@6HZc_%imNK&Ht_oyc;kY9U8%WRRR1)|+ z1RCN^(Mh_VES2$x%nu15{t6(dTMpj63WI~97f9!@6K}WsN$NGUk2HHcppU|Dz~X}! z;7ICKSU$QFuDvVg>l$-)E-s_y-Hc-332opny%^5F(|?m~Hi;a!t#?dv6sn@Z)@!R?hrSZF(RV5Jb9!OTc3J4#?l? z2=jtxz2b=4~n{9Z}cRQ%#E7F8gOuMGS7=Muc?Ed@y;GwB9)Gj3g2iYao}aN*J_ zUcdB5&YN@-8LtO;)_N26$Qj^8R)ad65~RGxXK~pwf4m#?mCNjrhq3BdtCLd;Y4rV# z{29|XfZ0=H{`?18yg74MgKqN>QB-k)s@dWA$jgzYG91gs_7PDzzmIB9^}|~qCCHM$ zx=ifEXGHk(R7NITjA?p1p1CjB4F^?T!PvG5%n2=B7?8AL+bi;LeMCE6djAHWPFsNO zCBsazmO$iS9}Eqp6SXI=!Q)l}t(SIs6oIyZrs zEo-9vKRPhqX9vEWCd$4Lui)*l<9s-7tvr-af@M4}82x7&t_x4a8oy-Xq<$I|2c$8p zW-(2>x{@w*)^^@@!KHe5u zmTbagG6@w9#i6mK9u8bI;J3K=;q@D{aGc^ve7|r8zFE76=Jr)$q~~4SS9BReIyhg9 zv;pcei|EiHHTX1bP@0Cct$twOu2>6dm3?9Whi}~T}MOrH4y8PnP9TF9VT`^1|Pk4cztw? zEYs9L{|(Wc_QxG^mQ~>{!9XlMr--Km{-U;64IT~)z{BMg)#Eak;m>*gXeh+-a9<~) znD06IeezDi9A$8J@parHGfZFH(L=9sb;SAm9enV45e9DgiOhCMB;AuRJL3xt-gbt> z#%#vqo<^Q|kO_MseLU+tXv=y^7_rX_#<7FvUZIHSJzTFV#{Sv+5s$`fBpKI3=+|>P zP;Ye;KVGlGnPH8@`qx>E+@wQ_SGwUBnb~+GeH5byiZGkgB($C0g4=sa@thQQ?FDn` z;NAv$xpyv{vhjtK;zFFjo zmJkyk76ht#KZx~sPBWanf$T}V2lBtdIi2tqqT~IX^pjZ0_YaBv*dR!VSL zKVn>VQ~_v5+QN#{z3}3FJ-BI!(3t{_%skat26E-Y{08R%W-FWpIrpky~#e-ER% zE81w!mbv)$kOgdC7X+WrUVwKpMi4yt3xD!u7i#Xm8y~sE(sM}&yQazFlIPE8+mq8E zaCnGntdc?t4SNL1Mw%_d(!}3c#6(1d;}|8ce*fR z6R#+1I(@N!6WH-Dfs6WW2=*T4boAQH>5+=Y?} zp-|Sg0P5?Kp!eHt=t!_9x95*SnA#X@PtSvHK_k%Gzn?}N*8%DI*T7}FKO|2%h_l^z zXzW;z?-#Gex^42H`%wieihOZ;Vm)tcKm%nXHd(*O3?cLL#MsT%6g@@bY4Vr0$)sa7rO zo+?DU$3yr;@f(g<1f$S|RFv0}W)H03p1BxVcC~je&gXolPF)J@+kH`ZbKo&uWX@@v zxXf(TI4&!lV>{+vR-o>}BlK_W9NJiPgwE{#No!Ts;nl2RVm*0~MkbW;PkxIds?sIk zRc6hTHaTh?s%8zx=Q~1w^+THT*9FaM?~#`eg^0TA1Y9?`8Z^#L2Ol_ruLhr?hx0WW zzr6rGZvVkoxAN&w!gSJPxDgdPa`AL~2|4~a3?}`Gg1lTA)D%_*r#1etVgFS+ZF(X9 zC&#@u8S}@$XFKrI=i~GT`;)$#CBw@d(4+c)R$#t#D1NQh$84sJw@TebQaQ4uwrdxeTRhe26+DSa?w7wRUThHW0+N2>$0j$+Q*Bhx>F{@#ESxyT^@_a zY98>;uqt3|K0xITJHV5c0cz{(2=v{05U}yYtd*h=DHel?f17x!M^kZXru&jGIsFZ6SaLQK$i-z?!rH?E$OQObnKiss1CT zh87KWcz4}9lr##UR$&F$LXyyTz>QYDm880rt1<3*BMr3=!P9TLNZEX0YIQ6d42sXd zUd6&wC_K_HJmD5C2rr;Irb9m390xME>5RZ_D+#DQ4WI{jEQQ^0AQXjHnY4=+t*X#L99)USUpQ9pH#uco;Hhvpl@ zn{~6e47Dq~CXFc2X(=TK>;&-Mc54n)=Sl3IUE^&W+XnGJp3s~)PxelGBhO5 zg$nr3gN?xGWghUqT_RULaXyNG8DRcP563vRLi>*t-b6Q(0=)V3jZE^4B5>g>icvTJ-c#?5Y{Inp9bqt_@1DrZ1QNC_9qa29Su zDJZWVh6y_&VAldJPgW&@OnQ)qkDuJ9h2siPL|`j+?{FfGE4LGe09DA?nMLb;m02SN zHMaFr1jd>RuzQ~*VRC~QzDk(OicXbaEvH+s7Kw`VsRN(xJQ_?)CI;d1(p#uLM<2zr zk!~q)#d#dJ!R~e{#-^Xe0`2#_{@5v)?KxsCm*Y)V`PE}!X9NE3%)$w-nbk9hJgI*r z!~f-XjaX_oQ{4}fG3ui`UW=Q+TXnIA;&do8!GT7fnpZXADg z9ZoL(fZlV}*n?pYv2wvl%!(tZEU}*m$&Ye*CcZQ{+M2f6-$d0@xy1QtCBC-0hJU?S z%nQnb>h4Fp)kng4JJPiBxLP#dP+74ihi%hSW5+HZF-IMWlPi2$`7c=YY!Wd`KV5Ye{m08@mh8g&D z5Jul`B@CkpVHkzqg=?w!Qa^m7qsIIG>^5oseG*siQDxp-JP%#YXJEdM95dst6tiPN zD(nos3?15)a7?%X#6P^n#rH+o5SK}8boF&Ech8hf;m&)LR!Vcm(#yD^u7k@dDZmcS3%(^;+FJb-C>Tz*XN zBMhBqkC)TM*i$x+xaL(dt?HL$3tIM|^VC|rSZhcn?=FTNj}7rwZybtS8iS{kE9rk6 zOsyLy!W5D3_(h_L3|=`;?v>udxq@7VSmqsGh%@($n8>5L;2m7MO^gi`XvRr@Uf~Im zbnH1EZN1{XAFnh&67@CB7Yvb3%rEZo7uQ`LX;j zt+Kc&{=W63WLdtR`*OPS`w&tH}C%SH|3uj=k?9!(QU_&*Y93JE+4)>HNj4^~Uqq zXerD-)wqh^w@k*sq(bhXZDv~UwUL|bY_spi8k;SGhiyK39k*$>TWO>8cc;yj!2LEWr?0T7 z+_Mco9^Q-o zY$U`LY-V$NV zIhw-1y~7qdv)+?OzodBukEHO2RWJIlKSz@9J;CMUGid42n>1d-5lZh_!NQ~lD4#qG zajYW<l2JXEJ2^2pg4`os60uP+~;z8)iY$_ zflmJFb#LiCXK|3an?~Nf^aG`5B@i z7{|k#%p2T(T!78|eHS&q&O&#~Ks>Tp3pa6kgMibMVfNmWxV`-q{hi=|&DW90=&k0f z6{gb<923|7bW1hUcM(Q~Gr@J03(Cv=C2!{%(67dsd_VJj{BDlPcX{|b?xkh;vhFe7 z?>k4e=Lw<4x(0Nyx`BC@Ycb&a7CcsTADdqMz$M92Y^SR-o7|?tuGEueUt8GX$!j0+ zoEw+()DnbUx5h(HMm+A7l7p6pD@4n01|FWJiITlkx;wI+`M{=x$>cw zVSAeyHMcj+sm)_d*t+@5&jcri3>z{p*>Gl|L<_)oVDm_-OP0lya#8!nf_;oEWeb|i*z4xvn%*;(e=>)TATTmv)idKlxN zRKplexXk1Q#WDw`TtlOWt@vRmg^X#PMX@cMHa`3o8IjPzm`_3ICRt8|3JE^=F-n8o z)2z;#9HYBK(ukP)4k8zL0TY7vLvgqR{r=!OSPND`va3AkU10e#+oj?1#LFBX&k)QE z)bP|iAyE7Am;c+ejS2-#qG8_0xHZ6BeDrV;UgP!(&hvutiGLhf{c{8GKi8An{evXL z^D%6poZtTUX_S696<58QhC9RW)3It%A}$+%zk9s!M7t}J_s*!=Z@_PZB>W*11=34- zAm^K3{d>|}aC%uql~2v5cjigq_+uilAao&bUy%W14&5UTk0Yt&o-umJq6J$yf7~s> zXslCg!*n`Ev^ajsn`cJW4(?HO=;TpqsI&o`M@;cstOl+Za75=Fkq{q|14~`C(1|}t zo-CRI>-S0F$W{%qq*ROFqtedP5|HD$Hwu7`&TCXn@dy7Umx;2rD0syZg4eqYSm@KZ0{BNM?Rr3dJOfNV1EZzMil zP=fsxSFt#4gz^&?;-gD}5rhnpm2g;vER-r88qD zW7?rL7+i)`PKqR#U?Rh9FQ zUf+)v;TwpfsTWC~?Z>~w@nw!ZNV1j-`G^x`j^kthcC1RML}5d9T$gfyY;H-x?~Rr? ztKI9x!_rA1+jP8Uz5UKOK~;>f0D((EHpMDrmY%BHncI~N*Zq*F64{4PQK=rY>6 zRR@2*;X%cO%_LL33hzxdL?LAnwxwqt+TA)pt0p>N(McutOP~h6aNmWpn?z`DnLX7p z_rxI~b<|Xdr~m$KFMUgLu3RL;cN1~K`Ikh=-T>M8z8o_t6lZn+rnU#UY=(DUye7S$ z15x8OlOz=h9B-b0^rH= z@1mA%B*`w)C86yfc^xVYigDSDyou5@W48oaJqjT+FPfrOZ9I;S2vPH1F;v{ufHda{ z{!q#%j)isfkWClf-&>568xyeWQY2oO8-j*|J*e3I0ynCJVb~8_oZ>l=JPgvrA!{!G z=B5nxPDMrMax$nAv+cr@M66s@b$SmNH}B)mGKg= zz~>TOJzIeCUp11-G+(mtRv@g)E(M{mXgIv&5^;Jw1r0YH0S$5%wURi-YF7r&c84l3 zD^~IMv|5o33HNAMt1xC-Rg=@70i@q4V^-#6@Yt9O<1UBLXXXk_11&cRF3~X z)fa*uc!0K7Iap8JPxyh>;2p))g3g!mRy_!ZEO`MCQIx>dH|K$%XcDN6xWS%9K|I|F z=J@@*D6Zma>`IS3>G;#`P(;h1Vb^TT8|$q0k@JIw$(dk0-v`DC%D{)}G=L>WWai9k zBy+(H_;$9B*6D76nT$5wdM1Trv%0V+F$1i7YoK`KEb?QOpzo{>@#peFC#{ddEv`jS zyJ$9!e7eSi-`D89fEY*-dPr2$`$=(;Jo2sv!f&r@;CkRV47B<~<9&H>jo4#tl^}() z-pS#a<4sl0&yJzj6d&4Q8wa7elevtrE4;3WS>%VsIo?aBW{8&iLVS)~f!;t$PVSB8 zZ~D?|UBBfS>b`Km9s1wsGbleL#C1o{^6v3PdaT4t)eHW2-%Ql zgNMr=@Hz(d(0z)Ab!D6lN~IU0-ar0mJ;xlAr>le3#4v15b>Ug=kASnnR++-x7c#J|WjR?;KNrQ<4$@K2Ox j#rhWFsJGT zzjb61(|t~kSsC&j_HR{ZwjSUA|B&~lQ8{*P;I~j3Bnm~PR3c;ZbnW9jo2Vp185)pT zW+G*7(mcpenv)`FCPUXgb}3_oREm(fBr-$@{m=XP_`YlX*Lt4&!~5aA*4kfMt970G zoUXl(;rHWqUtPm_xG&;f_uJ03JPPLa9Gp%UUFnaTpHuku{Q!J<+De$N0`3h=h8M%7 zuv}gmhuv(3Y^!HrW^hD6_xup+M~#P#2bExo{ zKUK%8azYIF>H-+-G91qjGo;!#LLpCD5e7zFqlIm zm4yK}L-mm0{fdIhP3qk6%yBSTO#{9Z1+!B=YuWQICzgA87E?(sVjnlAvd(p}%p}~K zUAugOwfJr10A_RD9s1n14vxEeONSeh=*EpSk>NZ_bh*1~?p(H#C-eGwid`HM%w)!8 zvfcg(>>IzDediH+N~83+5aYWIucKvQrqcV=WsMAl4CojEM*BfAJKlg zCCfcJhaDZi9s34KvSx$9%=y|Z9R5g*#yiz9uQ!F>7(E!Y)*rX@ZIQ;sgSO*cw4+;{ z#dri$Eu?MRN&E{xvRLaTHotpKH)LgCimpX@lavJbr(1$w=>W?=(XBKw@1j_0&MIU-2G@ld0D&#PS@1H1yiic_wz}#Wzsbq{$nG_)ycs& zV}UicZYr+aCPsJ5QMlOV0=Cy1FmJtnY)#5>TxBtZ4QY!+aaa+I`omo5+tJiKL^_zC#Ig<-mrKw6jzKbFIKh44EXQaUYZN50oES1Dc zj>XPJ8?pakAui&tif(hy5wCX|xM4~(tm2o`C#xQjA3o8<`~EO6FVw`CXUEaAcqhuW z&c>DHL-1bLYclNa8nM*PZ{k%i?db%EaGWC}E1Fv@BU<)Wkxmx+R=*Yv6BTSZhe1z_ zp}M`&!mXtrUT@CC-6|n;M{+uDh!3F~U&Z6oMQJ3=zCUUh7}2S_0i$#4MdLlSfKNI? z_a@&JNguzA_q>a+Ma!O~du5OvZ_d+_olRmN-9B;6OC7o^JC+nI zGe)PnGpK%cys#DuL*BHB{5};adcIE@*3@;-N71J-Y+M+b93t>DZ_N=6E>*zjy_C+r z|Crq3wBXgY`6!wyJR>?mM0!LpJeoh9>Z-mZPLm99R#FVcNvwrm%4u|5t&{NN)YFsv zA=I4FLKM~A(Xv5sB6Z!TSCdA7XToWmHMtm1N4ynn5bA0t@479n*GyIh2g7bmmW@gvxZRg>87 z!#?CVoebR$mXLj-Kl-YEByIN%aC$;6{oQ*3ho9uh)+th)$VeBerHr6r`eyK4FbW0_ zQ|3OX`vBiFiVOYv6MAoYp{CtUI%M{FGPz6}4O9y7*UNN)t-GD>kR6I$xBT&(M=NgC z@WR7AzPLNp;-gXO=<8EJ-IjWYKSxNCrTzBIQRE0fnH{tD=ek8E{4gGa) zHy*y^fI8I&MHd84`N`l>(EVmR{ZK2^r>__Qg%%q?S7!m*S??x#SDR^)T`xJBZ-s@+ zgQ@l7pfJD6&ik@B&|vG#}&9~lrMS@Jw_x93oRRs#Q1$+JtoMVr~7_q;cp^^W2&2Qs_uDQ7Ho%K ze|DkEy*G5}khw%W{ENsfZ4V9hG(aoEK#@<(4t)1$0Ea`W;A&V3xT_zBh~D3@{qj&^ zH?3WC_>mKFI6IxT<=>!ng$O||!I13IBfkDd@U0e=!_Rg4@I3E0IW6xFD#caAYvmb% zb-YM;_jHpEk4mhbu?Hu6hLQJSKWN3na18E01AI-Mz_lV3dd~N+$o9_;vau%w7EY7~ zC2JFqyc!1Vfl4#YrSR!!~U+1sJfZjyQ zF*5?i-g7gl@81fNc215xH9Ua@x^AMvBkM7#I}r!3*nsy-lF>axo?Ri*jBXVisy~!i z&-~F$+3kklIvL2u*rZ|4qg&XgHHv1>%o3UQ`OyAuBbm<2C>)Y1IKDoH&|yka^t)6k zh$07b*Q_3hjE`Q1zx`ynx}|f8u0k=<9)!?7Vl_mEGSpMEV3U=5keUVIhDqbu!K@IB z9IMV8KepnaaSCkwi;Hx&=@j<#!Kx3v$`f6E`lmLJiLnI``NW+*VyfA^0Zxb}B<3nGZj^ z1^?qqefYah1H%HpkV#t4Xqwk%TsnIy*;&{_C$ITP(+&!}Bme#=x4HvI4M;(q{#Eps zLO(pWL13ix>ax^@4X7WGi1Up~aaZnfk~8E7NE!!2Sov-E$Y;U~yD6N-$>(so-I$v% zA)I=TByX58Gp2^c{S1bTyZI*MjT(GL{?v%Z{5<>cX+8NbW2S;g-LT<({3H z$)%0cVuM>x;;0GxF}^{LVZ|pLXZIXiP1CUKt|`;Ml!U??56LGvcG~j-o_aWz?fvP5 z8>NRZt(7Y5dXg!-o2SLhM%;n6t{4)pQ3skWC7`>;1g;Lyj-kLia|V#Klq<>5QmaJn2(Pr-3|Pa0$Z0iudq^Tqk{3-G_hfD>8GfTDn?rv{~FO z#IiPJc1PzDT2D)-I}VoMiHSM%+sL;lCsB$)`D(0i>nA+$V>0Xeti*=I^--hrZkn=r zD*JUf3%9q((fvNExMqY{?!!05(Olo; zBOoa^jGGr+2XzJ`xy0qZocM+^mp^767v}U6ewEGUem@?;ZF}?>*ClJRdi4>^uWmG> zON~*xYYe8WX~6U=AE?yuSGcO~1{2LsXYOV%*c+2lw!=AxWxqbf@)stvo%MyRedc4f zraKCwgC??}<&vmu{uH%YDUP}H5bIujN8=D<_GYf&&%Liht6yp3+H@yu*&PlISrM@I zk_i7~3H!7~pTtxBZNO*HdswJ{4R&mD02!SUqAJw}7i8oiotVIR?WgeTV=5V8GK~3_ zH{w<`JAAvvn3*0}jKhTcGfgfKdx(T^4MwrDg%qbs%dxzGR65~t8SZ`{&HNrG;GivH zde1`^BL$}YEAd&PE9(p0>yN<5gcykSyhIzWekV7zPk@}z=XdJnUa}+cAnqto$J7UF zu`+HTrppK7jG!)IKXe&KA3sK>oV|_)Gv=}Bg3nDmI1Izrx1e}^A8K41%JLd}@PqaQ zCcjvQ?aPh98n0dScD@O&4=BR=%UAH;BTMw~>yJl-x)0B2A$RQteSDa&xw0=gVBmhWLYD{5I?wXM&pqKA4QgANoh%6Gu{68ff?uFDt3DO0N#e zh~bO~sP!k*E!$ zm~KcMw$&?PRAne`l1{{dxBIgZEy6zY+)Ke19U-0?3y|>K6oUnZ?KtCcs5ShnNVI7< zbp6!k}fa690tR6a4DXFy|TA1B`y?!|iP{gw}x0xlD0faT^mP?w6Olj8@# zjSLGiewGME{>r9XcNN3CQzZ}+Tn!JR)3N3LV%*}AhQow4b@Y>))aTR*dQV1hL36Kh z;B|(Df?KG4OFb8vDCVO0+g$U&EbjG>``mPkliZrZGu)%>bS_YcO z)6B%O{g2|f5s9cHE5ejVH6n|j=ZVIELzw<6g1Ald6Q7*^6-#&A7PT*_!bQ*5Ac;Co z`>VZ!dt=SPqW@GbaE~;XJfjx&9y|^iM8(8CY;`yf`}Uz-=7N0mf% z)QOIy7lmA8VDA_4kG8kiS`{hUT$_)c=O(}gTWwgE?SKyBHK3*;9yfh`FDAWxb`;u^|8q%LIDTQ6&hy77h>lBFIL)9hCEbLsv~*hyE%Huz2_pT-@tVHAkKi$G;CD z&1VC#HrOAt6naEn<$1JHV5G{O48}!+Ot`?Xec+hc3|7UXxP1#ALZ-P z`3kL{{FD^m2*BPoxVsOvLxdrd90g`hB6c{FK(oJ$19LU`Bi9l>)JK_PQ&Tm|w1k{Uda_{g)(LGZa_7;>Xbbrxa zrwVQTz8)q!meD&(Ct=%BA23w>1DA!`!!B_E^@-R{A3UxBJ#T9`x=#iEXlgN?HTSSb zN0BWrTEUtQ*fPt=l}z`*S!{GRWo_{z*Z{7aJU+7wQr>10-;)*Kv-=42Zrulwx83Qz z?60KrLlLaM_!?H+)#Q9h9r%7phm1a1Zs{Z?AvRM*-qrNuzNDW4{_R0%sr)Irqkf5+ zB<=&%kQ{no;2fy-T!T+vuA@Pw8sPJ@7-nk4LBO}qaNkafYck#qA6(x+-R)5{rF1or z)RXYRtR0$srMPt8n*s~597x)kDqLu%~(WFAvqNwI+z z#+;|LC->mIC%1P3g~fLyxm{0XxV|zSDCzzU=b@VH)G!lYbr3_Qo+c=0HACmc3GlIh z5Y#+Kpl;nR@P1Mbq&c{-ox1LhinthNQL2&(iFDHgt`TXA7UDu--Rr z%-4A-lhY4lR}MI`fzlalZ1@Ux(0m758!!Cr_zvdcFJkZhoMzQkw#?_=Ato_6fHiB{ zunU!L>=UlVdD#SxQF%!4-(vabb{YNcewaM{dWRmlDY!n?MZ$xX z0=IB7o2#M30wf*r{rqWc+;^T$O)Y^QohuNK(^T%bKMjUL0Bp871J=vbxdRQgAaS@E zo@&U#j{V`52ZC}yd(J?vhQA1xniRQ~D=J{OVl(6gtpo1Sb~Jc17I&N!Q-hV!V#9AU zanZs}@cy;~7{>X+q05ydEHIKpv=fNm^$t?L*odAcbi(C5?J%>l8>UuOiWaP;#Ijwv6^N5kSt8G2#Sa`s!&3ZztdLkCco1(MRZTRIFNFEGnf$ssK5VYoSPkRZ!XgpXS`w1cgDJ~dfL0_d7uHSb8m*5W&+$F{J zpK=4L)@M+5YZ#teC;=Zs)_B|wS8p25~ z$b@rVFW_8$1#EZUMi%%q!O_GSU?{{?=7i}$eq9%=kdov=pQ?b%iq%l{+<^PhCeIE2 zASTQ7`~h6XagWdFaO>?P*z@?4s24woy_D>sIXh3Icw8{Lzx|ARUR=T%8TL5iW)qlL zzJp4U3}k(8fc&^eu)9qf%=bJd@_I$&fv|?F8RW`7C+4!-R)H+(i7QJC3T8Vmg|ImZ zk<4pVID4&9#3l`EEPuOZw@6`G5+2j*q5JLRF~YZjdNe1}1kZH5mi*HpgwVZ`(@23rBPyL5i7p735@79lBC?%pKE(mXFhjg`YhM zc%p#qibdGs?~FG(&eE4MBXHhQ2_aumjmPdKVAmEu4AgYOfO-8aYWg;a=cKe^;oC~l zm7t4|ANpH-@J)~4JL2K@wkTqKT$ih^LY2&vp;V^rXo^6>fu!%TUh!&oY?bFA-)(4-q&yDp1z$j+5qf(h+U7WK~fO z?ddE+$sa0YL1i=T){n#kW|!W`~s1 znh5c?k})W5-H#s@d*FAj5d960pu{wL9M|PfFWO7vidtdq8Z{ZOepF`-eKI&cWgvFC zdf=jgQOK8a)W_~T8iWm}a%uChpsfIxKYK?OUx}f!8%ATQgfmF1JSBxQI9wa10h=$R z6W6YXblO5I>N3lT_H)tn%_ni`aq(yHOJQwvGib0r{C4O0V zn4Imu3|s2=K$c`urIY$8#5 zYECXSy`(3e??9u)vvK#vNGuzfOtk!iNzvAiv~c=RdQ#g77cTrv1}tcx_k*-Srn<*+ z>K|R4Rq2fjD@^Fxc`{Tt4Y29NKG2zMMxMo{;rtX+(&$`*{QP>lF60OOx$h$SIc>&; zL)mvu#BE`na7f{(~E?TDRW3_c4w<9rv%WhKPc6tYJekz`vT7P?Pm)rvG^3z{1 z#lxK&;u*>X5_c{?FOIX>vXyI{yN-*>-^|_pe29}t$l)BuM{u{Yb(pF`3))=G#lE{` z_;BJ+%m{jhV;#k4IORPqKGuZ_207fs)5ke!pK#7?#(7Tl-DyrTE{t=qUd0)t?c|b9 z9pieZ4r2~ex^YMPb8M>4#o-BaS(4LeHf^mPYgL@ZZmulA>jsi+Z<8rozg?Pn?b?s} z^OJBC9Ks(O?Qv5-g+};dqb8rr!QfljRDNiO|aex z{MokNe4G{{roM*ACaH)1+?6%A#}Fy6!u8(+Gx31gMn>9u2- zao8KAnpHUbV?9nb72=ZTZE*hU&j{FXD%=#coqDwP_{OnWMpMizl$X zqnw!arv)tQj^MT&W5Z}`2^Q6#!MNR<*+kiNrmLI6&h}rx9D>)eRa*W`_Ud{zJ%D4i zbTCT@n2ljsIXLcd683Glj<*&|vk3kEtaM^6{+wfvY3==)`uf$(agjXJ7~#s!MeSib zofokEuBJ>+n`fq)D_Bp`Viu_~l!=dDK-0zNF?-b*<}Y;y_g{O6VT=CKTTeIQ_5}{C zs*Yz@1_0~#OOJJ>$un596}O)q!6H_fu}xuD@T%n^_W12}YEw6v`N|1-h*Pb2{ah

EvO|(R6%X{Y{9`$X1kZ)~q--R<5F0?j!pkQm?R8R;k#w^P{j6`OU-!$5lM+ zu&-F+Y+I2~Iicb-Gp;x>WJ1NOuahe7--n8a_f0Amd5o*5r_*t|@OzbRwM%qwKcMK7 zA{;)~M%_9K5RVn1YqJExk6WDDn%CUJt##ZOXGvc2PBZ8F@i(_KQ=0Fo>*hq6gZcC- ziYCtfBwhU;`iExI@Rk!OHC|fqy}crLTh%~sQ!*~F*g?wLCP4bJ5<1GU6jvTKz+HpS zU`^^iycg0KJ|ir)VGQC`Rb=&eEicrP><4;&LX1ZS3uhTmB&#O+VQs{z(@Tf%VHUSThX~wAW zB1}E30J%!J)Nhc$9?@Bi%lJtkJ}(J;?Jg8~F2kAXU+D-PbGFA{$T!6KvA@G(S;BZ= z+|Si)ThKCAq3Ok94=iDC?wv=u)F9MRNkCVPrC5GpDsJnm#^9V?xFz5--jfYPqtkzo zw2#L^wHgfT6tS{QDdsv_k&Sk%!k5KMg`7hh-mZ3pz^Ms%tJVrVly+c^!8%Be^F;5f zq0nr9>2i^V7CuoA=N`z!aSLW$;Xd6#PU>zhm#KZ9)7qHDjofiVP^n(!-dlc#2B|xs zR4|assk#Xh^<_B!4TM{jKAAh0SOnt>j5({@vB*wmlFh~sNx<4-oP6w_Xx=AJx^Da# z8krPGMGhA5*>NDh#j8KxZY<5K3PrbFS!#SR_T!z?Rd~L(o4YwolD9UBqqffJptaD2 z_P8yEtS&1wu+9hmk}H|Nky20XTcVZjlOV@=8?3!94av*f=?i~pD)QNmCriadrfq`Y zWeJ2JCtIlcYz4W&_VnY8!mod0S~^df(sk;A<*lhxIsD{!ap#9Q!xhP zZ8AXFW<1E;AAtM+7M33~ya=@QJk&ompzp-8Vy*gkx^c{G)U=r@l8!h6duAR$>7tY5 zj*kXC`Q8X$#A{;XuNchl$`P+JS&Nd2Y9J7NaBpU;_-k7jycdPQeXot+9J>r10{4kG z?#v;Gvrzp~Tltd05@Nb>3=H=>OE+J=N?O(`0x>cqa-M;>p#K<{)j0-SHBRBJt=n`=?Y z&l2dIQ6e@}a4l`!WXm$F)0qAZE2bE_jw$rx*@ePTmN#t`TYox+C{+mjIL93PtRy2+ z33I`f9;a~Ywq4kIDNx+woJYPc@kY9r$5k^1i=}>jpep&o{V}M9zj;BGwiGr0{NdkL3%?XJt|!UAhn!Wh2IAyeioekfh1td zIgk<>Vs^?U!l0BG`lUh*9*Ac^W`YX_DvIf(5<`)iN+6Uq7-6+?F8%x_2F9#+gv?2s z;I8`?x~R&5DsOlP`@^!~tnnd`zc`lL@yM04Q&s1#zIq7}&-!ua7F>g+&xM|mHdoNR zCiH9Rh2XGWDV(p_O2$jr!Zsl$|2|y_ekKpbg*)%j6Y?=ITtAA!aSix0+Yu)Foe?E0 ziomh4Tj&wbD{v>F0Lmf-)=;Ft5c@S3oExi&euFO^{%bhI2Fc-yJyaWU%lRv3_un$enhA4@>vreJgpGx2+7K(+?6mq4zYzEtBeo z-T<3o3s^(?akoN_z%;Wt+=K1u5N*95zMX7?w_ZZ7q3Ac5F7^dq!(j5arjX20t|VGo z`T%k*)I_mAT2KGwjh#6O;z)jZaMwbx ze^&toB55cN34?GaIdm`@2il`8M4aUerXHltB!Bd0d-O&#jj-)3+FO|^xNH(~g@4g( zqXlzxc!mK@iKtol8I5jRF*4v6`u>=YL2Kr)JcW5|L{mMUo@PwQuUSOn&1rl;NEhc? zOv3$RPGR+mG?EvQjdj)PsFs|9E?Q4;r|&yVyf=l}_uj%Yc_p~4QHjM&R%M;9EAdad zEqgUdi`}>`ipSUbs1Q53Hu^zptSm-#mn+hL%u~`~x2LR>8~nwh)qhofPJrVz=!NFvkHW zS@^eNcKO6~V@=s|tx2q)cM22f zy~D^ks!Tic07`LU(<~WX$o@PE#@Y$~MLG^-ZUKuBf;5j*KG>vJ`8qJo~sIiJ@ zLni)l9hL3YF^?G^P0=t&<811u0vn`9?3JkSO$2 zi>E6^P4x1!p*Ye{=&}En3@5VA!78DzZkA6hG2ts9_U{d@BPg58om#==erx5_GwyJf zpL4k4o-#zy8Q|BgTYVc`v{lH`%r!@}#W zqNJu--R%9#XYV^_RdB`5dUaZu^_2W9YsJ61R`%o8ThmF=d}`PszSMhwmDhL`tEuj{ zt^VO>?@Nr#u@VmdpYdNEzo~(d(ZA&HpZIf(TiLdNAALCIKP>Z0dm7ySC;q;0EGGH_ z%lyCO?+a7@&*z`>u&z~W^*`c}f5!jqJed4H+5e`dCZ_**C=C8P_WwW5k$an^`DN-A zaH_Mha*Xb~%6IBbm06xMDvWMkVowHYSeZqSw8}bPUAg&1KdWu$vnoGj8CE`BqG#o7 zagkHKzM)cjOJ?QzyHM$A?^w~lLduHIimdcrpkcK@PP)Rlog)*s-?Dm^t}67gcvL>< zHL2XY#ltGdrn2(1_2tUEpwpHA%v$^_}7J)|)-$Yz%9at&ap*TOZ8tv??}EwA$L8 zVHNdT#`>a~t+mmia%Z&w@47mb-@m+&50;GNt>-M^wNLNi{r`mV&8n{a z!Nnu_%rYN-eN+m+_Bqc7^HqGv&29Y5kR$x3_s+aji8G(}Ih?;O2n7b5iRTBzZsGr| zF#69s({QD#I6#>DKjXifzmchh*}wb!=^wC@_o(;hqt2}73r70$tvwrf^VlrDrZj}V zUAvbbe!`zmcz%pe-?fEbs1?b7y&1+gY+b}#jo!%jd`{#)t?}p2KV8T>T?pr^fQh1@Nxl!+4GBe!Nrp4n8K+msjFv^Q&AB@uM%T;#cag;b%8T{Ad1$Cd@7V zU*>P1Z(#6m@89ubj&o;z%L?7Z4~f@Wc`jvsDjifhk5!Bt%b6X>fnk0dz@uO*r`xrX zeShu8$$L!YhMjkVuCap4YiJvFRT{;WhK^)*$9Ia_uKSWEuWIglS)9-!JCQS#wk7)` zRJnEH5vb#}1X|;zVcy7E;`73n8``V|je9-WKhJN%!qp1@)BFWtjm5wG{SH{{M&w(a zFskSUb+cOrFCQGj?($*S`R)q-8hsW1tf>U|hR^iShj>)l7X!9E8$ezAAcRVIW5fC% zmNW9N;PB$JwB|d)xo@YDv#%2?3O&vJEjB_|Q8|XK(?)*hZ5$O?3-`1%X-V=TLe5%3 zQKvu3eL4pdjW@!M9v@KDE~f@h-eRrGH7JbDf`zljiQWrb;#*WGZmM)bAH7?!SyT^p zEFWIk&jr8mKwLZiAmn-odz0toSX|i(6IQ;ZcJTv0l zWf=H1F2~iy(WLP}11KDgrJ4)hW3_fObVOYdSzi4Jw(8eOfpk0I_*>vPB?q5ooxt_K z5@G$plen(#4t+BQsn)^0aKpJ22VH2Oemg?oz?@IHy|)mEXfbb6GJ=&C9}9(+uJGjKO3!pM!Un?tm0C zYgjh&i?}Fd0?}&wDejK%p{(s5*v!lq%@+8OhHp(F(l!}?%C^CTUqv{}DG`zeti|EF z=TN7z1|Qdyp~j2=X!p;~3>J!>T_rPQWFn#?5RmUKdP^HR9|;xY7ou!OKa8St(Y z^7;X8qJ!C+sNzO1SZi8`snuPye0nSPj9UiY`T;mAU;;dRdV^XAJ%jU~PZHIzBIqJ^ zfMauMR6;XRF>%5Ea=G}VCloVgdO+}$i7;-M3@&^Xh%uw($?Hc2WW&5iX!=CxZEbr& zeKTAz?xioBa?UJ2tn>yK@7;yT&E|Oi&o6rQn7}5qcnhaa6k_y}P+TXOgYWK@;NN$@ zh;-<4lHq6%a_hTr>x^uo99=33INl5wzbIk75SMx7^cc+rzQG;m6ZCE1E|ElV2HE-f zJ)9dMrr%<^z}njep1x>7S*g?Xk>gT)zQ!BB9Jr199gaa;W&=??oe7$?UFB}q52C#O zIPw1YJlOK;0NQ`%!Rz-Yl)P3Bp~Y`R8+*)A?bX|v?7vAHZaAzE1Y$z~UpFotr z;CS!lcFE-HVa!xf$GJvIG~tsK!4GX z?dYSss`zwgE;irqBN@4;pkdj0%xzsRF8O(vHbvcr^`Uu|Gi5qJ*ToFSKFNbUudT_m zUPcP^;$Yf6p-1ABH=cVq0UK{_#BXQAP^LW^%Tj)dO3XWPQN>-jx@j4%ZK=aATJz|~ z@{eHm07Oa?R7FnTqG0AR;eHw8Lq-%2fDhXTVbpR1j2IwzQSu_tSrh;=Bm2WDQcLH~ z3xpVl5E?(JLbNkrFy=nE0<{x^@sorfdcPcomwH~|Eo*fwSakx1JWdw9@;-*Og&WXw zzbnWW2UFk33=*xc4RN6th@wy}Jne7<%8vXc4wx(O_*R$Fc@Iy4Mt1^P?V)H5gyeK=d4#Eeh`#BGfw_gD#_ZShS@AJ0o3j*1WSsq~{3H zO9SzsbSQcpJOtX3InemF9g z>5#fwEHK!3H11>gt^F=hiYNyEeH7OA{-hr)M#Gw@UAVq+J1huU3Ua?rq1QJv^4Rbc z?Ah~yen0&L$T%y~etr%q>yMH$5qP&OA14oqgRg(X;nJIXIL}XDUmMk7 zIoE*duazNr6@sl~D~?HB0Uv6!(57?{c$PV$*~>uuUaf?3hmz=YpBCJya~RM2Hvm~a z38(C-gMeZeeA)OISIkX@Cu={@JhMz8&pZ+RcM( z$s}N8oBbh}Z-m%WkP^VuHC7ln^$S4ywG!>E0@>w|JrHSa|m9zASiO@fKaVfkToru$_ zl+kh03!)XY5)^Ic!nNoKa&Ocr7!-B~7th*{ZmEILR`7-n_1OrULf?u9oS1`rS0#So zLlIV;ffosy7`kE#^exW8dxHkT%#29%nxiXPd}V+3xVHzVG-FTErzpE@j!)t z>+(MeR==b{QP~#Vbf;iL#$gy9u@;>_T_C9@qhM&8BIsXLhDftGlnrKL{h4J#eZgEj zu&bCD4^6>0$$~^${tV7MosAuWC+U*jdAjNI8(cPXA(U-Ag+E&!gSUB}P(NCRXBDpr zeVLQd##jw{g6qiL#C*%u7d~Rtu4vE;3dd{b%AnLNSR|vTO|Hzp0RODNa?dpS^^*}6 z-@^EB*53w3f_>~??jHy2SY_kBNZuy!*f5(7&hubzyRGSUw?pftLe_|a!c&_b_#nWuUs<+!{WKXe;ekl5nKd^ZQ`}RMr zKaDKR4FBc+@xiD)`~t&bp6RPvotHhu4-Wu7;`>_OPkKK8WmN{RcxER*yKN*aS}gn>r6hu zQ^Z#;i{V=gXY%>cSNW@IGx?r({=D83HU3ln*8l834#b{c{XflL@XzW0%j+-Pb^rPN zb07Y%@hbykV{_wwuEYNjzdAJf9yiLg7M5=~jw-1a*u3%tZhlY@H_fPw`;mQ&wLh!i zM#f0BeD^>1&Hw73H83%@__zD#mEH!teqbu!_eF}| zekFw8_+>ADyVa7HbGGK?EzS6p%1gYI_eB0ea1ozB&xJpM>_Tq9lwfP<#&$Ys*tx6b|7Y>Sg zL8RmFJnU>8OxGv5VQtMg+{w*`2|AUc+NgfiU}gyE_e2eXkS7BSm*B;?3qn0fe<7zG zLS6MP66f|fkU1#f%!CYh6Hrz_D9aRgRYRf zj+ju6Z|8^N9la9tIiV$<*inLygVfl=S>G(r9&M+MKFL(Hd>Z;j?ZK+L0+je#ilSx@ zJT8C8B4y1hHz`4hR&=YuWR-C)(h3^GtDiAM3-agA^(L2{H&Jc7N`v8KK`BqF}@TojTk7@S_i|t-qA34?qfRn=V}alP)XDh z2#GTe!Z`{@%8zYo!5e++aLt-2;G6`=Q#ThqyztSJb=W5$=0dj48)?ROTmOAKwA|vtHtm@E2w_kA)$zsnjkn z1pI!>av4$2iJ6=NEbSbF%bpEnFaJ(P1?8`(X%K;G4_@Q2rDED+mVLAfB|F6^wSOa{7gTWe^g@tO zG6$)GLi#~#7i@MN4DPdZ;A45Rc$aJ?9`9$tUaYic56=x@&xgH1pR;PLM|B>1mF>bR z``a=(Ar7`!DUfwImf-&(?alwGdcXgF^E{K83K6MDMb5Q0krx0AlG31(N{J#$O2ads{rdg~@7veyc7A0$x9jY^&RUOkzpt6Fkd3mB zMtc#8wF4&1SyY}0eP5%kmok&N`y6+SEJE2bF}CpD6XC=5bnIGr7;6(Q6XTS2G|f?D zNh-eFtb=yk@Uz+6l-rv*>$FZtQCq@s|HW{%M^|v4+Qhiiq0?}y*EDu?(sb4|)|j;x zbfEL^8BBD_Fxu=?KnYtFY6>~RrWM)z_tiZ{TDe31hM-v~m{$LIp90|;I*?8u;GKGDP$z*p%>=(`$`;yF) z7r^+8Qff5UfE3sT!EK9s@FKn&f|fJVxGxdpoe!e^hY=WXFBYWS_$+*_kUmsdC7j%N ziulMT6Y=#FX7$%VQ{@=$@sni8PyYue+zh$qZV^sSBpG;(2KYwKA=+XUq}?`v?;+I_ zztmb`&xj}(__74P-h2nX)8)Wo`3yWO`B`%l`?rQ!eRam&rLZS)4*@WzCsFOG(B&f|!>Q~td?LgIVq2v_eNQBfEUqSoJ7<%uSF7>B#~`}Y@+#h_jlr|i<)P+I zC>&et1<`Z&qF}57Y`at~c$=7vy)u-9O`nB0$a9iaucK1)5ZUIRgVBq&fYn-QNJc|6 ziSB@y?-!uy?oQsv6G=Ww5n<-~N+^{KMV%ZUjA-6X8Yg66<&87AY)}-J8P!wk=cn;ADWhNA%dc4@vmw zt2}cyQpfY%B218c6VKWqwobo?lk_~OLAMM`=DlWzH^pFpT|3S2Gh%-CL>X&VVuwDw z$NAfN2D-^8IRC;(V7Y54{e3GCPnTXJ!4j8gc`?Bdug93OL5h9hmoew?+kK&b)mW^y z70dLjz_E9gS?zE!9dmD(#_l!}> zaVX_^9k1Pdg=6)l*kDx*MrIWXTBe@k*@aJWP3kP}T$wGmI9`*Bof83HKC5xv{CQtx zupA!u+HrF6Be}(DDOCE{Dl|S?Cva@GK;0~TX1eREy{LF9`i|O+drrKk(VF$3^sJaz zTA0)Ao00@SJI%=7k_z&1S~Nue7YqSvlVQkfE}DNhEF=Mk1^2%<;;|q@w(f%on;odc z`urv^U(**H{nVdyf1 z!E`%=Y!$>_y%3^q z{1G-KuNRv>0-K~_&aQepv2uF?SHwNAs^JxVt8*M|Ij6EujbhMuCI#%AxKE-cRKI>o(+CYtHeE6KRg~H^qX(9dyjMEVNT? zCCR>o&B&XKJ&KQslhg+s?mNL}ZYr_$r!_NpbQYr~)L@aKJ@Z;Rk)8J)#bo_>j@0)a z9B(p{+Cna#fGSh1~6CTvo=FY_E( zkAANvGl@6DXdP6A3X{Fq2Pr+K{z8}SwTi%y*KW)~Iva0~Prwr&!_o4A0Um60WS6>@ z;MA_a$aXKn_l1V+p4VrrsBOclBihWapU-7p5oHIO^dT?L71~sXiOIuC92WB4uHBbl zAMd#PQRc@ps-Fs5=1Vfa&u3`D-bP%JoQLtxuA!<8!+!HEk8 z$@@}xtilY>tR2bMF2Ct4rCNNeaF6b9sKHlpox;GSt7u;KNcQZK2D>6hc_uOnE{tiT zzbxMK4si>#zPFaXSUyZv57nTozdL4pI7P+=)q;;)J^dD@g5$=Pk=s2_iRkZXW!)Fo zV&;OgG}@50}oG z!7-O=n&k4CCjAT!XO$JcUIAz1^zO~X1J-k} zB-m+M(LA2TA0@%xSBI#x;uH+KrvvHSUCgbnA|>mT*~Tdu=ot4D>m0V=#Nq@dSG(A554Z2hY4TfVXJCBT$BwX!3oOTLl-s9Jmf$4tlI)@;-(~5 zT#Xx=*?=eTi{RJcPQnNk5j1c^QUp%MGAEeuxmkX_91~34>BE z!SL93s7+lDmU9{fPvnk(j^r0Xk+?T~cxelHtR0Pky!*}Gb{bw!FQ--dd-3m+r`US- zJo=0Xqt`@D$V7Nc$LL+>Yfc@cr~YE+#J5`Qb z`d}P5U5Ld6-NfPL7yR~BpB=o+KkFw-GmFW}tZr%}&)PYJ|kVfKA(xZ;xqTmJk4KGIpmKK-h}Zv!LPr^aY({F{U)7u2B2 zGiUbdqCfYeX#?kJwTe6WMHdVn--o`|b~r0FA3Ds}apj79?X9fAzWn%wg~K{b^38h; zi4R9|)QY|FOT|YyS@mT8MmL$wqW%qo?`fSo_E-y;XVw3)F=g=VY{9?i@K zx?$4EW!&6Di?~+y3fxRQxlzy6xZsnfoZi<8sE^$Osf(v`8`cDIolk?f&yBOVfpJOP z_n4*Jf-6V4&|8t5*H>H4G#x1-ba* zCeKlqEW-iUPU=#A7%P>N@%QmXxOTo63p60C^*Ud3`TRhG92>Ud$#&eRuExFFsmZn6 zh^K98Rj{AGpU?8FBwF3wJhxJoi0{2m;#4xAXoEZCnaASf{msNIay)d-N=wvdUTBXS*{g{B}dE23;Yl!}Qt^jw9XTyjB#QVSyNZHir%=C53vO9| zhXsqxxPKM`&f%Up=MkyGE!4XQ3e7%TC(3c}S6&1;KMnR)ubKu#AI6ow_QE|mfH|JO zdH16_)|xuvsA6??dxtXjt>!Pt&z9mg27MvUtKJc}&moZ8VhhvfYQoEiNHBbK8@HbR zfg)EJCJSU(TU#CdcCihuPDn5w@WQ<9YN?!12A}CwVoYErR#jD_C0}E7MQ_A0A|k9S zuLKKBPNBmAWlk@17=9+3(X`$&7~FG?dh8eBP7oC?=J$~Ba8m>Xeivb~3;kF}#(AtT zTgZBsZeiUnGuRT@5v){x2Gj7igo_NtU*ntx#AsuU#P@1`%*OM1waj{_i6 zl1Uq74ntB@cG>GEIygME9h-V*;!5vpSaiSzbzj`UGh2tzD0dUCKADZGj!*F0R96gi z%HjF64A(6Y7pz()gFf>W@SfHsGU|63zV%gS-wM~^hW=Q*E*=h>yyv6qlxj>WD8V;& zs?b!mkpzZCqFdEO?!nem;PT0wV>4Rd`g#q{XM!E~{EHpe^EC_(YgR*f<2wAQz%z?R z1Ykz#FfJn(sNCy7Iz92M@Zr~+B&F-A@XJ~!Sh=|s{+iAt-r165-H&Qv>(@sDRv%3s zU>QVdC%_`{Np!PRB(^o@!t;VivPt7Ozt4OHUw`9w=z>Mr72h11|7Z+*+Ib(JzdwnW zuJBsw`QzENzkl)Hh!M=kOo~-%9;Ff%Be|u5SeU$dJ=tbZ4T^pnh4;?%ljJ=SP}Y_T z54T6bCUZ3w#50=mNH}hOqRiHQHDZqzG-9gF0u~cKiXBT*VWkfCyc;MDqeV{R{7HGj zy0A`Mv|olb@ARiL@?PVa>LC2VKTpitYw*!88&+|2kS=fehjUf6asT97n7PZ2y))-I zfKyCR>-hhC$tQ(x|1Kv=Dx#R?TSTF9H0&)t2J^cL$lI+lY}Ar4yt>>LqcnMLT*-aZ zf3M8eS)1VegWs|3(q4?|nufpfUZJ4lCq@;X$K&&iS@ZTZJP<6$Mg{1y#p}i~z4p1_ zcWEvxa;m0nBZrA`MjmLNJ_VWfli@?zY+`CNlcr{t;@&tt<`ejbej1QuZ~vJwjh>6B z^-GR*8NR|IPKU)+O~JbI9zpq!Pv|*yF&u>g-NEJ2;LMszTmL$Ch~hN$Y1 zoJ*b}*{1ao=0o}F+Z{JU@5KC{D?_?wZeUl4YcCfpzx>ILV7!!(FqD_toDg5bAPMP?(Z1G%&kVS zvV3=zwfY7w@w$yMqI+0fLjyEUKS$I4&4Y1w4)Z?TNYJzVEBNq%kY|g&&_6n5fIhAC z)XqLSE&L#E-T7P)^vRt@@m!N}VxDlkbtK^R^^kFCKKDbygbS%T%Eg9QbBk?txhs8E zT<&;7h+H(5GoEYCMa|Gl77B}v4A9qfHE~x*9ChX_M*N!cfz%-^4?Ayqqx7{$ z^uK^ODBw99z9NPoBe4bld&xVWHA67Q;V2jc+u{~QL*7e~fe%LU{;;nvaD(j+bbXyg zM}2Ll^Aa0qqV#D<@?8h=Ue(mN_%wZ5wIB7;cz$lDG%kJG0mnl|bB9j!!mSzc;P-4S z7dBs&j_VTTy;&U)plCrZE%Jj^Go;{Y(=wvBVgc@oFQB0{Hz6bA4v~}ZB}%&ewEArw zth}%V_URhH)kiu)GqFqzKI;GhR?1M9vIH-;JQVJ`SquBOjYBEFRM@ol6d62q8zT8R z$iC*2B+c?OJuJBdrae@Ic`*j$P>e12w)!pD#cm}vb%tE_-X3^QJ>f)>I+y8O4*q99 zL+PIrf&qumbd2E*IQIMstq=Ai6UxkC?CU`ClIU^qqYlCq&t24Yq&#Rm$b-!Ar=%w! ziX44Ah3_{AQTjpw5zP@JwO{Vz>2?`*$!njGSbjr;I0+UtCJtY}kzgWT7jf|c9n`E$ zz`O@fc%S@k%vdJJeqGDOXHf^J_4@)!V(wvKm@NG_6bYV}L~-xllfpSBm8AzJM1b+x zO5xC!FZ9CZ6mU3Gg!|jxqM+x#K=O+(7OhM}uBH^fOv}Wt`}nNbxgp{;P=|v1ZrBj~ z2=^KFqL%DXDW=xrK?zT48xx0JtOz%zniDyX0dhO^G%YHtA-lfphk4l-sHfZ*+M#iQ zb_bLanS)P3ZMG8k@s}c(+$YI#jwi^K4sFh8Z6}Dm5rabGIFd17jMb^TafD>U~u*r3`@Nwau-Xf zLQ4m&xnqtGp;(@7uQ6Tmc(+-KV(VtCt=0*;=`YMY!q)rw{bsWPZ zC2s_N8qb9)-WTYq9wlab>O1!2mZ5j|T-1`%Wy2Fju_V;T{xzeSUEFni-ls+HUX25x z`3U&CS`?-K`$v6SH$wZ2d$h*%I+W8Q;4MSg5#@_Z=cK`x)24Jvk^z2_vB1{>5uoVt ziNu<3fyZ0o@qNrL=sVm)N@mxPp_j*rWcF!t#ps0~rbit8y!Ya*=6;x)@CN#A?!ij) zmC(EQlE87GlgvEUM@4zIl)ah`zCULqbf|bko6Xkn{cA!dTpSC{dSl?#gf#s5Z5kY& z{D69ypQqOyP6)%(Rj_R!j2Ld20a{yfkqJ&vd6AhYSa1#3OnpFq#7o1y6@x^HBvZdP z_vqXDaQH8#0pxs&Aac%VSm9m|!A}c_#myV=VcubA>YWQkTBgLV_l+>(=UqO(hM+Zd zB??d3;?UP~_%zu|aIiEQE#N4II|jnLc5Pg8_bB;~>n3|6%i!ndJLK&E?@Zny2QS{Y z!`-u&sJ?q7WpC4|V0bFz^*@}p>d|4k{^43!ecv0aL;jG8r#}U=-`J3;^bW1~EP%0r zW<>JI41N~WLR2Dz6mxhP?E*dp=A5{% zEWK|w1ml&oxe@n=NmS!4@Y-62b=72x2ZMsj%mLD)8PB6-F{iEUDyz-JBbBV#et=zbuq_hB$l{vQ=u z>Ius~&Zkdy7{jla2<+RZ10P(^3GU6=L2mbR^uw(OV7WY8pt&;)TS}ZUXuw+NJ)B6_ zy^p0uQ}!|ap`EPe@_yE>D((&K<#U>6>?MR(GXzA(_cD~|sKeC!uXNkPJ3us$BkzDnb|772xa7c%jFUAFd? z39F8MgHJ}OvLmxN_ImslHg2a9t1Z%H?*tjb`}#tm__`YcVoSjBk}P~TaKfG5j7~1p zMz7umvd6VmSiNhd@S-cA&XG)k`GotB8s7-(MQkAW^K%l~zJ=U>{sJCdT}%?rJA?0- z>)@TP$j|Qc$O#`sE+j$&Ce|x*3vX+&6idXGBU|uaZW`X`j-;#8-r%y^ZuG45mC}ad zZp>JriR&b^VQu>+IH+6-Uuz>tv-4rH>USuR;Xw#ikArhp?!Y92CMa|qB7;A+!l45% z;k+1sol=uvpZ`X>#6ca}ZFqN|{B`nB#{k3paD7_Vh>KUAG-Z z-Z}~;=O4h#PcnQ~)DBihDAVjjF>b}s2Z7$@X%Mhx7G3?LpzQWHPZ%?^3{NcxqLNo0 z(#X}Ts44H?+oH7tCr_>s1Rv&I!L?`T9N`3F@j`-`d+{F5wp6UE8OJ^xYbPSZH=%qj zp!}F)#6fXgq^x-uEmHil!CY%wg>Oo4_JD}1xz5K-~g;HvC+esa4gxNLa~ zGjyK86U9B$BCtsCgy-n^_Z|~|StSYob)O@uFOJ~iOXXOS6GQ)(zuJAaLPErZ4x< zbou)p|Cn{4|8!LhHN7H~sa;IAtzQQJbZ3F4LNEFHMT0E;n1FL_x8jL#L!2ldhuMG9 zF>ZV~O*^Iv8&x>e?1_tX_7L}>185#Mmh2d_8f-6!qg2ZnxF#}0 zX~1f{eq|>uG|j`;35T(GmMqNWchtX#m6cj3LrDNJrV@7Pga0P?}I?8(D2Ft9xb z7c6S=*2^JSbxV&cKUhTm&auab_gm=4v{Jgaw*cLPR$|7)o3KQomF7&)AWo|fvoB^T z7_E7hG%KpIp086tYuX!7)egt>(*n+C{YNl!P9Y2O^XTdMIn)<#fmBck&$Fr^f{x!L zf2Ru>o_B}lo*K)n=P9s^Ll4lMeZzHa@9=e^4-P#RXNx-Lf#=#fnpl7pMKl$8*<`WH_hY{wTf92-kjGjk?#H$Y{&+=;+ajq7ipt?4!}d zIwzf;ni5ObD#VmVrb&R^QVBFNRKy8)mZR#yvEV4B_(VezZqJ(v zXU_1w-cVOzJg1AYi%Re@S&bHcQ_wL%g%f#IPntY#5T9O6x=p&DE{;7aOb@+)X)X&$ zyY3<4>-`Z<7 zb#E*l^5@-W8`RN;9>!zU;@C81EcTQ<#tKno+%7B0GTtb%+iJR0(#Mk3oRJg?B6mTA z^L1)&FdMm5;~>M$5q@P<3X5B(V`_&ocU^rW9COOCmxsyBP^=ddCtb#ju@A6b-xr@9 zZzVUQdH-&ptuQ9y8!*K!_*GSrxcOa2*Mv8?X_Pkoww>Qo8ezp|uFWVjx5=i?-=xwZm0c; z@%S?=6<6F}Mm`lr!NgC;z~oC82D?O)8Nu@0nBQ};x$``7-=ZLRMLa1HxlBbx5|>eNT*Kf#~Jp={_DkB9pT<#ffo zU*rM5pH&y|np$8o>fO>s?c0tlM(+%Bv0u#IXQwfl@4MNsQVdGE+G5S3O9T&v!i2_1 z+ITtysz1+yCEg`8e9lC$^o|AbmEY-dYAh(KABoX&YTVDuUG$xvDjV+S&rXsO^FOG_ zY*)B51+M~}v`&S(Yrlp*3mbgQbD)eT2BP`=#UwgMnQPf=#@syqkr43`cqq1lsm}~! z4Y-G|@eG+)!vvN&{uSD&bixK%J1{=31;ygq*|^;yOsA61VcuTJ++u-!T%CZmBYml| zqZ)oUjH98WIo4(;!8+P?S?mEXDsnCjW9rxAn_W#Xwr4lJ5MxRIC5Cf3hh9R!`wZN~ zv#tgcO~}GkvoS}06^rZFWJOUou=jlt+14Qohk8ZG{13Zv=|LgRymU=wk%>P^Qv-VO!OR+QHW>GaiiGt(J^d6 z`hHg3Hk%z4Nq{ktmegd{OJR5POzw5nFzvYV1-*Ejc{+7eA zcF_w6+cTc-TAfHDIul6t*%GpT`xU{qfg+62mxBu@SHg(QO>iS(Ix||~!n}=-F(-#T z>}tSac6;_4JTPVjzWbC#Qu;j5{oN6Cx-f({_RDhZ)4#&JPd4@@UNeNNyxlRm<`t3o zL_qqBfS;w;3EphzCyw2ka5N$g(l51Pk<|(+{r)_B*;zr4yFCYdt;C&nJ2tJ$dNZte zoC@x`8}N{cB--X?f_Pgs=Dya&hSdz6pBb|bS1-KarH%tUk6hpOGsZ?~3C~+E;6CQ5 zf|Hym+G#8l2C3e~e8Y37t-PNJ)qL3grO6m`OOHK&mxWKWbzs9oFIG504A)=#kD879 zi?0fnvvZ4%puGPA=yLf^m%iA9vRbp*&D(Np{JP!5O2L&qzmksUms@i|CtSG^H_t=q z1QitaR>C}fcHOKn7p*@^ve$Rz+2nd#+-lJP+xHjH$#cBuj7QP1`s_Zkzvd1}5?w5e z)l5aDAUn+d@S3}idJe-&vbic}X@@tr%pEE&RC9g9OrN>iVN&c z<`x{9z~RjrF81tNE;1sQTho}&UCW=%U3@QA-ZERUTzt5cE&jxJl$JS{>z65)tIYYy z^xag-&n$V)%H31h#IB#LZn&KFT0dkLjE2~gm+x4CR|4y5c*knF5A3I|UioNFrCi1; zgZ&8*E1!OFO1Y)y1Lh7vEU3n~d>4Dj)<+2O@@Bd6$gV%^UgAq^ZSG`-1*6LAi&n#K zx0_6Fjb{19H}N>}cNR+c2eQun$?Sd9BR2F?v3y4%W2*y(*jZ7-a=URixhmOVuEDs7 zYZ(~ppxMPaR2kplHm|UD`25w*;c!SYcQNe}n^~w>9;+S2Y#!*Af2y-9SDGPJUhXVY zeu(LoTTGTKcX|Dj(-zlp@VQvPZSWlJu)SB@!RxRs=lw{{AxiTH_uXkL_w(FircEr% z3l>mj^d^Q$SB@@!mHLU*2$rGqp?X$lf011-k02}4)4ArQPdL4+>YQ&xH8=la5hwfF zlZ%{wiR%q5=ZcFvxs8qT4iiU2aeqF|a#;9#w!@^Chq>Q3yc}BB_&Mwo%it<%9 zrEgluYa@Z*Oms zNdhshZO;Mn{F*GQ*5;j~wyF+Iew(?bfGG~@#)b~bmixH=@aYagi;NufoVIb6>o2ie z5gO%PS323;#NW(K)TBIYgF?A^$t$+_fq40>fL5mEqRuH@&4Sa!f@?k82Jb>v!GXtt zT;84M5SKrW%r2p@m(LKaixW`etMS~{RfTkp*?Mk#{5_6TZse@q7IF{udbxK7A#6cd zJgX^>Z*dpy8EF?*y+?CIG$J)N*xu74|`kCM1-M1``^SQ!>MZJZMvG2LY2@Tw} zEk`*QtE=22v3~Ah);hGfpvM^=P~s+Jek6*5ByQ=SGu+!tGdatat=!VwecbX#ZFFXQ zB=%^(0U!5#p>XULtUdVzPU_2}XSg={^drce&ta?9c(Od1W*q#poaHo*Vyj=6qI2pz zxR%57)r+6=wS@zh6)Vc!vHv8vP@B)Y5=L-4{@DT5RKPxiTo8SG4%YAM!sbS8oT9yj zq}O*~;aG-MZk_njLmrp>Gi8>8ec0%i%`}cFFumBL)LPq{4gYCEjreCY`@~)db9_!e z%vwSPi_OTE+GtWabsfJ4G6|ngIwXuc6%T1Wx~%l+5T+dbMjO`JL2KqHYBOF6m&vI> zqk=B)Yn8&K?f!Vk%MNw^r3u9>z6!^++=9lbggf>{k)6zyKsv_@ye?`mf9(m(Ipqr0 zpBaFsDM3MSQk;z&Q6p`0eQh^~3()VXqFpnKtPEOMv0u z6JUXJGu9qn$h=1K&XA%LEbXB)YY_Q{KDzw;Z)HB#?^5JhY87zz(_ebl$b{Kd|0gVZ zV+7Le`*{b`cicSl2ukLZV2^GK3Wn0?;#)m9EkK=1JfgyFOgaq@FHa!3BfrD_{ny~B zs2TLNm%#ijCR}^t5IpXf$ywi94r-orpvmJ2yeoPMvtR50txyf_?7eX4&v=P>n++gV zt&YS#d5_bX1`Em4U}YLH#O}Xl?E5OkM*g?~I)@*@=gp?vv6W}h_G2D>akvLiwFnhb zpJIz_9uD18$LA6baANOT_-Hj7lP@d~49u{kPwY~Om{l%bwO)l8n+&*|lQx{{$qlgL z)m12~kOPTiW$xJ+TfD`yJHCsQgZIsNoSS|G_Sqf+iO1_OaG3)2fFo&65V|`h-Npv79MG>CDyX4*nhZ!E?0F1lT2kcEqW0amZXzUhAtRc z_Zl11nz8ElXb5HMthijAHGW#m8F&MCb~%CUU9ZdSzazsf(}}}0TukP?Rpy?w zw}ZINDNvju0spFB3O{GIf#G8%XlSn$%sup(1jr8(t#%hC!uxRQvyAY2fHPZC0c;pr z@zO<65M2?A6%(vk@QPH}Fq{Mrj}+6PJ2Rm1eIQA0a)!IT*RZ5A3C~{Ud%^u5ze5n)a@?S#O79ad$xkd17v>Kl!QkiBlvWu*4cO}gxjd)K)4_~y3pzEQx z*qh?SmR0uRy`R$DhSz0O?K;WHctDkz(tNS<^Dd;wL}Rx4TVe3C%ka%!nWYc; zqhh5!9y8YBb_9rW;b%3tBcUaNb=#i8pK~4%f4M^_XIe-$-BX6jA$LyexD@wt$pq@_ zu>!Pi^509;l_7Ne1f27zh%USw3)7aBKuFYaSb1g?NPcexMWtwvc(fC{u7rc(jeNA~ zy@H#E{-7A^FN<(^P3L{7!Jgql>ZGKKOK;{2#$HdLiz}ni+R2JstxAHu!G3H+03B=>oHxy-RBxF%-KMs?iBLlc8RiJvo-C^%sD%2Dup1;0ZxiFfXN+JTO% z__=LpDfLzkhPkiCGSBQ<-0u8d;9sMGm-+9iqox+o1wPkt&3*@nEVJZBtkGeczMO#q z&j60@<9B8}i!t(;}(K(MA;K=9axHWD7uYDO5sBe9M1=G5aivKlN)6KogEaK8`{CsX7%z0WtLbABUuxHlIx zABoVq9nLsbqlx#=uESXkiy&@o3%F$3u!GZn{<873fdJ2QBX9;(@t^$dkBs`&8LCdS^NGq%bmtO3 zBYWDY=8PURo4RT$G9#xJ+^?oCICw*bjf_{K;adfGVPQDE<|hi_a%m*ytQmd&P8)0= zciS6}y$5C`iMZ>Z65G%pgw31w@Mq#Sa(rztLc5oyNrywiqG@>2d>SNf&Lrl6;yoHkIEM~}C>6vhX&&~xFYaJbqKUS9o* zvpRkWYv#=$o13hJ2aPY6O*xu_$G?k_l=?`}H-Asf++TuJQw3O>w-Cd3@`Cw?#^aKG z;@EKL0V(01mEGeS@Tk)>n46pri3@Vbb-yYq78nD4H{7Vv)OMw0v(?5#`;xw}O+1%2IY#q4xZ~mIUP*`x_akRItk9A!LCFezW_|Sv{UVqQ z2~X$3hP@-;&VymFm*|E*o~N|+$Zh=a_cFRR8FHpBC!x0|RnT`CxHX5YIQ)799!bVQ z=QstNQ5Zs{i3dguCsP|?8Cjxai|e0<2w>Do*v*9rWo|Bl@N6$KQP#+6z9#gqZtDU&1 zOA{ecB@kQAXtL}n*X*bJEVtLpEfN^)OY<>!mW0EPZD(`!06;&+IwajCI>TkVk`sB zW3x!+8lLn0D+QKsG@=D3lW2_Fcxu?=hV92ULr9-I)jd;Av(l5`gQ^HV+vNi07KF4R>u+ximu=?rg0AmR#$?Z$a_6g8M`BZ$;9&R8HQsP?_geq zInT0*g}kO&WYej1o*};~px)zABGpPk= z*KiG2zQ{qN4gTnrU4_p~#PQNiZ4A-U#Oci$sJ^8L-IxqY)k>kdPa$SkpT^6xF5nJ( z-qn2f1=T!e#Js0`x6dtHOJ^@?7H-TtLrvm4$@Sn+SWqee@6G1$xWAnC+?ojWc?VGN zZ9A&FN;CE}NifRh9GVAZFta*7pedW?DFoUA7Q)U%5b(Tetl+ zEpgIf8iK2z2Y{Q-A3;dz-D#O6xx%B88tlC{&&r!(DJ-5MOSki`Pkni3Y<}Q^t}1|; zk&gxDJF*oT%i#pKrfv(SHiGcF#jAdp#9BWTy|;Lpfg+G#9}ktZ@h)%BZj^w;~tB09Kq*+PrvX-OD|PSpIN{=kuSj2vHIZU_enS|)EcLmOc188 z9me-@U$CY64$3<9VJK@5?EX+Hyl(pv4}4D$s`zWu#h*@6U1~?Zt=vrB{@O%j^DM#d zTn=Qt6X$00_csKMtpx|L6?d)YDz6dtGc$@Lq_=*A@ZBnL_*Ck({r|O3vxYBlsyJ!Cjpv&0R73 zLi}eeTMbVEDnAJB#k(FA0}3SrL1mt||!rVs`1`7pcU4Ltj32?_35n2@wb zP;u)tNvz^sJio%Jj-MWcMO{LgaR;xTbc2l^!-Cwjc3SW1f-+gcGWUYj^ds*Ksuif? zJ^nMlRbf9$Ds4tLxx4hG{bxbXnjDg}dMCQlw~-N=n*k zt0bXPp=_cdBBUZ@X1ve+N+dH%Lush|Qfa89l=OT5Jb(C{&pGe$jO)Ix?-k1o+Uqk$ zyS6j4#kH6K?Le?AUBy10I6$%lLA0#L4)%m35&e!(SU0RgcgA1Flr61v{~=MP=)5x1 z^~IEl{;3Fyp521=u210Bn+H&3EDcvXl*pA`M=(FU4ad))35}O|m+cvWUHAi0fv1NR z&R4A>q2dt`a`q0J>ret;|J8%mXQ-E zMjl}4?*x>miR6mf3{t_Regi-$w=`My@0_h9w&K6Gp=g4siFY36-JA{qJ={?2uS(=*zM z%pYN9VeoZm`H)PDLG_rjWlCjWQcmV<80}qevqp7!WQvMWS{>o2;ldid`gK& z{55)<@9=4l*MiUO580UeufcM_4~*6&(YtCp8Mj1fMqTbE5B*kTdK)bmNyARKCOwDQ zWmp6k2Ybk-gD0rfZ@!Z}cnK^ob-?DAyYRu0MdZJd6zY|*mc5|i2&TRhm~{!VjJlP& zV1O=S415m2hLCLfUWxp|JE7NS}!zeXavw zE3Cu>s?7z>$xq4OI(IBcu_JSSnqf(lHkW%Q23vUzQehp>_4K+%8jRAQcfUDPWN%BZ z)W?AEw9_y#Z=b+%`f^a>9)sSuI0%^>HluXi9$_YwKW z%2X!LpNF%i)q?OrF^(SXpo`%KJvn6z?M(B+vYs4Rboe*MBp9&HZ^iJleigR;Cyu{` z_p&8hj>DZpWng|q3z|Mv5c87vWQ1q>F5*4MudiQ#3kB)qsz@=pAMu&IPE{iT0(&g_ zFNUr&{Y|He4q#qmIr(R3kFyO@Xu7B>_P2$RFzpwpy5a>M8-ljuB=|tRmR+fxHh~^%pey zS@GK7c{)z1h@9GOi46>UkgTf?2Thuw_R=1b)A5SeYTiPc;Z34o{s6YFegNSPbKzpV3?pnZ3cqTe zV_qKLh1eyFGoAL~)fH0kZe1?@Ibz0nJI%(|2ZQmgs4CaKG#X8&`_iIME_m3edDp0E`qjdjYX`@szwKFE-ZUa2&;GZ8Gs=o>d_pr>9C;cQuM{*edh?$S>Fvgugtwg&A3RwMl3 z*T%+346@6n-gcFAe3>tdy`&Etl(o@#oF43%xDz7VUyx3r!|>w9FFVD#j-1Vh-)LVE zUHyLLb$s?<0KbpTw9OmcfenGiybpOfwESKxDDskF(7qJDxV>ZB-trpN;u8Y@q?O>X zGauCO2K?T#9uqwOz@}NJ1Zn3-=!yI`Fe}>v$$w+{US~;W@AxkGSG0>BKlX}_bBhHl zawych54+^!q0(8Dxu&iG60Vb({%lhw>G3ysq+5W89hX5XEQ6;@j?#tW zQlRC+RoXD0&l`~YVBZ*s+A}rj%F}*qfj7gxFDWEb=nOF35lYv8`vxD4s=!5|f!zKz z5#{}}@Zns4@XE?XTQMd2`LvGU0kex7Ufh#4@S-Tk)U9yMa{~poVEn47l`mSJ+LLu3AUx3=%4$zPJs>HyP#fImVbdGcm z{wg|;cf@n(%Gz~U+~&l0@95!P(er=*l{*HU*JekaKZ#mpql z>ra!Qu^Z^(%0`|6J{J5Wi${`}*zlbWYZC`qb zRCH;`Yb_Hmw)qr}lJMJ|%rTqbM=-`-7RV6f0w0(%SS8kZVI#+$Rr)>VBFyylz*e_RO4 z8js<#LMRdbF^#6u7+erLiB!E^jDc1vaGlq1PnX8i2XZ>tkvoaLh@FPkzr5grfeU%| zOOg&PI0~2TZdd=dJx`*8IJ#)nCG!5U66&~VL#}!d8cm#vcdBv(nr|MF9xoMIDzOpL zyB5Mw-(z}r*GiPq$gPt3z|dRfh8R7hNX%-~$jx0Q*zh0kkDqc0xBaQ0|9!edMN}`L zxN9yMyJa_-+}y-YU2vM@7>>Xdeim82#tMrgWANbDW8~oeDm!<^hxB|g#CbIriLSL0 ze}+9On6*_EuQ|WO8$4G?^5`_SGHgij1a_0eIhOdKNC{2$zoL7O?BrU8zM$;=g-ozW z3Ef|+z$DaZG1cNVuu*vko_6Umh1(-RQQ{grJS@aS6#YV%$rO|RHddd%WCYs%@1QRs z0Y1rXM&E-?#Bo z6X!<9pzU5gZmSQ^@S1MKWxnphcoSv9XglB%2Xnf=E{8PsR-$TY1wH5@!=D%3@XPf| z_R^eEs6HNs2R;$b$9FB+KQzGiAH1QKe~v(+dntWAQx;mMG=eyc!|Ts;(Thqm$MkG5 z+5QGKS$3Apsh6MQyZFk0UbdqU*&9967TL;uZtvRW87;?e(N| z-4p7u(F20!I>NB2IXBmN9N%AB0<(q>WB#LK6KA!t*UVyfS;_yBp7nkKNg>UWmVWRp+4CzXshYioez0!5q z*}F?n%-^lLZB5Wkq!+gwT#q_3_4L&xL)=;}1e@ln;GRPh1<5_4pmuE^-nNisIOzp2 zvwI?_%`@aWUK^na&oz;^jl+3S*7!z;LkmYcsxYD@xYK1W?%8gTozkAu;@c@Q63&-?Flq0>wSvLs9dOFtX|&b$wrizUc{ zk5te+qnP)z7~y}N>DbRRumWd{g*CJ6i1MCXD$@{v*K@u=!qX1;JTM(2BgQh(mxP%B z2Q^UMmk%3nNt5<$VNBM2Lq3L8f&0%3RIz;{i0?6FG#6eZEA}=L;oCCs&)JiHz2^pb zS^LTM-{+x5WICjoXOewUl)U(r3>u5a;>(P=U7sr ze!iz&kE~@D+x5`~*E^fwld!AU(fkp@v(~`Xt(}yP-voi37r@=^IOvC4z^*l`z`X92 z;HbSKz34L^9K+whD#IVR^k^5oTBQwR1hM$)gDkAeI|Z)Cqe=F_d)Ux&4WtYMpna+q zlk67;ul*e0+^2J}?%iIf8$QTdZt=qnj#0$KCy5TJXW-dAowVgw1WF9~qNP#?qT(&~ zTK-0Q^eMnj<259t#sM{V{-6pk3&^JPmuZ0g3w$`e0HaQ;fsmRvjLJ_$&17qGWot7m ze<%fHwIXbA3dOB_f67qjC@quqAhmPf(Zg!LN#ZUU*mE-u9_x!kTkLysa)UYJTrih; zB_Ydnq!}<4B38^zrWLYUEa|TU2SD!NE~wW~pa*)y@$Q{SvUBMNs;ugaZ#{KLan>m7 zo!NkGYU8TzDm%h)!7+r`1#tIZ6|E{%grB>wLfJkCx>H9S|2CecaYa+G)y4?kZ#TpO zr*v94T>>rcMv?-pPEdb;o=%&09aZPt6if_@goXcER{QZHtu3PoowK4L&$5H8S)v0$ z<&kixVjV8u+kvtVvT6TtHWtmhgW+Lc_@44aR8cyC_Htp^e7!54)=_T8D4TnPUjW0ob;!dVJjzu-Q;HYE5#YXX;-JCTHrRzkeK z0>-{j0HFa}Jkt2DiH*8@ znTj_(rx%?n5R9_%lFBvsB6bEY7I(1@v;3iGtr9b1i#O=syb1peFz~BUh%{*I181il z5Eiix-TK$U`%P~IZ@slJ;Lbc4^Dh;pXb*akEfAb)1uL(efLfaqY`vi_9HsFzv_YhY1bj=aSk!<-T;p`QMmmjo?PcyvCr4?o}H^}c-h%Xxm{q&K< z&AE-*5^~HIrG8MKQb4Z#?jYmSpTPc~7a+mc9t*|K60?=aD#vU-UHQeO@7QN9lEOFqFknWE*co| z%r^nOl|72lbr&(D=>R2WdhmSyU$h9VMapEO!WtP|zwaJ4kIceQ11FMIamTLPMh|X* z25#@~#C%qQ#Cdfgi~5|mkpsqxsd0nv?%)gcr}S&jSK_Ezia&onMm2|Aa^p~oVEfJ< ze4=m?`VKsYPrZrwb6_I0Y%anNL-#PlwhQk5dxVD*^YPd1Xe^A)#cRf5oQv~XEQ2Ao zF6J>_xgU*#_gsiCpY?cTvmQ4;dW<1vI_OsV9zP~V;}1&%+&;Dnf9XxY)J6QB7$Qzr zCB$Id$#B8^oA1cIHaQfZIe_Qdhxi`w9y+vTFZZYOF$7qigiW8jVe_2`q7@(ncbq)n zd}$bF7c`A$i5x*j*pT{m!?GY~i>cwe$bO-8 z(j<^oc5+4}FKDA#U>!PEy#3@9UQlFB6JgHTgU*`7G9peX&axo`(ZN zvDjGafi|8OQPZ&$)BMx0jFU$ghVI#W}PutBelrkD$?o{GFqp&-1#7 z;N1aUr?O7P%jMdrH>8VyCOn2y*WW@w%1%DxIe}d&p~idP=3!paagrOt3H;)XamTkf zCQDO-DX~o#ED6tNjti?W+cr6KUkk06r^e6OfbWaA$Tj|uQ|^cj#Sv_&XAZtxSc|=j z#&E*_JgLnXbzH0wjz{+|W4yX{GeT24;YGJG)9GZyO!Te?tr_niN%B6JM7P7#yb{>* zO_Z_Q-4CB$^g~;~CAcK11A|r(;2B&73Z{`fOJ5DzTR2F5J`pC?sWDSlpJ5)jbVI`& zUT2>W!ZhbdGs~Wcknau*SPlLMr<|w3vAeI}ag#ig(0*5ND5uW5Lf5D;G4uuLajx z6%8}y-qAtg9e58jpXf409lK$UuM1a{(*S2rc!NatS^-_GP5(p*O9*V+f;j^iFGV ze{N6V#(Dk5sqYmzrQr#j)GBc}cFTfH5B3whYvcXc`k(0d&ga-JR{{!J!c@3d5!BaI z;H(LcNVs|}JbR{xa{WHE_o^FHCtL>6M`i-YsWOU1cIeyGkCT*MkXp?r_-8W0gz??* z3YzKUsIM?SH54BA?<7gqhuHu8okCMOMIym&Jh2ERrO(r{qLlj}vjx)@Sm>A~!ls*u9mCq<^on@LrwVCLyC}zHHE@Pjg!zf&EgRft<(xbB) zF-72wYqy$nes|TlwHh^eRnw50_`Vc33+;gRvhgVOR)d-!&7#v&vQXwzJ?~STj_abL z@%i7eIPTh9OxQ62-SV5E{J1St@zVT}^?$%zZWkn4@kHt4k3lz3o?E_gCh7~a@rBb* zoWH0B?X>1$lUD%xy0l~TkAs4i_W2P1ndg+RH^kvWFFZ5zFtA8zzK$eL%r*scukTnc z6@xB%<#;}KEucT|Av>)D3V(dTlkbYZUvwN>FV#WZ7JuySI1ZKFp_p1%1ZNxPQAZnj zo=2NOq%y7GwX-a@fcKElK0S21-i4hH6G_%kGd-kwfa>yW<()ee1)cRY#KC@@L_|B6e*Al3<) zHTUs(hyoqMp2P0@t>lTFB6_CNInmz=OzMIbkY7^)r9ukKgZ>jB@n#7#s+oc_ zcx`-A>=k^OItB&iX|Sf&0DPYm(wR!bxS@RuSgHKO{zDCTcaJ32^Gy1H;VgW;aS}EO zt;eP+ORRZ(hGbSugDcZY1Q|2G(F;r6;I57$Y%w|n>_<5!qPGUZ-Veje7e8pFe>Az4 zc>?2aJ`_|2lwno4IgDFq2HT{N7#zxCXEyG)`|1!xmnhfL(2$QXt8g*%&8Q2m=@^qs zmQx^VX*>D348Y;mb39*p9?gBOPmD#s3dv2c0C&3o>ARkTslbJxlcY6aB&{1?GnTd2q?CM!hvp z`7_c#4D4J$=at%_Ty_yUuB##belOVxKjyI97aR1q{0&w6b75vhAe#3Behc-+J8K`} zGBzLG{dr$>pf`$apGS`B{09f>huF=d%4qzrn4BF@#<#h>=%~O#*B)o^`EL#sotX)i zz4N*GQ&(Vu^*&&_@1XT-cRTrUIquc)H&7_Ygv;ux7Wfw7-6{*W`Hw(M5e6gY$2{w_p)jb`EHF#iAXHs9&+ zY#*j=66ccPC=Pbs!Og8F@KT^S&3`|hyLT!X|9sm-t%C#c?Tuno**#3Vl1Au;dtb?2 z&tY&+`HcS*bLcOlWb&ar22aFwQOl*7n0f938Mah|3BMzV-a8R&XdVE;$U3;wIv#sg z)`9r`ftz#*P-~gbvTeXg-fmE=l!#k1<(I# za~>L%xNK1Z*;(a@GyYPVo!iinl9rP_I%K zE0096#r*5_J=1Z%&{~p`evI$jTnYgu;i$B1F2rk>l2HP5o7f21&~HLBe0zw_@i<`Q z&4=@vn1Qf2vjdvqSl~3+MmBqpAAGN_}wj5`VIY(AaUjR+k z8F;%e7r%ZH#}zN1(_2lI7-1!c=k0>2qLd7@_{^nG4uzm_=_{-f8HW!(RA89Z36ym| zf#lvy&SO#}Uj7h>^R|A+{GwT$r2QhU?o}N<&GS|lF@;#K(oN>r|Dzu+GrSjOGCn;c z!GG4{d~S!s`1|JYAmuA;bjTsEg8KxMPFnMRZwY8GFv7H-p@Oi=el4rGt9; zNpQZo2Xl_A;oG5L;{BWNFnz2Fl^edWD??Ag+Dj{;H+B+AUNFWPi<`-yc%tB+SSfz! z6@&G5TVcPLFdk&)VAIqbIx*rLCe}3JzD9fcbg&pc>hOB@4_Vl7p@ck;Wua(Y2xd>1 zhsW+aU`9kQM#xE#$_v|Z*6Qn&_@|OLB0s73(yR2zKo6eZss;6n;^Eh}bRu^+o{pQ8 z3w72@Fv@!|?zz=EBeJGwVzqB60BPUau?nNuJrSZlG2k^GWvNPo!6il1A4IN$}8$!m@Y`0up8ty%R_(e6k_ODRUPN`hU|`i01Zphpxu+_l8-1c zF4Gl=@zMJv@Wfk~;p|s!7;1$DGb(A<_|tfHw({Fcv(1vUQ=Pz_~%;TaM$7MJu!3&xLlj#he_hI3B1*N*l86>ovQ#|4zYs&eEb1}!a(}xBDi?>Ddx4z!@tT|sA8y(a;^ue z*Zwo6KTNCyAIAQI-HzR4&kb2_=OsmMk3}RM4o}6LOYiXPwr(`vaf~J%<2#K`&c!up zhf%z|61Q)BL&yJXMt4yYZ1yzAGe=Hfp7bg~^cu;VS>i69e&W-@evR+8j4(+ zE*@WU0=G<@j3LRhaAf^`8b0$IhJLFixli5E^jb1L(2c};do}L;OA*{udKdNn=;M?V zGa&NUW_oy67+l(uL9T7P09OX;Nxo(!c-~k9Q}=9xMnONhm46DBO;3eQqkq})q?o=; zxQnae*1!Y(7Q)GVCnIk}@j;XrBg1QABk=@NLixNvgbEmcHU^^hlBS5UFiSNNTE}?N z@k|z!N%^CUaz52sWrLRD%7WA_%CL2&KAm7`0~a1Vq~}-HQ|*K(FiKtwS#y=ZC|&^D zpT@wY9XuPibQ|z_V=%a*$n)AS;6jsfRM{1b^$V6myy9%wC6s}Oss^FVm4mLCW`w=4 zlw4Nmq>>7&$O}7bl;mf%|8+@{NfR`2uZku$Gv$c*q#bDXcM}xVB*6Ifd`GgxYq}Z_ z1F>*tSAXZzTtC-C&BG@+*X=YW@oQx2wQ(ravJ|%`SfR*BG}Uu6W)C`N;|v8CEcfe& z*`AN#7;DOwwDEjRUZYW(Kc0PlnuUW81G!XA)r zPkm@Gj|Q3GE^3(l2u7RF5uq~oJ_iMND|j;21jP+Qmsx zM=s?3sFQ*4yrzRM%h4f`rE{AlxT8r1Sj+ulFUa#+;$sEAr+q!oU@?HR-xay*yFa6z zvKps!H3lbzWV5xmp5f*_^TBoLA|M6vB=D9G#%K)_)frK+T$b>eTs}u#TKQs;Crkfe9AK-G_Vz?mzWcJw@UCM zdmXNmj)qAO0%%oG1+C5%;+E7Ja${cJB=#D--obYUT@Jqn64Pz)5S+rMJE>5S97!&p zaEI-i3Se8KJ(+HLn+#+ur<-G@!qNdF!5ynIXx%auO2iouJzIb>m-#GWkRPkCz!*2z z&!JBwro#J%bZnA4&F97~(LG=Rs+yMJ+UlA3`sW+yQ;#G6c&+^N-Sv3$-W`G6@GaOs zeSo#jeMU>;p0fUyr|75Pr*tkY6x>P7uiiT&4BzfJjQ4k!;GN}_7{YGCFM>jRKDHcp z?Qy~#7x;Pk^!G&Wb|Rn{lAudU@aokqJH@({sN-^6;N~gMdKg-uhul8=yS$ZtzMRdc zAe4B{<`?|bIf>98mT<+&8ZA#})9jzN^qzk+9F+ntx3w3azpBF;{Xsl36pxQ2{csLR z#Z8}Y(BBJLGE_y_*ZU`8o<=Ip%G(B3#iuZAzAjg4CB$SMJr2|6eu4Kc)uc{I1`70x zi1oWi$Zn}@bbN+49u zjp%F$BVCi#$w6;R_+HC*6K=UL=v=|~^{MpIee)DhSxd{dKXEsXTbNJQ%sD{q3MA+V zhZr^c0$%_75HI!3;(E2m3Bp_X?uL0{-1OGH&|!E6N*-SU?+aZdFX2BjOL!79yk`Yn zr)q*r@U@-Lj5HXKSwe1W`I5FcLyX)LF8HnVk4!hqrX@qF_`OjGH)zGuM{5+(cW+F! zPl7V1v0w<Pdqx3h=y=5NJENLh$`Hu=Qy(F}|ci{SpkI_k}hn#@(kf z`pNM4r5NLGZN^k?e-EL92)6f+2!4Lt3Ma!h5-Z_pq;H9U6s~?i?p57|BX`A^M>Pd- zJ2Db}NV$NO%ngWp@|vV5*}?J8o?OPuN0|3XlAFVSW-0iKr*|{9%aniPAV2%RD0ZDJ zEz^d7RVmOa-Y2O1E&{na$NA@U5#!&=VU+m|>K1x{oi_domHK^}zEDbn^cDp?x=sl? zzMh37qjz-P!(XI*jT?MeCkalPkr1y`PD*c2fU+k`!O@Y0<)VJnvR)sL6mEj47q?M^ zVMY4BypL{ANW=2ZRvI$#E0HOZM$zR~WV}crbZ@Vsa|fr=A2l^J`C|oDt@K9K%zUy# zb^-*waKhtHRahOa9s1ooLD}O0n9W@Xk{_2q@a0H&xZWOQ+9rU@Zv58 ze&%~%#&c<7v$1L-;EF0!Tx!YtNIQ4qkj;M59XTB)u6;tMcANq>^b@@|wS&EuO~Ci} z3zBQN7i=bl;q7Tzc;v=ee9Qk9bRLFcTaXLcD}9-c$m)RMgU{4x$vJXM%MZS{s*}vW zlGuKZppwM%i>a{Fp&+8eIl|8EXa1Wo$ zH(rV>5~h-%tJejzRrd-pQ8eyJWttp(Xs%aqTIMZHAf zwPk3a!mzYK0)5NZ5O$s~nV`K0ZgmB*71M1&ZpAV*9V(}f6UO6!jt$)t;K}!cxYDmh ziSRqJPhjl(lon1)Bu;rE5K`nsmtI$bF$$7`;O)8~pYVuXcIX=#&3}uLe|R?DoLGE> zpQzC5OnTLI7LBu?L2i9=fJke95_~lh0!5FJF}Y=MsC1#+{4)^EEe2NMF8NVkOHvoSBRXZNkTE+I=enwq zl?zYc?anNWNshoVWlzvlL>N!Glw;WJIQ)Fe0GutCLe5l46z`kO6<9sTIivqj>YNB? z!+GI)gXcWg@*u1!jKQeq%h@eOzXd;=ZewinT6}7C8@~?UM04_u`i|D)Xy0i(JnbL- zeC7r9n*Emq7}?{M_5gYyG6X{=zrtDNDOfstF?P;w6=eR{Kr^LUp)WX)WZ$dB7Er{n z*k|NUQ7zq~ABb`nHq%$4qV%nhqd>b}5A*)c#G;0+=qt67I4z4rn=zpn>-mOdPLHKD zbP`-m5&{Pw6O6jZ=M}O5C(aSY*U4e1a6t(g7CpeFN3^-}WIk70G?CNV*p1Ki`2Iu> zQ*`6+L9r@wJS(OPwGTAl%s+?FiTCKl4JT7vmxc%4tfBLkUPW)OWvEoDGWBN~vh2QLSyQ?*}Pa8^F= z{bF-S=5$A{zvL#m$K9e6&Dv=2xEA!CsLI~B5(>*c+G6<2Lc7Z zp2qW8SfSZRiQdR1!Ct#raQ?9eKUbE<4IvFEcs3gy$1j1XRi6b~=G~~l>fnFB_3>tx zE~oib3l-wS=$!Dq^k5s$ZwO4np^!EjGV?U*)x{u_Md*!XUPR8fo67ag!qLAs@F$;* zb!_oNoey$YC}oOr2Nu)XIqAgw{x5Q4?=E zl;yH;x>72#UAnk>|1e=vPvOJ19y0aqZG3q+AC1=nc^%4SA{Un#4?TW*xU>H_c12G`)m~HZ+PMKASND;sCoS+!T!$R2DkCwE zCs+8r{Q9@{s>gHONQy=-&m}KIou-XE6GRooI~4HSwy~(^G|GZ- zJ?O;}FfidgRo<$&YGw&`bXuWrq8hH2Dn+h@?=zAsrETBm*m()Y@T{^v5L!_JK_1UY zP*@hL-(Lqk&B>_l^9|DTO_;NMR`P795))iHmbr8<5@w(4gj0!fO!%B?yFC9Ru(YBY z65~HYSpGxkb-o9@Rf$QN;|BLbZV|uNzHpX}=2jboay`cuaW?IKoayOsF6{j_j^_%Z z*K%G*tB+tGsYGMPBMa`JvNq@Sh1XFGk8s!dq9Y<) z@UG>Y(n=Rjhu^pM_Y~sT<-%MY&(d6Oe2}|(B8p@8Byc6~zM}1#W8BAw?%ZIWMn8W%2R#ktF!=h|I@xFL-ad>#7( z=XAZofHxk@t6%br;Ey76qC=ZGf0Jh=?GPp(V?-E_@{e$^=9)lA?ilxa^;vG|N=?pG zaEz0AwTClq73Gc;Sb>(uOgzGOzTNb2hTH!(L%IzIlUB(vU1nBH{+t9RX2cHKH>`#7 zv>KSyARd~JDd%7D8S`(LbI&@Lal7lqxvf_nxP9T)TuSZ^ z2z`0a zu7ti9uk{LX{`tA+?WD*}T5Q5iozCAC%VRhp4QFmN(3DfpS}h)&jJ_brEP`VYO=1P7R>fZR$E3~#$V&cK#XAl`@Sm_jkgLj%a*r- z;^HyP0yl=aJ5G^l)V2bJ>_v=OW(%D5<1-?33ipTg=Tt-^IP>JaoJapruBIl6n>70s z>Udk>aj|I_t-qVv9js$<`y03zVOq5!%K(o1#zBpIBaHL!gyN5~jH{&#T+!YHABJ4P zS;||G*}*>x)%)<})J@nB#?bLaiDc0nE6!-ACzoqKjiXx^aEVpoUeU6U2T#U6%DzMSHg3Qc5$rh&X1*0c3V0ca>O#O9^ zez@jKXZl#NUte25_FWUEq4@z=mnrd?&1&ZLveiu4gZCIeqnvti+IU&-CNVjl4uR^o zNtl-u;}gCFOu3zqe&r^aaI~MiJ}rx2HbF4b(Fv5dWfvIWga~5gAb+4i5k_X ztpQPRdwDX(zfxz)XAO{`c|8AHR+GscwPXs$Y^Mj>=HRyob(DMLM;o;5>7fg!+0&LA z&`$CxEI4Ebc6(*G&t}!M4K4Vrd=WY77EdoJKPU5~^>O*}P%zpS4;zf*h>Au%-)Z)Z z#%elppLq7$_2F79%a`Po%FlwGdphkRy=B? zBzfN0FJW3B-9THqXJBgVVwlh%%V@;^08jPh7O%IEH&>DCDXC!%)`iobL)*#7 z_H1Z4t7unIRVqk2y`Ale$|SP|D?oCfnc)5lyax9ZQuluc$IF&LHtk}R=gTr9u9D0W z>#gWxeGyAP_q$D__n#SINNX(|-Y(4aT)71U>atAfSShB7Pxh*; zDZoQNXK<2&w`BBWD@JeOFtNuPiqAcQna2ply=D}9eHfoA8L&U|9Remy zAuroPQDwz@D)`Tmp0>@$Rd@dqv(3Ez{2>^#W5cnuNQQRbQDhB*HJSbh6Q=scc6bz! zLwcJ`;nasbKA-)ZwM=saYp+nEI9i4~JtVl~o9RSeelzZikl@1lnsF*4%IW`mkGHo! z#XlymaK`X=c4x5&7b0{L&m7|CCVDK}SB-f6Ul|d#9MAI+?P12M7??f17Bt`G5LRM0 z%vS5dMykpQE?RPDmI~PM04uE)$409{J44zD+Fg33Gf8NeK zs>bN;`;976(j;jlL{W-{v#(vKNHS(fg%AlL^Bk4tnNpH8QHDmT&c3#ik}{N8nvl7O z%;S6i{(YbIK7TyVTJKrw{^P9k$JzTn_rCA5uj~8$ejrG8GKTkf;-%_guza}CPwg6y zd+udJ!-OL!Dq1J_OVsJ~({Gu~jq9|bNIY0=Ls)JuF{ z;A|>T7io3DgQCgvwwTbFEvF!7(RJqPqEG#^??c)KHy&cWh~HN)0lS;oT*}^)7kHi} zlEaSk+aCUW!k*vwkeKq$okpB4K7v68ay%;1jeC|I#6_<)xOwY5-nD%M-`A7J1JVcb z#v2lJ*Y$Ef`YXrY#KH7m^dZiA?xEGJZ4fFvCzHn+3k;+?qBh;*JfvSAHtQ>i&z;}E zmF$9Wb@6Qym%fzsi+_jhR@$ggl!{~2WqHCQ8UC zem`!E2S&Eif(viy_CLBTYG^3UUY$>07hCaf#fi9JnHnu}&fx9A2l!p*dUA1CINx4= znERco##V`VymK&}J}9lC9O?MGvH2AJ*`k8Ew?pXOxIt90F@ujerNyhS4T035 z3B3J~0*|?haQ^TGqT~XmvE-WYS+#ZXe;u+R0xd$))EN3s?W?-nhF;{fY1eM)x^pcDkAN(MY z-fT&sPF8LBY}RHfJF0-bd!3KIXMf<%;?wA$4Lm0|fPeU2j>E^z=Lu=!`Kjzd{QgFP zi&-Bl`Vrayd(TYgl{?N5Vs?N`I=q-~f0}{Mf6T<=0b{vB?+`vo_cj)Xn{vD2KwkGm zh4*WX6@K>!{{Q{jU(IJc zxKN9>oT{W_9M+-k(7EVx#G9vXvc@UTZ(-n@Z7BKgKAUWE7NxX|(9*mRhs3qe!_m3) zvSz*QhZj%i>u+ULOpXaY(qyW;Cy-uqC)^@?0)OH-1nT6&c)vv>`GJ0W(b_ecnV~S)mNlwx7QFw?5WMl}B~Cth6s5OhqNJZA3*DMb?575^Gd-(t zKm|bdk5oR2Exdbg>YwRF3EIU!v6it!*L%zvxilBnE0_BdxzW<`>(u>Yr|9Vy^K5R z$EC5$bt#1H5rfXg7*c;G4JLID0?$zkaLK9@#H(Qse!L!o(_XZRG(0&tNd zCEz)+Zu$wP_2=-HyFE+R`v_ajYlv3;Zek((p>o;#C|p#y7Q5vIp7X*~X3^#(zP{Q8 z+f|F%R=cCvGoe2mKQ6`_lMmtSYxN{#SvsosIO0?BCGlAIT&5;yeFi&4kl)3|cqy@$ z)TG=eWzocLBvG|W2L546md!-*pX zg3sQEEX~~l$JRCygE!+**}0ju=vJ~Pv4YQd#v-KZmE`)C0HXg&ALFYA5wUfvsN%~| zaJVs1So2F^&JYSmY_`L~#!gYTe>wSKR6>H*NMQh1Ma}TzWc!R*Xwj@;U6li&{JIJ1 zknQO8ZrLZMyxU;5-MkQ zkldw@h)c;f%pUA0Dj@yQPQpgG)ho)E#!$C{R4kD2F|()Ig~jAy}|$2!z2jvHOSyQmJkU!{UeHu#s{& zck5e1Lyxkmz|Cx-%w>F9{h@N$g(=XHb%~5^_CviLmEvEOnIt!^2ujb_!Ljaa*nj5} zB)%O?MX$?Ak#jm;xo9dLH76F5Ui#x)6=kxwH-jCi`NWpp&tyl{M!=u2+d@XhZ=5bV zje`u9!_d4hfa4W$wbKNeBKSp=c{Ydep`(mpS!*hpAJsIQ}rmf86jjd7}DD8d)U1G5pD_kh#6s%iOJ7E z%$9Uxwkc0xSo;OoY-|l#zr*pSxS#ECktKH8k78$sOVN#j{~%#`JfxlO1O**kGPg{O zTR%);8#bQAdDYig^6M+`zH|8S;Kz1E!w1fsd`uqI{nMbKY=S$c+EW%tBTR{@gBd zr|>q|J?~`GkMCo>(GM#9oJR4{;{zNwT#rw*X}~bw z2=v?Fh3aDi#m#5DVaVhg?5OTnvi5^KKO|Ow#J+xT+IlK1X&OSWek+8Zwz9CRyn^Up&2E6@8EsGXLa`Dck$S?ei*Vz zAMe@>rp*thLH9!$c-{LK-;FH5K*5}$nW@iF|OBlu>e8o@Ui zg6(r|GC7BMJlS;(D^vZ*tQ*(J`W`jdRV;^37EXhS`xNP0@`2pBCkIcrX5;jRdE|SI zHrrmSi6*fRM2SApkQ$Q$yPOZerNXh0l52vBGyO2*Qwf%_7~(q^rykjW?S3ag@;H*=7tbLIT(IWLo4`O|AIyJumAQX?2737t z^!1Uq#KLSdmb&;H;`6Fd^#{ z1los-*vG>#!fOcq;QoxP+bK_d=NxWT#{pOZzCSHk|L&+sO(fW&Kj zBw=b@(CV`WEG*)fMAj#iK6wQ zjHwg*dg8d~(C$y-kUle1@HNNHDtU0o>k%2}3h=#q5y*P}f;HU^ltrOK)Qs)XEoJ#@BoWcR}Fll)OnL_P1ViGEHlejJ*`rY$hW-{rfY zrF-(+5dO{(jO6lLK*hTal%KtX-HTP}>OBu&V?{M< z7?CY5{ZuO6{Mm-M&5VR1tzY8i{<31PiIULao&&ntp?LLz@L%iZC$YL!A$n|8LwjML zIp_3DGQIzE-0?L4Et`$m-q@*vhT0Xqk93ernvBJ1)Qd`XK4)o*Q-yogchQbbH!$g< zE9h<15UrB^ivwy8!)`&RJb19cx7(Qqb&J1MJh39ExHk&B@|9WDmRd3=>Kj}0(HnpC z4`kba_p#>5G3-gB18mD!1s26x@F#f$-ud+%MrV$t)!JP!J%0jK^c2w<$Niz=24ZJ1 zV=GtdV9vGYr1(XL=#=6?Hf2BoNw-qKS;|6&?spr=?=T|K(TA){3Wm`BciuzxHDM2; zvj`gOUXs(T6yttL;Hz_2t(EfKAaCG!2&^55!!GYe%ji|`Q0@qf{Uq!^bT_g~qa)$@ zcDulWwfao#3&zmMf4%I0M}K;& zV?C9f+(K4(>|h%OjaBHuXwbaaA>RMxIVsbfuc+h^G#Tfk3P7W|acgvIbjI}JS8VgLDdgzVD`KU{SbQ<8 z5xkd8B-Q$gut;eXR(Fe0NlSP*U4jbA7h0o!tTISG2+wLov1-BF z@~QVBJL7j47ZvZt*Akz}>F6Nv{aQ^@e|{#HV#eSZ-Bwm>-bQMZ#*59zPOE(D>IK(V z4yIo5igaP&uJ_>yY8DQf|KgbF@i_Fac@2^~prBs?;4;Q@hvto&TdMy~V(9}#WsUUGl58+3T?h4vXqu*EkR3~Sq<|6D_A=A%ICD+4jsF$11mQlq7By)gvu zvF6<4;AuICJ`u9Alo#Iw9Ue`$-9JMkf+teN!ESVFOeED^)(AH%`qL~8Ybs%02Zq`y zaJd-hGSO6eD7p%=e4OaaAPs6L{g!NvW)N6C5e{|5aH$Dye2dZz%;?DFF5-ADl`?|& zE#J-4@+0|N12z6a&4GJgP3CesB3^Ii$HyH@=1rF2oHPXT%*p^ht=d88RYmeQpGNVC zN58U}O<@9yd?oh_X~e^6BY9SVHgEFuW`&%heBz@Eg}2+^b>fy>ku9Ds}vGm4xw3BWavBEKrDNLxWNuv?y*vurx_0B z`)arF-*@!6MR6c1JQuRFV*0SV){-tCA3-m=M$nt@2hoR)%cz<30otl3Lo?kc(XdT~ z?mM-Qs{Re5_Z#A%IXr`|a6L=y8x=v$A(-wd+D6N-Nz)#$)BH?b7BAB{#G7Nz@Uo?q ze9&|e?@+YivCB;Ow!Nddn}rt7%xuIDsTFL>Kofz}Yt8+vU!m6OLVj_y5ik7y6p!_| zVCW`4vf!&SR5>KG$-b*F$6zPwO4bwEeq%@{nTZ|(=YML zR3^)Wp82Rl4;Q%7v9^1mzYdR`C8KvhPc|`2_<$!px0tOb_Sdj)d}i;{y1Ihdw;^?MF+7}X*n6S$)$wrpJ3xv4aDEEud>Kt%`j1HuljS## z+462LifT?r(DS(kAN_O-Q7fz=q;51%m03zhj9x|e8ttLCpDDpeUq2dOoq2-ImQPGicbYswLia{o{BTBdzw_X4Rl_}IsRi0Mm4WrLAWa$^(UT9MnuDeQY zde^=VbOc>?)67wHVfA=yY<>#FHVFFEeu>7~-ho_`1h_Ta0sd8aK;Cc{ShRc^^^_8r zBXeWHf)hGtm?ljaTWdSvM<}RWoB^Ny+=21WB&e0q6)-H@4keG>Ks`W~Mz5}hDg2^1 zrTi>hyx0#+GOaoJyq#OwYjZ6}IsW?qaK$%fymWK}J5Xqk)3x8TP9JT)&eV-Rta0b_ zd_;Vpkqmd->%!gE<=~R1D{+Uz5_agZ1HV4&FrP7FDj%?Y77yJM&Y#Kk<6q=TaQN&h zW~imj6<2EreG@N!!%<)i%W3hm<>tKd=Nc{%w-QSurgf z)Raf?mQmYzKNB^+%wQv*sXL!LiDS7*MK0F3_F?0`AL&wG2@O-}>96Vz{qaJ*Lc+0`) zE%jZ{w> zrROkSQLu#PSnBbB%S(B5t{zuRQsdXE*7Ny8#l)<`nT@)pOHLd*%xJYUnWor}B-zd( zisRq1_hF0JjoljbwV;KIjY=T{igMt$XgeedzNI)*7nnRW1OAOvqna`I(W=^+H!Had z+F^Ij`vkUDwKdN>IgSsOIw#bu!*NCPKrVOUFgN&V%l#)V=AY*+;In=Sz8U$W{L8TI z{JWq}H#oG47i^l(RgP}t*H5kDk`Z%wOYI^aupVt{si)xDMz2_2FZ- z9$ou# zbRW5C@d0*5--DJntKrh-CUBZN3%YWiK>BeG$(zLx_hK$smMnuut5%b&NsB>K%NhDT z{>Hp(q@nwI2|NiqDC%kdNftPaqiyfDLFtutD0Nh%GiIJ8r1c!+59opIJH~-gxZrg- zs>Ugs`dn2ZA86{xA@iR4`QbgFBaH=oFD6%^b0d zDSS?ZPxhl=n@l)tUv(6u#i^jYrV#p@yn}k-ds|LFhM8UWVO^~w_5PB>4%azDC@%)n z)vEB_>MWQ%7$r(w(F)Tnzd*v6=dg3kYCIXdm@ADv%IB<+WqVH4qiVT3-yf?0uLeF~ zKXhbyhxI(NQWNlO*d*D``{^^;~1EdfxGO^i?oHlvdP*vxOm+KaxBUhPXzg( z&ivb`Gcp*foeb%Lh=*9Ru9W>p=k;@(9%=Qc!!4nY@u8$L229Oo1>1w5tKv6V9*|B< z(-a`Vm$7J5dDigB7B)(ki3d1|;JiWxltqV%!Xj(gRMX!sX{k%JTf8Kz3^SzD^Nnyb23&>Z>St@;#qjKdn!qBNLcO-4Tctd}_*16QRsm z53cssk=MEd;j3x~>33zmxGlTbHrw?CPVN4Uh93_>9N0is?q~MZD-iAUMxx$kHKM-} znXXV@4yXv`hbB!&i+7#)F=`G^c25H1?p-kN=s8FVIg9H|^4T4IN2;*605z%y@Dod$ z(O$ZUnJzYi8Ak@vIon;acyT5ueH%j4`+djcKV$f=Z?{RKwKSdDmIRA@OfcekcBL9m z2fjZK^Y07H+Rq0etzQ-yYIu)a=x4(m1%~0<1ux0jqphOUe+C%iCX2JKZ9r+;!+7r3 z7txv*A)=Sx+Qhbw8{oq7cBVV=3)|S6N7lcLWL8F}SXhfHtnMCwH8E#|tRBI;IQ|lz zB}szcPJu1#$i?&-cAWi8ge7({kQ_CMXB?R|k|ncvuP_ZQ3}q!9P+`px2v_n^(m zpW=`5=AuV6g1&9)ZuF%mV2;Knc<{bntfMjm#c#}6wv`g?jvGRDMk;Uz1wj)q&H(>z zp1}1cPeD`nDpGoG2bhE}0o4`LnRCZ6P>?W$j%}%!kQa;T`rDY&uubsztD9)~`sdc3 zhju`iK^iQyI1NU2%i!JKPAGgLMU5Kr#bF-{p>o$*DC>?#8|MHB9pD1$Q^sOp<5XT~ zFV8KvAv6R|z@6vx`K)Uj;mlo2u;2cZ)bQ8jtBf1acT2^WG$mj_g$igTPZLMqix)rh zsbj4(u9Ait8M0-!z*t@Jk6lU%!N$+2WJ>KRP(=+~`Z*SzhEK++%l%o{&>;52Dj3gs z=F(Skf5EY=S?s&Pn?CZD5zFuG!s>_Pp=U=qe)Lh|LEVC$_k0IFO$i* zF*0z`qL|DzOJ+8IuCd|k&p}1mNN@>%&mMX0!p7xSao6WjykydI)}G~yBtV5*f0Cyy z8UeQJE^NZy>#Jb3i7{pzD#QLlkX^v^1U#0m$V+|;d*&3O9=v@hH``v0)~b_v%=C5q z_P3RIK|>#(5qZ9={wE9A@RaFUo@YCc2e7?c3vqf_5b_o&o>(RL3u*!&|K1?n^SueJ zDjIQK*&C8*D$jqlPv=ul4(B#+2XnQT7Cd(CY5ZXKi%l^0#DA%g>}S|19Pd6DJEEJ} z;tE$bU$L6a()PoK*@E`VIS)0r)#8@ZMd)X_kSn$Y<1WuX7!v8iTQY}Hzr3mN)%OVV z&Kgb|{bFFkmL9fXiUd)Q^T!8sLfHMmmDn}^B{JDLxcb^4er;bhPVBbhR=e8poo5U& z6t!dYsS}WwB0G64UkKlqq@;pAi1*IPB z5m)Lekk*q#ytHaH6pzprDcxzonhou&O7A45Ulo|2K36bD=@F`&64tifBOH6I6a5QS zc);&7BI(3-RQI&te}2lqv?=8*SN#acFa1ZpgMzqk++1i~kVY(@#aE8-p8@aUmP6_w z9pW{Eis-vSxa9POcqY#P@!JQu$EZKg5OiHdR=JqxUxDI(dq~F&A+zf39(CRE6ovw=AeF37%-?F?%QOGRNS&lkyKZ>dn&R~xy z37anDiWGkdaa7CQ=-S_B;HT+M>T|)In!c5zCO!c)&|DifbSXp9`Lj4z%?+2WOJXLs zgv{mr!u_W11VqbN!i10K*gA<-B*Ez}^Da%s%Y*NU!a9zNw|xx}S=`mbA5Zmh!H{sK zw2HtD|7e`%)QtC^4CZkfxAFb;*Er#U0&iFli9IP1=rm{`U(zQjuCP_aD_SccJvM;# z+8e;yU)N#V{bYzt$RIWPr=fY$T!$JI%`bm_HZ4tPs#(cl}UtD@Zn#TURO(tr*AcX@z37Hco z;rEA9(VYx8a4s1t)QdflF1bM3|Ggy(f@E=ds0>&(C(%@0ArTY-9&NMhfKJ@ooVMLJ2l zk$8LvhVr|YVaGOC(l*f_pP%*=6G4NX*jGV}ANpcNV4S$(LlUV94k7>cl%m|uCTP~5 z0C;~itl5wZKd#(|qrU5jSwyNRV*Xe-0jcomOD=Smxqy{N4J(}93^l>iAwWNgWjpym zr_%|j&09vgUT34jn^Kg>$-(wnX5cYh6>fPH;@59uiCS+UgwC8nlKB?wU8TS`Op@jC zSBJpjPsVU0d>quyKfz=QE67gVfwOO}Ak{MjHsRqa%$neY=8IxQ;;WjtuI?d`3}|4| z|5mdjCgG${Ck*}E8R|qfiEU=*gSY(y;^`O&No!vSHS^Ex*Q?!Z_|lD-n&^eY|53cs z=t6Ek7>#M8%u(yaZ6-H#0L<4v1%ISYfq2tCSp8X%4z-r0@z@kwGn+Dl+-8JX2F^s9eJ?SG?^0Mv8W15Ob~9s8F_mtsLLQavU|qi-Xn( zTKLJ>og?_I1CEH}r#~coYb$;+zKZELzpyb=PgbNPhly97{LKu7-}Kfx8%j#HLapY0 zyc=VVOT9gz|Jp>N?HwonF|rcQcX&XZ(?HQG(}NIscQgwxdBchhPeZw*K=K3Z$b+I% zkSjIE=XHKKvicYljwVpD-w1}TJI``fhT^q)foEWnV!Lnea2$P0_@DXu6gGc(hYfGc z`NlT73$JQwvPVf#vI&!`vB=JK+>Y7r(%z=gd)KatkiJq=7>ny&z|~4@6Zj zfN3{1amxIg;-=^SFj)2nrhM)pf43I0xl)Jl*K#@PpZ|l*H5b?yD=S37d>BkzIEZ%L zUJc}wEPdXUOq&NLi~e@2(kBJUptEfg*)X)6%$YqNH%^m9KJGh<{5lptXm~T3+OZ&a z%22pJYGcBy40Kr^g!V?wwkG9C>{)d#%kPVUs8~I6)hma2y*f))%}qs%+9Eu(NF)~C zpv@RN9BptG0{)#~)lz{FaIJ$>7^GqU#NBK|+Aq;%DP^XybRj$oDQA-FHQ~*Ud1OFD z9!iAX!?7j%QC0O5ej1*Gi(>ktjZYi=mRkV^<=bHJl4SO7$4&H|u>oh4mE*aI{ki_# zA1K+@MB0}z(s%6{Q!#jhzj6%tA>SbUx|6}pf(=lcRaK!iU6o$hzY2InDp6fM76Xd~ zp6zH|7$bx%_P-v_8V7`6^6F-h(g|rI-xWeOkGz5kYCXivSChm`)#D05J8Ljj8po1> zU^S|Z8LtY)IWBVYnIk8fNW@7<{O6eCA}u2!Aulhy`@df55+LCnu+n$!cAxR9ytjIf zw>F<-X>M(4<}}4dV#)vXB_R=L_un1=8DI6MjIa8_X#R8jcjMFfFXOYGWM(FePwW3Z zzW?sK|9^b;pZV1#4b=}6=JucCznkBGJ^$8L789)hSLc7B(=n_#p9aUIBv{^A9X88w z2$c{8@|D--k&6prApPz@ZW*ctw=a&wXLClw!nqYJ;GG^gPRyg<{3r0p@JFIw$e_DE zvSOjoSDmz9U@iA1;`+{3c5g))X-XN&1BY4CH7^I!8$X+wd1C{5%$zNj|V#5Dy{x<*X`NuoVw?CL)a5?Dv1$*zahwRUrmR=4jt)Rn;-d-;0cdKgmh9gy; z@4fBaZr0g(g-6;oN0?QO^VGGM7^_0#ItJR^jURY_@aFu#!L?;Df^;vWU`R4H%MLFs*#CHJHgaY``P330OLig09U)7BRvPKjd#<3tVmyZ{@A<#65_qmdKHSbFXZBb;Ri5 z%kaf#MW+8v8@*IMlH+sY$XDM`cKOLP%s;4yZ<4JsYFQ3h;Pjl4+$VxZJCH3Hvjull z^kMScSlp6z4QszCaDl^u4!y@Pd__CyP|{$dm+xj7LtnGW^Jfa&!c?5SegI&;kVRsD zi6~!rS849QnfbT1khR|ea7yqn+Z4Z046KgAT>n4J@rOIUE6T>G15+?#L?ipFQ-_jf zi}3EQUs!w3g9$d9w^q} zTh&MLzQ3kC4NdtA@nF7d%vj#^p#pul1aBSx9VaA?<+eLN;FUf>-_|6_m6!JCw~DIK z=hS?jt1HVzz44e}-k-0z`xz5H$Ds2O8+?~#h*o3mab5p)_~%F)+C_dw#e|`J<=H#9 zL!P1MS0=ET_T&27O*l1MfuB!1isL_x(M$>^z9Bj|z+ z_}pk|ZhAtDd2^evr#+i&te=ZFb{)n3<3#L7&1t3}c+JkLbdbLe8aQm!PNDXn&&(WR zA)@h?Xw2dy){@@DM6^wuLfvrRkY2LC)B=~@D#32$eYj}hOBT0mDdvToL(Rs6I1bNZ znqMXh5IJC~AFr&pZ$Xd1Yd9~x9?j-$#N(y9nCS0>o)7Xc?aWqG+vg=N5ohB^#aS3a zb=c?aA^7_JH9R}wuvp#u1j^P6{3}7zsoyY|-!O6F`GYs}-uGVITF4dj1@PEU&B3ojCoYM6tBGW z8E3s5%qIzKo!E9ezGqu6{>^>Hk{1kSUVHB&vFrygzT9RP^7NSREm=&+w5wb(wUW8b zY{i3)0wX~bi8bNUqgr9A+}!{)=b z`Y$9mXC*vSz6@bw4nWwJS_prz5Ufm%p!v@<@IJql9BVr)u;bE6z5fgnJbDc=E$t)2 z&IaO*FaB)LhBf3~q$0FO1&h`04@8ZzwzxDT7f(2iLX%NO#OIt1j*;@j-)a9KxcmeB zT$}?dx7~;B>Mn5lyd!+OaTO#MMciK)V+phrkeET%xpMjd>X#by$#bVHi6~zFT^ME7tCCxNe7+30q4I9 zZ0#Bj%f8$s3-29*Le(zFU;GUWRR5A45;xg&2O~D@XB1mx+9WEH3&e-{`Dp5Ufo;EG zj$4M8U`V11liFKKQYtr-j&JU4hT%>~o+1IQ>wKZlZZ{YX@q@bqei9ryQqEnIP1+SCB>PH$&MY6=*lHLvdCH zzAgJo9)I{Mvi=}Pex`)s>RE1>FxwEeERAL>Zg-PeZRxmI=L~uFT?!t3-ym`^IgM{6 zqA@8elI<%wh3W}+u=Vo_^vd{%*A#*<%P@^#I#;cN0u$ zH^YRF2g$(oTB!Oo9h*zl;kkk))(4D+@~87L?u{?>vZz%>Z&zc&Q;n`Us_bw5ncd<&9|5il`tJDB#0;b+k)2sk~M@`brD zK=2*BQ#c4!6+*3h%>bHkN0MHX_zU8Tmf$Av2waIY{Z#o4QX`MTxI;hT(|cR8bsg+cFI84|rD5S9sE_-~OERNUi8^Yb6%NnH$f?l{R-3)=4! zK273+b*ov=X)82&bBAdc#E2XZ4;Iz5USQKtt5()sEn>#|)?w+AZ|p<*Oq?FNoGFc+ z$n@=F(Q0}ux(u^MGFuyc71Qwe#Bf$&{hig1(GoaWTd-(H8Ac9l!8w8BP^-EP8^Sxq zb7x*;%d48vq5M5Fn|>9OVwT~^*aDWFR$%+^XFryhvcY{#&C$f zjekZk^L!maN~aW&``=?A;LjSccK=2^#BLC~!WFh_Yf_Jzp>(_XKj_h2Lj8SJ=z(?x zx^TuUntxM`E}vpaolZEyib74yuHOWbQv+~};!rks{}g7~cbDnJnvsf2=P~7^8-{*~ z#sg`ykiR}Dnx1iiTsOKW>iiMRE3!^3;l54X(Mt(=s#B1)RLOC zwYabUQoOBP$)=Q-U_kGDO#GsY3%4!BA_2Teod$>S413x5| z<4d9c*%tK>uS`3I6QqRPcdam-EO{9_nglV>zUE`=R(enITseITQB_D3Ur{f&RZI_$kDmyDYuV~FSc5h{kGd8hz>H-5LOrLZn z>WWW)e!&jNzGupl<#^tL?HDQK7r(A%df@@EacZhW{{9el`6yB%>3fNot}y(AqQy@x>b@njN^pe1M<^Dt`aIdqDW z!|XA(D2nvQ>;bCy`=bU1O_pM6!(*{`Pb>QNn;Dli`m< zZ%enrNbf90i!8xp^5e=&<(=Y73tibCAvcch)P(M=10vWTLVgVz&WfMd!2%)$O)rmt zq5nT7;opz8+DC%+o6FFUdWV!RYKCB)EEur(7X+1$g*!caV6*E~;D!45^kWB0%DOD* z+ErM%SW28a$qvG7`b3?#)WNf}AN@U9ii(ooflkyvP`Pvpmi?R@S@CbCTNMyE!+GM`qbzKmd0a^=tKCeY!6RH$82%1Y z{&c}2g|A>d(ioymIv_o(mFyg-Mkgo8)7a`+FlyNoGJRVeQw|D%hcA0z#NzM7WM?S6 zQIenuf_L8L_!3BQm|VH<_&$>Kr-^;4mVg5DL8yBE3zP2N2+8NV$&06tMP6Qhr10D< zao~?LqCrzUn8TU9tRW?;LTmFJGSbP0vxJ0-5>mQRbn!RzlYY@7vS60 zk)WD<1+woEh%FSu+KO@*vu-pjoBs$h^@q@D-V%^_{to2X-Ui3i`%wIhLRX~?)Gzr> z4h~3%rx&jiWtH_1aP=)n2eiO*HU@icufYjtrD5rVqqx$iKX~h_VXFT!EKR;Zp4Jb* z_FD%9U2v6fAvhcU=KY$9_ahl0YRKyVFrfV3npHt3cXdvyIO`?}W^><6mD z{6cBc8)^gv3mu6hco2=lQ_=13GuCxrC(Nn|gyhyzXuFdExbz2EY&846A73^*qWD)q74&v zv)_&c#%u))KD>rJnfndCRsMj5M`UPX*;zP|6bnukm%+b7iMsp#1?QmWV0GaO8R^n0 z8gsykeOVy|Gb2xue#`q;Tzz~8CXCb-azsxJWTMwe+=R(9tqsOIhHGjM)85x zJNbAyFQKjw!PhqH(?6Nb&@6rmQQhz0UH&6zx!DFI27ZL?2d}~9HQ(V`fivHgGM9Iq z_2dsCH}X;&Oa6|B@La_pzFWxjl5d;F->*rc(vMB4`~IEOM8}&ha&@LtPS2-x0e)06 zY&9*oypr0x&!mF__S3D8{pgrATj{#%OX;qb<+Lky51qUqioTp5Laz-C{mDE!eG~t=Z3$ORn9Up3gmb;= zgm2T{&f6Xaaig@2{OOBXJo)=V-b@$qg5l1*?(lT}fY0N_?j!l9XZqY&&==ksX2*5^ zE#gr_HVIlZcV4F!$%~t(@VzbOyyou_8tfiS5BHp=b5u{zEQ17k?r19Ye|>~rn43d=mKo zq3FEhv3lP)E-ND{8b(&iN=7B|+}B-^lB7k2)R$5kTGFD7jL;CG5K?AHityamP14dX z8b*^8rBqrPzw`Us^YYI*uXE0QU7yeUZA_2z=g0Q(-%-DISv<>R<-*B$D8;tXx} zzfRYe+@fy7nrX-3Jo+sA9-UBKNnfir(ShVH4cgO0pZg`ye`lZ2gYu6k{<})u6YJ@Y zDa~}l;%fR}w>BjYC(!Cst&k#I1M6&C>YrdqBQ6c2GydsP|2RsYJyoK6&i;W7M?b<< z+v#+ft__tvV@)&Te?#4618TF*k-iw%Knr5;Q2(9jv{3a7J#xB%-kMcIk3`*|?WY^* z>bY0w)t?QdZO}}(rm~V0=QV@LH(grpF9GpewCRW#bt)k(P0i1H(rTY=v}L3@O%=z} z=9%m1kaJt;TH|7xqZL8FdFD_aQ%4PcoTkT|&QsGf_0;ThsenMZM~g!1>6#t+bjF5q zYEg8Z&iZ|cmf2L(>rdvMOkjaRvQ+;{=UzI6xZ(r(O`7$(O_^@Y!Qbx#;#g z?0Y_iKYMxu?V=?3v;)Rmv-KpG__vE^>^jO@??>>QJzKfQ{WSjEKb22U$>wHJfqd$U z0^Yv1G+;C82v^7luN@s~3)_*1@}OB(FrmE)K3{u}E2mkQw{dj8_+ zyTkc44<&wI$T>go8Ngo$UV`l{CNSXEDd>nSfj#XA$k(;7ga*FQQG(D`;Z!Z7PyS z8n)^QHS_yQzu4ZQdT^DV@a~{H@we*Z);z15ITXU#~U7ILZ7d)`_)#%U>4lk=lXERyKE2Za8(BlyQU-0{YqI`r(< zM(LlaNIdW0r}GS#=pDsD`D(oB{8v;B9m)MGrtwRSW_-J*60cb@k-J>kga$V)_{=Lh zT*kt{V{;nKUzk=NEpy{#)GN&z8j?%GwIu%+h}xU8nq5QK+j~X zqd6m|Q2mEi^uuN=s(yDhm98E|n=^vx;7`lx;kLn4M`txXIAb9l=&_K>@3Ekvtwwai zs{C5 zYD0JOP2(nU-w_tPynGiwe$k3N>pm$eR#JmB`!_^-iZzk0%3&_`gV4q@pB3iL!nb2X z>5Cz$RO?PG)$E!@Ylcjs4NH8ea(e(xigclLf+h95v5>DgG(`Bn+jx+N6R#RQha2jR z;~T_kT-VTq_g1QKp4pEzn?B&0!$Y}l;Mv6xqF-@|_%7P76MdvKDDC2w6`fzLAA zu|7nC=X9*(?xC`rxY_Xd<|}A)SA*Y8K7?k<_B_zjfXg&Y;G4^zV%Sp3eMQ!Mbm2^X z$I*#*xaXtBs>OWn)opy&&Pn{U%zSRHF^o5JSDt9B&fg4~%WJzP@O8;IP;F*AE|d+! zUH{B@VT{o6da8rB+yCGTeFNO1dy(n4$??;6t9W4OG(KwDD8Ad-nwOfZas7Xm+~}hf z-+k4bADaA3UcM$&{9g znXYaD9BeC-UdF z%(&U}rMybu5R(y8`J*atUM(8VZy&VaPrg3DXO_VIUz_n$PTqX<>v4Qj&3^v@u z=k23T5-zkg%v#9K6Rv1z#ZyKO=EqIyP&WJ?_MMXC6T*ryF0mDTd^Xa5=0WsOLn2+@ zzlEZqF71h0OXvSGq^AzAq7Bj`XyToNcyFT=zqfuUpJsg0ue;rcYaQHpR;@a3YnjHajhpa-ejh4dlH>R5N1*IH z3AC+D7r!rF&u+D!Vue}JWIBJ!mVKJf9@`l*(_=tA4*JtVLvLz-Se7olGKH=(@}lFM zKS9A3Rr-0b2ko}^;P^E4|7|@%}=}XDc#cCYv~|fa-mMxHwn9^ zuvz?x@_hbV&xtoYGvl9s&g33#`aJa47`|cHIR57BBChW{fY+XC!8-;j{P%QA-s01Z z)*j`8lSp9JF0kYp#VS1Kpe1h_WzL@m*>cm-4*c7~=Xl9kU}ZQ8Ec1yox$jjwem&Tl zKbX0Wum8`JOBinE+X7Viw>sfnKYS$LJ0=Q^HQO;D*A0)Bp2W4ae{o7_qu_ZiLGhm> zxUFRyJ3F`sOA}Rit(Xyf&Uanjyl)x*;`Ru&3blEm?l^(j_!Pqv9eL>a zQ9M1q5B657(Jf<#!5P2XFtjBb&SqUB3DRO%_2V}Qk7Mw_Zxc0bvZS{^jH8~*wg~Q* z)pV_`Grc+7o+cldO}E&Lp-F9Nbeqow`WX*Wlqsifh9&g=oVD~?$RTR+I*&qc0`0Y5 zNvHpkqY^M6AROZuS6uI4XPi~I)j()?hJvk$7L!YEk#B52El|HyU--ht3_TO3(Gqr3XLFrpNT%=;L&A+OZz! z)Wxb)?D0=bYGTN=)A!&}X$+Wq3p~Pc<3V1oO=Qf*qk_pAI2$pENQ584RVQ-E{E}N@ z>lGB67kgmm%vregm9gk-31iLii7=sWDd4};ps%U}e-*chE2mdMK>IG(Ugr%r%%p@& zttH4Wl?2DN8RUJwzqsv|32SRz4W`33gX?EIkf?J6t83xdn)#PK_q&Yq#+<=Rm3Q&| zJ7hP%IACvMp}_aq$4;0y!r`3)>+#$^{JQd~c=hz-jBK`H{HzExErx@UcOki3pA8B1 ze$c(p1+2a1Lf5CEEHY&=sa$rA3^g1~;^npzodpBIrbEO=>}q4L7NrtpuQX&a57^iC zy{yjHi3AypB`dDqBuz&i67}H$@F2g2JpR6$9hEkRyugzX9UH>#)(wKt)KWaQpc(V$ zkKjs+Y*E-~;K|So-0pY{LysIoyh~B%Cxf>MXJN>NN3bqhf!qo#hMgbN;B4 zln+r)$EKI|xUIJiC(T@h&zDMK<}-i%W>SMYCWqtoyARREwHQScSK_au8R+*?$V{I) zgyjh`yg>K{D*UD-oUspMih4ap3eTZU;hKEir)GSu{ZE)BnD7&k#kfpxY3)BajKAvn zPrS%C0UX@)1$I{rOMY%u-Oc@A(-|c!R03?CwGwLoX5$0pHF%<4*p+{Fz>5xQ+|~US zMxQv3gWhh&SFV$|Uw8_pg)PPgA(!UXzF64Tlw#HoMXuek14DDwc;5nD?)LZ}=68L> zUaG;>2N>f)T{FC~{Q-`8^$SO=tVb39Qgm(^f|5Uf;pQodxNUDGZeIHej~m$G9-mn3 z-!Tra>8!_7ztvDVWgh%+ec91gpl2|XPWKnCyJN@lqwqvNw27NDGhr6!k!*;Ss{ zN!JRWL_EOyCD-v)!9KKHdjR+B`;9Hl@6m9<5L_+z9b(JO+1c`ItahZb@b`UeY2XD+ zqUSN^Xbw)*&BT{gE?Bm;8^>(1PQ&XF0fzM;@dOH;gKR*}#tVIKPQtaG>&f)sbj)mvWSyI9ZR;i{k^JIEEWi6WvwQSeBy*;Xx$aiQ zukR~F8-83y*ZCu0`O$bdDzF=RyOY7y&`^9l?i#!k*dhU2h28q0LdZO=5B8zk$+T-9 znWB{@=(owjvvvvCcKrrfa&i>9ZAgTN&%#C9e8w{+kqYkGt3;AF=(FNovx&wP8Ss96 zm$h7ZOngeSY#fIRY>bo=+d>(0qVn2UY<)yf`3-C%->=w+9+fP`lO@V_~>s^N9UL}(5*W1vu2SK5$`^rhWqUY|`{ZX$xnjEe9vbU|8xgf>wWUfJmnb2wc?!-VSPX-POkcSO>5_VgX?+{LO1yXtS^$FwzI8qx_TgPQpmy+7P0s`>>ElK=b^c3 z9;@_dy*PSbBYw|4N3JC=CE?e`!O^u>h~`u~xIADTb6ipd?kX89b*4IwZf}Gd>9N$T zCP>(qYg0+p^^j3LfXWIzl@P&;k-~Wd78_X$VuZU6f$rTOUb|G zVbJ_FjO}5UX#i6_DIvOxGHDgw6b1{4i=1^bJ>LdKaf)b+A4eY__V);bl!r2v7qcIJtVkMSV( zGc1cW?@VWL>!iVL;RLv_^e|g={w(X<^Nf73P{8uDLEwGo0CAgsRXn0Y9hQEG#@;JK zaYJOGZM15d`1f<*)2=6Q{xOEXiHhX+-|XZk=ehGAZu590ap9MiZRWibis+T)F?9K? zla$)rqaPO+(027p)N6hoJ!W1(cYLg-Csg(LbS*c&ak~$1*8e}d0QeR!2i|vKDgUnR z$8V=vaa+keSetf+ebE^V{Xr)oDXWEKIGKaw!5reb^Mz>n{*~}c;~#0c<{+|vGZ9w0 zM?rhgGZ<*Ko)~0ih&mGDg?@o7EYly(r3%jC``A}l9-t$*A%^jHEpJeM?I>;&y${d- zr^&BRN#>X2DK8!_ur){`x7GIH-G63s7gZ0gy>$(LGiWrIaVbVE>tS45N{#PV|9}l_ zAr80Pi!mDCa9Z#Ho-|5$FE;t{Kkha>Y=}9}xa7k}D0uVrhOYct^KAZluPfh^Glw6j z{v>))XAC6*?PIz$720Z=_bqx-tpDdi*hT>lE| z(W@7))t`@i%6UwzsK?%E-rOtBl=ryG^TW3ycxOT+-_+>EpV)2XW$#4%aUbRXrM(~r zi#e=OUBOPtt^#P*ht$GGk)pqf=*6KGthTj^WoeJ3FXd&ajNsQEKKu`)Ms3w=cFO`a|ia=rLJMi)wUaj$85oC4&JP`7s7qVvnn|~4H zM&GD5+*bicZT-MD>XX0}W2*4o2khOp3A{QLIzKK8s+4q~L1z>is~4~u&Dl6K{j=zi zQ!aW+ox;Xh9^%h)9um8o;moAv5PCU|=3aq6vBK^hW*3j;!}rN?kBB{l>Mrx5Nt=L&3uA&})Dw8EKt zk08JKKTz$+huY`GY|&3E5ciG8+l@lEH(QfsSH5A#ZYzS>hXN)ZQp{%8=7QQYb5IvO z09^yYb^q}-Osc#G13Pu8Zkxajin;~kd*o@Z$dXFitI*abv*`UeE&6QQPp}`aN6(7X z=(P+rdO!U(ZW?_L>#IidCY?Zj=ZXgp%ld>rj*a1Q#j^Z@n->q7JBL=K%%VGo7}L$2 zQ)rUE7wu}_L3iy8rCpDv&;zEzy!_m8Y&7i=Z&UUrIfbS8;Y$HFkDi9ZuYDJM2?J63 z&^__k3OD+6)fU>Ze=PO4bfa?rcF;H_KRV-@GTpL5ji%ZAP`Bli8M~VYnNk1Y9&1%$ zZ#WobPK(9EA0H<}@?zMx6=TtlOhjpqL#$ZHU}p+^I$@TEp>mh-d^;DdjO8Nlpd)O? z$B$4buTI;=MzkUIEHrBB(e2-cQuTyR$ck2=9%skV(+>J{ZwXL~U7IKt1W@{5Hm&{T zM0Z@$qBp~4QtdZG>1yKzCL2g1e){2V8$ZZVF2^0K0`-P7s#PsVhElL{?c z-2=fhdcn=_Eo|)Vgk>^sz&&&lmFm->Dw|j{3FonQ>3+6nOEpeuy)NE; z&e+!fmL8e+5%uWVJ|9 zVen#N7urs;y;Rxmhr;>y)*;kgE%@Y`N--gL2M$*ga)xma#CBD$MYE4>$NbrzC?A-D zqyD*Lo%M5KC~rhugHEHNe*k&CQ=Z8`kVBoyW4L9`DU>-o3zut)Nb&-~&9Ow7@eRtu zR$nH*xuX=jzf_~v_BBjCHk9>eUM5eJpI4i;2a@Mw)$#3qZOFMig24}EOdsGVYRLS; zytc(NZ#^6Q*D@M|bZ@cVqiz_Y7m0b_=b`q8g>YqAEE8!ck(1xHi=r;&qoU$I=98u_ zigPT&8+%`}mK?#MoU0{zZ*dDk$OM}2KbbypQKVWYr0Ibq3mRdkPCbkZVCU~)^k?i) z`opmd3io=_X{$%j;?i!2U$cNN)Uu{eBxUJ4!E>bZc|O(LbBr!okWSBcZli^XzSP!E z*aKFk)5lvEQk|cN>6h0U^fZ=1pTMnAS>*_WM)kvM-w2ptT@0OJcfn|#HWi5*(c+aJ z32fFtsdufY^ZS4o`Kg?cA}4c}_r1{`?d9NCqFA#48Ph^~4JeEtBBAG(j94D0cJ zPAc0WZw1R=oF=voTDDV*-jQ#YQy39lWp$nNJV5%=(5bk06V#EbPn{!2D-dUuz8&{xKS!OmUu;Ld4(}gbCDs}94KHtz<1HIdCO9?YQZZD$pJl$4f%6pun2|!dty4k` z+wfKBqxQSw;@>r-Y4!=S^VvM;{#FKovRk30Tng(lrelGMGe#9^;N#)S7?Qmm|J*(T zK}q%ut_H%BqjE4fFkMVe>9SXoiWmyqhr|+rvFYss7l)|9-@>C{v|=87s9eoXC*NQa zH56xW%vzPvrmy2T5QB4 zAI$Mtj!5*nXD+TQ4#Q{vj$z1TI~*(w2Szz8!^Vmg;!Negq~Tv9bBU2eG>aypvaO67Zy zPeR#xku2Q2vl;sWE|TyXCU}beu&(zx!hG5KWv8B;VdSt*{_D1+Lz zdZhj2F=8KbLi|bI0p?l8L;IKo#Go^gGz}<+eQ)uX7gDt}d~Q^U{<6I|dB*rk(#jy8(iE&m|;2bZJntc~a@*@eDZKhY#qmacodj0UB-QJw4& zROP(}-FRgr-Ck!+4?F&b-5ZC}_6`Ml@2&zJvttQe**}K%Ze2y6|Gfixho{qbmhT`x z?L8a~5V}R9z4`tXW_(MABA+@)iOX)4E;&i|{Qt?>P`_*XF6)x@5z=KyWk&a*U$;>;uaO^aS&%6)ekNR*{H@H`%^(K{M+&F-H?e=1a z>ui#Fc!2o)7YVA~G?Vsd-v^(qRy1+xOL+6W52DYtgC_3)|5avGD{?7WtiFP+T+B(t zOl9(X`V5HG|ITV9^U3$t2jbk4YPQTunheP36}#E%!`)kw@F>Kg%JI!0tRAex3={L9 zesUf8dSnar?OH?2l9$mv5;qDP%e{OKesE&5om1r9x!NtX|~2~*qW zP~X*x^xg_5I>yU@7LE7=GP7sU-l?X%_iib=$d2PSF9&hmF~H3W~_IA(u>&{s5P-l4f@_l=9^m9D_H zwfC{&)E`#%#~T;TNnl38^^sJcg0Cm`vZ*DZxTfs@44P94@tK{_x#PaTnAWGuyZb>j z%^l8L&w}xKn_<6$7QL9~LceLZLii><`k~OA>gxU{I4S4S?Be+}N+A?Ocko$0_JuZUVU40_;`n-m&n@MP={vbO0tv=07 z@T8BUM$j*VCJ3{YY^=Q8g}Vpb#@WXo;;BJ{xUX9dwzZwa0HI6vYM2eT4!(kZNsln~ z_c?rGV$6^H6+DgBA|6_<#~ZtZy|z&%F|BMRcNe>g*Y>R;n&yYm{(vp`h8$$+lS;_g zC32{GPaCt(BSwz$#+HC=W`ELDe8OTkPS3E1X&w>~Y?;Njf2zV4!na1)@Vjin%mb|F z250_3&qU2xEeKD}F<;XfGF~M|{IKf@Q@uQuxvubmza331bgLr7+GfMacc0kGD1A`e z^M$QXnFhh@!XT;zprkt*4Pde>6c%My5O;xX7WrZXZfX=5^(DcWd22J2rFxR+OJm7(11Y?ly9xHa zNMw(`sAI?9ldw8JpUkupylLCJiAn80W}5bZnT<^h*Qa*oASpX3Bb|yL<$0=sGNRP8$mrZ$^o4 z-t@rtN#BtvzDHA)9~ik4v8dM&4{fQy9p)8cnqH0ZC!?6k<0i;$K zQT`qWcGxQp^rji3+jm!}Q?F(BOaW9Lwtz(O{_5J5Hp2Hi1Hm=UZhXGR_S7lhpJ+w4 zbbKI|g*{+OI0*mFKaZip`SjQ3d=`D8i)p9q2YGpS(aC=`@WQeZ0{(iCeivO)>&a5^ zpPUIx?PEme?h=v0ay`hJdLH(EJ_vX7is0C-`(U~>n$YAWpn4+<06wtJ0&BFi8IR)P zeK=Hn5fzg*;O=lU;JBI$_{L>LE9IucvdBrsq{&a$6AeWS#un54NM~|#%Rzp zDsix=XdNlpZ9xOnh6!`N2-qGt9o3YklRaTf6Mvm&iXas=PV>Fm|5OgJR{|Id-IBb|>f-<2w6es-5^x_aVe)x_)qh#=)n{c?8(rOoHk}XI-t~!lZHyPkYd%!Q=PQ=!{k|_)G?a8vrFz-~jXhGT!()n^S#ynYuhq9z-`m(cd z-ZBkdnV*Dh`JZfF{)vJm35TIg)Gt0YB?4TA8AI%$@ldhA5!D>x*yOEBcaE>&?*wsRF+@E#y~*zW}Q7YI=i zxgEfb?XjdV6c6nFPI|LrF}`#V9FC1=RrQ0})2b=#;gu-1ROJxv{eBn+k2)sm2obu6 z{(a2ZD^ILEQ-PT!j7F<>g-q(}5wx?Ii>0sM35r`y93t$UCf1A>ay_?ftqrxrZ|Xl) ztNOd(osD1dwDdbPF;BqRTgIX|e=U0XUto8cBYM`oz)7i>@LsJoPE438%wYP_`)Uj> zT9AONt1jbLkB{tTS{?fxbO@jRxzFJGLeyGai1FKtG2_>M?9NQY6S{f$^0q&)?o628879IHys;n!hNc*ivgBi@9g_Y8jw^|+3kryFD3 z#6onpmv;DDn`tfb?qD|gdHaCp?d+Uee zM(Bg!$Ame-P7rWR10R*{#;G?~*33On#4OlLh|3zbvY#&*CZ z?`3g1JIj1-h(PaO2=&Ekt zG=jYCodDzJ8DmmwgeX&g5)s+W!98)q@pe!+;Yl;l&2v6Up01BgePx()JsqQJ%E;03 z`BPx=AeM+Q* zbwT&88*70f;1qlrZVv7xA;lwLoVlXReEzmCnQY?q={aI4nvXx&k(~0zP=@ z0P{DlC%r{QBI$qmka_$7lbzZu?&&oY`Yp>LD|athyh$4-ImDAKOYGo-hZ%{d4~fJE z;TvT@3`Bj9!#2Hbkg`S#X4g8Ba?dt4?OJ5`2$`H zNz3O`)5*~>veYz1=(uMJ-%|yWU~GE|-nvAxh-22QWUQDx@ZAA=K?+3sog`>2k`c?l z42F2sRnXvY9KLTg6nX+>P`_yzM2}RUkItQd5@C1yx9uhT(!9(9(v_j#)dAWbszXfa zc_k@*6!;;*Q-H4a`Bm}1$r z4a6oW1r((+m|w^V!D;Y|8T5}u<0A^NadQIsoqUH}`+SIGhL1#p>L<)s`v|P%ebvRg zHru+i#lrxF3(S2$0_Cmy(DfYns&~Qi@aM3&{3+}UdI1^7 zu7c~Ca(H^P0VcI;z{QJo)dym9Kw;uykwr)kp@;5}{%w(@JTM1l827UGoyXxu(^MFC zTY{NYQamWtL8SHyEBEE^n7-X(Tb&3^VzFx~)Cq2aRjYN0rCKh~iInX;rwZ+Bp4rT5 z6+u(hHgsH*1efj4fkMd*h%s6Nt3PnaUY-YfwkA+FNfHLSWJ2-u3gTv(%|0JLWLq5_ zMyAK6fv!?Ise7LThq`{UZ;ASltY{7Q3~fn-R3Oe`D)2VP3OiB~iQ^X~k$$6;=*f*G zQ0RCON~azHaa=K&VJvhO$ijsrQ!wlBf}M>kAX%S+v0@B7U-K2_JReK9-PWKxu1L|> zCAT5<@l8k@5d)@OCiL=yXz>V7EjZurL>`8OLZhTJ936QHmN*`R?!C&OoOKL-^G5bj zV-H%KtYsZn0sfq_hxE{P_OkpuF%1;1$>BVvdhZe#jw%Fy_tP+bSS=_$E`lF2d*IC2 z0Jzu`PXb!(ndsdIaa-*w&^)4ycaw~8>e5)4cgPKu>rHTg$vd(9!NDZyf(g__*%FJ* zwqoZ6ez3#v4tuJ$3%+$L!n$FS@Moeri&ip%Z>x0Rr*S1o5PFu*CxhYfhqI(o;iUNM zcXeEpJPrFE*NaY_^~Im{vDogjgot%slPxhfSathon5rBK53e}G@PdAUBk2wE_YMV( zAF4F8LV}h}?uOPQ#*ilt2DNjI@TYXL?Z+ApO2;3Br>*Fx?sio6)u1XDYOE+0tJ=o2rYt~?ADMa#kWo=4=*<8iQBZ4zGU zbY`v_T1CryQi#~j4)d$raoiGj+isa{ut4)2^o)swO;ZJ?)Z}AeFiT6|SzM@2a;t@C zc@d`kGho+5@l5jmWGtE+O~&7l!;u>sm~O%%65pPQp~_xxOeT-;xbd(_b}~*;+lE|C z4%c)H!6in`Y}A?>mOK9*`EknG_Fs-XtZ8&7hZASOz$deys!X^~|2=1yI>v(bJi)>E z!wNbKd%#9=J@j2&1XBvfllXvlkbHeAZ0zYF;v&xGzpxY%wCS)T?FJhXKa>pUxI&)% zQzH!}N@Vl9p`h3x1%J;}!SI$E_;kuaRI}d?`j#kwgUeVpJF8Zd{rIE!>#8eceNhOA zfkz z_2?Y@%~isSX1icQ{~R!UEC=iQmqVvaBY8Ym;L$uhS2cF*1G4?Da1NIp$cCg}tyXTb z!PL`>VPR4vNtj{Jwj@%>&oDrh5IJ)B!dk|=`^b*q7i^f75iXb_w6M{HRKGpI5+}?gHv}(0^2Y_Z*v$hIZq!uAXZI2hrx>{8n+7S>D?#~2 z4?DFahDEuaVWv;#i3{!xhhqk5Eah>Y*njvp^5|QU$e?38e6m%ko_`^loJw2@L1A|Q zBUNE>$5`8^Bd@}w1Z`VchZ^!=&u?Ph*-5@=3j0?1x1`@KNnpWzAYJ-dprRcmlI^`o z7Nu#kINxj%J#aV{Mvupu0s~y|_!&!+PJo_(*~I$ZDO-!rhe@f+Xfl7;0+wEo1ruMs zf>!x2VDWM^WR#YG(}EK4sILXdwp%b`m;@EA`YUkH1((_JHdt<)21`yvfy|h0(YZNy z0TpWC&z*WvjVK0WM+8D$PXzqvv|tdC%Z}=-h5Ff%#8h4q=DteCP41)dH$G(H>*_>P zDn^P2?R7-G32)g!lYG=2tB6fOyn3?UNYw4#NTl7x6ugI57h&L+>rCQg2+GCJA!|-=BaaqIvyltqu&vdOC|<6Img1+dvHB5Y zNw`~Uy|(n!>t4XML#WSpReIry6|-Jfi%%b3M|Zr5Z_PD`nZR23lpIW+SMS3mK}rI@ z;xWivx1!3gtf{B>IrwkdG!-b0~bX=AZjo7C~-|m}8kL{XHl{~bledra)PFJEAFU!**#XRiT0TZY;LC{IUNJ|3!kvL`K=^djgrQ_!u~E}Ay|~j($o(V=}ehs_;$J< zcG`ABWt$-l{wdrGen7{)G^ZQAf1yKf2aa?d%U!-~K&zQw@R3I@E_|ZQFKrymms}jl zGjHBO{jgY^?_>l^(rB0Ls1 zKgq$+0F z9FzjvqS<77!)0;n&@kcrcpcw5#i4C)65f)E#*3Tfc&hj|UWmPkK3NiI=XMOktVZ%< z9YV%CZ7!M(i^N<#6~6n8EI%FEge9*u_|Uh2iGx*n&mSvZ`#BqbRS9m`6kV?Wrvafu zi|_yM8#eT`K-57!I&9%1_&o0wq__MB-)*d*V#p|pn+1npkKq5_+76Y?&Q$WlNV@)N z3#>9-O5guoMx!O9=#i(Z=%Nl)I(vr=Z7qtS!3EoBMDHd#>QxN=xm}eOZktU{U$Up( zWtud#@&;`14uQR%vH;!#1zG8E_+*m?i}qEL!D`FE;_@eOoq889TgIVHm5`OFy@B%s zx~fNh8iV4Df!zG;V|L+jk?bdegXdN z$iRxLHvGEc9sH<;I9=%trW%arP4oUDGgyUlJ^k^{it|EV#vGTAKY~$B%djcpA8utD zJZnM(GgXO0OE)!sTeAlb&3=bx&pgKW>ovHUL8s77yo2UD<#?;F8@ji+U}0n-tW`TC z8W-{gKBn&%<`$-~T-_6PmTe|$hg-s|f3Jz1+dYsgc?;5}nsmXrKM-DEM2!xNpl(|` z;ptcoacfTsT=4^RebaIJ^xSR=epBdw_blmbJAdljV@RzMWN6i-b+mUv7Y0tdBe)Wk z`89JH{zCR68r{B!*-IMHKP?FZeNL8Psv#Hd=GWo9fp|(2W`+ z=`#7*bo;#tXw-V1H9xtF7rQ77$KrPvG&v~^E7+QL#9~6`3)6ytC8gOeM zKL|^?b>diVSR-^e%YGw$H<(X;{vG`m-ok|`(tP{Y5OUFX0h?`PBTAj)O}0g9LLnK- zGHaYghYu0hw@SZySmsVTHpPP;mRdn?OdCjdo}EaGvn#Oruh=-Q@rYw+TBCBD4dnJ-LU$xS~R@UxiI9P*B)&i)rS3 zy!{*6D=a&UJ$ zt^h>-wi)jW< zT5}V(Z&&5kjT3oF*g#(V{WAJG?ZN>m(|A8D6!`5c_}<;l{9@TkK49h;?tgn5SB;s( zht0F)Pe07zCtD+N+6#g0uk#u;z6i6NrSH&Jb^xEZ>^&Oo-HE;>h>Ej@^KFZTL7c4& zANckU`V`INvNI@WZ;bejsfI$g@j3ebk!Dvu?t+fNCn3b?oCtiTz?Z$_!7zRhXf4ks zvU|$dN}NE8m&~QTFZ7piMg4PlO_M3KgI5dGj9 zxDPFcsF<;|Yjq^3c)o=ZjSoR|K^cA5&1Bby?!-~PcXF*1b0wj#i6Lj)7p>aV1eA4;C%p?48%&`?@(0?)ZM)EkJFB>Ejl%T?X5Kh-| zVMqFgv(zeQJbtJIUbqZ{q^a__%zZn1zWhCLoiz+9V2H>j(2f)qnq$Q~A2jnV5^9Pf z`|15}6P4Z7<$A@r`69eqyp84>R$5PjH=|#nuRWi!*A<#O0(Z z34VH$smK?SdvDU1rhWk~+`1W_Ki3tM=B1c^HXi&NW`g-QS*jDN0K>{IL(|_8bWHF; zSgEK=JqMM+Ur~yiNBluX5WLKV@JeS4F9Ww4-|&t zealAXf|)|k;UuOSCEzIMG+eHG9HWvwF>ud%d@VB<;y<4je^!gdMS10dkH&}vH#}w1 z7CTT%aW<}#uR;3j0_ppGPr1BK+;YAQUkE<5qLgyf{kIx- zI1lBk+AA^LI0I$&r?AcB4o1j+!F6fYjFxm0Yv|Axd0 zHP9x>cw~1LK&+3@gPu`BMw}T0Zw5PHUymQFtLSFy&gS8QDSg#Xgj(3qtSnJzMmX^g zt3HvL%@s&4_(+Vio)1_VCmvFcf^yTRdY z4~ZT54Wc9S!PNOARNPmkKc0HP&ER}+kx7D4?waJ;tpwcI?`rk1*Bs}+EXRX^pRhe} zfsmcE5)Hd0@Tuz<%>F$9`)t$L^uH(BrCCF;Yo!@Gd8?Z3(ozuNrKO}WTnXoXo5HTG zaKeZU+V~{n1a7L7Avs5d&qh5{v_bGi==CZR`PM_YcI?3;76_oM7wi5-5!C61_7{Ahkov$jkN<@OmnPs|1p&C+||nbK*2KpylWUY&Qano zYZK}FSBt1cgE95cNv1#St!Uw7ecIYEpRVw}MxzjF zwZ@4?kBy|V{*H96387bOxAEz%n+2YTBF{Xg&gUG`;l>vx3Yn*p+$l|kH?@!9;~zTk zkej+ZY`n0CKj_KFBq(y5swS*IBF|M5Ch;+`?tIHuPhM2Mntw!RUg@%hPhXzLLR4ekj}Eo zrZN38=ubFISG268DRSZT{rT;5folT2Vsnswdpdwd$d0A;+A=hL^<$X*`x97K4xkl7 z5+U3?7bITS0>5d^^Zl&(jVA&8W!em`^<1Bay))x`mzi^yt<(7m8wbAItDLrl7t;~` zWmMLwiiY)O(c*vkw1sET5Y2M>;d411HT?<|ndMOToFnu>O*3r^tfOadU7_x8&(i_P zSLt7gT6(%{Kir=`gtl9^L2>6uTJx?9dTgTMq@fL!GLWQi|9*xuLSN3Ov_EZnat!>x z6+lj7Gh`o|0jD+!Ic`EP(|MmPT^n3US2e}ZV2ym5qgP9>T+5~9fA`YaiJY1)EvBn( z$I{i-`H-d^M{X640LP&Bu;%SZA~97Hr1JX6pAnXD*ysi6aB!!KI>*ssWnsVIEBHHZ zE~d6Eu2lYL482zrK~Foarq{h2gj`rL)pn1iH64d(>%=oFD3)JjV7JYKBn8rTtz#_{>n6*`ncbpZx->GYG zLWm)^{o9LszrMwH-}`gp9uZ$RdnRv@_2*yLNAh0c$fNjHK6>JKp5{A=e+^p6Exs@0 z#)B7g&Hh$=%Ick5Z=w-DaA_-_puK^AQ5wfz-dn{-9&qIYr<-!Yl*xnkn{z9{v)`3t z#KUz5^39DByuEiiPuzBoXkVWKif8(72$T zm(z=ljY8Q!m#VD~rRv8gQkhTAG)iR$RVMxDl!=No-g-ElmAZs#IFF?>MCa-HXP0P| z@HtAUmC>yeYG_5)IeNtKCY3KePraA!r$FQ&bpLw-EAM7KbF?1>o&3w%;ZZ17f?KDYqZ9vckLM8;5> zRw^p~$5~s{EEpdl0S2D~$jTRQ;HjA>__!s)^6A&$P1|>3M%zKty8z}(CxLBME^(+W z1ld^yBxsc?983=bsV&Ed)Y47l?)D-!Kg$D}4?Cl6ZW5GF(f%(BkTtl%q^vMa00gjmbPb2g-&K;uRNsV6ORg+$|k} z+Qb~6wC`k^9~xQaot7%Iq`~4i{{%EhRDjIPaABX(1c`oia5nKZ82zgPeG@nE`E3Hf ze@B2~Q59TG>lOc$3kSzpaiFokm-RJ&A~&MUaMZ{RaH3KMnphqv8SKT~A*n3j-+vOJV22{`YDTpB^07ck71u0u$IZ{X zSi0mkthqdc%#8?Qbyoe*C3`+Ta+M%9-DgE@t0nOBxuF6x-2>-^{t<63=wUgtYFMM( z15mGr68%%W?4?W8@z;K5;ocr_zqPz*bNkEwLI};S$_e0~1 z8A5O6I6;wyc#QLY?7B4;i#zPlXT=wmy`+(qX?WmS|sLA zJCa>-i5b~Bu%OLXNM5=H-oA4{ES;uKFFsrjGp|$&SvN)y@bV&5s_lj&ua83PT!9~U zKL<<(nWCl8zxp#TmbJ_aWHAbAO#k0;a&E;Y?3g!&)JB^KdxpF0io3ixtDio*@aZEv zF8E_|&dG~LY*e*BkNt6e{VqG{-Ft9h^(tK6?*Ka@6)WWI&LdmOl*MD?t(b;OrFfy^ zO3XOI;mwC31n2%@ru05oh?JP*uEQ+z*&(Rie#QC%zY%3T^v*8B#nrl;&c0X8KX9PbMjRp_3DG+nO1{SI|2tTie z!?X3!Y4&0^FL*Y1pHRX{EmN@kWdSU26^p;S4rN&{;!wv|sEs-Z?BfPolxa3++fR65 zw)8;U7BWb@W%m}GY<_?{+ZOZvorifE=JJB{BYZbj@FUAg`9OteE?=F-&5c&T_J}!b zxW6;W$+-x@YA4}fQX8pV-~oMZN)TZwFj;rxa`rWYZ+0luy+awj`RptmqHu_Y z_gYt#g9$rGu>y1z4HCKxH=LvDV_{VlWM{7S_vJ~rJA0A9$4o*5hk;fFz&Z13>50{KVB!nEYmD#EcqpH*puN!a|v9M zR%O=*on<>V*28WUbuf531V-&S21`5zqu)QKpSB;M=21m-xVV_UXt_tj&(~3%Ut$_@0%^s$b9B+U0&3Kj!lN$vaXFiv ze9+xEzRqzemkN#Nw;Rp)W2@DCkkte(@u{4L?K#hPCRgzea)ZB}b%g(^zQiN9Uf>_* zALrf2O8MLsH~AQsX5Qy^jSq^u#doEA5g1VKdBmo6zVAgVAHMoNpPIOrk9r-=Gn`!b zTv zom=0Kt?7}}LOY3OwH%}c0*`3o#WnPCM>HM(VIv)XG>4AfmOuo;+aDgwPLA~ zQ99lE>Jrs|ca9FRI7&yzJf^eSk)GRpnV!sUp@A(ObVu?rA>&ep`wI28;(a>2MW_Q$ zn5fP}lfU4OQ^UDjiv-t@6Z{B=61eknU+(ZRhm-mv{E5K1^NWw>>D}`oBD%tR3(dS9K@-PMrFXn1(_0n}R90<0wLX@KuFjKjzawFC!r7FZJWAFH zy>B(IPk3hB2l2p7r*S)XqC;MFE`tgo*CXb{KkN$yS z2{zO_%bco|o71M>e_>3kB3)=aoqD>QhUdL^AU(DLx^~*qVUNedpUh$4Hb;vNTC;~K zzrQU0-dzFYmlu__QKG*BWa$2T)9AJwciQbdiJsY^PTgY0(W3*WQ}Lo{FsjW81JlE? z-2a+LZEQR{zIY&>Z4_J37J06k{NIG z!A$)PtjpShj?-U3R|Ff=5d+>sj-_x;#c}lC^m){H}^7X0UFM1~Emz;{wLVS>&wzU>%M&uFYMNi3{rXYORF3%=^O%mz3N#eQaV*Hmm z50*~z0iQTyOz*N4NqaqG8y8q%lXO3r@+?ZMp8A$7ezS!|GksQb(H2AIcpxX`>~1*) zTS5C!?>`ZSy|;vA6CaUB73LV`@{pXga)u&zYdEcEg_q@{VafdjkjQvI{t22YGrS`D zAs2}W=e-3+i?#hD`x~&Y(iduf^dqv*4d9@93gGKkV6*WYJQBW-yQdn!qc3G-cgT72 z_QM(sSei=qcS(S;>{zghnJ4U3C&4Kh39uexOUD*2pug9?gSUNyXu}6hdSbH@)zR0Y zty=N$d3`q={i_DIp6meU{u5zuZV=q)6y7I=-{2eDO&nHv!X=NlFm&`D`Xn)r4zycM zz2n!?VF?lR=b~7e?;b`iC%e+s1zV_4HJ}cKGW4;T7PWi!2U@m^g}lK$;;Sg|_zmyE zr$>fxP|!_^e7nV+7jwlgoFg#p-7{>R-XG7(2-or~O{^Pn6OB$i!w4m1{I^};Bkjv# z>OGBEqxJz$jXaE3{TkUVlWTbD!#Pq(yik6QKfIiw2%i#Gz)7b(z%OZRlvvPPcSXR? z$sMBEx*7OFP1;Vs-$OF3s7(CiOCo}4Dtq9o3?ZHonEJR7^mW&YVmCd3;Z4>sT_lxMy94{i8!Jy{JO13NMppcW5L$+qjMdK}l#Bm1*WE^$N2gfi`7kUVd;&#*KQKcl6=(1D#*gkweE+9xyi(Wzk$VPF zN5gjb+dhEC_QY&fQ|E!6(@5MTS_nsunZFxn!-m47==i6Ni}Y$I=6?DCy8GGXL6-W|SDxMS_my zj8!0fe4GG7H9p-(5c zte6Ua%IUR?j8oqg+;J`e*wH#ok<=z5?GUy1S7TD0f%0NZxjB)urK~_%`6(4-;2qC-d&J9 z@g-{sAfRV5R$#*ICKtckiCex%lZe66Y~RgHSoUnUy^LcD30wX}thKb2bWJm3GY$-a zo?%7!@Ldi5ZQO@P2ME6B^cu{|(7?wr5!gC94Xf1QxJh5f!^II^`s}6^XT2VH2 zhrl=s$Imb2$+QMDP&8l4j>vAqq%T{c?T;M3{t|}?#nw>s^$1)4YCH^8mt;TmEYWbz z8OU)o1oGUEZJFT*E=5IP^hgdzO)X<_=WWHofxdW3<2EU~nMCeCh$mCXbrv$Goa6-^ zL5rK3@Gf>b#O@TdS-HcBN{10_?1~3jau`P0xZKrr)~Q&!|*j*^DkZe@|zZRMQtSq zr7~fY(s*4P}owk-yo#L(gI*>ss(%&PZ3{74E)1$W z1nnWRq_1-xn9aMzdJah7gtx<3_3rsNzF`w;*Sx^F_r7DtpiWlrdKq)Pf>BRej9pd( z(Es)kTXz*PhjHx9=5Gk2FGtt5`Dbt z!InIKfD1=0z)`NIXfyb#XkSV*Yu9wegSsbKRILiO*l)uRS{i8X>RH`v{+oD@+|A-I zXRt(x7*shq0?%bAWj~@(b`gjRG*OHsegOL%U)WFVa6|}F(DC0?9Riv1*h1C$!=^^)M!-Q9f(gX zj)|7|=%T}v1-NiT49+Mo!JcpDu*^FJJ)L~;tdih)ZT*9?vov_j{w=sRe+Eu7F2nBA zA!yTVikDwB;NaAO{Pxf9IJ8N~&a)1{-m+fSkmHPltsV$0kZQC)I0g^BjKZOlU*V=v z6{u>rK?L5eP~WTs-y~14hXQ}$s?R)}0C3x4^}-lJwG#8ql+ihZW>Kyi1%xCLHkqtM3}vu(O;5<(?8Z+^r-RrFUXo zq$+;c|4;C&OAy25(^2=MGA~~K9@ogt$0b=R+~{E+YJ5408ZS=bo@31zG3bI=^UyD} zsXLA9_pCv&piO!%^$^{v1rKl1XS7?T%hsi6B8ClPeT{YERf~_3nP)DN?w)%rM_?aR zEofq%e>>U6H%(Zn7lV@j6miDSJ1jHM5y!bE;jM)MY)963yz*9#oHSp7*H!#6CM*@b z7Wbg@6~WWhoycqyKcTT*D;91Rd??o>x##ExdmmXL<8jI}th*;@la}vbu20(V@xNjm z_^lDUcKcyv*(QlT){)a4-r#n9 z1}>g^*M7n1+4w5An^X_GNEZ6FvV)VoVEr;=Pk$y6-AixC<=Hvl_Ck~Ln@6E4YX%;e z=f~#GJ0Uu4?kwm?4>Hw7(?kQElW-#)iCT+mm<;)c?iX`d;qK$r!FvM58d7KQc$hja zHoAo0Cg-9`XC7|R(8b(PK{I!5A7-o7vDtDZY_U4x3eDqe|A$rh`{Pdhxg;Lj{|+TX z&a|?1yTaL(ORB6r*#`aCwZc7%j+b3|WyL%7IUp+(fy>IdK?KfsgXU%Zp8R; zOIX>lJNVKm0()ncp{40f?A2_+H(4jK^MN|<7xK+Qir$u}-DALo1IU8*BKq)UD=Eo6OOBPA!nF7RxM`UD2V&`eSCq5EQ1rjEO+l9<-lS@^s%7XzLs^7y=UxbD0i58C$~`(4!J zJIDv(ZMl{hdw9dQFW2p7z5LD;!Ah` zoawkm26>O6<;f2~Z-s~+*d0oY{)OS%nOAT|w*#Dyb7oIYr{X+w1Ke@Om@FtLsg5bE zK&#_}_|H-2@ZQ|-xT4$<+cTuOClhj9GhI+SEf|9Z4aBRt>sX@4VsX~-Li{r_3A1dD zGFvhlB~-*=}X17!L`R*z_e6ALkJlKw}m6f^NxHe3lm4TWQkE3~|Cid!O!tGxj zkXo4xy3#G;#uK+-txXC%4C^QCi-b(80(E*>W;Cq7UclaKorJg7*RdIek?>9}UhpUs zvz>JlA-*b}&01FvnVS#5n2cvouvU+%d@O?iIVF1KHlgNrkx;}NKt9?No8xD(CHroX zA^)uKfpP*<`;sBL5Ic`tRb4G)kTqf8bA2$-t|8mLxD)9=mq2QSG&LBI1xqiP)4t0o zaKKuEss}z{`_>LYxpg1$S=lkRaE&w`{N;(T0tvI-qWOu?g9Be3b?W|8Ez zR`Tv;D6w>Dv~N3gO!Qnz;Q2Ug6!HNzsrvg*;MX~kE-#uxlY*`3+xsGVGfs^U3F#RwkWyR^yQVLrQSmZ#$WaA4`OrY> z8#9u!0fOF8#+6P9SU{J17*VC)vti6v5zrV}fd_pU9J|Hf@6sPC|0IE7L=7moohMbN zVwldI1?aXdhG`V^RO?3j;enIiS+0IO`R1tsPDRIAg5DzhKw{Wm`8eU(Tr9po-HLdmV0oS2yl3|eG{k4P(3zab@GDUn#a=6Iw=5Ad1Z3Tw7?-Lj9 zk`#Kp+TwA)^}##bfJn0=Vo5D~@O`#`Sz$GcdgaeHeGGuyan=|kaG^fV?PZbuC!)#@ zQ+%zu9?Wl2GTP1(#+Qs>X(Iy2J(=yKH|n7HUjIyNsV_v!mkV+E;Ol~R^a7K#n~E)( zLXNWjeZ2ViiYP4p7mLe3CR&K6vFzx0e6#Q@TYN>4FMmIRf2#kATz(PkeysW^dKi@SkfDyOfY?pS|1yO$RFD+@!jObHTAv%8)(S51pPs@jxM&3k%Q}~f)C}X9h7K7l@?VLuJapRf}Y#o9=0m}gC<`KsMBl* zi5t1#zgvf9g$<@#UZ_!Zk8!jwaRPNtz6u*2{-wWcL4p(H$E~8iPQB2z#!mgLaVUpKy*ekGxuWTKH zA3LX44|z5LLp+b-7Iib^Bj%vS-qq-SRTY)*X7X-l(zYwxELOj`l_O&{*6U<^jpe%Bq7$cZkQOsiJmU*%OJpKya6xr7{u+G} zBiIQXBY3N4KR%2v<6OvwAE(*h?dfc8zqPnx$4D&B+=7qP^`I%mog@kRvZG`l9$SvO|#ON0#LYeUh0aSYmD8O*DMoSGHiRJmdP1C$?KgGaRhQv}Yp zU5N~T`PUVVy0gdvDZ+}~D@Z}L2imr-hP*#faXY}#l6Pp5X`#2h)^T561a zpO#|qQ*ZpPV29R^PGXV9B^Dbm%WE3tc*JCTPGLIl`Df1e5`CVtS&I8;Sqi!*;O8@5 z3OSYDJn+{TK0mt!UA8!JyDeti@0U5hHA{l01W)4<$)$L}qX4~4f^bcvHwJ&-fa9A7 zh<3?cU~{E%F+_eo=3^b2wEjY~KT-nlMdmKet8W?c zA?A9#UNjwR1>JJ#Z$n<&Ysp=9OY*=svb@!^4d?w+LFu*ruy1NIw8y8C{!fQNN?0a| z3P^^7OSeMy9(DK{F$`tZ&fwFQ>v-wGI1I3D7FcR#%wx`T%&)e?Xq!_waQ76xJXVRn z9^HVG&CEGOY4iJYDBrv;gwG5&<Pp=G*Hr#H ze=6@wHs(WL%keC)Yq;^P2H)yig_CoxVW_1wf7Ts@ZPnAT)oLi`Wy&~ld^oCi?Pl9w z$Jo!C)sKDOaKheUwkn(T;VkQr+Kk)uhvT0OKIH9YMRC8$O-#Yo1edLw85hr03)Np0xTvmL*@tiUu~#JUtBO1kEK_Ug5iR8GQ5}U zIlh-Tmx@H18${^PmjLz0w~(S|lF;yZ1|bKBiLIx%Fb9=1(mb&UY!ltYX}feF@30|Q z2ZgbhvOVJ4-9=LJGcZ%ijIK_%a4;N{F+m7d*=A(12KI(jwfq&{}Slkdv zC<_qSq$z4lG|&KU&vGL&To^9K*081_{#?vaB z@D1xH?wRTX6U&p}&pcJ|3O@__>AB#t|DXK=yV-18&>&b<(ar*!9Y8UpKX&!bLlu`# zq~u?_$o1_ofj@YUi5?o_`<46HlR^zl99$^6s=E^Bw67Pkh(D59`pQsv@dGK zKWygc1-O3UQ&#nFigdJYKn`;YCSpAM_Rt2GY1EME|_ z`A_UGT=ryq))q2(=x+$ct3>L(29ynRgI&+BLg>hYBz@95lA~t@8~)8_19We)CEtpO z;@1}O!b6elfRhC(eKQ9O9b24sRi2!Xvcy+2BG|F!B$WJKPiDrwWZ9u|&^kc@ZL5 z0B)$<6p;h~rHy&;N81=QG_+vHsTlk!`d+0UEbz*0tU-m8kVIE0e6(*EXs_uZ>n}uN zWls@QK8bDwj0}_)xaHS~Y33gG>Rt-TajmTO z&mDjn_xnh6pB6?3&K5YnyOH@M;`XIpSD1x zMBt&cPr{wYwDA0W2UHJwiv=A&@%gWV=-f0Lo8)>}hs6P=;y)H6`w3da4b#C^#S2sC zE)hozDIvaYhM?-1%si6zU=@?VpWg`DES6x2hZ-5Jc!5WhudyLbk(fDPyuj$13ulXS zpy%*#2!Tm3y-1p9Epiobo?=nqL3uKvaCi0J!9ztaCjDX&EsULAQN`q2^ReD83g178 z!NT=B@z8|}EcU}O{IxR^LzaZIG4tect3@;_G>6!KsES8XfgVa8F-28H1@>IUnXOtX z)GB43;XNU@W6*Y8B)^X1Ra;ebycvKM;vVMrw*?-yJZEg09x$PY1&{5S+{OLpLw9TI#?s)Mla8I6Sl&9OdjIJ&3*#%>{#$9!4} zJ~uYzCmQ?n66sW2tXF`e67n$X)*GCb5rxy#*I?(XdR7oL9t+GLimVevFgw>pU{kGT z`h8DH^Up+(bpiHgX)HWWoejMgrlHf8$Ef>c6DkWH%*BvZec!+ZpG^>Bjd>{!IHrK^ ziZVRbtqz?gzeN!0-f!L~pzlf#9MZoJca407gD)WZIp0Rd?wROV|H0ns%Py>qbVi>y zS8=cRNxZ$F0#goo2|q8#$*EV-HF*f1c@ey-f0OW6(8GR3}G^ zhF&)F=M$C^kt=!>b(0wDt;E5GT{*SQroCF&6M&b{_8?LlWf;V~RplWjs{?vYqzMVqemVY`swKf=Mjk5(m zEj5r{+PQkK9f7lV3)uO9n*}iOfDQ-w}I(jWGi)n{06HRRT%AZfw`)0@1$y zE?8nCa9G?z*zVpZEcwhHcu9q8w(SMErtzLct^P`+?Q$V}NDX{yyiIB!)(F0kPvpQ< zWq1{O2dvkZGRID7wk;qLr>5+|Yk88yXJ;86a_xs|UIkdOdyja1m_Ga>Gr=`0hEyM% zEbwR=U`9X#JTEE$KKLb!K6ek+U)*P3IF_*+SC8O?b0(;}MF9;yhO=qyn@G{7%_KH^ z9~yLQf^8GG;De46EN^TnvpT4Yg(rL2v|>B#dgB4hvtLzhy;wy2e`FAux#29tu!A`Z z&*f9kR|~b%R&nH5fn8fC33l(jMG0_TJkoj;f%oxPUpW#(J<`!*>K}2~vq-Y0|5!Bb z=wvRBKeC`Tabo#vgW*VnGE5w*&8!M{LE`E^tmHu!3>j0*c8pCWBMm&rh>|5h;_cw0 zwgSugAPF&xik!^RX7V?G7)RsyYOzY!g;e3IRu3H}_|ZvG&~I?sh1bp==`+YMfyipU!IJ5WD40G`{c zLXPuOBJY$=+|6U)t&KG~_uw#_6LOSX*gcnR7`6Zu)>=ZBmIWSqWCLk_vMlzl3G@?k z@6Q=;Vhso9lAw_nh(Ydg@}tcTo$uC>5q)vkd@m18k6mLf$pvIqayf|{T_%b!{!Bs> ziiz^LiFgAV33!>2g_&-6|L1<<;v+|*Rb~iznVm4!@-xJzmO<2ja2USM3S@RK;u3A>sOb}TJ7219yRu9C%heb6JB?+h>$l)6S9t~BQ5~5Q zDH0O@jajbJG7=IB3c_#yx0j{_NGuEWTNSWrh1v3D81bBAB4;?2gJ zxrg&4e%b6PX9aoeOWslRS|Y>G4@sdV?hD}lf~nN-csqVKwG*-{EHRo_<5FtOFSSl~ z_&aDRuQkrE`qAxUA24Ys{crusQO8Tegw_5x{)g+gwHR;vzgqt-k0M%(F0^l<3fzu+ z=3r4YlK$AU6^@^la=g1eg^sm~ghj2&4*ee-rg#7BfU&;G4)WH^96ybaqEjk#C;m5o zy}y+g9EG|6H~y#dx3>D>_^wdvx3w22N~YIhv}o4-Yrq11nK|8M*c=Rd*H+Wdd@ z{{QOz!1m-vkuNhha9*5T7# zt<+zlP5d+MGflcBWWgsQ`EUJiJ8lgO6W0FU_@A!d*5-fr{S*G>|MB(T{7OBPwDpC* z`fvQ7=BNAryg%4kP7ppH?f>ulL+pgj{Qi|Jsxa;#_dV7M`QPmMuzv68^3b=mXHz2Y z|K62KI&a}~Zxqn3gq`fZmv^=6-Ws~lpcQiu4W~Z@o$;aK9rUS?4|V3MGj}o*vU&wp z^;#uev0G^~4az=2k5sn7HFHBh5f8+nO zzWqa{iE>CxO?-$^(qdL^VcWAc5#m8|DQyxS+ zeBT-E;F`1DVd33eho6%!(TjDl4rOzt9R8dC8oiPjM`7;&jsMyFEhgC5{_n1zHQ}bv zd3y`%%o{~82FDkG+NB%hyT7bRrS^XH{R2YINa7sQJtU0z8?0pa+jGQWs~xJ< z!b{nWH~FIR_?kmmuDa3QMIaEA5z{*D%vBipWQSaDY`wh_o(`d+O(e(Nt zeA|~PE_-oAoO3P!I*%<9vc??n*TXXQzH15&nR9?G&h~+~9tuREF@b2l@)Li*w+Nm- zC}hTGN3zv=_z?iC(1?su@aQ|NGzBzHURn$O%xQutk)rQp<8z z7>I3+^s&n=7#MTKy#f=?vf2X8yUlQ&njx-wzlQ8z;DG&H?9sf!QCu`TSR@r$%q9eD zpu53zXjJwk*Vm|4f0_P=TsoY?nqFUGi>utxGge>dW6r^EBXrCff(wbd4$IZwy!B_mDObt8#(lX0|Pe^I-@6yBU1O5SM(L%nk_B$ledl3yugLq#A|mB_J`2baJ{ z%XVVNWT5ll8XOcp2c!2t6Zv|6WtRTqF#T^c`SPlci9br>s<$DmJ(OT6(}ST;PE}7c z(!eykW|8xzA1pu7NBl-j0|)PNU^lAniYM;W2WO|}>{)g&nD1X8=yk?|+VN31LpqA> zcs~cFr3zVFwlS_@h5~-U@tI`jL zZ<_@317@J%mz7vtKbE|@=#Q`C;#gqZWwEpB5pv$4iyeP1g?l@dVc&)yWJJeVCh_nK ztLUAM6T^q#0IfgdPoF9{G&^9dsF4{a_<`MVGswL*SkPjWh|*F*K&Lu@*hlOo1640p z--}5k7Bc#H;mdf4-f~JLv*orJ{1Bo&x@{3pNumshKXcG zc!0&aA+R}qDlWbAfJI74lc#-$$fe1;f=5=CO;J-9pGtg0Hpz@7Ugd)^W9lYxc;O;^ zAGVKmZ+0eH<%OcA)32DvUR9jywg`@Re`Q^#1kT9yTcl^r6x=@F7iarR3+%Q7tleM) zn(keRlLojkqbp-!$BGq9=j}N$)jvc`t2MynY$CB%F@o`u8Eo_Q*G&2BYCL>5joe+I z$iCg|Vgu)xz;uC)+*(~}PydPMb)wcJe==PDU(qk2sMn9#gOEa+DIGE)^hT_Eo-k^R|nSy4mqu|ms zK9E*c`^;C`rK#^G`DR}R^{NZ7NXq)Lxf_FbJU&T(TYr+5yiqmvCiCst;l|Eg3xBF&VFy7r?DJB@Hv_)O~6`cJTwxGkMOpM}=r zyJ_o^K3LY1p?J~}p{m|h%zQbUJSTXA^XLG!oPU65(L?do_)NH7XN^~)3b|a<5qI9M z7hR4<@zZJ-HmS7Z^PlS>WrG)9U%H5z+hh3q-$@K-(tKa*UgnbLaE=KKs{-@H@^9FPefLo&fSQV+eVy7D%? zs;JG3QCtKU_&4ytTFPDeyy~<#!%VNsh+Tm@U%hn?Ytcx&YvslG=G3$L3Ui^R41NM zHs{W^-qb0pkXkMJ;*=XL@M-W1=%OQWsmrxcW&KeIshCQS>f{tzy8v_dR>BR5S^bw}i5oZe zz>(QbthL(%y}NkfjLA80u)e31_xf908TO5qX}5rF-{Vv(y-Ss=>^UoZhoJG^0Abf( z@!o_2w4R`YlUHmPI)z#BY zq33Lfu}UD-5WfkM7ZbHFbGrlbtPIK@0E_xm~2IW~~vV{<;GIGq%uM`6qS zKx%q43KmYZ;9pI8eAnzR9GYax9@p}4=4>;Vx$d%*A@i3yT)PXydibEJlpnHo@@p~e z_%FCnTfk@YVtLeSPoAnd4n{jg@+Z?oKCr7ya2fJgoUfP5v9T9OSKf)MAAF@L%O=D7 z>5sghU-+-~?TuIP>s1FBJ)24&FT~*&=RrL4b11!h*on+-R7IuCDr&Lz;}_TDSRo@G zVg^cnQ9nFImzH4m;7+VPsGHzE`3Ka*1e2}taPDFd4A&**M(>Cp9R6U#`#mecHqMrN z7Hi@sg+c5(rx}i~{thSmzY-KJV(`XaV{BPq$qIMYiyqE*=vCHF>T6jl$|*{}Q>xno z3oJOTcOYQ60`@W2p*59{$+GwrE!!A``&tL{x{b=bYt4T&sw^Ih{HnJ0uO+d6l53m;uUz z!lX>oOtC#Q6&)M2Sgm!7c>ls#(Z1y^4U*pI4kvwRJMX~ehPz>nViaf2k3yr`h2-oX z3*ITlJV{%hX9celydQ0b^N`A+b`xvI9(CkPhu%^BQJFB~xCRSq7FhAj6(9FB$Is70 zIc8i5j6D~}T{dLlrD-o|g8MOYAA1n`B)Xz{+yZ)hN1nGF*(|zjz63&R1D*QN6$=BL z@nHWvF4pnD8E_T$9QZ(O|Bg_p`(kjH@+VumNM59leOYh3H(#!f!RhWH=rto2pM9zl zY`=bjSYJI_?z2T0c036Oy?rcLjfxW6cI~BISBuGawhK*+t);ZB+U#yGk5Ath3)+tg zalxxDTrTnVF@rqO;Fvx?^9#lEW_@9flnt_c(lr{V9wqHBbj9M-?$nymF3wc-lfHXB zF>0qYhhH-XLM*azV(xcoUca0k%q*pV(E@6;yD&%v(x!2*g!A*$aKz%M+KiD0#SNWO z`JSB$Z}AM|gIOzui1J@F@Z24G7p=vE(&f?lrVX9)IR%D$^Kq|MGQR8)g5&H1nJz39 zb|25fr0O`@J$)#yQSOEF-|i>)Y|Hg#pDAO#0ctk=p`~-m;YB`Tb?a+L=&?wA+OVH? z=U*oI!kJ_mbAqxQhv3jNkKuXvI%<FZY|oZoLSCVW(Z7wr$kqX#0m;-D|| zUC@b-D|n&e6KN-C`g!s4SvNe}u7!uDlu*rTLrxniPnp_ASSHOaUwqA}JuT&E%<3N_ zIgc!%0T1uN$oFHRd8UVW_d*hNk6$co%u-_AIA6R!ygOST&?jw)t=v7-0Hl-`4k)N6 zFWW?nZM9?jzzWK;mNGc^4a8dq?Qy4a6a979!nPaA!eou>kbS`s<0bE+p`TK?#9;-g zd9}!{l?CzX9&d$D$KThS8TcL|*Ix(Y^-g%JbSF$ZlZJi9O)nz+*>}fq+!tv_ zJxte#Y7$R8W8gUPW}m?I^4BW6w6JV48emUc)7m` zdYfz%6e5+WtG^Eo&*+BBhb#k8FAF`~jl_iu6ZktE_ik0}py0b-LE|3quKpt_cSr=R zzc!1qmlbex;3~oPkR{(gHdze2G)DOQ%AUq{HspyxM%=JW6NASb6+6!lm3Hw$;rsId zz7VC!T`&F=3}>99LFmh71u|azaUr??ux8iTTVU8jm+LkXHQ%% zXv5sua4FB1J3Ze;75UcuW$i_BEHlTtO=bYRa|CL%E-sJ)XYU6MdeUb9={c zSny_f0;;s+tYp>=n7VNsO0gc~pyvwA% zq5TxWPJ08?e({242Uy}g=dGmt#F{mXhw|AQaWI;HgXgG1PHcDQeQ5z?sO-%R!y>W@o1+i;m< z0z@bm^26CO=y7d7Z22yaeTb3kGrA3~@1 zR@_uQm^71a*PiKb$eP<#cu9sIUvde-+4EM4KmGl<(yo@8w|}6|#`1XK?Rx0`x=1?T zb3k`e3^kbdkvMlbe2^N*O6pT#ru%x>CX|qav{&d-?}LR6sTlk>47MG9LG=&3M8gP2 zE=)|t*yeodt?>u4y9Dyk(kI@fx%@^a<8pAdk+?FaN@tiGpRPc8?U@&C3$_H zr^hR2)AYPxwtusplrn;(Jl!&3XhnCyd-qpZy*rhYb{7iAK1XoUf?g0;k;L~V>(tm- z$MSo&$yLsTU!mG;Ji1g&3Q}-%LYPHFBO`0MjLH59)N*asrY&DG1_0y8~=`UL!*61 zK`+#h^TGn7gDa=b!Ax6OPDnm9+uh+?;@W%6>s+Oc$Ei`U*b0EC9EQ+Gs0A(p#5B zV$8z}yg4DKerI%CKen+eW4XH&wzS+pp3Ev=93j;oKVLj7JdoU>j7bBr7@ zC}S+xN;92*T7!5^qlD2P>y4MU{elCV2XKPu1O2PI^HtB`wQ&s>#gLTGaQ4<R?Z>QC~LC1 zrHf^*o%oZS#I0RY#$OJRysKpZ^j%>@S(%Msq`DV&&eFshg%C_2LzKNy`_tGzP z_k#%km3QLViJtsY(&1LRM)0f~BX~;bXJ~kxPwO6}VxqLGvoJ7%rr3q^ogq3r?^>p` zPi!gB&C2f58_DtL?aCRHQIp8K z=XS**x4NOvk)F8xvm!oC$l{w{`Uw`7{cz}w5j6E!mCUz?!~{2XLCTvz55^?(%>7qt zJ(DNF#B4cydFvY#rtgPGa|==X=VQ2Z(w;RXhHsBrBra_|MUf^E?4Xi>-us8~yL=yT zHG2&YCrlRC=l9{k2gj4ImnqH+jbjxx1<*A1qEqGbg+3Cl(k;P)80qLlp0(Mt${I84(u$^TrCr8bJXzuLqo3Iu>b}( z^`H-5_3-YozQVNMk$5b-3Lc$Rq5aeSIHl|fJ+4!SO?R^~bi6O$c;8YxB1nNfM=pZ> z>SxI9Mg(7KH^l?3aeS;p;9eR#gy>vd)HJ#+8V|h$k6!Cby!K^5BiI=3b;*MrkE>~b zxgj4|FdeEgEa3BRUA|mn&)??lfZYb_xaF{n*EX&ea?5{H-e`O9JlhRV^_oXsx&v{# zs}ZiWFy(pCxq{8yk@%!&5PLNg;TTgBEC{?#m}$o|XItT=6UM9}`tY82`Y_j5g&e;B zfn5b@>>awB9Jkz}F^=s7wlk^f*eB{U;6K69$e!=79fS@$TV=~mYv; zev~xe#Erdq%KFdrY19IE(nFtSj30z?chb0Zi6(X2Y!pK@l6dHY4d6F84nzB!!^-3^ z?qk}EeW#{V>yScRm|Z|Ivn*joLlV!myhM?6J;V!DCV25dJpP*I%NNByEK{u)9&6fT zxavsSJiggm%ft_#Zq3Baqs%dIY!*)Q=#Op_2Jy-93HUfalN%R}79RA8WbG%q3u!u@9Ttis)Jd3(SBHMI*HO_Td1?CpO~4r7)mNK`P*YBymC^T(<0r) zXP9J)X+ee2}tC_ZMQr*Oj0hFjD9`q#IjhTG!^ONOf?MIyirCfL*Jj;mZAGa3R@_ z1gpVPPHsGUe^8=_s!w4^(pqqLF2t=TFAM6ocS!n02Sk4?gNXz6scY0-S^@4na=|>f zEolh2W+>}DiRHA4EG!Q9XC=w=GjP#mO8oUle9&-XX`2Fq7}TJ zjhHpJKNo$C!xKj=#Hb^8#eIh|g>m%?yh&cVD?N}ed`#pz6X^{+xRusOdeMQIAK~U& zJ6cdFv4C*`cJf|EBYVjBL3<3wEU6Ih--{sQIycPJ{YGVDXTz%4ZmfU491cv);pBBP zKCw0q%Yyr$W@#l2e^G?S-yAt|Rv@;uyrJuICxl-W=HmVVo1no$1}+`5;qEpguDP8e z=q~EPU(bIR=Cs=IPyHBn{1X9&`$qELGw11KWHu!B3j)69jNZ@=tuAAr|HUAlD7kcl z?Kc>0gV^v^S&%nM$FIYF3MmJ|u_fyu?Hz1{ew{M#W@xC;tx z_7tfZCEk3l&qsf^!1~*&+^{wn#ujwvv2&z4d0{ZGigM=tM^?e>dCuaYJFO6QGM=^S z4Eaq@d)AS3y>ISrd_~$ly3jJ1`uc=nv(9dM(h&+Fk88n5;SY^zd?J*(-X~>=!&-FY zCM1n^!S9`oNN#!z&)siInfKK(`pPjl*82?{dbog|IXx2skLmIXNr-y8@ew>}MVxX* z9mkKKNh+iA(T-k{mh3mVrZ1K}AYG-<%|zNFrm$@PKG1V;M9j{_-@UwW{B$qwQLQYb z2PT7-y&hP-PLb}CyL9TyG)RA+jUz@|Qs5U`VX^mpT5(K|2Y78416pRoYprf9ACkj; zLM+g1*Uj40#4Mrf;}k5+egnD-Yh+H}Iv}T9otq`TURa?e$X)Y58;{}Q-}H-+d+rTv zHdB(gv1Y+T$~-UbHIQfj>CJ7QfP-9Lde41jz~j@^p!lf?uRD+|c^r76{(^pZV2CQl z9JJ%;z;t}A=m5G+h8Wo_Ww+i~AuPFa0PdMLfl#`Nv?5H!kQ=?x=b#a{aD}Cl$X^^V}c~e_KWAt&#?F0#f|d-sC3 zu`T{JSA$R1ntW!JF_wp2Bjtc-^#54`mIi55(cA+rKG5dmJRg3tXA=xvJ6726V- zI4L@Wbb_J|16I9XOyjK>wtD0UZ0NWmWycmn9AX;-)mk0UCUKY^Z%lEqsq{JMx$(c(K@9Tmhz{n!xRxwT z|8j!-T&>X0W(>VnItYOYqwrAQXY^rKF3VLGVq;1)#tv5DUnN#z){Jg7kgyD1+n7SO zQ8e4gzKKKDpP);MPvF1jw;;=29qy<(u!pci8YtX{aS|K7&0`1kSt0P2{dY)p-T>~% zRpb#n47o@?iOlEZ zE8c(L1`{V~ajzA{P;C{)=HA=s_bn|RY1thU=d1BtM>EbI-y0*FEb+U6^m!)@!4V}- zM4iuPMB8I`y*C6Mf!DVdgT@3;G%YEo3?FG%cz-zCC>$cIyv-Cni)m1R2}ku&~ zr5uH86nDl`LSxNYzw#`(N?t@`Lc;jh^kO)_IGpuY#PM87FS1BVXHZh1o&NSxe!Mh02@au=t`fF6tf41`m6( z?9CFv(mAyD^}$}y^{X!rTj7sww+nFMfq}g6aX0L2ZOKpNa|H8eBe5m)D@8~>m3zkn z*q3b2Im-;NZFMg`a^D~SEi5LP!*-JI7{V(t1n-@FCNo$%AEH!3=%w=ps(3I93?i<; z0z(&Ubxt5l_K<=z;kF2@4eEE&rW>; zZM~3><@lic+i2O|7t!LGS4FfmDU-@KmqN#;aMt~F5@t)9p|f2I6q)I;{VikJ=h#+S zza<%~cMfEe??>U6L(_4c+d|wT4*5P>+_aw7c$@&Rsz4t}$ zl^ek=qnZ}oZ59VFUn>qU=tDu@`eNQ59|VKJvIT>TdH>R_;IMEY+kZ;OP| zMi~mDTfUP_f^1=!6@3zyW{f<|EzbeWQd?{D2Em(R$N8gC$D zloLPeV@xus|9u*3h^FNm#V=*XX#d9(eP4%ibxI@M86;_C8^U?;?@%l|Ch)3drZ_of znrL`DpL-qN3(>FoiA6u7IAbGIm7NE!U6=<>8PZJjoh?Pzn!y0QPhJT(M?oBTN zr(G-Q;i=;^HhU$R8tC%|<9YP*awu0^H$nHX)3D`fHMCqX*vnxKz+nNrf9{wMA!(FR(<}gm-Pb0C{8gK*@i8@VvyCcfQJJyS}@@ z=H?ZcR$R47XEm=W0VcqdpZ?x49pHXL0kd6G4}mr=6EE6TimjQk6uv2{}nZ5pS+4|boS z70D+lM`bHKt$PZxlJ4MNlnKu&95KyLhmSs51}}bX0Pnpksp&%`UK^^5%M?O*sKF*$ zU(yqIHOb?aqi%$Da%fpJ2b34Df#*5a5L9JDmPNy1`I!G|y{>0))}Vv5biM&sCnciN z%j2Xe?eAZdcEimIT4=O&Abvfjh*SCvVWS0UQcm(`2pIiRaG0|ZG9EeN(3W=CZzeBZ z{1b%28egs{9s}=;efi0Q1(Yy+3|)-sge^CB2wE*3aNztPh-$H?wl4>So(3=A<_%+h zdv*~;bV=md|Ng?3keQHTZNw+6z1et?1L@|$;ty!@g+9P4|B%4-q(ZL+KRezK8< z9C-{IOH**dMFsBco<*O>E*EE1%Hav4wc?b>U+_q&fZzR6Wv`Ftk87MRpf98CS+C|P zOS-%Wc8zJP6{77R+N6rE4C z)B6P(V(u<;&K#tUxg$rD`Hu|PcO@JqO*usm)>!f)%ab%{^kZ^#pAEDAYD#bAaPIca zf-PMiQ-Iqj4zE8gwBL-ycRSl?%+DuOJUtaVyouDikCg@N^v0kI&0Ghq#lBeMY$p7qu^G-!z*V)g!K9}|b`^Fh`9g zq51>))_rZ-HYfsDeYp8{cU$q#1{t-f-E%1+BL z<4!u71z!TKcTp5|GE_Waw+@0N)}Z-|7EUs~aO`J!A!r8Xz?u#h`ZpALOV3Tz%Q1&l z?+(QYv-|P!x)A($u^Y|)7l3D@R*_4uTVx>mvG3V-Qdt&U8@9v~?C<{o&2}|h7Bi9R zGl$`_q*#^~dk=J%~5f z$tDa&4D9CQMDE^CCDMI<^ezQuiD0oQ2o|)yB%}AANvCKg*b_;=ZAk%VXu5FzSR!TEW_yZgF~cNd7WOsJ+PVR#>Sl!;e4qFtWdckSPA+3 z)oC3)9d(IpU)yli*hn1rQhHakbGX}BPj~1Nf!ZF7O=Si`}Lvpmntz`ks+ECjTyIR=-UAb3I$yFBpvP zbKcTc$;)={o-XL^Js)0lnE}Czhw=q&Z_LQ@a2!F{zWv!dK%pg z_C&MAA$T_2lBcwE7k2t*YjeU;0pPi+y+etB5f zcrX#KN`8U8931fLgq1?~+jUggzX<<3)|qR%`{AR*#_YCd2;$L5P7gQ7k#U_sd3QM_ z^{XW98GWFSMGWCB;O4`}c2{#-uDl)bfv@PLB=TJ`z--`eNUQ6GaFETXy9bSJgX zw8AZ6!Q2|@jBi|hS)9yNU0F-}HV%h%S$@1DFq-@8>(IruYEV)Sr7kbK(TPtict)3orenk4^I(#0#-5EHf=^pLjfhUf zy6Ntim#TqJ?k8}?ZUd|yR{#eukA^c>@^HM03YuJ9OvCohqxmK7+_+>U*YD28r}htE zaQa_CCqxyT;$11~(RJb0{?qg`bU*AW?vIs+v+$*Av3OOQK{tNQ;Tiws;E;G7@#x_Y zaqs@mfTbz?C}00w$?iQ0ul0)X>Xb@;Wu*A6Y4w z98(477Sss0z=;Q)6a|HzJ88=@UyivM#+PMrtUG-YY4@K_!(95K^%)iPQi|l;Tg#zt zuR47==EU3X%!2cOe9+l!FyzD?fY&_@vHnsZU3XIf{hz@YULomilY4UK0D{#zj@YJe zjB1hwJ@#i$a7a82a~4)oReTYao4H{5g(!M4B8>;isUhBuW-YtbLQofde6lHyLyA>+ zYQ{WLc3MNNwjb$7ZUZ^xyTDaxmZm2C{IkJ%cyyvRx^BNhR||Y_g{}er3pK#d?>QW5 z-?#SORvjF0cs51!cLT)SQ;jWsAn4yGU7L3Y&ecsMKpDI{w>7%97p_uw)^uKhz4h&RF7+Iy2~HYDql@#$ni$ z0Pi2t`*3DqS6(x?A79^Of~niK(&C@0;sLvC>=An$WZMh*>LVX?ooLD%;)l`CwgJ51 z=qfs%xe->MTt|B4Uflcf4mj5-n%&ndhY3AZQTdjnRc^H6$`NjeHsN$VCX*-Ge)B$O zAI2x=yW)V-#q{^UY{9ZZj+N4eK(EXaab1ToXtevY>pC~mzqbfJWQ-S_#?*kVRV#(< zSPPjwWa97u6YSUbym0dF8zH)9HQD`5L5;cFY39_mWUyrdZ6Ezk9Nyas>(38ikDZF% zCa)4O%>NFlHwNQ{g0po0ra5o36KPGC7;M|6idj`XalfR!od|VhFNteeZdHIg<1E6~#bdP6*|&rgfARp2Cf}bLd*zL&_Wqk<&V8kAaN5YYw|Dey`uBi0iL7~htnya%n(&Mr+YV|Lr zowFmQ&&LFPUSwnW)|1e4L0`#NLxEP_tANd;eu#P*iTrB%5OSVxj}v^2sPwrnJbEQ@ zwO5?+L!2W-Jm?Rz#^!U0<}p$Tb;S>BRN>pC?xb24&L4HR(a1Y@VClcE=oB+hVhBfY zzuPwa=ZFaX%`QTPxic3kcjj#n#Bs;x!yorb@zjb^%CIoR`PnJBIG}{qcaMTl&!3Lr$? zV9orGG_Iu|>=L>QM+{u}>gF((%ik%a&CS8F_ObZg&5nEQ%EL#I9=KKVX{mQ>hwVOl z;cjsl?$GST^RDOf&U=f6tSQIDic23w>rj7I^;2eJdku7)w9vcw$!BV-D-|wEwQ}n# zbzC%O9^6@V5`I+p;)mP4@OADZ_-%0kCV8Hs>J5u)M{9d>uhMIR#eNIEeB(0pJV!9= ziZSI(ABNAq%!45>aF_BDG&t{T1stml zV*N>d;I3N|AM{P&+Zz>FX?r4TU#OvTAJ2(5=4p_e?=pJWQU&+#Rm;Y%^G7j3mu?L` zC?2vd5t|;)fxF$W(yny}C~$@^wv1l@Yw{dr8P_y~aUY)0jA>Ea@cI*-%k&nHzxfZo zX`O^Uiaz}EOb@iUFix0Ir-BKGJ97^-#pDal+^Vqy0vux5%WD)48<+vN<8FYPk93Zl zq&{?4u5eL)oA}z>k~0=6Ve*JR_(T01bY74Ei8;=g>?n^8E25!WYZ#{*C1bcn9c=FF z$J;z+N*=+X{8G(b3MJBJyYbnzH%1KM<9v&b>E5a}e5WIQH@k4jgAX)JFqC|wbTE43 zQYbmauzte;?^`ah=y=9}T^f}+wmb}j{@xX?{W>X_waH`r9CsX;QOHXhn`rsdQ&c&? zk_Vh$KtVtBu>ZFZURtKaeY5XDN%>6Sc^^A);MX+gs4{ANl2P62NG{%WTU3a&!UytF zT`R3m$p#S|}SRrPJ)H=>YrPPf3J2R?vr6-XREkax77B-g5~H6DGv*fC)pnO^z?IgQt7 zxVfTvY_LG_AFLejjh*G@!4$VVEDSn8qfB4I>cmVg zoskWPK0JXDCMoD@uf_|!^~kMnXR`8-;MA-Ck1goX)n=dH*6l(Ao%whj+t=t&!aAUp!vh z=m=x3RfAjcF8Xjv1$D1F;3B0#{L#8yJo*JWYq2S*c@pfHR0dw1HQ2n1i8K!|hc#Mx z7}>24HEl6R=N@yY_{|2AU;Y!$&FY48({wQ)Igtl%_#mX@ysT|6QAB4qdH(5?jl0HP zhV2?#>1_FKnX{rDtXY)BEe<#rv+yA_T&Hv=ocpD(i-MosI5vDwx=Ihy-SM5DfB0M zBx(mAqJWVpm@eJ@R~=43!D0oP9$QaBZ5wzU^T2^?T||q?GsT6|7J{9E*71{vy3z47 z0{WzQ;Ophcb7WFq<)lZ(J`woz_Dtw+w^?=|HyH=)kusN)9I?NwJ5Srx1D)$t`EuBL z82S4vjjI@nD=t*h?p?YRcX6#~WZ}>2Q$N${o2odj#1dm#0&roMVBVo(gxe0i6Ad0r z6>n^?<^z$LK>Y#C}OseBmY4<-}Jf36C zV~=&?ZBM>aw8R$ok5i=GW9LxFr?-NVT&^(XhqQ+>C>cAYW(%v|TH!m>d_4GYm2l*Y z4r{$oV4LL5>@%T>YKOjoPnj3#M@tf(84(M%bK`LRGJ7^VPzFw$Y(YFcon|+EhubfM zC9bIw$~xLaosb5qTPEo#*Sg>wojbJtp)vpDg>t{#-0Q8FlcC33m#|>wRz;0#WZXRIl^AQ-PPe5q@F#q>G(%oS#!Xq=-o;%y zLz&_t{ZY6z`6B&Yc~m@YlEg+*9XY)?8p8&S;*m$)`KL`5UwZe79&R}e`ft5>;?rpC zc;LY~SHHsN&nA54MkEG}?!hu&Lt3NahQ7%k;Pp1ihb8<0Ec_PBc8mU!N>U6*by)L; z$MfMyft~j^ONoo=+C-NhsZ;S771n#Lh3_&`;l8h%>}{F~T6akPtVewD#j+}xwxE~f zMc0F8COi-vgKXJ`hDjcY1Eg~>N66;>_&X?v)#CkVQS%V22yX>rV;h=R^^KC(<#2Y? zV2Xwg>Y=)o&i7E_ock^G=I#^HsvjkL^0gl3Z2AY+OAmoKqKQtIN8qe4QclmNKD@on z3y@@=%PU|U6vlzYS0Smp23jkm_1gtaqj=$=-U#HM_w&EMm2;QX#szqu1%PXlyb(}k4>CGm4<|9sL468lW}BL*(p z2hlhBu{FbXE`iW4yVk8b*r^1E~Pibe`5-NV43w`d{vP+64ww>Qe zpVzDZKT{T(BVG8{y-MM_hZ&ot`Ab~OcDmq`Bs;erapnGzSX_?O<->LFOz!za163y(p>dEGguh!#kBy^n#TawYw0I=CoajO0GWalh*-(ol`kYa}PA`No0dgcS!dA zk65%r3140c<1Qys_+&^L>)f=aGpRkWPV!$2R8PaJ`!l(Ecobe)Hdt)-Y67Kt15{jd zn^p^DWODBjP4Zb!_rj$-(YAI$H&X?TR7~;cA2TxFyN}K-E`z0Gl=17>aDLgV0E7O` zhLx{n{PlDcx%7NOfu@<^pBEIqG926k6WJxGujGLkL#t8_QT*S*uy^Wc+IlkwWk)q2O(=n! z5$V!gH;WD)jAB#$VOSZXiVc2otn6WpR{9C_wPY#W&}@c<9R|4bZyujqsS4Y|AJW*> zf!HvoGv}*(h1-K{1oPeg-X>84xqh=ZPcG8L!ylE=sOpFiyDA6w%eD(z?;e8vV;3}4 zcnuFedt&vw=dym=rM=(I9{980OGvK#Kp+0y7p5i5CP6+FpFJEw4iQ}-ttne;=p-iydjsz7eA%Q zA9?t`-Vdh?&tm@yO&nlk!gB=;?9I!d(4mT^I5)z&3?+P2V9)kRikz{0I8KpG0tbyC zc5$8!c)^{`-X*i=;l2CNM^?vi%7>HKC2KCH@p z`+uN(`QfOJJnFxF6yLH_SU#i^RqU1S=j6*2 z`r-mbRKUr>!vidIH$mbAg2iG#Bqc-=WA}6eT2!HxN5SG=}(v2qv;fzU# zxGCI<-)eqiCX-9PZD}mkAX>}-T9=Xw{O$$Lcc@PSi9Ow z+ATi?=9&5UPwH9km?hx+`y%aosLdY~ztcp}=Zo3O)cQ)38^8tZp5K6{lbwXualNH` z#2!a~u|~!1s#v5b<%*bSGA?{A?TmZVyua-*T26tsnxF7&>qL-+F^Vl)|NNjmh`=Sb)@U_Rra$k z4ZEbbLz0;lb{$Dc9-6@EuTo~bSF&o7oqp9NcPe@Mdr)*)8}_N zd}Waz=6=bBtUy(^(+k2i%@&wDHJ-1$ki1qXoO4Sn#ap8laN*}fK0kf2Sm+rqK@^qZ z>UT!Cb)JT>;EORXR0h`A*9kXO`{C@e1k}8=lSVFlDSCONap9~@wPUub;x}W7Uplai zbb9CTgPHkw#is?v>&4+)$E&n2w45gU%g{4}#EM2WdSG+ER{u{ZnkhzNpNLmtz=N%j z)5nkf_uFzKj^qVyZ4~n65zX}ufWTvyWVuGSh2H(M@OwiJ)O(eX>#yCy^a&~aw)<0f z6;n(1K8+D|r$=y(+zlvG*5=D?g*a~E9brVmS8%bH&ip!8e0S*tsrh-sA!$cwGN{1O z`JIF#+g=KHw`_&jgI@fkN}XSB_2J|jw`ocpu+=UniBYu1$8VJQ#Q!Kd3%9DeCW?ay zqNKEdAR!?kNZ&JqNJxn&B_bgu2vWAM-G$iLU7%tYoEa4h6BDrmyBihj+uuKMpNGpm zXYZM{)^Gi1#D_eegUS(CoIz^T)b(_Ad1w(1eC5SGUIkJ&;h(!@pv;>Wngc|&Cl{YP zw6~QO+AU7T?x*^*+SNw+)XJ&!UU=FHgUp2ADh}U2*W~08u3Q=N8Lp@G;?nv?`TB`W ze6-RS4@bH1?9g8L^|cqqr1ZkzVcVtT6^=YBu}96Wmnyi!Wh{B?%@gnFX!cx^k3P}Y z>Eviz%-kh1(!EYYpHpe1Ju?vg`}0wno~;ITBV%#3rxmU?lA!N&YkV>5Fr2&gmm>YW z@Ko=1n08MU@;?yoao|?UJAFt%g5B z>-?_Lmp`1oMpq3Acu9IYoZRBcgIXzgogwmlyF6a8rj(@8{`e!KQ2MWaprSBQ1&gf= z`0g16NRiq2=VcA;sPn<-2a$X_T7`Pq(mzv|&ixW;o5 zjJnX7eI{L!HJ|^YL-RLL-*0PbRtdgFOIFau6j1_Fna+vkcRp=5+ z$S$Uc&sW8WSw95O%g?fF zi3)W}xsa9d?aPM86Kj;F zl#@fhZ*X>h_A~B@HGID8%(63Wjn;VKM=o12J@;? zUH(`(M=@rhIU3A;OG6It2G0=D7ismGI@Y@Kz7gG__!@9plr6VJ*ixC#Vrh5zR(jVI zOsB0K`K#J_su`0g2R1iIfhk8IV`ms&z3G8$)Q8J%-=ei**Z=HpI8^0!CXaiwYEnkl zK>Ps{p1!OTPn?l~;q59YK-Yni8Tq-B~Q{9kd<- zLk7dfubMQvj{zF%T&J7g9)S6CZMbyWh^Nn6M%H!37#@_%yP}6e_jcKwm1BrO5xffgR zxg^_4<>1gfklXZ4;gMN?sCc_BZwEaNzQ#2X-Szors4CAoSxUPW+@`brMgM~7F1nq$ z2y{(jxOt8e?lu&9x!|-ci2SDbC^9qZOJ51CxP?4(YN+XE65i;l#j4_LnG{y8NYx0y zmZ2^*`lu^!eAkV)U-=|g&I*$QU;xT~`{D76)1>q(j<$WDA=Mms1moUyz+Pc_kS~}6 z1zV%B`l=l&jn%`?&0iI6zG63IBIfz#U|c%)g_JmdJH&o(gJmXRA_v}q zYx*WC4k=;BCt+w1?}k=OlsIT(0@u&p4oaIhlktsj(((pBp5xbv$1Hn6k^7#Bu0<`3 zv^Yi$`~T9YYc?2IvJo5)8RE|{QyzaL2%9HH<4!df)P2>SAGGwv+mk2B?ivjQD_ij$ zZ+A>tI~JadQsb)Y&*8_r_Ly}i48I(F52r@Il`4nDh|HEU9RE~+hc$Dsq&bi)+F3)S zQ6RU{4VCY{*Js}{Cz01zIpNZ4GV|{Ny*=~r=F_?G`rP;$ga5+8EZK}^ zU3>FBh3iqt0^dna#EwLl+TkeVf-X!9Wzp2uY<7uRKX@NXk zXOZk3br@EiSMarhH;~!3BlePlv3&Cx@O<1{?W)oO-~V;uRz`7bYM760sw~;;?NYd! z+LPwp%ca3jJMpCv<*@JP0cmVl|95><}G)hO&;~6 zANEPG$9B6;(r}TLPW>aah3VgE^-n#{sQC|k+AGVy*ArN$n4;q%eJ-1FnzVa`VSd3H z2&h|4e|9Kw?AsS&j(I^}eSb-M3Gp1%>n91~Gxw<84hz=%;_*rwPFyrr9%#6Yw1Oje z^+r3s_N|8Im0580#X&gRQW?fi83J#%$TZo$H|h>@r0bn>Sh4g!P_GUV{Ts10nzr3B z^wL`C*x~7lpjWry-PY6eE;$HFvwQKbTn%h*vt737@}8bOjfOiP3^1+xGHA0{kE>ht zquzpLH$E$i&$MolXJ)wJ;kjw}>7MYVy$zs6>n~G%hh>tHbqMd)u;)GYyWomvBmF3i z;g;4aJhE^G%#W~wLftl0a@Uq?PpPwC=5>f1xInhwvYfhq$>W-naZ*8)Id`9!&Oes) z;BSqyYTm2NfwT93JD&eZqf{#3`n^)oQMyHXd(o9kn>WD4GI4K@H^B-BLeIXL=s)i! zO&?LfD|NMb_~UePUE;=7`hzfha7WG!Tn?A-#^9U!G%A3WWHbIA1EV@X&vt;R= z$f^eOT6$L|_GMiod2g8+MGxqO`u+U*iYL&uGG*K}#TOm>D!5|$3vW5vu=TU#UJWom&J!2=ToOo@%Y##N;*0U3mWkvCE2VD;>GjT-~}`3fH-`=NBt~(X*aKpxv_#xZQB$UbY6z3gkt% zPUxmU^RupE<_#)5g1E-aov;lV=Uu4H~8r zJJsKUg!~???=lU=C$$6k;!Rwq;HQ*~B-Gz2p% zE2(*}FGmR7wc_7=X@aK~{;KcHMep6&Xnl8f+j5bt0tJUN;0D|kI@seGxoCRgpj`H3 z01kIE#)bY7H13ncmRV;=Z+rnwT%n0W2R{&Zop87|b1F9%JK~D? z?=bGH3b#CN$F1+TkZDUc@4g?)xiN;geRV5n6Ly2z8>isD+Kx32qtozrpE%CFu7LeN z-+{M-nE&r~!&h%TIrVuv!M}3h`=g8C@Xv0%y8B?%w!a|PPc!8=w^Zah{W?X<-EvUZ z)JMl1Szu~^2#TI-DR$n>#y4iJ*q_>Q(^D%5OI2p$YDb>#G_Pi7Ob}SyJ_>&J_h@8t z2i6`ZwDT!RsJ*}hS9aV^`9*=)_t{>mwjM-hY=pnGDjNG)x8{5NkYWxG!ihb$fq{b) z+`pfJ{fv)7Vjm4oNqR_*i+9lCIq_UT%V?;zmeg}x5=QOnKoiV0ai%PjoqjYp*`0v$ z*i?)h>xR<(k2Gv)5No*|0Ap0)0T6)hrmb1i5=@l(UR|74#J>N6D~?{#@Z`7 zGhLZ*Gu*V}mb|Q9jg?}IvC;Y*HMvLN_!pj1 z(=T6KIwp;4sTv^ zt39s$vXQ=zx1e{T=c&I=4=HA(Ar@M-$48}~lt2e@>a3pV5S) z+PLw^b^9M<|^tTqK9IAvY*9yoN8P|IU z2I1M+ok*^*BfW%wkX-Ur(wBnR)9wSEzWZ3VKO~XL=U#YXUo%`D)gJa(rDNgcoz;y$ z^)b}c2Xo9%)O2aT7>@N{CFyrm1HhL*`j;)Oy|;^+x|wbbo7z9#c)Fo-3DvT{0`l&gOTZOn0>b&UEUss>8>%9_C5&T&Q_APj`Qb+xI}*5V~JFw zIj1Jmyb(IDED+smZF$Y;SyIy3eC#vWg?-K}fmWrh`Ru$u&^G2CXv zcRV@o?~OWnaU4FmfOak};<&Z*VRFD_a&PI%vjg0)=I2~0%&eEj&(-2RzE?rdNz8-W zTS$7E#epCD<8-eG9AoYRlS-4|+6q5*Snq>H>Pun62?h7>)|H_+0CN|;q7zlOXv8|i zakG3mzRegIVf{?L>()~+T)fD{)D0Kzw8p?&?r0ez`s4;0;atzoXz4J7H!kiC4bFBr zOEH7GySuZ7rXh{aI7JtF1o5FJFYNqjCOtoPhFVN|!O-yD{MITIa<`eF;~NibwZn{i zF3qOf7G3zfUoOwASFicJL}bO3UQ+IFFHD3J!-19$v>|^m?@2sGk())Y*HSkOOg||XoN#~u!J{<)peA3M)rUh{wgXSyAw4fj zrOe79qT47GJC()bzyAGsY`}2%-dIUptp{-5A4Oc-AQ-?0PYG}GV&Nst;M5Q66thE> zurQ|$KAYjmo!5yz!(esTQ#X$)9u&)qKlrj!tSSz3RAu#R>yQyhoeKQ4coI&Cd2*v@H+Mt~0OMRTO|> zN?%Fg?~Ush%z|diwsa`^EjXTzwoj2l z#ryT-wG5st=B>;zEwWB~J2I?|$wgFEM_TUYM zdAz1Ty!W@Rr^QS6C^jU;;qvx>XvFAFkoWa8kIx$6OaJ%s8SNzgu%!<iV#cBBwbCOqUB2y~&wr+-P>SwE*@RU&NjsJfHh-bF!>q9L(#6pDT;yql zH{$oy3|3gVau=HjXnSZY%=lf19Xys%S0fc%9@7e!y$Hi&C#qmpMwz$+W^k0vK$tAN zx<4+BB7-}#>FVdt(q%mXl-TRTlavi{qWe<{(=L~WrOby{ms8oYqz_*mXv8K>ZaAP( zi7!8iDZjszZMJ`hn`HCL9;Y&|(jz5cG zy9d)~?Qb9XpPMJWev*oo8MTm{KSzFeHx&!vnw%J{CO_NXoBA%g1C4K%(rkq-HO-g~ zCrq#VbyHagFWp*WNviPvOE;uFh8^+uZ8x@RRV|zTHwZJvcBhsb^JtyeF)etl;Q28M zF`I9a`wITaw}fY~<>zDRtl*f^2LtZDy@4838zEV3KP?{di^e**^7WD&R66xVvK#IQ zHSb#UN@XXSsQHLe)jRNsnx6c;pp=Fr&!Ld(Hs~QTEgOgEqth%y+MGR0avb8oliUYk z>fqz_DfBK}(ou%qbsng_^&17v5lmIr432Ca#}!3!{GxwbEYvc>TLn#YF=rQfIQsFh zzYUV7Ln1u8+z&TfIk5ItF<8h$SQjb`E?wez!x+PE|bkpWjyfqA-qXd!7JB)BtbUW>&0V#G)tZd3!vpj0(bIu!jup0*zWZ-aNS`K_PT$_HYoUU&EMW-iaVz11lv}Mp*n7P3b3!9FE>SId^ zj4|hSs}0y~kvlnm7wlDsQ!ub=OU=JiKft-&J}9#?sd>1=1)i%Omf|CHdA!#bdYR*n z-aX$@&%zvDlU)NRV^6}j_&EO9Py$n?1hd&giAVcKu!G>F?=o2`nDNu#h~QRdZ}5Pt z?{mqb)oUoPPlg?*jq#cAHoh9mv}@%%@J&kRycT6xR{01PE{?#~cBZ_vO%_c)Y61@7 zS7EPj2phgNp-Fp6!REgqsIL@{TiYe@ft#T;$Ec6cwgL#;$0}sEKKOn86h*vb3=glR zv%;`7wizj&HK7I8_-Eo3|0p!FJ0^{@lW@y`HXP}p!D1PUSB9$bJAXes-|r|j9Ow@_ zeZ;*c%NkB4Bh}tBAeT^FQK<{Youe@)>NczqS?U|BYo)H8^x5%~4nB@}ChJc>3TgqG z7&=Fnj$G4(9|2>*%H9FADm!rD2{UjxJb+i5rEt{bJZ^Zsg4`F{@c7P3{55(WY4%(P zu@7u8BI|*C(Z80`4{7s24L>w!?86_9HUf@MA{#peFR(Uc?cD=#Q&VT0qbX*J-nJMj zm~DAGy7Qc6jg*~GPJW%Iz_CLKcqHu=Y}(Qv*BIHg2NghU)Q}^%chG zpL>d&7HiVDE-li5Ub@uw{A;*-&K!M*AEwfv>0~nZ9c)dG$8nD*iEc|9%+WI8FZ%ZSs` zHq4L1n(gt{irvn4#9O!TLtwvol%n}tbh8KHevJu+-ODU|_Ev@Nm*!xn{TrpETdVytzZvqu8&|;gWjvexZKlZ={>a-u0}taI z#ARA&Gvg9j4fUse?k;?5Sq3}LiQ`Sm!F(Iiv90GHI)3sNga!PCliJ-_-ZzB|j3-0X zmq;!+ypeW1c4U>mKdJY24}O_r0O5^&;i~X5o}94_EVDL2X2*5V?tKnxFV4r??1-Fh z#pV+)LAPnbYkK<>UHUH0?13#rI=+0)`#c$Y9;7qXPI8%e)~UmNk~`V(ru7Lt_t=q| zo?AQOyWPf^w!AIY)_#yK8V|<(JN2=xvKthASdH;}aMQ&AzI|@4 zG@{9pL&VI`T4O8t>`kUcnuVNrDH?y?d@9-P?umsuE^IqN+)-!hioWk_^ri6vb)2@F zruZ+RM8^pfb5)lshZ~FC*mAi0wt`0N>%!5uqd7CU7gl^u<#%Un;QRYTT(Cz2x7k%u zc~Cw$87>0j-^b{}jWEUGHfw3;fj-zyJoh(;nF^-aGfBlOQ}BN@WZzspUUoSim#FB` zW`o;u?uBTcu(k*OJ9UhfG|z)ARtuqcoamB|`6PEtN#fxH-pPOWD$~b#LL;bnL|<~R zN)5a0IP6Fp+|l6}Sm&GIe32=*nf_9dFm^m#5&wIo9z98`^KKH2zp`pK9aMI`DfJzz zO0M@;$~VTg!yT`4`S7l6e0D{jHOpxQI~tO+vL9dlHUK|wc@2-1Z@|F{ zZ{GdFir}>`x4~){x>5sYfHLeZiKLKjN8s|e?mSyzM8hOgzAnF&zGftI6)d17exW=A z?6K+QY_M%w4$CW3xzE8BkhP~)wyjX`;oeJS^?(5^mpX9BB@g~;32ac3japugY}m33 zaz_WT`$jMDsN4soZv)ZFeDPOT`!b8drg*~rxLR6VUIxkwMb)1+*kHecR9Ee;*4WXC{+s%l zrkFKLmOHn~#&grTw&Ez*Z>uMZ_va|`^AHT$a)h+^YGZK6e>C@EA+EVvfI-=dAZhk! zN&R*t4qNjMkQPyyvobFzO_4G>cyWMRFt;f)#UZNy`E|$D;P+FB&4qq=B})ZeZQFBw zweUYFb;Din2Eqyre>f?+nEXdRsp&PP3!h9l0*y{KtQ3@nz1Ao=XOvKQ^Ue9NcRse- z(x39*AC_8eGvMk!ry*-icT|31gr=@>T=Fx4L*GA>zH6J{wTTJTZYV;unm*67eMrv} z{dmA+d$jIZOA~f&rKW~hZ1v~@97v0U3jZWJIHj7Z>ORUN`g!29vUl=?4L4}Q2V;Ef zm4)L)F3qSz6&%g9!sBp-rp$0Aoh_?rdMgdo6FX?r?JM9+$STEyZ3VdFP6}-p`HuvI z1;_k%9D1ughtOGetQ{Rk`hDZEVS(_I_=iyE;CvcA%v&&HD)r)e?J9OwA{#kl^cnh`)``-Jw^BoqKgQ}hVX4(dx-|T0 zP372cWYet~au2rWSN&|b%kI@u%lkd#{=P5%(mO^)=MnE~{05KC@myz^f|mpbtti(A zw|CBhPv27c<^w;N-NBs?%_(NxDihWjeLx=4U)(Xb1i^m6>M_cj2g5RJgn#&@w8DH9 z{dw_)j{J0&H@1)E?!8}w)`jkn^VbsV9KAUIaEf4Mci@87A7OX>A^5ycpPZMSh5J+7 z@b3U;u-~N1?vK{WMs*q(cRpSEYvYYU=igGkYOu(t^~8CD0&(r%4vN2TcF^z7x?DBl zAkCWhN-lc!71kN|;=tFps7>|?ICt!vJlRAI{yr_Hugm|*77-&Tb?haW9lnsFQs0x^ z4VD&KWbw9bopF`rBv3BBEO)&AOfJr@BD+!I(p)PQ+mxR`xOQ`&Q z4>kzRK+89AB6B#1vkRg)Z-Oq4y>OXMaBnOV{#&n6ahUdbGwtzt2)7dFz!-l8u2fcm zR;P@BA0%RrBnR|BGrl^RVSIP7Cwm-(O(#~s#jjnkJkNn2d**?by9fLkd4WvoO=(r3 zJr4`Ot0l7r;5ki3^W;;~N)( zcS$`s_v$Z_!otvcbWdJC{XXPR?#$ieVz{xp6JOEphn=sB9oK1R4F8ov4|bXR>Z}Px z(*ZqrOs`;8vQ37!!SfZL91)k(SLk=pLB>m)r+5f zlz8B$P>#b$kY1|cwXy>KFX<_1bejwBay#IRRlV@ky<(1jPq21NF1I_fOJwWX(2~#X z73$;fNEY+E;mbpZAWB!T>nC~0zBATS>$I~}yTyavWUiIg7u|r<7WcvW$7Q-XA)mLj zIR{T}=)-x9>ooLQ7ako`!U0V#yf!=sFDG_DXGI@AIchZ6r|I)<_Xswbvr-xhPMn(K z!YhUM?9WYYep~lddLd+-^Upi5`IUpTL3^lEP`uEWd>n+Xs@l7S%TBnZ-&-h{cvV4A;=ta*) zI^yjGt+^=7NcfsW|4y|hY`mnPHitICkEOy-Fsqz?N1Ai<&N&czVVd+U%$8?`48Sox zGN|Tzsr)f_FFYSLTppa#DA(1rVe_yK_~B9{Uk%;}`<6PO!~94*vPv-6*Y8$5dg*{i zrzY`7pU!x)bTPG*>+|C0QMk`R!lG!=lcuQ#Lt0z&wd54RA00vC3s*@SyZn-Mt|6&z z^PtATv!UTbGyOVRD))TVisSqSanzBnqW3g}hlxI*OP@4o^NDKd&B#s|bmt&km|ach z>-@OH=Q!vXc=NV@c(JIjoSJ(R_NqRX&J8ug-;0V_ zW$0e|KVzqrMl@$RCE_B%vNJF_Mv5Ya9I@X}+)v{Ft{G8J=6!a%ZAgF8eLAf+nb-v`Ym~QYhhS$F=|Gna&ocY2sYM2M4lRK?z@oo zT@PV_OrbaDGI8Cc;nJiC3qI5v=+wlXylINW)pl($tTK(mR2*^kv=rWXW+OZ`T1N&W z_sYE{%z!|#*L4=&gE-rjHMc~U#I(N|sI6_p@7C;vpO@Z3eQhodeyIaRdKYA$6W;7F zeJVH$J>B8INAjJdUr@TE1s+`)jJt0&(wzIMTxFcbPU5|nv}zwI^b7cLZ>6PId_{iV z8fX5imEX+>Wyc3~`!WCHTjZ+4T6FfycWP|?3QpIZ zg}0hB;N2}Z$`F2m#KdrjKVJfC3O`YW@FORcJJ8hmo+$4(zz7PhdVgU=pP{ALx@Yd;i91jBn)D;u8w;0+xq$px1=<@B(-4{sk? zfH%VuIKfh%_Bfb`?Ccqk9i}Q4T8H4Y&>tk5o6+BUe`({>*pl=13 zKWPNbA4D+1DHZSS>xqB-KET@kO~kyMo)m4MJc}-P@n&n-b+aGt@XkiJBbt0U+zf1$ zI`NfEkuSg12MWqWMs!qPbb7Ci=M)!V$HVoIP-hLl#Iyb@$A^+`hqLuzLmIO(mG<4t z=888DVAS?|vM=tWkkL!X@(rM7MhqVPwN4%qcb|Stj>6%hC)in|Cm1csfY04aXw>~C z@^x{?*{yEV&AJOz`63D?drT*-|Aal(V;BwBQk9|{rqB&V3I;v&& zzcaadBz^8A=+>x#I~UYae1~qdA+82|SAC>x?;@UL-v>X;*aze4RB-Yk1z6rJ=3}cW z;lzp~P_m^jXYJ`DxEe2DMDhzz*4am6rX)b(=&vxXd$N?eRShqNH&DAFS0qEb5*&Cl zglE3LOqQMcu-0P}?Cf34;pJ!H@n99)6R;cVFRp|X(Fw6sDoGN~1uf3TNI3&v4$S}+>Fj^e=crkv9} z5Ux}hvYM$8zNn6pt{yr`d7zIDu3g2RELP;M4^!E52b^0n8shdB;<(PMX`jgvDm>Q# zjg}KV>hh6}uh>fS7m54RttjC)xC^IVdf=Vq`S>WgT8{nu2nH3;h1|Wb;k-Ck?JT#` zqXDX@q|zC!3j;8Iegc}Mm`OeZV=-g7J#PPG=t& z=+S{S2W+QnMN#p-q(N@>}Tmw+$IUlCCHG7@>aFRX+C;**0%{F|3%{^OI@0vX3PD(mO%IgFYM-5 z41uS#p~9v}o}}i$4U0D_&XrU_^zZAi|HopQl6w@gGh(^fy$P!Rdh$ctMF;*Aq>`!}!jqt#xp~W{k_l#lrJm*s+Gr{q77$b2h-Aghs!>ldB~Uw{tM|M1M@KlX#?Fe|oX2M0yyq zo-TTr!q@3KxX0KA&A<9V|E;2nOw7dgOQ+W4ZV-2g1Pu;e+kE7|(_d+&VLIK)7yhNf zVmz!K!24BN%U1<==EJVflySwA;33*M*kNr_ z6ATdZ`ds4}+@KY~5yyM-7?T%dt|vH6v***npFL1#OC2QDw4;L^{iGwqO}XowU$DMg z9QwK$p>#T(Q@!fR^M^4G!2xn(z+gCVt;%n>eI|C!|4O~5JwKwnE)hEm?%$msKj_Tt z5LnPGW}m46JojookB(Zan6fQFE}iy+aKtDfQuk{^^i6{-vB0Y`{B1OX*v) zEq~F8r;2ICqPxM6oaSeeYn2Di>gY^v_TIdP9Xa3T8l39kjQJKJ96hfKJ6{?s-HI9r z9qm==!ijTI)>0R|65@(SZ|sFX=3}VEstAJZJ$dr7p6C_6iDE?etDQ+O=M4~_KUkaF zo)+Crjj=d#bT)N{NvHqO;wsUp`JQLU@|Ds`K==E2+R`3x!+`XUSfZ!zZ4mhm%f%;Lyt_;$D+RySB1V7b|?M=}5_A z2150Tm45BDh_tkS!Z$Iq4c%))PhRa5ImMxVktZdL($T^IS&5TIhp~^T@M~>6MO)O} z@N0P&R^Q`_qor_cu4#)7X=OCTryFWbVKD6ZfkHkTW~2Nvn^y5qk1MmYusT6^KVQ8v&@ zaND&U)UcvyTg|fJODLi072LSJLlL9=noi_?Bdge3a{eoVH1`awseevS*M5P-&)re+ zyiA7ILvWLA7rZ@Z5*V%C3;k`E%6?yLqg`!u-8AKPsYg%{U>%RBp%_a!6F{kVxn_?(gNZ+u193$^ir&Ng_6 zSK(}W9Sz#iC^q6kR~cIm_M!`M;a6j{I(&*$y4-||lfFNyIF{SV&wj0+TdM$_do=*1! ztD}8jyc8DF0*CreB!ge;VCje+)HOel`gZva3%h5qpY$GVwVy(8)&*+lE6#GaK{WLD z4rrrs7XlZjLBv^CEWZ>$ZT=asp37u-a^)Tr3Ssu*xYoG*xs`l$r#=Us?Mn+jm&5br zIiRG!Me-NjLAymSfRDZ%=P$n@srX)#hg3P@qv)}4=1MBpHujOvQ^l>F*~oVH=#ApItfqHI9=D|pcW$S{C7pEGIDC_$?3*R)U)%e_E zvkgJ#Njn}{6UCC;jfX`)huNBzwEUX}R-7!C&g-c|^tb}x52 zA$oacTKA#64+|kKES$#}d;&K)fxf8pWVJV+VNJ9-w(J$$Cm&l{I5|mbec2C^yq?gX z#7|N`H4pw<-Ir%}G(o%d`mp*(5TdOzN2qD@u?$n}WOfJ4>m#_?^c(f-R0%olOlxeT zCX>d6MCkYGo>cg2ncRBL7Fy%sihf5wDLUDPa8PNkoMLQ<3Z>Ju?s7gB8xO!ws<&a? z;{cjCwH;5&$VaE2X>6KySvE0>W-YHhkpDDO=&DgzG)-jQ*RG@l{WJ2?npZH?-X1OU z#t8nM3g>Gaq=-#E(u{6T$iw1_>~PGFpBCJcr&t_>1z`d7?$;hl`?L;JqaR3h`}I+0 zKoL(rn*uLS2<3Eu#ekzbfV-z(H^<)^JuFAU&GV%THBC;QDi!aL- zD0GaMz|7qjNNvhS$osCzMaMvXxxN*?@fZH;w4-oNu;n{;E`vff8{WC0gnH#_VOC-c zytvkpqFeTYsmKz`St;_kq5ZgJq5`v=)gVR8L=UW!@J$CX+ilFEUNBuAKCUafZ@WWJ zW+h;TeJsz?(#Py=-uP7T%hbo@a@bX0()@D=G=`j(`b&P?(Wn?xzT6TWY;&b@Ys9jy zS7~rb6HRULM30PZ)bLXWM|bt+`r1@1iyp`Uy8L8AZ!9@) zihpWX)%=M{!*+jvKvS_Ps;L};VR4~ky|X|5)b{6tTm0l7PlW!7(;!Rj0UU3Aj5fK= zqLMX&IV@)K7ByoyS}|YNjJX6A)9ui!PW0C8bin(o)2Z#FAWS}b4&Fx0tzK7inmTn8 z?74^Qpu*D)lLaqoifJ)l(Gxm3>ru=VE&dS~$WH4z%2SPcGenr;s_KEb_pf+f)SXc0 z;z0<#=gO)|HlTIAFI)E3m)~@LMkl)cfEzbUsckw?mHRh}ZsoyYxC=%dZ=}Ps8YJbD z7wF}mQ1(KbUD*5^m-!svcd8mJ%GRb3){MtP}U;js7-ep>NUv2f%QsJMBj+Ah+8 z`&Nof;_gBCcu8lTJhwl$So~91&a~$8;v*oU2Ps|Vz&XhPUy0oI z&5B(7nNe3WYSUw|^4t%9hWA9fs!UuptAbp0%|Ne*Dn8k;fkp~V?L~w+TWqU<$={N2 z*RDcdv}rr^o1M*5>^i_0ZAbdNtt0>9NZxj)4Zn0T;FXC{+*G51&)a^1X|-mUVbcO$ z1;V4fGX*Vd!_ZkUL<(AquBPctV71>^PCnaMQ#QQ-TCSv{#<+Gox%XAt_N1Hadc6=U zZ$E||)C<>qb;p6|O>N`jpzBUYi1ZI)&B%6qdWt1nD$3{N%Zp)dX;F=1dK3;TsT7{v zM|5=S7D$d>OirC#@qeVfX*^Y5`1emTgeF9pONItQDx7ugBPnSjm6EB!lv0{il6fYX zLMSw#l%j#Nu4M?NP*I9XQb~hKs&8}u{ktFjpWXM*>$M+vwwHaJz4x^~pZB|uKVK=$ z>wkI)|7kAMxSt)^9{}{B?mxaQIC#daF zo~=4eg*?AI7tI$fhYT%#&*kt~w0rD_CjFMsyxAA3%`I?U^c%8h=K(TUI2p~Kslxal z23Tp{Kx$=0M0}Sb=4`Y1pX@5peR-OM{`5n|zl#Zxo(O*FGC@v}YVkxi`7=z@VU&^6-%IXQnb{+xfH>O`LzjELi%hVK+0txy@Z z)!X5_eTs;eo9F@2Dl)VyOprP!R8V1aRN((n5sUvCidyV>NAcQL%W>yN!=qH5#p|H~ z8c$;dmU$E5O>!MgJaL~~sQ68_wiEbWql*$l20S0?5osK02!=WwtaE!qroH?`E~lB| ze$PvkUeLlr|NfE69kHajjgbd~aXqEm|dyH(gMZNL5@aMY&t$Op2w62wb?R@|9@X>o@%W1Uq zbD4nSZ;iHGIyQ|MOf=Fj=~e0wc1DzUP8FKZ@)^{wDRl0@NBUroImuS9B;h#_f{uDQm&D{#loA1&umNVhLtrGfvFeOJHyCN8J(98aj4}(%Xr}r2c z7Uo0#YAmNq#0Eqg0~Dc0jh~~qCJI6v%!wMme>%$874BFqKv|a*I>Bx<*w5qd^TT)2 zf-XLvn{kaaE-^vw?GzkH2g?f<8$rd}gM6JBNoQts)1(F$ygyF|XK#`NZ9x(#cq&1| z$Lpj2oC%m6f0CxDdV*vr&vcr!g?wMS5&i46;Ap!KHki(#yCzS-&zr-@1buBN#6=dS zn^u#1pGL#$0$XfQ;yc#=zEZI)e&%#{RT6sL=HYblS$NZ8ELI*KnBlw1%=fayV_uMuD^5Y@C@bO(z-3gJdkvZaB>|ulp}o z^~>?T7s~~x*!`J&mG(yK>LJQfhx4=NczRJ`I`!unE1u8nvAS8D>PZPu{!WvqM|CyN zzEz>$!ww7L#^#AW+82>)0}HX~yok^3uEh&~4e@@80_;*BXVJ1{Ci-7r1m)`%VwTTJ z8d$ptR(?pN_cr>WsHc;3)SnXQ&rrc?9WgSgq=FvodPAx69DJqag1fpG!@piHTIW0; zm#(ZKZ!M1zh4^DtKNA7g?VN?-_DjhAQmhKq^G$nd}Y z|9-}af!O*T8+|wJ@tWbee%JaL<|cDYjg4oUEwHu_Tl@d|lN9M7lvUt4Ql3)P*Vcwr zJDy3Yel~rp)ywt*%-p`(>g3c&R$N`e%)5)(+u7+tm3LuGvOJn|&pRo6{#My)^t=pV z>z#cy_sfQazR^uw{)PtOyqOtRPfz<<$<&XwTD0mqiqN>o;7fS3AZmuX+soP!k|0u$s2x z!rUe4dbN*DbZR}Oiq!^QK4rC`PjPPWWmDntMeC|NCW_6yr_(1iJnmL=cY?s`ji!-R z^1{p4wz#rMBkST(aqq)rn|F;rY*nHPezTYhKQoEF>;-YT?;^ z;hYy8HNQHdh5xhu*bFzb|EKkvn;2WnHvV6&-)%#n@GlD!8d!%4OB+Ij7T?2!M{mUl z=iNLY3{pEF-26FRm{AiWymll=cq(?caFNwg;kAfx;d|;KoS7T)f6jlsY2;oj{@VS| z@qcywEauFfHD~t!>iky?CI~OMZ4(C8tP|R2Z5N*TUMMUG*df$7BNP@ly9)ca?Gr|^ zRYLQk&BA9YtA(S}b_l!rQiO?3k-`ek!@?xU5k_x5C48KHL}-0FK&W+auW-z|NZ}E= z65&;&1Hwf&mJ37rLWLi??1g6L2ZTln{=$lNVL~hEVBy%eoBz-Hf3t;qLin}+&+&h^ zesfb3Q}h4T`t9P+(WULtFzI6_Jca~FE?fdDCqII9$;x!W+)TK;kAoQtbXbFa2};5b z+}_`fp>Ir?`;Qb1TvdfXOvf-sm2UiS;u}>DFt$kb+6>3cJWyZJUF2H13+Pl&TytX@ zxaWW7dj{vR(%=TlRvp9L_60aiwH00e$kSC%_J}$!8{pdSs3HDC|8p8eiTUC^O^3R4ysnN3SQ*!T*BI;a990;z>c5w z?Mp2Y*jqV6XG%6{h;kvqAF=|s(LQkTsvB;y^g%2+7@g1DJ;s#zC%*08? z&7u`HrR33xZjn`!G0wdfOqF|AL6v#EVA|Q+RH3gNMlT7#7yIVI-?lG;j6i>Mx%N@? z3nCHzOvC}P_S(Ft2K_g^DIAp$$+N&PKVQVkZ2P<8%IHm>n-*CtGOCMBuv?#HQ z;yRf6>@`N2&crkRQJ}y66H!yz0+OFwA(l&p(CyuVrf{45hzHA1O6)D}7k`Qo5AE=M)l9NYb}W-g9L>bT z(n*h>IP2o~F}xg?3#?V1U`;?gK2bh`ot8*IGlB|8;4p%zs#;(dI1RnW24HWF5vvR`WJT8L7%;>~{$A>_k42N2{Rn;bTzV|4 zyQaqu>3V_MLU)*Z#*ACnWdj|L`{2hd6E1a28Ci1e8B~1~=VZtIL$k^(d@YtsulP-2 z`Kc37rT+=KmAB)<{W`2|Q!O27AusazlSHDY93oGT8$+snG#m^ZgxzChP=95Z$lvD% zG#!n{Wt%10I73Y&aXzTJ`y_Q+wF{NC-qLPC7smLgAnd9YiR>l{KH83=Ehm#i*E5gf zN^Sv;zkLW(H(8^Ed^zg6=RuXlG>|=d7;{pez&_15`0b~Ul~Q5cxx5ja{GMRY>RU{& zWZ04ev7br7uS8VzsS%tV@<)m2FGQtqJ3jWzMad*_E++9MNDnOryJW&G{r(ba8|z_2 z#tF{fE17FNpu>IjO~K&Z?KsSECCUWkP}5K2+2Z3hRMt@sx17zyEoPB;FtZ0W)XPx$ zZzPhPU+_N_1D0r7io=w&*x9H~ye;p68s}_y&s{xUSaTZpRVlEvARX3Q5Q~LA+fXG- zf(<4A#MZ0fIAz{^xbY11&IkkfOP@hzlsk!hT}5xtm{QevrI~!R{z>&bPl0!Q7Py@`N77}NfW_2$ z5Nx6F*mwai!z-bD&*JcfV==_39u3CWg zo+5a#s0fBUZbEI@DDF?-OUP?b;LM^%a5?@8+^8`n=qb^ROGP#KQvN3I5&n)xLd94} zWC<;(+kq4M)LF-oVcgGFCz#LkMfJwHaGGI+yKiz6RD@T#_J84A%OH!(Umu;iO~~tq z3T(OmOZ0dJxZ=Am%e#67n`CxXweC2MC;ln2b>3zy_O&vbxkrnA=rP7O`~IT$h9J~m z8o*~S2Z?-EF_2X`^hMHGu6g4{n0E0UJeB_dM?VZf#kwIP!81k+^Oh_&H8D^WN$08)2Y5}6n`y?{3V!`#vlCkrxhpm zDdC^wN1~Me5X`#}ir+6apqte9s<@6EEHtm9k$G)I@VN=nWDDV_=3H{y=O;XVds-m! zmlbr~ISD#k3hXZz(KSD0P|bP<>fElOOa8UdkYR+R$e2UZOAQRjE5XCXq2RPkj;l7Q z2G>VTZ`nxF=c0{gpb; zwKq=VJ}Paq8tlmWf8ux+GC!S^OQ3$$mhp5W7>EMvtj&<*jpo;cWG_Jmn zFSf~GXx1LQc#-eMbLBK+^8nS&+5u@@VGw+{l-6B+N%mA9g_g$UU|18iM3@4M<6T&Uc6;edSdc#oc-%CN(0g3}xEwO9F8dzaChYlPX52rn& zY2yM@C>tyW^)1;n-m;iXd;gKHaXC!fyAI+7c8NF}Y1293!E~yrD{5NB;gRGrkzt4| z)+U`txyCL*$eKuc^PeU0v6_fGv<386a}+*X_KxP?nMA5T?5e7nI1RU}DndmGpZAp- zPiFhvqovix@VizIDuNxj&$C~`&6NeP;K>{4xT4Ly_P2yFs`I(A4iq{rJb|R}Eacb; z)ZKNRuF)7JN>MnCS9c_0#necAwQM`)nq&w%Px9Tnm^5l?^c=sFb7-TjhWFoH#wo(H zIO5t&JXUra{k01qgYSa$-c#WUB8uVVxfV#0ZRH(|k6_8JhhT4@2r$77$E3{#nW-zm zG;SGA;~jj19$V>(_q`-$mIb`tok|ufE$1e9CxDklD12{p;DS1v;cjR$xMh2A!rq&( z^YmU=qH~e#zr3C3JTih7q6rW350lbww*@m3ev^|nQ()R#zTZ&FGjsE)XwKhGWYc8e z@rE4yD`h|vWKPhAHIIma?HbIy@C*HwU!xTNOhof$vG|MWc=o}0)Up(3eceK~=13@w z;@K<3<7ZMfask$79l&M}TiiI%fM-?n(fGw4?EPhp@!1xl>z7?|MA#$hUtUU6b7N3r z=)S=A@e|QE)kzp7vd7C3`|#7#Lfope756( zT4yl$8VtKW{332OqlsL5A$*>cK(YJ=zwfjjc6jM<2CwC~xj#c-Lm0pgt-m1tybtR4 ze}GLfU%}#uFNo}QiR2S|s=s18Jr!I922pCDKXw+(wz~x9yiA~ZdnDYc?!hAyloyT4~>WGu&47nQD&bf9?DW>!Ks$) z{<=x5+4r@;)pHSSZpzA*18RACo7Cg3jfam|1uo*dh$n7*@ z(Xub`)7b0yWx+GttGNX`jbG!-z22nd?^Zk*{#Ug7(^q;?yqxrAREx|uhCtOsYy6_L z4j=BG3wifFAkAccRb=~Bi?v_&2qqI7sFKZtmA=V>S2oY-n#(_7)A-q(@|Vke7w#5> zS)GT~=~KA{?FQWAUvs%rV~2B5bKk-IcUMF|BolcL&JmG)#uC`7J|3%#5k~LPAqJ~e z!99b6oQW4{qsbwhKc4629Na-J$X3u-8qvfocp)|ZeOS9_c_u|}gIrey@ zEZfoBf>Z3rvWNrvOgC{gzE{v?@#zX|(QrHV`t1?Oq%cz}1CR?lE z%iI@4vGTHbW?YoRR!amh!~J{MI^6?|j@ikoGCkRu(cWxD$9{INEs@zY?`Pj?Oxcm) zmh6O^3kwuZW8Wcy-Iw0Wo=xq;!k^>VkNbOBRp=ac{KpbDdgE+XsL+nDwmgNF?h)KU zNj>hMq7A1zcOG|Sjwff_=El8kpTw1l6u7t=6)w2p5v-zfxs4Ke5IwCAq^`e!`tC2F z6(`Rv|N9nhJ8WcmzYj7AivqUn_D*J-lfn8=MY1)yy3D?NKiju2nyGAj1o9^mpzFCB zHz`Y!yP)F(%Wvkx+TzjBIr}Xf9VP}(l#<99cX{f$HVE?i4p`cLw?i$nV`N)iIpyIV-^gck1zlo*J{8JCQA{yv_qW{^9dUo7ty@AMmPTJU(+D$-dtoO*7}b z#Vpwic<0*$c2>FzTcdU8>F-~$XIdH_db$L^jZ*OAxRRw^N@GL(^;&RkIhz?{!`cq4Wi~zs z**P;G(d8MH>fk-7bLv_Xg2VyA^FtD}mvksqkasUU1Y*BI!E| ziGxE1tbA)CQZF*9sx&8bxsE)yF?upL+~+b>Tr}Wp{x*Z>3}fy??j&wv_c-pthfnZY zbqMmF&w&0O8P3Q552%ii<~)mIpmgFM_UeFiVffWMB52VGGNp*~n8m?AO^eru<+wYY7cyfmWt$*UVqI`X%ihn|9{s>CUgaCsJ=hrHAY1)BtPCh3KSjep7Uwj`Lg zungR+lE5#elXyM*LQQQZvRUtR*p|2eGFjaV7j1iolYSVIE9@Kan{U7do9)cp@0Q|4{7o~$u*#4vn3x=}MWfG<`Ae5a@yS!J|aia~LS68i9T0 z8c3L9jzi&xF>ihy_L%x(qc8!BHeAO=PgY=}=Q*r!--r_P4+~;=|KQHtKoZh z0}mPs4xXJfC@33lM!$j?qyuvo+@!g~qSh!uy#PskYoOHb!UADVg_Eyweazpdzj6^4hiQf(%$VAx1 z&#!W){3TD6W5FbtgNuO~L`^3Ne&PYp9GnI7opk`jGoW3349~~PrSk)vuw#)ExVmdn zKbw1khOP;qeq$wgX+NUY&$fcip3fwwG!MJgu41iqKGt0s&WQ6M?#-Eux{G>IzU?xG zc~+qPooqb3Ap|{N)Zl`W*?1}`iYgl4#6_VA_%doHp4alBXI7lGe8&IHT7Sf#abOLe z|0j#q7p~#r1eMXTpIfl@&Lk`dDl7;CT-Gj=pO#GGhe1yORhmbEkpr`+e{s>@!?>`wDvh z%Rt=Yf$M*XGq1(6Y;Bq|UW;9Z5sy#e{xvhvN^K>!oG8YSb(;9xM^~hEbfjp?E8f+j z{*KSJ9!JB+r_rbHBSn7$YMk z<-&*gcsBMU3SIQEd7K)i9G{NGwp+3EgDcO4t;K$eF44n~cELx(2&~-SgZEh!{@d1w zJ=3+BGu}fvg(LWG!foCScoW|%`(nfbf_m9XY_!<~)Z3-Yws?5qh7KYEMCCr7mY)UJg+*7hs@Bg3Ea<%SP_I zi^KlqVaI<8%tT~^nktpNcWDTdipR43J1E*1O``|*%EHMkO^Cle2SQy!AlvgUxOl7L z)ssA7?9)1nLW_pR;>I9-lOBW zGjmHh1(m7XGRioOy3<_S&9$6DTR1b9N@M0f_OlVko!Q|Rj%>~D{cM=A4ht2|W+fk` z*l0s1YPRtoUEdQ|Igqb`@g8P)My(2*wrgVI4w1lY#7rW^cg(KnN@LBfUfSKg3KxDY zMdD;C3htJnJ0Ap~<_kx--7_5ZHm<~&OT72quNzyO#{xrVK-(3bJ?x z@cy9~^3rfNExEmhij~Bnut$b&`>>Qa1Ty}8aSDE1bh zCp)j1#=HhS*~casHlr;E`|LMiN4*XfO9F1sl4j1Gt<)+j4Wre%uuSe0p-y&C(-clD z=C1?4D-v`8Jr7n!D{$QS)wJnF3HYtN3-T)`^Urs!fWlbL@?18zS8WY95FW!FZ%OAY zF3sS^PIO>$EQ-zT(_k5gGMIthX;wI46I<1JlFj&Vgq^F7XB}pfEj{L+CVqz&W zHCy>i^a(Vmc6%hP)x1IG?T&-0ReTOv{0uSG&?aNIx|5pJarmG~kq)Tp;`D9Td58K8 zl6|WSm(H)nzROv3>_Kt11KEskrLfKw} zP3+hu2R2(TnF)7=umd~Su@8%`V_LyEjQkdl>61-x*p_a*_EnKxn{$gcXL_QQ%><@5 zn8^0krZJTXz^)v0Vh!#I>~E9{`!L>%rS!Wob~>23nJTlm-2$evG!eB8oY@lHANX&M zJUe2Zz>XfaVNV_x;-5BkvXRfCt~j6x-ySc)15J!vn=%&bj(o-I4~+1#lMEccKao@Q zDTmF+f5G1k+FZw|C7jjiFVNpQhZFzLhWjtmkoz3pjJ>j%)GY5kojQ65AJHMq9Pt)i zcPcW^A7hyGs64#Xy`S3~G@EPS_1^B~w>Z69bzG8c7Nr`(3b7|!PY1^m0z z0f#SkCEu6%TK?Jk0mrQ=LM3YfU6c`yH+OiF1NyaC@$Mz+@77^!Tw?LR7ekn)K7vu7 zT%0)X3L2$GVQ2jwT(s&ZZ4bLFnj%?^CQ^3Q@3kQ}*)A$PwSu79~oUv*F4wsz_ ziYy;ZC8KcR1xL&mJ)nKZct0rbXcO&QPd4safUjNn{Fs9UB<$NtL(aYxj5HC#=@pK& z;6?#9SVU9DZIkfyNflD?%?bV_4p3sV9ILP0rQ(lIQZn)wxE?Gg^GBV4=DT$wkx?o< z`gIsoxA48-`$ynU(0MvCY`G$ai3`4w z5&K+Vg66|2&4Yib`9nR-wX-7n%Px?Iwy{KX)dMr`HCt{yJxGRyOOb4^A!2&x7{pJt z!8^Pc`}B=q$%l=Y zsZ&97X7U}O#s=zlAq=L!tD=o#FXE}Mp{V*ri|-we7OmaCg!)amNy^%zd4JA4OziQ) zcQrYvTz^#L?2v#8twQAHgyZ_DMWnhgN_5SEznARbyWHP1PZ}dnZ8xp#rx-_E7N8w;&(ea z)SDlMvmOtUJ<f{xj6_0c_aTyqWQ^qS*7?UgvY^99m)HKLi=PE(eN;fR3( zGID@-RtG@ zfcvKKEtSs(UE3xYFXvQccJ(%CU$qocAK8MR(>hdPLb|SOIi{XC#rNv|qfMFP1ox8O z;u>pdcB_9HmM#v!hc!n94$7BFJ>zHB%GdB;+is%yZ#9&LYs1s==V7>eJ(X*GLp)92 z5~Z7N^!!(SNY`qjvVZR5xcU@<+KDW>@>nxY{ZNOurAO1avIvauc`Ztkn1P2|buG4s zN5bgH82YSm5t)+QLVu24Eog|{j)%s$6S}%e5c~QfUaLtIocP;G#C93s(R;(lS(k1q zIdB5UnJMDX>ItB^_mp74mK!8N{S7?k_dQE@CPR-)DKKUV{$m*2UeX6Hmz-I9t_NGC z>cFbsH(^is5WX)|Wd0q>IG?*nA8Zn5F-Dbe^r{rRPizOJNBiKVQ~;@pbcB8(-}5cH z2la_wkkp%oep^>mQ&^|^6d&&G#bo}x7G+2=IgMUa zGb=@%r)^YtUAAgT)HJFv`UG|rI^yYnxx9biAN?@cPM`Pftct%n8ZM2y30}8?;7aWc z%VdoqDD%rFmoC){R$Tc4icV{}9}RQ3wcZOjscWma(X)~{(>#v5w#JLAA0NZbytADP z+Wip&cIY!vpApNu-i&FUEqqFS1e@P2%`&{Z&~K+FPH(?mJyV&r z`r9*4pWQ6riXXE&JAyU7{Q`Am!#V3zO|CD}lv7Mx$Ym}Q0%2xv9r5Ls45P z?stjhy~#Uqmti_u?<=L#{e1;L&uKE9U`d?t%>-|C%;(CMZ{#+~dvGsv?YPg=;MMAWrf~99J>h0Or&;5{F}th>l4H*t|)BtLY&ybrXQD^?926LkPvQ3UGob z66<^A*@VU8FfZpej?%n~56;Aa{gX_~Yww1ODuyMo1Ha?gpW$2BfLkWJF29k@co@yx zzMo?Wu@OuWy+yYm88vDcD$H$=08Veaf=Y%rVuGM%|c zhp`z}>1@Y7dG=UAg88Oap~;L!j7hnN`uhh^eekcy;ng;}X+{Sw7_*1Fl@rLN&!5GO zZCK5+sdzZ^$j@Q(xgxf@IGV|w3}ju|{_MaRH}=_ZI18ojS{I)EKR8MusBRqp^|BLlFA;yea z^Ph2>FA|^{8wRDe5?H#%AJ2P@78yvnV(5ezY;T`RE5;Y$ffNZ?qNhrFHNVn3@&f#1 z5DMLTXJ}lE6Mk*{XR&c;4mv%gme=GaQ>EuoBHi-w$#+=kd6s;mlW}lsBW{>jg2Qt^;=xgRxNWNp{t+v~q`kHn9i2)QeCnwv zFi&uPtS_0ZU=DUK1>gqR{LGyb`QNeygVZ>Idv6Xo_IxTWJ@l1a=4S?NR?3)d^-8d5 zvoF>MO-3KyKjZdnO;yxqDQ2>!5^p#f;X1Y17!-L8YcD%t?)P(8^87De^Y}^~rKRbp zKUw6oTP~b2lfwI_1fmaubn;E*2Az9djJ)Alqj@KXP&<)-e%M=ygXdbXf9r32vGoc~ z)Sk-BA1Y$Q;e6EHbPm@NNn$xX32&6E2+p@3!Lhf!aM;vbnlS7JUatE_V*|Ul{QpBrL-wFySf566#EyRmB287%hwjOic6F#CXzou79U_5K|}N9Sd1 z%Y$dUA9g0bS@ZzK8Wq@zABrs9R)sYdX&qtiV^9t4& zbSepw-EKm@)pam>(N8Su65#!SG{lN4fpxtV&psK% zDWKdY$;nm}!1|XGoTkVRM$)Bl$S?|49yfr;5>dEPoM(e2R*?5kjrbW>E&3T#Jg|QR zK4^`>=I!6;iZSEKS0isSsX_xn-z_FyXGYU!sjI=_+y>n8a}&-Rvl&Jj>aZ~}mvOJP zC7v>QfL1vNG3DoL>>G5$$jr+)6QVIdW;}d*m;|{yCK1PJOF)#EM%I6M4A3x~M$8&P zMtr&ed#x{`Tk#Kk#P@zz>(ro=w?DGeKdD&0cz`dl-8y;6q$H$@}} zIhIX44_u=CJa7Kl`W-~NRt|sF2+(zS2}w{O27O4jLu zvhrv;rF=4pX&i>X4?4m}{o$}+p*$&dva1?fwNsS+?xX10f@x4)kS3DgduiKp3oty$ zN3=a^Io7UBq;DH7AlO-xHt+sUdmiYJ8J{yTa?X0RI_!zXa@x3i$9^0!ej7^5$}sCx zTYT&1O#FWAz=L{Klx?~~^{pH+FH(+#Y|0YpC7%HguRCD=W(FL7a0uE=CIBaSQLyoI zE#KqMhr`Fk;j_6N6+i8TO2*N|V#yDICn~_V`38cn$AK8kX=0~v8EsZ9$4JMEJiE>X z_kKEs=dSat#I@4&Pd!7&?~2r8{X4qHr=OIKvId`3`^mdsjMhKO6GBI;He zUv2j2;vJy=7>PuN8LQooTIgEQgtiYJ1|4e8LUSO{aX@8U9zQP{M;1nb6o zqmo(*UhE!&Z^Yt|wd_Zu-sjjgwpa8yZxJ5$t0FGJ6F@uGnfHX|qLKYtymOP!Q<`3) zGMoCz(hGTl)jyAs)COlvhb-P#k}bGkepXc1(?Fg@FT}Tk}Qg({~YD zDlGZ#l@u788`2-6r;>LKLC_O?j_CIOA*m*h;0B*@aog66V}e@Iphb@voXf+Uhi~xc znu~aOh7;audylor*J!y=jQ+cqgx5DG5>>Z}_%`7<&Oa1M+8!*Xj>9r>-M%4Fw(~|* zsn+KAm|F4B*FIG3>cc+2g;=GnPn$}=V9)-G^yy4BtX{Ycn<`ZiMwH>tFk9ZQ5sqPV z8_`4S9)5Yhh)(bl7yXx5fRDc%#n~>hq;y9pj(4n~D(#EOjpt>=VbvJCW7I$jA{)p` zNh8=4uMBDa36Su;4Wi|4TWXwZgO#c?x$qkuWQkcVnWX%jbotDMx!){tSe^^o{eDS& zhmvum^F@>iKR{NNje)^JUGP_*i!VI}=s>^M%n&v#h;DZV=8PiR3^_p)PhNzs<5y^vT^hvr598E>GU4TcGrXIp z2BOccN241N)OwwH)u+cUJR4&{)lTtl@tV0 zO{Ox7?0Ak*`+lG>rwmu@8Khw?FL4T=*|$sx!W;debatXC&rMNAb)LPDbg2sSTc)D* z2Q4TaC?+qqUPp;Mf0UPWLbLct)Y+|0JGc6yjZ+`ZYU`zr#r5>QeLEeHmByEsC*dpg zQZv0oD=>tx^^B`uJV+ay|b zs#H+ACL6cbA461}1^S+)G$4-87f3!Pa7}|oi%#KH&jM8buMG}Kx`6oGNAM}X8^*}i z!En#p;JE4}F^;MiS*lio*eEeb%bNmjkvu!E?;v=O?Gh9mUkQRiX|63V59)q=CN`^; z=p%U^<`G*=m5Zq8<{AxrviukM&c|?T?Nw1}RxSS2|Hk_PMqs<@8s4AyfGSNXpr>q~ z&^E>8lzCc_Nt1q1A?9}{@pCt047}t7 zUPgyu>#qHlyOWeTtNKA$KKVOvz0%y{==U(8^)v3*w7`OSA}Z^=7C&Z>!Ta&guz&kz zQlGvLH!XF;y1BV{QutEj^ItKEjfh4nIDkzpeF6=)29!~ZCO=&6ld+Bc^jJz3?i?o0 z%th0%v*;X3w0%X#e-`-ezvI;O+-~aos0T;3oW^@jF*t%fq+sF_byZbop3cG3{kQOTQ!CZ~5lhxRiKSPTr(%T55y8UDTv9G24Qt)! z5tRmAbPT?X&wjr}qj9=;$om8R=^ce_p>2dt2_S1HjiNQ*9+0D-`2PQXWr*u`0P&Td ztLD56#|}AwrLLjydWIa%8Mg^O4-V(~XX2vM0ik4((LGYQejkbbaYV3sY$dTd910bI zhcLm*l{C-Nfps3o(DU3$oPNxn4jkoZ`3QMvt{aPb4^qi!)d+g?tOWday-mC-*24P} z^D%6sA~DU-$H|EnsFC}Cru~yZot{+E>KX}$SM$z1ZChgIPz-o87D(hA=$N$>zI@@i zrymS4c~LoJyOj}_hnvZipaJr5%4DLEJsLM~ru66~VU=}Q4bP@*vy8hs2fN%l=y}tL z=-`!#3m-0|HJ_%Eq{&Y(e*9XIb^9?aZ#6{IlXbXl4uAcXyinG>8F!Bu3Ex-TgZSAw z#HQnm=-%UH=kxLu&maP$8Jb#QF-<&V{)XeBpTV<^Mo`V`Lsno)# zkPJVn3k8Zrf~5RGI^R1Q!}2Lr+uww0#|x=}&jzd<)j+;{Q^PbbAq?2A2hqV1@az#% z1$BNOL%R^RsUD$Ugj-?V$w_=~=n{=kCLn2T}hX0FgBws`1I)l*{Ceid98!KT0u1XT`qaZ*+R+GKZ2wK zo*2}n0YP8q;_DYN=B;J3FiD^`2M=J}?HRMSEgkk)DW-(-qu{en4|Q zUx+5!{-)nu3`9AuyhBQ29I{KRak_Ubx$5Zz&Ib(Xo75So_}T|Qzwf4*%~hfVzT2a6 zayDHZ>`h8rEkT#h`ev5#j&P~f{M_@9=zW_!d{gcaTs1ewd9P9g*$!4!M*MxG<k$fA^8FZuQ-b9M8B!#Gk5eE=Y$J~^$A`c6sLE1mb|spUo_d#LtBkvX=N$JGIt-; z`oeQBj1iB0k%f-ULY{eAL=IHuLr<1&D~qYNMF}1#KZLezZK#&J z6mR{NrePi4sL&NhPi}ZlEySi{f5<5Mb6hLtS%1NiKkM=2ED3hLD~->TwWCGvKdM>y z3v)cblTpVWfPVBR2n=|~?=jbdtI>0Cc-3ifX1z4uH@*SOPK?EO8^us_(P8|dbqhyw zn{cM#34!bhQ~bS(?>l7NAh9z1JO8Rf0wdkEko+tSZPgC}ckwc0MMj{L#|@&95(XWI zm*TxZ9h|5BMDUt->A8)WjLCmn(0u6%elA#r!vn7ITzoS=|GgIDdDc+4ubqf|nuBHe zLL4>j2o`_4N>gq{5b-N(aA4RBh~HKVn=>ELI}@+c)0;2BTB%%=yXFXyooB!=$q%ef z@mv9y9vB$9Lhe{a!}n7qu;OeIIUJt~6Kk6ZV+67LC_f|r4x939F>7HOQ2$p@<*I-d z`kCbO&6A=-!3ji9{xFSrybvF*)+A~t4M8sACZT6|C$RS^K~8Nr`6ja*Kk}IjYu}xs ztX+2rgeXwGF(pK!-Gko~P=o7=$|z}BiEYnnY2R;2@bvwUYK+iE_YYr1m#4O%UGRQn zyHaWMw@et8APXC6G~mUQk3?qm4}llo4PUw12IBrs5G{P{T=y-Ziy%- zIL}THA{_~vn%s%Jr#kuX+juNlnu47{(R7Di9yxZw1W(<_#LiW9*%Y|dqEcq!_A=_}s zZ8%(ix)3e9-Kc(qEvcDWL~rQM#2WPDnI3Pk_VG0g>^ea=Xer{_$+`UAQLU&{S&od{ z#DUNA3W3fRaY0!kqhdu<@n^xus__G9IH4wk8ad7Z2VV|`dzSzj&Y~aRyOW}~H6WQ9 zPF~I9*{#8q)O+uKObYeDu9a6&a%3W2GvJ>?Xa2>w5o6H(z!Vg})s1Usl+fWm@5n#d z)u=sm0=I0LjSegC;>6Grfy#)1N}03iczG7m<*Aj#nB-z!aFK}1+6&!jnmAxC4j%lGUP_sy!Juh^?n5+|cXkh~X z95jYIyX7WSR%DCZ77hs(_EB(k5eM_)Z!kG0h79i>5U6dDrGGEoMK#;QSn>1>O5b%s zF4P@YOutOEl;cHic2SVK`#h+_FJiGPLU6rJhh|G9gZ6)2WNb_)8ERP!J{LG-k(a6d zk_5aJq=Kp&B-oK*ymPruoY|awfN54kcqh!AjN)gvD`qQLZqZ7`+LjQ^S+Wy8E!Duo zcTBNywgA5y9mo9>>+qw#GoA>XgY(T}F@?`F_t+0&OMXe!^`X=FHDnao`Z0`L$&5m$ zVXjpC|D))N4#IBt)~C?e7lGAfFUbKj?ugq9Q<+EZIeOIbx`$leuY^i@d4x!;cp z6%my*s1zkFl}bbTJ-`3`;kwQ_&+}RD*X#3pQT^z}qT!DT^IslHd)H5(#l7O(+`|X3 z!TTe==jP&mf-YJ^_%_ly4WG+JP}<}SJCkCf9>2MA&77}n_UMP!=|@M|0|i`&4V$CI5D`OuUZ=b9}L4 ztBYvslhcTmA5Mg;3JK?PNpv8{r_zZTVXLqQk#ig1Va0I!oCJ2yXksorm$JB$pM9Pg zi^CVjP<7i(_Vb+t?mhg;OxE(Qs7>uGe9302)~iBmleLJGpu=YGNB-U99f)O74a{$P z1vC?EA?Fe-vbqRK zcv<RL z;KY$IHv65QAoQv#Og7~sU80bv?@}Po@;Wg>=?PoXUk=5ml4!|y5ZJz2fRUUx76p}) zXHzc<(xz>;S?!bvtF@c(_rp+(x39rW6;=FMUxU1hcksmUAtqHtQrTKnI(u3d(Q3${ zHHk)arSTQf!|@&>yW-1adC+Cn8NCQi%)mX}G>? z6kI($o&E|jq;E2u=vFfkUB$Z|f8Y2m*q7!`kGyark#&ZG`<(US{EW+*cW~))AUpQ<2Ie~~K*6$AEMj9aIuDv+i?1yEQYOyL*_Vrfk~1(G z8^_LnG$!+2jH7RT{OPI}j<`8$E?pg@M86vCrqzD?$)#o^cD+}E*K<~Hn=`I2Tdtg zwsfdCeVz1_o#%Mwt+STR<|B2Ht#|@!hVt(Y(;9ZSE?bboyH6xfTVTzrPEki&581M?9V6bUaAJ4~ zx1pb*$WO#)!& zI1b~7b}>V;0P7?xNZq%QaC1szdX&FcDonsI`_oKQeK&T0Ppov)`OPF2Y-C>7E(!is zNS9Te>b}mbPw1c=qq#3otMcVbC=X0cWeJ z`J$P$qBVo1i}zR15Wt-b=+ky0S|~^`yk5P&CFi3pqo=;9D|; zRw=G!5tsd;{JCA!In|O*x);j|_iM5y8cxK{%x4zeLutRWAw^RPC)~ zI~<~6Rwjv*(kbNijWW`edYomRN#gVQrDWn*Ly^~{UQ+sbK1+P{Oi<~k$E?#AjJ`-v5TJKX{7p0g>lclBjIfB6yH_I>pD%+&&Q<*lsemmx{CT19_)cfJ*np5kJ%wpx;&Zl6kg z@-3+Qb!!?VJWKTh4-h3|FTujZ68ib=aeCO$j{avgnVz+oKutdNC-19R@)jvg-Z0G;(Pc*2CI2>Q(;8Wu_=CXGj-h>*kUYAb6tm+`5!uP7x z!bFx9(a5~{naumf`{d5mGmy@`!2J66v%Ys4P&yWYFS4nE%=}Yy?lBQHPa8^yrnb{( z{~l0J=W;r{zmNLAl@RK7%Ly&*2AJo*W|8gT9|C(n1FR9cq3rq;I?7HDy{FC5@Np!z zW)6}I`%?v)4-J{_Zd5inrlG9L1IZO0C{o=IoK$2H89T}IJ`Fl1&y|+j?IvrYCLzYM zSCn;i8~rtyAG6{VMj0(|5!-h4BJW*OTUq0 zd*)Hg=}+0H;rjHocPPm(*-j?(?xU9r2L(r4=b^sbhCRIO&91#~6NrlWJcq_rQA>$E z6<@KLcCA>7`nb{jbIy}GIRB+{RVrv*#CMu}ayZ$)qEpaG>S@Wqf27y@Em=2)ueoQf zq<`8!5!b*kf}Vf7>G&NpX?FNo+7KH`cNunpVs8Vgn|qQ-N0+eXHG7$3&<|F|@8xW)Hc;Ew?KZ}r&j|J$OA@Jh_`vkc6!vU& zxZv@*BsdO6@cz6VP}cp#4(RYR_p^7gUg07RdzP^{{_bg)te;J@T{%0O7|%Li6hk6< z5ZyfE=fCbKq{lkayw=Oe|87qv-R19Vl+WXMu{Ir?v6Ma?x|q9hM44mKrrh1_0}y*^ z#(m71!WmuYMnY^Ww0~Ve*M?+>u2dmrRvCVGr9kFM3u|3zj{wD|NU!Ncl8PF7A3a3b zinpkFXv!T5(B~E|%);(-;h4tHtGz;A;H9+`SC~Clq!?YwGEQt^154Mk))6u-$M2>7DNnijjzCBhmy_MIdmu`T!pNqrusz1RzGU0k zoNQ%w=B+fHZ>~hAyeZ^sk0n&<41Wi|Dv9dPlO@8tj)Dp6(*@GzJTLZ*KXEJ>0v$Ph zDzWeb3oBWGnv)_{7=4_^JX_8}la_Jk$Eb4k;aT8z|3TgvWv=GIIPS!sFlen^fDN^o z*!le!z5DYy)z~?MZj-mAKY1S8)&*B+`t|8dV$Ck1Ghc_5eNv>qrY%Ku{TA|ZRu$W) z%_B~ByeE?RX3WB4lpweM492FdW%{3QvHgKFS%IM#V&^BaXDM4K=p7PnvXi8?R}+Oh z>Cl|7f}&v$MBYIUAft8$o5o%yVa?qjo5KagJ7sa{q%jvRaTkBvRk`7D_FPP6KQ>(* zfTFvAE8a24bH$!v%>+IC;Ca?JH8o+E>56`{UAPeMj}v?bLaa!g4ak+?x&3pT)05_8 zH9{fQW5g9&H^OIO4clQD2&?=yY&DC9iRBco(?^Y~Tv}8qiqzmHE*D48%Jsb8&d;9e6m*LRn89dz)+8jbw*O(##2;_h zmJ*|$D7wykFXU#)arb9T<@fFrxrf`dxW2Nv+}CxQ+{oG5JRib^d#*~j`ehRI#Ee)v zur-VpoIi>c)gH{S?j{Yh8b*RsJY^5g;h?=ZSK@BEvsKVha0On#&ZV$1tPX1-;taiu91c;}OV zM-Q39CVrp&D1g3t6G-KDpG4B)bIh{5)Mo5K1H|V1VzU1dv0?ZwV#+(-f8GB?{xTQr zdnb+I>t(52*-C8uTZLbuBuouCi{FQ>`R6?E4BWGbIXsLYQXMDAu-*%7(5#9)c&H6I z-uV?AYruA=SMdGkNd)(2vja;UvHxN$`eaw)pUwD?bJsn zm1ZA5NID1C(vHRDBvXyQ8>mU95p(>BUU>--|NLF>r++|Ts!@Q|y6I>L8BHq`k7CTm zSRDA&LxM|uMTL_J@p*$ER=X!*o$+vtp2GX8Px&A!`Xt7(Fl6|whq202EJ7Y8_Wpy3 zWGi+heaBC&9?_6(@yJpu5XCDmhmqbAzQ##rUCJ}?{9-5jo&T0}zZ*>qVzy%-W)Iz| z?}s1a6BtMvo4WcMWPf?$(@%3EBB9t@ABqTG{TO)08b;&eVdkz(?k8VF$aEIk11Ah@;d8y{2kdn)V#uhvwnmwiVdCxExZ( zm1yVhdIBDt$6{9z?4ODRBUdgVq-Pn<91>Jsf3SghUQdK6l9_><1TLPA7F}BvK&rPX z&}fx-v0H#^IBc7&!R@{NhK(33Lz;v;Ug}73OaAfqCKY@=x={;BNn+fO-v%gK z#D6EYHKIEH7V5-4lTLv?)fDI;BKrjS-7$@h+@Vd)ROQ%^Epqfq-zrl5ubUrKWMk^f z5=iko{Qo+AkYe`%9eEs!O6Y-w`XtCYAHWfW;)jTzZ-iXLXt{iJzPo}UNvH5llHccD zNJqPT8ojgfGWE?oO^0t$7g|9{Sg7!ZI;1?~=d&r)Bm4}_SeDOH`D~~7R89I**-11e zWI3KpFDJ8?PQlO1=kWZX56WAwP{SY3Y4@E6^vHJ;Iz^$8PL6D#lYB!&m&M}gzI~Gf zUvG{?&lp)2+^vObtyum}z=>>~eUo&4se#1jD=;bPBA2}a=-b>Ef)FP$diQe%4SbYB zJ?{n3ONT32#nrX++?|c|{m(|0?>h&VD%R1U!5P-c2i8ISaiwVOTt_Hw7LtmpgCyj> z8}r_^(`J-Lvxxh5p2$p2VB@ZAq=7|II3y9ph8Z2C_olYsfYB1D8d{XA?+sy!|5mVZ zkEF@V&gD4x=qFKp)WTBT7Zb;XV2sF(gW~w>nDRLT6L?R;7A&N_6?3EQ-kNzMO#jQo8rW*2YXpgTq$c3 z*J0U-QS{xuUZ`g4FxdmENxR%Df#kDPL6Xr%y6kKc({nP0L#R3>JYBygawP3JCr8^| zw8^&TXXxJID{PsHH!1WLXU#qyOkQNgrG=7eIBQ()}Y6+T>J<+J+hN2GMgV8$=4}C-F zN}l~(E$v7zZm*=a6_Iqq9dSsgw}}b@EvU;GRW#7iEcUW2llIra(Y^z0?a^_9x0Tbe zCXAmQSPKvzD9^RDDB_B3GP~{j20P}NV|(=zX0ogfj~A>KxfMJkhi{!iU!@H$MnsC{ z7*9i-pEh=SPNF6)XG9~e?5B6We~r3%0fxkbTP*(Nmiusmtm~NUnMW zv)K>Xz>HjUmli?dUL5Y_iXdfGYUA`@EgKyai@cnbf*oI1GUacEm7xiakjXlWmVO(o z9_=b>oA*;R-YXlNHt)e0r-zQA)tK8SN#4J{&wNF@*fP^C@SsU>nW4i!Gq++VKR@v8 z9|057NocItjwH{csF@doG?vXi<>aDigBnunBSgkjo>MoTiK9CcFmJ>jzIT*|o%9I! zn^$1Vh}+=4*TLQR49trzvAXGjc)OYBp+4b6P7hUCdF>-&`Y4btyqrZRc_q+i;#zF| z5?9uoZbet@d_WuAM$$Kjf?2qI7Vq0orWakNphchOZuhD|ZyTSZooA0WyHil?y?~G7 zY~b3b!RJylku-HHg4_IHVKoFUdds2GbCZ zh8k+mlYI`Y9WO-4Q9x!>xdp0-F$zA7Bml4X$>ITWhMe9&po{enINYMOTk~x2U zB%1MiqDcHtEmK=uO(wn*()>0D_PT$gAh4XDgZ_S7`LQd2rheC>xBiZSVsZoygcV?3 z%Nbeh%Ea4h0IxJ zK`nNxV(;||k;Fbv>s5E6VbyO!ltOjMm#+?ZQ}mvkTRfgkwYkJT?@2{>?J2xEIs#v7 zJiyJD;KrEzU?aa=LytlRlCP{r_R{rKs-=@;-AE!a!%9TD1}3zpQHG^h#fYx%bs&qL z45f)Vew7m2f~cZ>8ym7_2;62_Qrx>uwyd5&i@I~Dzsd{JIMtncUfWKOJSt%Q@)mU1 ziUMNbca?}1aQmzQ#{lvG0-MDmXG^R!9 zlJu%OB>iI+oQn2BkT=oWGy4!PNGA8E??Y{HJZ-SLh`=O$UK|8nwW5u_jb)yKkwvK~G{3I@*p%Z5M z;kc&xfR*VzqOs~XXt~IqPMWltrSJVtzLh)Byoebz&T9dkoA((5{*9=go5951^kE;L z!9Skk1@i}O=v#Qn+HdR$ba(sC{4?MMA9Vl@5Gk>-QE6LL600sw^=wi3i;nUiSG_& zn^zMjQ8kqXqRoBfWVtfWSy&;%UG1PazV#(rd^;9T|Ghv;`%#i~qy%#BUxSR5WM8UJ zqO^V<8?kaaTQw^jw$t{&-fspx=VoC`%QqZ!o+eT=xgk1pgP%*3X>#01G48lQIcf%! zxyAX?+zdN+ELWe5VSA3EZioUJYVR%0A3VOegaSQ+n%o5oc*>ye4s z;fHBbWH*rsnMIr~eHJ9O$g-)Pdr4-IFLBOmAT0$$Xt>TqlxQj;eV-|^UUreS>sK=u z$2$;x`A5ci-a?>kIP?teL8)4oQ*`fv_b5fqz^oE8hJ_(+%2RZoli*tV1ei0>K$guO zE=;;3BOJcKh#oo3s6e%n?#Q*ErullbNdFOS-rS7G8DgCAgRi)|z8@a1x-oLE1Q+8w zfrIi5#QTkh=Nd;8%;)*2=H=8kbtnE7D`Nl8GsJUPmf&j6JeW2wV|LGu!%j08V{S#_ zpNf9Z~LSq5%ir^6&R3+WY1OX;_|0&h?F; z8kuc$++}mTd=-UJf<%FMTPV(73PXukAM41F;5s$JL^4^Qk>%n<8y-i}+QS#A_{2M8 zzUK`x;Hs-D9< zTZ8T?&}CC*|Eu(KR>b+#Hv*MmTIdpf6AAymV^Kv3e4SrJ8g70U^tFExC|UU9!i_2$ zi6>Jq`QIwR^61%k^}!imo2+R6-UMdmu!=secu&I8mJ@?W#(rxP5|I``E0#qGUOcwJ z^^H}c%UY@Q#Qt%x$<&~drDv)2=`OM|?LLcMDMK%EybI-|v23@iFnFB+%PXOfNOBV$yr&M6?^|(XZHhqIW+@rg_g5feG#ghp1(EWHO_=4J zglnH1$h(9Nh({Wb>6L-3O8NkD;(53eT0lDe%?Hh3%+b*cDzu z$E0a^)nbac<L3f!A^xIAS-w}-nbW|Zs<$4*}@ZfnfDRf6~)v)mOwMa2eT&VqAw{^Pn68H+zpwa>SI>CI(jy&w zi!DRgRDO0fQWGcNd*IUbCQ(L|2R0Yqf~w^PLH^q{SSdP-^;hd)?*AKe_&KHZqAnc2 z^A}U*oq^K&U^Ja9!%(BwtgH4hx{u}vrj+~BmsvUV`#fc8Y&%rw?_EzLys8BgO)Kf> zuhlfUK80Cq0P~;X4XZGo_u`eqqQfbw?k_~{op4q^^bRJri}-oHE_ZkBPuQOx#l85? zlv^lFMEH+an7zpb)5mIZyO+z-ql@xsyk$7ux#%J-9k+xkNbRJ#59Ns!&*AxdHJ0vs zSBs$s{4lV#9-IEl#TY*ht9%^MXz~y;$I@YYq7mOl_|k%nf5`HtFQn^xAPNq4Fi*z} z`eMXvY9V4Y+QNv=e=rR1PNYL#-j})g`C(1dSx6{TzJIGmi$OD#LViI!xgGY2wb=D( zBUaxW%9;KMV}@r9uwP>%mc9%^M{f{H^;Y2Ju5XBnl|}Evkwj*TfW}P`(B+dQh}W^- zf=>s}(vb`MkrbSQgvyt!H2DKEQfDLM%t4Wa`E8iJ+=FvLZD@K~N=x6q70o;qOAnc8 z2%7?i3gv5t38%eVAxs;)Tc}hzLs-^PN22wlQJ(dU{cOx2f9!@(o0q02?UaYgs=uUH zqef&gT8&%tS&P%pbw!N)V?O`=0Gkf*-qIXRZp}w??()Mw$oj0x-#kciYC9US?X(3~ zqhP|x1hREhifycuTV zZbFy0(!zP`JE(r`aN+DkZJ~^}fl$X)NtpUpM;IwBFZ^fVOhtwD#APIZvvqO|Jt+B{ z$aSowXZS;tkQ6=AG3F9IWYv%OS~967yG;!bTlcVNATH@ac1Rq2**9q1rGR z?stAMdor#Yjb^!Q#)opIur3JdbJF3>XGZQzxAM77{>IQcf&A7V%d~GO5HUGrVf45% zYIXk&ZT)wH#&lZ<^Xmq1p<*Q$r!j|e(8Snl45LUcC`K)#~@jv=aC(nD!(#e!a3R#f4x2K3|b zhY?&svlI7hLo{w$MnT?fFYI6CBcjKFQ_x?=4R8GnU7-gjF>wp`=AAAlrdL5eDaOFI zXem_h8W0;bGuGdu%CpDDlmDLdv2APz@-kF~o7Js^Eq4`!a~{kUZnAHob8COmZkq<` zZ>cXl!F{0DOVi2r-_i*9dtVfGaV62Kyv-D!+tTRhI0OuA$2&P$>VDaW3+d!@w6`O; z%KFn>QbiO;hP!bMN+&sAlR!?3TgpvymE*MK?&3j23YsoZu62V3x2xd|j`*8!`{f=Y zMDHCcdvxeB>RH*`vy1la|6Wmatd36jFoW(lsV3b8GD79V9ki)Nh=keSSlWFnSWTS? zYqK6q*t!TG|0!{v)5N&(6SX;q`h8@wAcNlI9Y*JZbcJKZbLj^Y1))v5v+$qe7Gapx zI-x=33oJaZgugKdDzC51Woul7IO^O;WbGfJ^Y2+gBHT&9VWt<|7HnWHdzR- z&nTjYTi(#ip>D$DA#;RJwpt4_@8q&^Ycil`F9s<98Fn> z6Wg1p^s5Bg?5s~yAK43eMT*dTw5~93p|^0(#0;U{(#^s>%gos$9YdB9^O5X)u^fTZ z!dPvEKV3Ieg;*>PqbK;evAVQBj64P~acHk7UG*de+H>(Sxfg0C3D`32E2@(G@i{0+ zByJGK=Kq|DM;l7X)+dLFVT&I3XV5 z?lM!ITH?Lv6Ipk#79PjmGSAu4&{Nap@Bc%HR@G z?{O!_GEJTvf9!H9#-sz9ehOF>R)Kg$Yr!8rubG=T4riKV5t_*Fm92uHsB;2Y>-ii) zpguaot1* zcH-Gq-s@;o1nmu@*}W<5$o5Pj;_6cT?V~>mZ(EVR;t0WUryyt;+rVJ7A3_|=KpHM% zOSLXv=O(dDL;fIF@By_0TX3K+oViFkLCloDt0*6e^Lyk`bXx<5Uhk*wih)!lQl(>; zXyCu%M&dhjIE~Qa*~*Enz^WAdSmp*x;aZmNIuFfB53tL>kbMeU4%v`VbZWnXs3OQPva3)vs_>}*h$v3@fp=uUaWNRGwHD$EBO6WpBA;u zC+aCPX!M#1)QWeDD!rLZpUrck{hn6TKRQqp(O^c$M1;_jTX#@l*A{H~%g^QQUo-jn zUgSfhIzq!6VLGTtKRq=;QAh%2{op+@y1~qMq7f}|oq>I$r(thL036+d;W4|d@<*fy zhn6K_lzcj@wv@7LJx%TfpELDY+lZxVU*Vm)3sUjp5Uel5J4|~-e|v^8kD)I~&z)Ej z_u(_{s}IGKZ({7}uzK7Uh~eqnIME-UiK2?=1@LIMv^KesMcnO-u(m~t_s&O?iuFS{ ziKaVnnm+~sMHg{^_Y%eY-iQx*=b4A$QS9jd&3vL_Mc=6uot@HUJuYr2RlsuIdz;QS zNZ+Vb-87YLuo+9Qu0KJJ$kw1Az^2ONz{fC{B}DE zg+z+hz)lz|UB}YF&6wn>&dqyo#I?G{Abjcz)@wv)>I64-D|8c0_B%mm@VE@2Z6Pr@ zXu-_gcnS^HjUi<6^O;J zVvrzznN-B3F;Un;GPCABXZlNYsnp@wF*$CWunZd0(h=As!|lp=4>!JdQrbTP zM_nUncb6pLLPiLiyJymp_my;V?sO{f`AfWfTLo8*HqhGj(wyKdpP%LXUZcMgxMh=* z(0A)1i`~+Vs5U;=y1t#Qkf;-6ObTInO9JSV$a;1>XEe??GHUQ%4w);DL1J_Soqgyo zK1{oXwdQW5L!$=g^3!2G;VIL&oW;(!dZPTi2L{h$%HU|?`H*zsGG1J za7N#dgJ}9yh;L#sWZde@#Q1ZhK(5$T6e4LuBUhHtQzVJBj+dpm*E&dx9G?v~7E%+t zT)N03jD3?+VP{(TTr=;LcE2>8W(3N?Xw`S7r{ai8Ggaz$dlKZ|{w9?k%V`Mi!dgByWwqc{lk`6ltcCJIM}wUZ(m%;IaywFu_3l7asw!8)-RrS?xy2wk>N zcu*kzayreL=FEoVhEhjsf#}Dd(>w!wEYl*yV#(cy#lMfbjhp}9$!&Wj9y+}zEm zFi^tpqZJr_a2Z@;cVldN7k(-~W}i$=a7FtH^nY~2cWDrq_F_n8kHOOU4eXRzD_Nnm zl6@GLNCgZ3vb}FANYU;2^weoJ_(i%4mWYK>wLRioaa0$$6#lawp#;0RS0I*F0AFPn z4180A&yi%Dc{UY-IiaXKnt&I_eXwnHDFz<(u=5)Cv3KDe=I(YL`)*d@j_+QPgY9(I z>N1k${9A(k%2`BO;hw0hCl&wo$wKZ#Dn3d5B!`d3(-xaNC=P1V%w5OmNzEV3-rIw2 z-mFFg%+T2qZ!RN!3)We_}SdN^$a6EM? z7S-%aW0Eqz*sqm5x1pjDBX@(X8LfuX*C_s^h;#bn4_++juz9j#H@>*XGT##_5I9S7 z+qBA2wIdVh5mMZ!&JozQ&X4Ik z$#5e|2k`bou}!GOSFF<6gC5m7jQ=nk+}hnR%y4ICVr99_Mt86=_$vz<%`?c_wP@dh zeKh8D581}f(M4kh=#UggzDIvd*3??i@2OYWPmPmgjOi8pe=c#TrO(DPHHxg?c8m=* z3?|N7hl*5c9l3HHJ?@v}FivT>8dq9j#OL0d;5tTvJGx1e^XOONMrhZGKAdi)9TgGu zijAotU1|+2*%?f&-el2BPc=wz<5lVua}Muh?m+ADWq36jBWg+&oEPy~-`k;BYA(as zES-e2ym!@dWHS5j{z94*`yJ%=4{Tt*&6 z@mx|-INfJ^jL^gYLE6k`)XQQoU2=IOWmb2oq=gxa}#%)`18%*?AFCtT({kBQLipuy#w{NpaVhzu`#7U0-#KyYi9x%#{-QPJTzn>6((FT5;j6J5jX0 zPK6Gc`<8B*)kf=`&S5FvKZV3Ef<%4<%*@mUnySkD=l+mQ>t2LaN6g5uGp7-pUIa1Y zFxXTbKx=0ra_#()WlMNw#}IZSax*-uRcX7Sl+d~C5p}2yAcuV)Qghiby6{FM9m}(1 z-z-U{-C0{`*jq87ky$tW`YfAHRW6`O88sxb>oEOQw3$}BG}HYOmT3O~&!MO=^`Sow2&hOWFukuzJe?6Qi)ivP7qs6k6lQ%nb*0I)-Q3UPg-x1H$7GKSVIdL z;rUpk%U?@ed31u7-La|$xm{WrKS`$%Ny90X+-AuA8Qi@J-y5$Br+$#-P}(d!Df zv`LkaR$$*o$#Lq_rMQz_YE15?lHjz{0Gf{G zGKV}})Sv$+`n!~OfNr;=3$zXs^&b&*{VppSp>BfjQ}Qq^Ll!FwOmKU3GOU_zLv2wY zWYifv%k-G@8g2gFu#WX6Hp89%!RzEbm^`l@R{TN3iih{mUC8^IoabTWo&)5ITC(*` z=LvM4Hec(CcG3K`t7%uN2YI=*l&w6qm~HZYfD3-wTs&X@UaHdKX4Z;u_IWTG?$qL# zd_9JfL2S6WkBM$d)BI@#)OS^=!18`DElX9R&Q{N?v+}JglWvVM2uuz6ICc zZYDa0Z^`XWNhp;@Lc`0II+lx=l+RvT*Q-i*R5c6ct&tLF+HWCG0&?m0>nik=ZXmsp z@RhE3|ARibc#(!^DhRh-GpB*;jOZ%y8Y7jplmae57dxL2#d{THXh#q052s)U>H4qQy{ zcxF;Zsz}{#iP6y#StNxj(=F2fQN4vCI$+RB+cc@DR{0)z)$7D_Rb&vPYy-FQS@fya zUbvPziLUKhMz_rwB@~}pNWG?e&{dagg{$996h5&N6OzrQ!c}`F2=6YH6b?7YV^)iG zZMv^I)4i@i0voGTfz_xs5~lZw+*mx9_BEx5CN~Y?29CVLCWUNhYaK_~yQ}aYHwwml zE@H~_#rSXcL)?y!z^t4-$Pq|z^Q(^|yVDSECH_!2(uaxB8u-Qh@cZRr1XvaEd3G?1 z=nmNbe$77a%V9HR#4v5F4t};gL{4Zi?gWh@-qkM1a=0mY^CknzwjXVE+B&WVdgWFMe4Y%d3Imtkt?YvHsOXvHl`u(Y6N|eR~6W2U{m?54%h^{&$RblKh}qT0`jL@U3*ZsXDjLfp88J$8mNpl#9w8 z%RM+vq zqX$}+(lI}DndXj2s$6VL=Z)gs*mf55^wG0Ks%ZtyA3l;x%2D8S#;@geuA0boO?!{F z6;@otL{%=|@(;Lyshojk1uK$^!R(*`+}zX1d_LS29Sn^?QigyI)0Ack>FpT*a;>0t zXg>*%-b3>|pV3WqK2-FxiPQ@siDLQ^dP?L0l@VQMFW0-U+Lf17PD-KiG1j}Lc$6I9Zfg845yu!QH zm*IPz7UW}U=-{$zbne7#n%+H|)(5IZ%@*!qTFtyCd8`(;mwREwFfDrdKq!9O2V>jPK+?Ie zjy&I*$kem+s6@LJl7c+h(!BZPL(EiaRVzhn&z+?AHeO*WxvA_)&jwohRi9n8L<=u9(kVOYsnpct%zpjZ%9p16Gx8nJ{Qai@$G~bxJYB)Y ze5>Mfr0eiXM5z> zFqdwBQG7`iAJ|JGU-B59sw+?xKP3bzoPh28txT$Q1^xVSBZf*lkdXmD7yvCV8 zcu$8tHQ04yZ`=XA5W^{ z@Z&l7A_`-T-y<;cznM^bn+%s(dergT0zBBx`xdH~qveGYeB16JCP8F#>-R-CJUIfl zTjt0b;v^VV8O=%?1XL#_lg;UBCoabWsBxVU9Thc)O1@skuA~K!HB%1q4Mq|!DM>*5 zS`s2|`r`>XAvo`+$t)^H;QqBD3}}Yp=7u7yRX7T_nGkMhmD`HKT%Hf@pT9Kr;*R>-f*NBEO|cIXCuz@?+JXA{(*YQ z?f7~10qkcEV$8d-+#agM9ooDUdwh?vTN;5_bS+t+^~?zeU$oowDJ&%B#&@vJS_G>N zhl%-e3GTGvP1qK82)?OHan4>n$fzhrUgK$O{+x;PyPKgqCyhPZx(t~=LfLb>@mNFC zku&t7=#RoVl52Jztz%UoZy(3sxIH6#>q-UB&2I3X1z*7^{^oaH*ABdYvz-Vh?T1eG zbVQC$z<^`8;FjwOT)ejx1;=(WWB#_jW|4s3e;>oVyj0v$9!VC?>tNCLg(yBk@Y6Jb zJ}nEuDgSI19b!S(A8sO(&&%PzQ+_Pfr=QsM$g;OQYsBJaB#H6hed>DRds_;7Y+Kc4GfM z<~oJ14Wu5TrY?ty>aS3@s2V!cDS+O*n?oB`l#(k^_efmYQW}4LEPZmhi9PPBA>)Ti zu)&qL1S@WZ;YE-(UDG<0-ca9)(EQc(L2VS$#8x0vLIqd6r8zY|TlX_L8Bxjk_^Pp< z`JS1GojcX(+Pw=A_E3!I#H}I$`%UPxWAgN9Q7)@f$RsYS+SvI~7jXPr22M&nhCxpw z6trsb)+_-peG6f@JrwbM4>7h=2G2#CKq7Vv#;=`&^JDjlI)vHSInJJCc}-yY+2yQ! z3`DnF?!hT3l6(nsw5ivu;=ex|*ba?yv{<;ntuKRFeYC)K2M1(LsUdsTpTdD(!BFT~ zM2xncgS+A$%qW_L@%1`5QuGktk3Gc&iIMO+%zyUFMsWT94@Bbp|IsSsbHniqkr9}L z260bP`ez>|Up|b(m$qSRt}-S*P$P#v=0P=a0xR@COuhw7qRk0=u(Kcy4n?*I)NEuE z=FeohY8M33aceL(DGeuXoFmJIog`oEBL!9G>zGIVBhm8#JE%{(2$we}@s|YQWu_83 zl_zi~3Lc?+r7gA(-o>oD`rMDD2hena&)RSo;TWmLIqxpQA-N1})&aT|USsA=NiM`( zp4&M)m`Xftpjj6l(mzcPXz=+6dNRFx4rl?BAV)tz`xDj}NY zb8t{p0r~0)Y!3a%<|aj9*NuAKT7MJDk6vNI_8vT$GnZ@g9>*=8Z^>QXGm6Vp9mADJ z+EJO$wL}FcX#CZ7k=?v}Dz{`c&0f7xaHi-BNws=PJEY?9M6np``E{~kQ8*6m^hL2} zC|etoipq_3B5Q?cWF?!^(D#9~#3G&SUZP8rRsJ!$Z7Xy7%rm2VC*oO8y=ZExINru4 zAz|D$EahEG|4n#?y)nF>D{B!v*Gq8EQ~eP-I+&hR?WT_Cr)~v*==0IH=(OdwLWiB@ z^!v*P^iFRb{n2B^r4J`u_L9~E-ZR+G6M{7(Gu&IHjx0b#8_p3%pFwe(l! zG-20eY2JrbOP4v%6)yjxBwU#!qV7>r!k4!;;hb|ce4pEya`{(w&Lz9$rhoD~{H-=wOx99=rQR^Zfsm8u0y zrjm1F=xNCmqFb_#R*p)fKTq?Fg!xyHsHMtDVJf|)mW?CZ|Ki@hPjtQaVp=Kjha7*^ z&80o6=eWx;+=~Cca6$fGxGQ1x-0dkcRacB2a2KBBa!t-7xqluKT-!Kv&f2LMa`*MQ zG2eb*dSxXl=1k`XKhEXOdCx(}Zvk0*IGjvE8B;x(h2AyOiNw=5R4llOavM2vQ7Vdy zI^)lEe~9F^q+R1arZaA*S|FF})6Z?#)y}ntrg4)e#$t|3Hg4-3gv6ri&;ZmV;)D-Zg$o6ptO+zknXMdM*m(uDuUD;CZ z(B&>pYI-xbXL$v8_wpRxr<=sxS$2rC6<^53E?>ljRW0E>mPB&0*6TT&uvkuO^=JCN zOGN!g{h_%s-|2$OQ-nE-wS>Pm`3d(V%@dv*vrrfpa-JJ*aEcoo8ph4Nb%{$DsOCOi z3+D{SU*`_~ZQ;6a#Qu-CH;=~Zd;kBkQ8c3v) zAw$Vj5z?qa?sM&%P>Rx=W(^cYgGw5|r}tXFe?GspKI`{>y?$$b&szHr|Jc{w=RW7` zeeLJj*OE*9`LIgFJDc{u~At^gx$%Ey+_%BBRBJ$jFdVqIdQXsd#gqY&E+>?l#>d zPg_z+%(%g1?Gb0PqR*c6jW!|C9@50S#+?jpHz&ScK4erBuSM`#DCIyc_Si&~FFHDV$A{6*2!-k>X z1butuXqnk~Ts@@7iH|&tAMQrt3TI;#CGqd=oLK|1;0eID|>hT(C?+4p#<* z<6X~7+@m$qxvl*7daT=SthP?VtrOC@6S3FP@=YWbjOgN&SB0bD%u(<>!3@_-tQH({ z*afc)`8tLxA34{`9l#jvX38EcfwsY|oQt^&uFHFwHbJr|X-Xq={@w{x z_+>2U=)cEY95xcqEh*%3c`um6k;n1#+i9ZE-{zuEa_Ly&os36>aRM*-Wn80$izxPT z53{F#27aFe=&nXlE3AOon(o8NC)(mCjfeJK-LsfqOUGM=r*Ns= zW>oJ#gg?d}!v$cB1&T?`r`8qt@p>}X=hh=S*_{Rs8Cj4$?i9Q?FBYw+kVKOSrJ(K> zgQWu-xY@T}GMk==ux0_j<}n=&#@=V~^)xpekZHt?-+Y{d@V$&tKf$m1JR`1i6DHUu z;_h{C(G~{L<`+-UzV;ff63)lDDd(`VA)j#?$=5$EJit7j8VOQc5As_4D*|_-!wruZ z2`6X8LgM^d^g5}Byjdu>sKXfJ^#bsU4(~IUIvI;A`q6*CEfyzx;M`jlXfIU7L}L$p zI?EQlUsZ7T({ho`y2J6FC|J6@2CwjI|2biGj8~cmqpy3239u+(wl0?f*?A|K@Y80@ zfMiLO{m{>-YE{DEg%Nl!*8~%Hxj^1+4{l3y3A2OG*FV-eh^_O+;_9UbFeiC5_am+a zCogWn3k|7UobPO$9$$>9Qp@d2J*~OBvDI9;iXECc*`vwv0ocPjO@Pwl*ua(lKMfa5G z^qG@!km_FE7oijvKTg79J|FSkDW2dc#2feI>AN?X zXnDR6hlG`3TO(gL+rfK}uxl`YXW0Ha6Neeid@d>B5ag(;5OM8A!O;XUyw}|hO7+7; zPEz|}r`#o`_E;Lq?T*8@Bm8+5WF9_CN#b1dyqLQ)#hgTU32yu`6U`TV!};yqxG^?` zuLH57(Sh&q&bBf1-P0@lI`a+=@=~UovK0V+zGh}_2?6I|lTGKc4_T>XNf!Di?&e-9Sl!eVVFv>=<(?bFwS3{)UU0ArOr2*b(_MVRGmPKNCCb@RYLu- zbg)7f*g25IOFYPe~$9e2Omme>5KfweF10a$$= zXE@zsbThXy5jT3_YU@Dq;QatHNuv!mCMlD6?d!0$UW+u$X#{!CB9Q*+4{b(5ZZNY` zFmSc8AW#>f$m6Bp*LVSAKJ^rs?ns96B1`mp!{-}}PBQPJTm_!*c5?wQ%JAK~Uue<7 zp?>6Qlx4R-W8e{px84nPjYC1oyaleDIm3P&>jS569IeB{tI@*})1 zdjv9dL%?}dB7AbzgW<&^8TYIoIC*e9N-KTkiraSKtjUQuZBVJhd*!Q`rg;#r&!2*O zR&2*7>kpvAxAFY`Fdy5G%W-PI&g1O?r}%^LUTov@U3+iaqnvUXj`LH-Hx7vy!wQ(k z=Q8oy>vC+X%11X&0crOv#QpUcF=39#-+hE<`rnAm7VpBD0g|-2;1F*7xDAXx zCBWO9iLl~I9NbAMg?*DYxb<-%sUL=fO9yb|56hk-@ObXRRIjDrQC<#UEK0}nrO;% zANr1~(vpi8F)bsW^C?xL@k>u&pyOct@$)$TTIz=K+AB~wryUz3JF))l6MSrb8j}nS zQ1aLU)Y)9e+>zJ~PevF)uu-?*?q+1tViWC8Og{-y7d4r>$$iYYoK(~w_8D&%y%qHt ztJ5c&JFqA_9;Y05j(!(^a9$3F(2aP*x{L&H;u&t4`@3L(b~OY^>cG-NOUSzjIr7Jd zKO6Ei#M|0N&~rYSlbLpGv%>2e4VO{D9c{Aig+0@Yu@(AS@P@zt%FRA*!fT90YMfO;z$*n5;C zKhrUm3kAhXGns*(E0|j+cY?R21CE;2jTa<{=={rzTw(5fOtKk-{zrh{dv!9Y6`^?C ztO+FCJ0ZHy7~)eS&|*T7=)>9+Zq!dx?sK**rr(K1y`b8RbIhs6D-SAL?Ma{Jk0)=(%^<@x+=%Ms=b*8# z9d>>0h2Z7Oh_F$Xgf+KAt^En?$iKqaYrb_j-S4TAOlbQ)uA!Wi%_mmQGJEq85Xe@!r-kbfS$KoyM=BgG#jN*hRb_%@rHE+*Oml zwt9mi;{h~IVkmX3kHwV-`Fk0?5AW~zg6_Pp#l1^IX@JKF>K7_c4fHPInlL;1ZtHY9 z_oqMI_eMawq6}!Wj1PUSu#wJAB9wJu>A9LmxT*O&-Y}O#-E-@!CmG3OOo#$g->i?P z?HlmjM-}d-&s5S@5l8m5I+CpZmE?J6DoL!{MWR) z!n#$1$e+bOKy|bR8FYsNclk4nIX98Ij}v2LycSiE?8THk0d?9ko*K0A`}V2p=~!nw zI_>=#-uHGMu5%trE6pV!JmM)=xZ)T$Jk1Zhw&lPo^_$GR-fxV@=YE(e5P|KD1B`j0 zKODKZ6ViiU3VN3;1c|*Wu=*`SEDfiT^-~s*r}F$>bVUr2lvzPcw6~Mb$LEl-)Ah;b zuTx=8Pd;ZK90%`bo`R3c$?%Z80;Ags_~U8Bh2vuq(l2HYHFUaK~J=poe8 zgAG3Cd}jLML1F?AS0-{>?W{PA&y9=kfjsKB%P3<({oDo4);?sM!oU-{L^a_64tv9n7#_ z_f>}-I|P?|V$gWYIMKKA7^ZPYX|>GGXk47G0*0IA!S=nqVC9WpjPs2hxIWqme@Q*! z(l)HcurX=eqOLS-6kbM4!C8hUR|zx@?StK=rOcK)aS(BS2gE9kVXjO&$JFrW7tuP` zMTeg)=A^I1iRP%wF=Ij|BH=mImIn_0r?xG5{~5Fi4adWJqq%m+EWsnWTIR^>e5S>V z=e%Srg7T0|M(=1!wZWJ(+|I>$+-7MpPM&;%XP_O&z|I1ZOU^3v)IZKu5;t6(dlvH@ zV!0V^@&jB)e5#j7k&yV?X1GbqNJtDA!2k6>uE7!@v2b;o~s>@8hV^S`2{?!imR} zqa<~m7o(M>#L33(C6{-rlA}R;h|lSR`#6;AiO3dN2-?fPpQ!nYt$r+-7XF) znpJa7VPDNbnRu3DY1E$oT34g9+_Pq|VP#D~si-ETOs?j^_JW!U^*c3|2KZ)LWw>hfA9Xb|MLEsTUp!u%lpT7`Y*1(@!JF? ztrPP9<8S+K-anE4zO+|51~oNb(|8_M>eux&7x5c|YeY*>r9% zS=;%ADZH6Yx=s4v)VV#(kro|dT5L$RJNzL^J+h?nq%nyokzxPFU-zV||DVmjowe=X z@6NyY{;iZq5!My2Wrs*CAOUZbg@tJ|h3vW^>^S`;LeuoA?2xHP*$nIBtW!ZIDYCR> zf9cI-6IVWCH=W5Ap6mnR-}tQ;YYP8S{5EFh7XR}1^TL{6F7VgiI5MqAH2kCQw~dAM zf8zKD-*1T#s-($dfG`>cQ}=zk|Cx{5DEU*BkLhpw-<~Iv|GAE^v9PuH`#v}N|GtjU zbe}Cg#l2%~l~%IL*&X7)^ANRlQ|CYJ-^z}E9{!8|hn@%)f1K}9^U3B?jo;g#+Q0p~ z=(uV8)BbJ$u1Efh{+m}B2phlEIJzHt?^w0r$mGBMyAK*U@gMeYXKBg5&;E=4Yx>1_ z!s#(qww7~6?_#*6%8l^#dL|@3cVySSY=SE;W671hmmoMjmYB$g(SU#gdPBk%3|DUz z-HfrV);~Ldrl&t)_FEqSsrxRV|8p-%adE{ci4M3O^@IymIxo`I7I8tte&Y1;g`{I_ z8@X|VCAVF6FdL5Sz+KLg?2)!;vh-G5^*PV2oX_Pz`gt3ze$--2|BNmp6IerbL*z~J z<6RTp|E4XzeEKoHHC>6)hH}{bKtKZS&k+lkj-|rUW;pM#HuXuKM*@tciKOdD`r*oW zv7OB(@vU(s^z)v}xH%}4cKfVj%KUi^n{gg~Mt+wm zurF^vW>!1N&^D)GV)vv$G^=?T?y&nxR?l%4eoW4%rjtDJe$P)Do2x3$3j2kHC#CU5 z@Y$LHE5_E!&v`&K57bhTRTjzx$_NK>ZS0h}?qVigzILL#LG8Ei4LCXU8$Q3WoeL1_ z2v6g*xYU(xQEf{M>f~5^btb*z*8-Gx{-SWDmFIO(6Q;E*8CUH{sU2+Kd%3_Bg%r z6qj8fPu*W1gJEyyiss0Fz*x!AG(9vG!}grSc_XINsdqBas6P%`hN+St^MlEqlxE_x zP>vdg#n7SBmjri26;SW(PlAIdl5Z(<$(I`?q<$)cj8!$wSIB{BzeU`9H7Dl$Kq(Ba zGlXr6iy33zcHC@{!o22L`!;9#P;r|zwc)i?-la-pzC|tmzS55!um~c~h`GJ@ui=Tt zsj!r)&^vj%iTTD^mv~^N;dbyEvV<}EeB7ZXZyGs&#gud%GJ@#Jx8OB- zAgajjh=w^sfTn5Fv*zBZm^W`8P&*inPX)(`t3&TkY1RIVb=-UO5U zsn>}0(PVsBGn{nwd2@Cs89E;o=;;~UUMe1iuWRlV|Fhrf^RsG6z7cMjs?8JmWDX&P`-=NPex%t z-Duc9BMMK=JwPVOdXk+R#}kce4;uO+m(t<=eBIY)?7D41bP`sBTZBAml&K~b8*kDR z*LTsn3_Af`d(Gf`-Qm9TFfwAe2GMXo2J^`tTsO@CKBmPBc82*v(fBy*ayfzt z)7}DF$6?*@Fzm3963CXN-g$Mo&$%Xzwx-e0b zV{V#khJoX@GdmN;(d69Kcr`lLEiu$MU(XNx>s-g2_qoj)N;;vlrP>5QX-4; zW>X|uft6* zqH)tPT>@bf={JKRf>Wac;nXP!GAW_}^yU?U^+N|@9Hb3Tx9tJD<&<^wAASWnz|cL!Z|rbWDR`kJdUe+|d35?8Zt zcT0)Ap5=(wP3FWy#oq>3GOSO1U)@kvYEz89v8;jVb z1+}d1`y%2x;RqRB%8}MftI2_%y--zhh6apjKo9?N%v;?+R7dv`kC2nl5F%n;$`I3?k>hm-{D+(}Rg2jn4Rrs5ezt9(lyE~< z4}0`E5kE9>6kjcn62E*BB7U*dj22F76dUUfs|m6lQ`59&iI|yPz+JeRPKwJnupjT5 zvp)Rng&SFg$-!)jrZ#I-I-7Ky))2Qfs*A6ie4_RWAGz@tKEuEX z&Y)^No7N06M(67+xoYOjo|rM7G@ckt#{M*cAFmg}&7B8m)RHDE^avk}(Oo}A3U*N{vfkd4Ypwjs^TpCwJ^sn^8i=KCI#B>SPc*{a} z*lBzf8_aC@b_R5sHjsz26veNqrRl+IJ@ELUCAIwM0EPC02Y`2J@D@+H zrQj|qmJb$BIrIjP)med6pd8(^dN?g!s03RVzk{;f3jqf;0lyl>-A|5jt?xRa=+Q9A-I1(h+1C_Y2Sgz*wS8<6oH7sG z#c#1&HG?*88bb5K5qri<(z+fwayE~LIz$&R_1TB%wU%6pzYfARnYS={fCPyc@feGn z`Fu6$#D!n^c{cnE_K%iusg9|5cF0kH@Tp)N{0NL^F2lOr@0bCD#jw@r0E*jZ(LoIB=ZBGBUqV4>q>0?T^GFINadr1c&_RWd(IQ`w zNGMgoV6AxWXwe;q%2-dPJ2#ZNI*g)EtHL2@Xszhf!H*E@>kXH_KjXdlq-e4nTOB3* z!o@f=gS1{MwC2i!UVG97VTYWN3-RU}E387@m5TgHf0Q{hp;y zQ_Io?bK9+HrP()!Q4O{(l`sAJE9xm<$fbfVm zRGi)lNp_y_WPky4a>GOHP?-(Gns-CiB7g9iHkvwC)#1z|y>NGuCOLlM7MM+(L7Kae5aedg9GYUypHp8KBsmWtF{~j8DQ$v?yVscsV~&IGp$TO69UUBXCl*Hc zGSn_O8;4~d#&6bvu%~Pwd1)R-s#s5a@M|E33;G0CHF%x?Cqakw)#4FxJCz=>UEK0p z6=c&@asG;rsODcpW-JOPqfaIXqV9)?+ZV4FuPEY~SDO<-FVh-!E57*&Yp$@59b{lHc%%E}I7LaMa4f0d>ifa5f(%Y?{ zz`{?1*d9)XI~FNuxnV23ZEJFn%jUH#fy%V0LWlNW38bn)Q4plWGfBTC!kHa!@Z8FU zw7O^yJcYB^!E1P4WoqGw%Y)JP-eK5r`YdGn--X-C@3^p0y>L2gC-WxBijb}5#N?EK zYzfH%`S=E~m=n(potg{!^6J2L7^wqyuB%g1+idC> zw1wKHS<|gEcwS$uF0rQHNC{7j3DisAHP$z%;?+hvZR0FxoKyrRRsKY_{5FwP^oDA) zGMwAtPvrx5z|%ly@*~ZP$TpjSliU&-R#=X+)(oL$+8LnweIR@sn}cVSRfu(`4*fW{ zQ}9kDoAK>E0o8w=G3~rY_Vkcw7{K!>S3JH2Jzi&Ela4;Ao!<==vOaXB&tAqmri_Hh z-4~3^n}e5s9)=fLi;0QZb%tAF3G>fr;O+CL1OemMip&PpV$x7U`}oa8$p57A)T<}( zJbX4P!ybJ8sRFj@Pof3)1DWUB8M-VY9!5;s!djQiW{vvXsF(L$@N;U1zPrBQJMJRL zlQ8n&=1R8mlOC&lcm_34Oyv&8xsuBro@B)B%dpby5IJzyUi>NOwAg-rAst(`maIIW zLuSqT4K*Y86B*a@I4QzhtT#QCHdyDAN!Om@%e!Z&f3zemmKaG&yiYr-Xw6B7VEZnKe=Y^N#}l8N{64YgMikxWS>s~Io0h0 zF7ZG+zg>ghI_m6;i45zua;L?DZ2)|EIr7bc>~x>@r7OY^XB)=zn&>M^+@CCHm z^V*XSJS)Ppk^bWI7I8fT$ib~<@JHH?tejqlU(`ZHCqtd#{$So~X#GAk9=#l@wwb|Q zpMfw%ehWSr97^Z=bmNWKJ$Tyd3-=*$2$>nb9j6!buY;GF@O{N=nDI6NENx;rX{Ezx zI(#L3^fjRuKfHmRYqV%_2<2jvck#UOm(1t6n&f7V6Ft_vovtNnbPMn6mTz_ja=W*~ zQ5_NP_WLb*m-HHLM%SV2I63b8jLWcd-$SNn?{s?Xv>}Czmnd+zBWYUK!F|hhX8xsJ z*t_pC9@Ushe_S1f+v~G1fsrM9Gp%sR^*U7JbuPy1$J0X@^&nyvk_N9!47lji&kkX9 zXb7PfnvWt(Q>95&=4h~6pJb-#kPAAG(ZlcyX0}d*Cc!ciB|DjOAEQp}qfCj_VkuF) z+8gdb*C-tJXdGN8#^hsv2d8vq2pO%*;jWivaG42m7!tXO6#T4(txBB?vppARKM;5Y;*M|#}ogbiV%NTlMLminuCL7a66@rQWK_>1IVaCeD!+WjgD5Lrb zho2bA9o^-R%h%aq_R5Z(tO|gR5eY3f+Q%0oSAd0uyIayU-TLQ~M z`?z;93gq#epJ3T_5WZh463r>rFyeHIY{7_opSOmpKT=1LnCn8(76(*M%)mRrL zuxlh;=nvB#l3Qp(W(*oZSEc(1pF6A+F3sK`KHcfUs%U)|iyCf=Phai^`<%T*ILA(G ztM`SJM+_t9RgH>sXs2K03&ib>(xmv^ArSsPNjC%@h9~|laJ%y< zdWjFfOp7z{X7?Su-5n2S=ubvJcO<#$KOF|oI?4U!Spl0j#N&iL3$SF*QP|A0Z3X+E z6Yra*M03@4>YHjqH*{vwOyf+_^+K7v_lqN6Wt2&Mk|O=S^a2>0&IG@azu;a*H5t}D z6UG*ff;TP?a0#0V^%C2Oo$DB~Zi@n0+}SFSxNnbF?z?b8>tMu{;WSJ<2JP5;ymuf6 zD|+&9bN?jlPS%4IcBtL_CH!~Br2$6|{vlEfRff~6^5FUGZ3u0-jI7EdR5ag@u8$;P zLR2a&yLFdYt2-I0wtt5p)pww`zlHk{FUM>=_y_fFE~3A8n9{^=QFPyXJ9Lby#wiob zAoT80W_4;B^DOkPAh))#`t#BA%<2_2Fy=@QxXjb9S$M&y=3CH^8oS@g3RjLo%ELNJAMGmXPm`vp`|P{yOy;(>&MQ}9xQg4 zHASrUJ5rqU)|p;UlV%yyE8^0{Kg27VWoz8sZ0OVFL&bAu%n~=6R13~mWwP7Oy%HA; zkgM4sC0nzjCXc>-Zv#=&Wyw<$b*NuchxRKQz+L(^Gj~x3K1j;MCt-1D*nlwk+&yOe zJ87yoI~JsDm!ZQ_2hMg{5$;|%gshZ|gC*D6xQa8T^!w3h5U+X$U52}v-m>8&!NZ&s zbS4mw#znLuA`)f!F{?P6frH+5&ameL=WIGnP?%>+yT(tZY9p*+;p$n?xx$QQo2XLz z?QST^djVM24WXl6zU1Ex3!$OE6I+YgF=R+G2!A1S;BpQ*HAEg?#3|93%M5Ki`5d*9 zEg@_DMKG;5B72A<*|t)h^qPG}sSUn(tS~{)9_5Fw>XPJuU2_rMbc;Hg4uW&^{WSDazaGahxdT&B3sZ(Y(|ASbzH}SjhJvH z9dOch7@L2M+t+@8XWL$4f)Y;()_enzx?dW(-aV5n=_tWX=LJ-2NG`43(1wj=i(#y> zkVFaG$gNRT03(C&(O559Dz^)hA3qZ0*-a(6M&}^bO$Xb3ZiqOZ85CTU43<}XV2oV~ zdaG+=gYR{mIcXJ!> z9a01~0XdvSHLd@06p($uLcE|HvQ2i|K&6OE2 zt?&Vfbm0 zkzOtu?HZ4%8)l&6BLm|8(VyCME8#xgTfksRCh9EU>nA_$LET}>WW4u&2z4&QqlYdE z>?UPm^!@{&G)V?NcFe$8Arcre?gPx-a}g_fPV71J!s^Q96ry?GXyv3_!3BLAgq5+d z^?ov$!sm|<7d}I*~1bvGBb?i1Xj>X7*q10rju9V7!+C zxlgr-{fA6J|L#|)rZ5GAg$w9F%L!m1Ng?5R7HUhbqHcrN;>Q8@=yFt%W=LDmW6`&8 z!bVx5)Gtjwcbj6fQWGq@m;sHR8pNMz1>KKj;4Z)SaSTnK<3+nhN|1(IvSfLcHI5$Jk9Aj{V`^O*)ZaP-1_CQAd7y#` zIqI~pe<;^>Ly;Qr%s=wN03FhGVWrRrC8p1Zxaq%fT2Ce8Gh_mJIOYZX2%W-oclyzU z#B7?XVoO&Y-+|``?!(P@R^vD3G2pjt{4-*N$~AiEI9dyXHy+2%8BQpyZsX*he}&A5 z+c;p(8+fr-o%9`i16O@sgG$;R@RMiIH023QyZ3=xrfo-dkC-XyKYtcZyzgPQeGxO= z>W!#4VK!M|6-6?7dEQIMc~ZXCj%ZGcLOuYx3eJOI?RGL-W-jX*o=U_HE68B8CUW1o z1~1N!p|c|{FnXzDNb+e1viy%05$Tn4*?iu#val9D{cPnbgbbhmj$sW#yl6yGCiuEj zl&T%i#b|m7I-^&>$uCkhGr9w7w!hJ#-J4}mxcvvp<*KrA`BH4?;8vPjKdHvPF{maa zN}ismNN3iE6mvh6{Mm2b8_2GP%k<+oWHWk2thd5y{*2R^sTjY4E;mgUD^5`(^_%42 z{77x#zE`E}GQM`eBy%>s`s4`>KcOYo4;jcP+04P2ZPM72eIAF^odA#aK-}Odi>g`a zm{7g~oTCd+WciU9+9gGNcOHc9-wDhgNf|gMng?og9kF)#MbR|-m8|-0d-ki^bXIZU z9;o_cDc0FITpYr4K>v(d0KJ!8*vE}J?9(7EcFhVW%#l1phZQd8R?Cr+%kcD-0V$n z@Ib!mjt2V&6#$US!jyYRy&Nu1gIk%lKo5wnJK5a8Yn#OG~QRlhW&+1|(e zR2@zae+Z_J_b#PF`7y2^^NK9<+=dmMPtZO312=EN4Ln`vL646bO6UE)j#GbKN8dg- zIFN2fbR?vqPi?ozxYUY2LzST8{9fZK1r^XG8%es~(Uz-%~`Z#v9;n5j%7_KqMnx6R1nKT`Cs-az^LQDccw zyx43T1-DXka~Xb!8iK-u*aepB40cKO?eBFw=kbfkUt8qg2!O6oD2)lLxA>R(Wx8d$l=_9D{eqvl}02ISvfn$l8u~WVb0>PRcywJ2KY`*~&eu z9EacRbjaForj;P`97W z*4eSF+JWLpsvmMDeVe!EKYFJRCt42u)A8H?Oa1QpTPe7^dW7gm&~f_it&I4Kp9y=? zw~`oi2hixjJ79&z1dRUm7(zYAkPUjH=#cs(2L&5>@slM@ya&k`I;&YmY-c)6+`oSU zzUiX0_?;u(o^pWnez0SE=XcWTFRi#&dLZjdG8oN!BT1WkGWFI;#pxYYXq9vbt!I6s zv(uXK$Objedcs6}@}`+C>dGgUHSRQi!2ySZ50}uk&jabB;%C(1;40X1uZSi;)`2PN z9OrUjB5~9)BoFyIv^f7#R6U?bZZdM@{^l4u#qDMW<2E#!dm-brLY-7Z45w4qtcD$99$?Ewdl+1cOw718 z_`20v6s;mp*2*anMc#K;LArv87#t2OGc=j++Z(ue(|+>l=OJ37R14$6fxgRJNvcAv zXDjoe>P z<$6ca2x&2S{dGGDs?Q;3qg*jDxsMu;X(AWzs~6^v9@3jW?Guk%w;9`l7^7m2d_f7%ndm7=o<`JcnXFW1d^v=buhT^6_?W_=JM?1 zhCJ54a>kQk|8aT8ni&ppB5XQ$8PZi@?wQAURf)|YdePyLcwZM4x9k!RoyrW5-BZ zI%glqs~>^|MHKSAIzYcVjy`MwD448HqRmc|Mb@*)7&S@iJv@mF9%+UG*SWYa*&c7* zDj=T2%OEyJn?$r}P`6bh=&v0;m1LH zlZLqsKq{urL!U1NAQtU|%HQ(PA9;gG@wOl*+jcQBr?Sa2VJXQkG$JCJM!r6+fd{{S z@?KD>utcH~r#o(g5i|1PR?-!^B~c853S?Yf9S#@_0LeWT7yp1cp#u|2hen)h}=~< zipNxT5p(|eGnlJSE34L#YS*Dun!mRu3YAQz|16#@6iF|6@^xA=BCd6q0Vx^W4y?^h8Ew?^ueIE=3a_U78k*OJjqBWcMYWvb2Rv0p#!6rC%K$AzDfGAFF* zhi42m${tRf7d4@xi!QTyTLgJ?{sM7i?=cOn(Qr%W4`27c6Q=c?=U!S1sc%HPVB$SZ z8eh&*SuGW6X~ug&@wLdt^{Mo#Svnl5VdzMA8*+PM9{Q(IvhVr?Dzb?s{_*z2=j2*A zy_2DjKRM#8;u|1ZHjVcZh@U)+D*`%v<9{Y+u z@aE5?TqMPN0vD6O1Y@#b$$ENX`$=lLeLs2oejB~(vy&Wd=%s$=uTt3|I`rUf8Ft#G zOT?n9iEi5PnyPPoPP&Iar%l%H$prO_Bc%#^sQLuhMMpnad>1?G-5;QF*G!PFdf|tjAm?gTgU|*&NR?^iVmBzr#=5pq3{s`Ecw-(ixz30v@m&C$nFOb=Jn_E05 zfC)3c#%!3`0UjaenE_cA{kc7CYK4o-WDA4#a#E~ zc`zwp1nujYg`cEaxyvE_*ee;0Z#!*p$HK1+w}*wJ8kqtQWqBf2^MYHAEsz@eh_Qz_ zrsApw1X_&aHi>L-Kc|S_Zz+;vKb}AsuW=gWGadTPT!HXssahjcp!D7)F8I=P&TrgV zP+OD3c#GO$)w=o2n|TueomRumgaeq|Hy?&E_n~3#bVy$rfX~{iu_pg6*YkY_ct&M# zX?OdXH4&D)*YE+D`e-!$8u^9$ogT!PIDY56Th;hH>KU-h9R_3bGN7;R9JFg|!}lp> zAYX9{9)C7LhqM|{xt<3f4WENTUpI_7El)~s92b>uGsR)%t|+l9-(lG3YMdTr%RR45 zM%wUGaOJ}T=G;Lc$*_G27r*kls~L*mp8S6(I`43<-ZzdD$&MtWh$c#!)_LxOq_k8N zO@)%SN~IwpTS#T^k=a*@jL&l)BZN|~Izb8tsCRTX`=$CoXYG$x~? z?qo^cYdmyp46|g%TgLQ#4*HHrK-13skotap?sTmNewyKH(roc^R7Az|vN$(?8g;(08O3c> z@zkE_F#B0AnK(6&&({Lj{>nGLu;>uTo)M)pSPK|UwM6f{M#}KoPK?55+OUn%jq2to zZ?#yEetHkNwatdi^!UMqkJi!$_qSos-8p3E?Lu_>QiiE-Ht>5GTg(K3z|q>7ULJJ@ zpA%~!$k80McijSU%e@eO6TzizHv98^7Q73(Pd2uRqxPjTI{eZQ_7vR(+p9C#xks)t zRzC-bwa7%)GesP?f4GXO`!A3aO;f>JIRrya9>%@1)}Y^>+c>hO4_6d5qRZs-cy`Yo zJiJYncnkdL;;9aJ^T}H}?YloS4qeE)AyZsr?Ma8Oq3By1H$ z&jG}@f8UVdcD`@?{ZA@l^HwlEYzi^X=padd|AYH4_QPOd?EUxdedoABXUVH{Lc7s$U)C)GRsaFb3F_8e282V>$$_w-9xRy6?Y^b zztYf!6VYKL5p&Y2Nta11CcL#I8`^fGbmu#)L~A7+xh)9+B3XLoUblNUbS;Y97=$NAjKW@IF7x&yFgWdbd zrQJcG{Ng6OnmmL3v~(Z1i0H6K7c6A=Cl^wMgaj<(SPryRSA1*nku4J`({saaJFEnl%%;QM4IUGwcf64bezDEgMb1pPN~ zXq7oz<1WHhS38zD^X&SI>Is-=>V7;_oaCbv%D0{Awk%Z?}Pvf$?zg z-&2@=r-iV&uZTjTBr01L{``K{^ZOuT6&Aq%bPOKIAW1?-%( z7Y1U2VEmEmuvjYqQqF0>U!&(xc_;{)O&rMXsh`2~$v1fTpDCOU&4AD9c2F>Ch%KM% z;Ce(WIE@;DYoITTi<`(^J$M5iNQZ#eWeRpp*C%D2>=I%z}IfRJ1L|hE4WhGgJ>f+f1Q8T^UwK4#I+w zvGi?#Eig(P++F7jPn0_0wx0~^S1Sp6&V#VkO^7Y#{YzhM55S%(ZB}1AR6y57K=|6H zu&cI(To@jPAfYUHwIvk{SFMFzp4p%q+78{D2>W-W8uq5yqff;&vb&G(>DIbN@)pd1 zhOrB%iuxB~AvTd_{Jw(OKKy4qtdUc>BDnsaChU#5LC#;F4DQU5vM6_V2z{`Ga-kWt za&102uCNwVbe~c8X}#o_(^@Ea5J(faYUbqGL>O^VgUY-`ptdR!CZxr~k!NqAym=5r zQas>&nKOJe5o3Qk0jk|;XU;v3r%TU&r9UN&an;FCL7w+&e9Zf&9vro#lk~L!?nD@A zpUeTRiwSVd;vHNM(S%JrH_-Jv3yl?TKyq3jw!fOg2OProIBRa!7@ zDrJ<`KLNAk>FiM{OX!ha1zBG!A@99DT**Yx4mu7oV*5cp^AVW-dj$@)Az*NMAMZ_< z1)X-DU0K--yZ4rZ(|#*KYX1Oye=z|6nvYQh>;k)?AZSm0Oq)uo;PaLtfuzY6$a-D} zvmf$$H1Ek->N^pVw?@MA6PH0;&<{IL>OolHHgK2X?*^G-uvz#uO?JBgQR)fCwJG() zQKXx^KbQ&67mkPY_fqT}{&{c^y#ifdeuD3WdRS`ZgU@D z{f_a_G4LMd=;Sg!*E8_%)paoE%tJVzbcYmFs6fDp?|gSuBFu0Jhnk1wVA1lS%%o3| zmD(-^n~LU5RaQMv%~EK?wEzAOYjdqP~Bcz#dnLD+ilD7<&x$^7){ zX7;S_CsVdurO}juQ0a5k5~B|++>yV;`&;_R3ceGqVx|T}{Fy@2 zld`B(Pcsyn2+>hH34VTXgIv=a)bU6{*)%2@Th+dh>q|5F_n{kJ>q(@QN-<<$Su}3q zwK=#S4u&h!Vg9pq;Ck{itlriQismXL&QN;UNi&zE0hrM^pbqU4naS$wAX#7?`!4EIzduJi4Sv-}l8B?fZ#r z-Kt5-w;ZH~W&*|`ual-U$OyjP>;v8@O{JJbtMcdL z^jWN`*b8`ms0cQtbbvxjIciY_>nr@dF6ev-_Hzkx}=0`cS~j()c2#Pm@|I3IEWWg`A&|Q zOpw>kp~i>LlT2GJc5b64dwpFUoW1rORFB8N$ny1In0o_^cYQW)h_EH)e4aD0=@@Ja zj3!MZ_n=L7B11F9(Bju1Y1-dFqIxypozQtW%XxwF#Y|XyEsCBF@1&CA)zsY8k4WA! zfJgf;!sNe6u(@*#D4v_bu-n36K;a@d1cbmp#RK3aI*BS=xkZGxK7^-nFNk*iZ4g^O z4rDtlA?Z~M6VWpte%zi#_WTxyy!QR%+S*z0*uWMN9k;^CmO5tcz$Eyi(M~>R1W+$q zMHsK_4;jyb$-hH?Nv25x)fot-8dXNvGcXBtRSY0x2}`_8U%-mwcd&!cN{JTbdec7}f1w6-4MbKRpihQyL zu67X6dmCr$pKU=#^8`fDuL&<4AED50{W zD>l-@gxhYgSa=*4JFl6hT(^OPd2i9;h%&C`v$UDc^SF{1F{n{K4~0ghx$0(36cmTU zwcQUfV)AWNm%Ie+NvH7fJ_o#haV5lB>EhH47U0o41P)VDFsMKSotR(bTZIbewqBKb zC{1C9D+(^fx8vbox4<$W8ap-_LMObsWkMF(9w2CA3chWcl)RIL`#+E40TmgtJ;WPS`Cipn#T1;}coxqr=%Mo` z-Nveiv7}}kh1c>)e74#-FSy(V$toE+iH=-83e;4l>y2b{Y3p7J+)@77*ELOr>LHVwch)2+u7A+weQMdBKWNvif}J(~rCx9Ntivg7%#?9w>LVzrp4kX< zbLzo$dvB$-(kO%ifI0sIhVF%pGY=$Rt+xyJ$w2BaW zL!}MljJ%j}UF9%E!U@|C4gu;rq#%O8tS`ej`3!3R6WW^puNYdbaLy>A&Gj$xiX_4dk z)_kwzxmr3e%n)kzj*x$R_HyshHE^-z1pO<&0+f>l%q+f79t{8AF(M09?)PcHMgVP| zoj%?@0=<$FP&YLWUY?weQYJGndtMYZS*C|$ZsqW7`R(NAx{GM`ubhtRh>}{(b}XNK zgz8itfQ2*lAP45=FkZRu1nNSH&?$bB zQFzosb$m}iN_7X7xp)I_{^q|^cP2i`+lL8yov6PaQDCKt7k*4Hp8Z=e5by1?1GZh#Z>^8g?9RuF~iIeg4#K zK!;l&I|rG-weWm(8s_v%&{-c2QA5%H@Y0PcEL?Sze%4~s|$0xC(of2eE z`!x2>?;7yRc|>OJ&4$Z=CbN&8YH$jg!dz|eEIPp=4bd+V|9deF>$chuuPv4I-<&$S z@3;_Gc5eu;_b*1Z{cc!c@(cC;rJ}fhHhwTwN43Zia{S*d{O|oJE_ta1SK`IE>PHpm zw{`!`&?M{MF5jus0-=|QW7n9(W@kM1Ob)Z%&& zYq-RYFFnZ~x+Ko39gAk=YL~FCb{t5Kda)BK#<0i8LFoQ+k!5E`u!d_@S^ZQiHf+^J zcIT4+V4RgD`)c+acBRb-Ce|E5u|5@&t)hVs?9XD?i!`jZGQwM>fvCCD9T(RZV{DW; z9@?~@6z+b2QQa}P@yQipa5jb9+~UKu6ooP&pM+`PqAk$7Y6?rY7U82$Cm_A<6I@U0 zEc0@#Bx|RtlXIp@+(v$v{5^g=+Wb)F_0%7D#6Xpvk(o)au0M}n=O)t>erCVE^$+Q^ zz64*Lzu;^u5AfMqL)P_%cCijCx1S@{=5ydnj6VKXsfLZ;j$q;8NP6Sb zWi)g(#~U95aNm>5xRK{}&f%hQYRw=vw~OHI6={MfX+`cEPpfx%$>&u`BhKm9!3NK< zhRz-o8z1*m<%=EkQsOtbiC@#V(-&)A_`(J~uMkzM!8=u{?F=Rs=FGFyUFZ;<^h3yQS z%(?}gVvXI-uw!)x;hdW{JI30Ky_=@X799y=v#w2LXD&!V$P?w_l;Uwk_yc_Xd%(CP zwS<%()aE%6ve2QRj)R8;Xpp%XSAM=n##;PBvx0+YXQYMhe@7_oo=-CAG+fp6TJTiQ z9k$v2gDGo-xbyAam=~G^Yh5I{<9(gfCF?!BN}P{(6B5D0Mx8BUub@T8&Qdc6A$Eb( zTa3)eK-<4Q#Q&E%dRe>S-&1^>loj7yh{>Aq>Nf%&&H|D$eSJ9w9YWO+B8@*%<|)#cSEG zeO@#$_#sWO`~i+@#&T>yF>!Lb1+6dM(v)A>f>eDGTClYDCDt7XUWhQ1OqbNNm)|5Lc*dL_1B>7coaA83BQ z76d+=z#i9aN1;=@Q0fz~M|hw8tE1Ow<2xC4G}D^8=lbz}h)L{jX0cv?|W#o(N^(^gdk}<1n4e6sL4^{9BsuQjV7|nd9l2 zF0d5Nz)cRP1h;q=bM@kJT;cHqd;qT0Ecg?CKHP~_f#x`8@FV_7xsBHkrqF^x6^x)4 z_}_nlx$oVA7YD8)Go2!Iy~B^Lp*Zp=67T($<{B^f;+9$I)cf%z_){p#UUFujL8YJB zV|$DDa1}xSYb$cGPK@5_cnoeV-$_4dGfb|!34y{oT<7{9RQsJU`(u#raL*kizP`P1 z_TWaEhbH*yPY>pq3Sq#a2s~iFh|3>srN^~macSKTH1NMhR-dkcvUtK)M{Fk}26Alf zEIBryDh~c=DuL9s@8B!4k>t)11BJ<>*yj10CbipQT|*%rkT!wYt9kzZCJkKbj-b^p zMJtY|W7*k0kUuR(op>gE#A`jaDO>={avaMNf7H^TBp-CKH-HCC^SFD<-qCB#v*6hp z{!A;WLiIJ-uxjOVvYZBh<=u1;Q7T30odxuT+X=A0dI?vn=TKkoiSVG}4)r$W2wzSL zQyw0{z|tu6N_|Mi1P0)O%N6*ayd5m#@1F0qmcZ?tcc80vfoD}0(S}p+pi#;K>)ONb=1Ez`M? zL19iwKOCbXIXpgh5?Ap2BZ^i_a$ceScyqBEi5#lH6$(GldiqIR;%mUw%UWWVD4=kZ z828;_3S`$yvT1SE=(&ty#aC(ekghtnPPqh6|B3*;;zM}b_Zk!0I*qORFqvZti|~0r zpBv*n&^~$ItBcYK&(Nee9d8J%QF+H6 zTs*}K^YZSaiNP>tX}rPCnI>F?iVq%-D@568r_k$IJX(E=!h*Zm7*cZ`ofUhj@T($> zk0W$E!+-8mAzmGhMCTS;!5zgmT>9ZND%)ElqxTsNrd6VXcrohUxsSshS?FANSTOO$ zbv%5#8^?OzKdz|c%7f;Z-nsukW=o{dr1{U^P(IcxSxhoCw*mX?>Ba zCdTeR=7HN9ZsPEM0R83zps+;~Y>U4O>fKg=dX_XcUtIyrnoVeBb|14{i*mXD^tk3KQLa^m=VlEVGqZb@VaF3W@^RyI6g!|Scwl*% z6zUo=xu@1aQsr3qSGWSh^v7{e?HA+Z+C~&Jli^a2G-AqA6K;2wKKEYyC%zbr#88Jm zO!E`x&b3N#nj=D-M&WaQ{vO3i%cZ$b65?DWcN)Lce!?BMF7n+1v$&;?KGL}5Q}KL3 z6fX2M!IEPNa3SUkw$&vTm<;FgBJa+cxlQwsQAdm+Z~T|bf%_rTWO z2yzDg!6~^$fM{`c*N2I0ugN2r+JG>1iW~ME6(*^kpTPgIH}&7W3HD9B23s5Qz~yT! zjOf1r)eD}qY~m$U3lqY&0C8^Z{i~Sd+<`0NcjK;QIrvBSF|#-{AC*;d@JPfmw6>qd ztu+3EH!5CW-mn0}53+dJT$V14yNL~&vFP_{h-PUf2t>EZl9irupj1Cd#z@b`n7CAC z&g@~-sK`X8p_#^6W@}MFUxpJk6Tz>C8gNLJ*PHi>4?jO^yu{{oVXpYdXDk#bbIZ3oSpC( zmj8~j6FfJM>kGjzrLovFJ{l*Rwxit#e}USPNtl|}itp0>$(6g!==gFJ9TrDm9y=L> z4Px=j%r5eydMu~FEC9)0-Q=Bx7HJCYC+erqgY)JXGWVYZgq8j!YyNveKSewSna_M@ zPmL^GogK``Y!G5Q)?I-|CTh?$q{NoIyoU4bUgAU1LVEv$0(b6CI~Daig37k4yk2QW z{^QLJw<0U?+r$={vvDk^88?PYKQo5Q%IrY00u#k>t%vf3}SIJ2GCKEybiLS9GA%SY|&3TU?K9-}qs7USBw6UY4k z`q+!#zdUHdUuEgIe_IQ(kgYNJ= zjLUX>z)_9)_@-eTcRodhd;7;0CwRZY`}s|1D7hKUmJc&aKD`he+nI#Vbjwi2&kLU! z2$2YI#5l{@WUu;VycDa5+p>68*fcBlEImo8Yjm8Bf*J#{l4R)gaD;io9 zN)0oo!Q-f{sA^S&r=C8f8C5>GYXe)FS|$dy75w+#*hD-FlHp9L9+$41FVL&L3HRQO zV2ZLhMyq{=Ri|FjeM`b{v!yQGP`&`S9Mr{g`_7=rVi}Az6_6}#9~^B~;|@&!KxcG_ z!K-<*x$#qyupr_;xY?q>?TkE%Q_fqKWCYLP>}$l($3PUG=bCW3cQUa0@Es!3pvrBq z730i5tc7#35qQGtE~8K&!uF<%ara~*F>$DuG+1882R}`4?8~Ll6&;B|lWOV4VV=!! zFC}$pk4d{zp6~cwZ4;4QM?=HO;Vy$_qgJ5b3`tPNV+_n+`hg7KwzAO*Zy4>D zVwdYiOZOI!MlG zfkkS;@T>3%JYKjTI{hPwe9s^hZ1jTM8XYRqm4c&Z>#+A|97wm+qgv4|#8bO?4UpmN zBv=gU3Za8`EogMDpH}J2<8#?IS>;JTqWm^on-3#a~~;*X}l+J_2U%ZKaq!p>E^PAtbcd{ra% zqot+0l|<<3@qG8mhRLjlyCUK4J%IBKg%Gk#7Do$m;6&Fgm}vM2LrhPgb$uixj@9NQ zXV1fcHGXvCi6!`-+GAQ5REu5{R58tW5sK`I#o`xj_+Uhy4&*;W{laf_!{KW^yY4&G-rI`s>k@>>hT9`OI`mu4{F zB*6+Vw_$|~lQ6rb0N0NRFfQ3xfvdXO>D~u^uw(Z(RDL^9CJ@w!k2?0jn;GL^{?5}d zJ0u0#TV}8vf5y~bD*~^3T@bkIDp*I~7Hs!30haG=kH|cQew#9QHrFro+;tVtm`HI& z4l>+-I+|RW-8g(0sE&GnL}5**B;Q#&0RAn`@a60ya1hi1%kODdc(3AnhZUKn<&tz( zaT=&>`UW1Jvh24>05Z?zp!#1wY<3m`tQZjdD_R6TFCRcsk_?+YF^?SU*+yrTG>|O; zKCq#BIwa&I3Zg_}n3gzmqVtvS%PX4+o4Yb$_U28nYr#x1*J?GaY%C+y%aVy|oGcf; zYb^IVq?w+s$j9G-Ua-9=80wFIAtw4dtey6BHuViZ+nt|AT3HiJJMV+14JF`R+yqu9 zG0u3wlo*)z4A>z@SBM`!Q;@4!1pAXW2=eX1P~IsQOL`9BpZ(cPzSk>bzlFkVpOP_a zd8G&zi^uXB%O9rw?Ikk$zy~X46$#8u#URM^4C?gW#I;I7ocHgYxTHEC?^jKt?B7Xf zxvv>@6aDar+Az8KpAZy!RKR~r|B~DZ!-9&%ziHdE?R@5Um}xN3#?4Dq>DD=B^oHFw ze4G_tW^Yx+4DDWzPLhBZ_-8QWvjSuvE(L|LBJ4HpAlNQlfji&uT~#yQp{UR)PUx{J zH)g*q{AvFPQ`4Wr*p@#adu0qHD{!#2F93G`nU4i?Q=nRQD_tOR1yU4eu+@+IA<6g? z@jYq{2D9X-cegoKynIRDq^N-y|M$MOn8a2GDX=(w0UVMPgVopkp~(wS^ldPl_V*U} z-4BJ}$bV47Gi{qX+Ti00S@yT^3fS*Bf$jx$-Vfve9hy>*ae5GNQ#za^)2VH}Gj(%( zfhAYEagEqG?jhX3L@odq9eGpATE)|`i&D|)tq>-V;#iv>k*^ZV>C#B%WX3LoVk5cA0I)#};KY{&fSH&=COd zUl)_tPddT8X#oD#3{%~s1<>uD14o^{V5dM5WefRCv!6M-I6F{}1TRo~nn$i#9wTRE zW!U1bK@6Mmhwx)0+}QLIO}0HPb11NbYZ>?H=U20tZ@=B>Y?obB^-CV{n0Xg06%Fa4wqH}j!?sstN$DG#^L{|?^jMy%DiV`QWE zGJw`H@Z|68hlxHl5DJD;cLF=NeP#UCsjv=HpVFe>Crq|TJd8_-z#VRzY2XnFRe|Lqo7z6+9nk@?kU$Tu3n@3~tcom>Y8MtKOMMle98$~sRND90s zzh$e?Zeurz&3_JcCu8aT@4H}8x&-@BNSJffR>8ln%RzljJL>RHfzU}6SRp_ucli`%g& z+Ko{7?+q-zlSsN&=)wt!FYqX492tHt4&l+B=wGxRG{3`r}28(?qd@K!B?EYby^f2&ii5f z)i)BBZkU8MlTzW_RdFb|mxLo14KH2r+B09M>WYC*v2EzR zsvdhphS5RnE%D$xE*U>*)H>Bjgr0lTPnnfeX4$l|DOVb3v&${`we2iU>zzl!CrGoV z&+Z`}nn|oZJBiOTCqdF>ak8w0(p#E~uAGmGY*>epBdB#PFLK-O_8h|GiQ)n-(ApurR zJPURz=B8#s!m;ZhzghuY)tX@%zbD)=;)LR#A3#2L21+Di=x+UN93$j!ec~c; z*fx>u`?nU=P0x^Dr!(nzeztJgB7(sR=P)H>4Rd2dRoT&4H#9Diz^l5VM9)+SKN`GY zj{9gq%SLJTCC^lUADs=#WqwfQqJSIsaU?BL8RjNcV(V68bg&*FpACZP9#MB_QCb5> zOn+0kbZZjkJ&8S^F`qmpO4Qm&1}u|<>4%g}NFRJb;eFFlZm5XbJz0Q9g{}+KT6!2| zelHedSVi-%uf!@XS?#9owbV3b3EuG1p|g}HQ(4zz_}Xg>x;v-S$h2O(ELA74`uLk(6wW7y zt51<-8BNSREi0_mf?g?*(gL}5IUyB0S zJXVFZ@3jTV-WEnA@+@3R_Tp!%$q*x_%^o5CAarmsy#1X7wc4dL)KCwod^)||=*#o% zk6?A5DraOIM0YF_;Io{^SQXMwtPLHpP{NOno%5MYZ$3+R`cbrAA_iyX?-G<`T2jT~ z>mZfvNXio=aCJ@&UjNQ}#ODv;ZT^laSS`sZ&K$s4qkQ^J;tu#ctrqOQyAnE7{J|mA z2v#YIKx{w4-n+{o|Ib;P|)e^tV0@hkKsHsZqwqT??&hT`y|LV*$Soa zzR}_iX{-pYprOMeWMk_Jtg>~%9sF4ntyoMYPCC#qy(!pM5I|;^uYoVyZ;|JY)|kmN z@KQXU(b%+Q%vaS2Y>Q6C#=G}P$bJTIUylNjWk+G;dp$f|F-$gVDq@_!D9G*`g-yz- z&=O+LCU?(dEhlxusRj==YEX& z6`Y^NzWHE?CnxN~(0~j)`8A3v@;(OlGa3+=`eEWEG=S1*YdtagealRa+1p@*lT zQaKyXq7iM(Or(#$2Vs`?NjMiOjt;};aCNLOm|IC;e3uA$8f?skeOkkHOjG3UC#!N( zug%~-&yfU=s}i7ZI+i^#=Wf|$o^u$J)(M8MVqsZ~F}viPBr9QY4@Nx{aOvCoAeOTf z%HJ=By~POV$CA>b~*$093-r6cs3-f zDYI>d8VFukMLDrz-hcgs$OTc-=OBUK7y9G;-ucA(^HaP!;g-=Gl`wqK7Q)CZ7vVbl zbkL)h--R(d>490A$O#TW)4Fqb;KC6sEsMbSKfYpKN;NLNeS$VLHlxSjCY8JeQ@HeKf~Kxb|$ zzfVhmy*KWX<8%?&-24MFg?*6SeFvt^-NLHmSK!Bwo@D&4bTU?XCoxwVB4w+5$gb5a z?ERWU3jPK$N7x`#(fBA>?zM}K2`R#0N^%xr)^{&s>9vsetnJ zZLoImB98qp8#eAg0a`bc$h+5VFvT(neD;%;|*WxN}OTdn+)nG2*tA>SR614!bPT1T-kanD%zuf z|I8e*`QjB?a2`>S@57#cVFw=dFyfYP`-{0}Cy=6b5g0k;8sB;EMJ~nerUp$~Oo+WS znRuv&h8|VLX-@*+aL)$VwdpH8uRTC)n~tEu>)GhnP$PKO^98>T%;wB)24LKbaNKrh zEed#DVe)%b=yCIphT$93;TDlN*55b53UHWrsN%5o0(D?cliB9q* z%O>xE7b~=3@*O9%l|KbH7iYoeIge1>pokXlZ88o&xCYyOpOJMEyW#Dwzk zE=DUnLd!`mXt_m}UVC0zcJ$&Q*r?|K3%Cgw8oY;OMUEro#oorP%M_q?tuH+S(`YM? z;5^f84i7fU5DU5(iseqjxuFAa#zIuE^ie;V5xWHYOcv0kf-tx-`6jrnI0#mKkZ~sTaj?TfFgif-~=OAe0#nTggV<5bUf3NM1VdzmkFxg9u z*DHDxzfrr=SNFe{Z9k7>(c*q`k@vJGH`GB^$R}ui>IQywbK$OG8*KCVKyo(m9*)rz zx+(TDe(eqwO!0h7top-AyyFtwD(*)eYtv~KQ9_Nsl1$)m3&?vdAZIlr7`?isC>Bft`Oa}45kc5_R~#1aIm(CywWERlv!uCA`L>PG>rF!90UBSg|IN zSt%(F5w#znduRx@9hgEPY$}BIrNCBITX3`91LrdM{-J^$U@n;|NV_EhNrLO7R!b7+ z_t`@G+6W91&&Sn$RiyTrGU%o7JP(6mvV`|()+hNxyLK(e@_d7UdzFI7R=xu~(ww~6 zE(e8kjF~`wPiE=94i#<}Qj_(wsg?W&vUz?U8R>{3=En|TzK=I<*-5cz7EVd~kmkcOV0dVd`7_Rp_aTU|Z_k>76%)t2ZBS&3=bM4eB|Zz; z*9cwxcVT6bG_h_M1+u>fBIn0Lc-b3Jk~<{$U8r7mS5kysZ@C7Z%Id;q7k$|5ri*%c z4#a!FoA(Mw(S(k4l4fNDCP7mG8z(}-vQ|jsS(pyKb%ML6!{LSaRkEF_qzmf1NZz3f zxGee-o~{>%<@fjC^jkMDd5H{_^&)7`2vBOQ4bMB9fEl*QCIr`K(+BBep)YX~t{jwxmy!?3%Z{0F*|QIGukOW9 zr}yE-g(LXe_XqyexQM4#jfXAM!*MD3hM&(L$K%JZGmn+8<7eB|C{?G2-OBk?+fNqk ze+QF!6W#EcX&rrMBuq0s|C0Fi`}w&}fh=Dx0~-AITF|%!>bEWc{UZxtPuvC~O|C;r zR0o;rUdL-B<=~twN9*H@iCy?m)nz;dcgYe9Uo+@l%?mREtI`Qt<0F&+e{ug$+&3bacW7 zGTWgCejcNOYO7b|+5uhSZl6S2Kmdzx#6q~89Vo2(K)mE@pu=G=+L^v2CpjXM9+PM1(zYZWFr4_9c$a5E+n85yW%pZ9cgduades@JgWpK6!x;3L z$G;JcLui*<1r2}r6OLpkvzs)}kOoaDvTP%P8Gbi#Ki_kG%kCNx9UDbOKDaRTR!E}# zv+&9LSSS5u17wV$uKud&XQDff-n)vSt^Te*&xJ|Hv?{~5nLywlL`$Jcr`Vdsm^ku zvXMEka8wmrE+q>5=X;THYppOpg3nFpn^EcQi$KmG7K9^1;lBp0(((t72=nQhu?DL} zWMiI|$+nx)?H}ILEa?!G1_?CC52C^O4W!j>H*OY)apQvh@af_a!E)2FT=gzjbWrQY zZ`RYvj(7i|pT;#bKJSl*%`EWsYYTX>)svhY4kc^LB#jSN^Bxu1A2j*6F>NT=fvSD6 zs3x~paKXh7*@av1o5u`j4mStY^hJ=sO5*5GVfbbg0H22uJWflXn{)&m8+Qt-|B90; z$fW%V(d0&hDB2awg#lM%m?wXZ@!@l)2i!8rtVauR(d#_epcV%g4n3on{`iq|y*aSP z<2vm-WdO(8{)06CDQMo7K^OWTr~gD8aSERW5L2(Bp9fsAce^B}>B$PdqEsEj=U3-Y>XbWaczKHwP+nx%pnbK3-6i+V`5%P(rv z>p_lud0YPpibzhCV!UM8ORmVTy#GWz6&_;Xxk z5C%TJ{%Gdsi*mJl;Aju8dG88ExAi~B*jH0&SItL(-SAU^y~9n|*eeF}HU+^{w*w$= z?*)&B)yd{Dio|wX6uuk$N_6>bU@Dyk?!8TA^T{-LcJcw7rT-W~Sp^73OoeMAi9|&z z9$c54hPlQ6qv%Y-v1+?8Y#t&iM3jt$B5A_D*VY_KgQB9MQX;*jQkp4qWXvq0WJ*HF zbFXbklp&>(C>m%`NlB8@x4(ZKM}HKKXWeUE*LgOPjC)(4sNEU1MKqDoJ`;E~t{%J} z^%A*#b|{@Lg%;}qpx;Usqdy)cyE`}G_i9sI;gU;tKX^>S4@{$9`(b>72i8V-qeEN~JPYLenl|xt7w=`y{>=Bx%*TM!b7_c+Q-i^-)!3c- zhTiP(gi|xLz*KA(Ovx3e&fgex3rnSDV)F3J-4q<+9pT~8M^I{!NoGWclgxA_lJ`BH z#_QCQ&Dl=`b3gXueeZktaJ&KkwWXj$*9AVaWsbkEM3U~T`Did&hKqK-!0a2pQDlw_ zmZ>hpji+J-j}=^)OFnz?_T0Qe+mNK_7b=s@|qNfb`mkcLwYPDgRZbsrxIDu z1&N<$!^U}AalYzG^YuI{7c&8+#3l(g#{`4$vSMbn&UJ9pD}s6R*OBazSMLHHZob z1+(G_aCoCP-lp%V^a%&(wHODHt|NjC6GEU@c@jE!zNZD%g&;AWXGAxCfa8k=^n7Cm zHvDL&v6K4Am!JarFGL02F5&%5C<*1Wbja8@|6xzt7SNoKKqdCHGXd{QsKjwONaN@7 zl~bn(q+VyhosaWr*Jf3!bsoTWUJx1FC}Doq^%dbPq|qvLEwm?zvhhC|RC&WYAwBa+ z>iKA9egH=m6B|oo%!TM*xw*u6@&@qxI0KK?13hiX zb{~Rj(>GA0VTPHiUid}51Fm?i#M$NcD6P_n%?}mv!qazxMLVyX@5omZe9!tP_*q#; zO-eGU?U8W7m*i(SUE~q=?|VUo?{r|<-p919_BBb|Ai#{JIb>|}LA)}3CFYndz&)#a z$+YJu(41!syg98vABe@{rNe2MQ5=l+9p~tQO^e~U;Rd32(FHdQSkZHCgG9H3-#wnP z2a(0P{MY%Oa6#T=b)q!U{jnVv4t^^ixR{0=V~WW3BbvDHL<82nT#ZqRDL5?ifv&&E z@6>kP#?M~%_$N6H6Zik2ic-O7(^N<{NvR7)ua*0!{&>PwRS^uYGyd+@#53lp^u z16}cx^zAW0o8fXiX&QpcOB->?)`^@86%)MpxC;Rj2cXM>D}6(0LtigTib zxNkGVup&%>3$PUCx+i&ItN?JdhVyq} zVUsV6!}Uh|Z7Ivu8qVN`hl=t1D>vR>xQSb?;|o*#?lDVilA%#aig$61z_#LBjMcs( zVy|=oZpfY?V_!Tff4|DvY+ZFTo}5*SuB*{d0;FQJ{WZqISR38?CEBkwi>{eks|F#)S&lf`SR&91? zlneWC&vl;bEy8w|NwHQn0=oXN4TPGnp(jS-fM|-rvPe-F=W!SWsy$?Z3IF+hkfWV` ztI>9O5)mT&g7bF*J`5g3IluFm`TZwq+1#e07xM9Wq7~{W2GQ7bL)^VXjW%o~B=ycy zMptYBOzkpv3Pmj>^iS;p5(FJ&-8XEex(ijO#uHw~v6zzNQ-zsk4i4wnz@?-_=DX5^rKcYiP5~ z3F>fIm^|>{XNsdGybpl?-bC<@0e0N{jr$-m*O`w{3fzU6$36vaJ@=i1rI`r++pk4W>$AHIBAi6F4ul!1pmHiM)q1e-kLd`4tj);&B38(&u>~vuBWv;~3m&4Fcs=6@EffC+t|oP`GdTh^s%v58x(QJC!;yaZ)lZrZt%iNJe&9`? zmv>yZBgTuSV9Kp!Bu{+}1hmvq<<(X+F543Y7Hi7qgoQ$_XEGGW$)fx-12`O_2J%p@b)<`nv!)0 z?DZt+yMK@9=KDKf%wsL?#JBm}`lKhAKlT@y_E(Jky66nH9-V||gv*I!oe>1J-lNG+ zXVV|`;>;JVDzJaZ_b_BziPOGN+`J)x$Qx%s(fx2#+Q#A|h5x{9S}3_R zNcQ>G(3~G-RHn%tA6!U6!)@Eqa#1=rR z+^D;Vrn3LYx{d`@{qA9$vHCAjb!h~XTdSb1KHoe+rHcv+X)=d5UPeWyNYoRzBx)aA zz;90!aN+4>&Z+O_=YH{QmKBePV{HWbUOj8(dxn-BXjTB(Evu(NLWMMFt+(Xir zO@q$Sv(&HCm?Ly}y!4lFdT{n>T!RQ;6GRvVxmy{1p8Y9BKL34AV%V zTA1j5k8GG5N517{!pioe}R zv7qKv=CI>iuV7uE11_8xz`T^tz6chF)7EL$7J4PLE|4~NScV{72Q=FS6J^^jh z%Bc3l3RJL_;GUPMql(Z&`r0HCR~VNu?#vMk43fbuxgP{!Jl|LE+Xpm?@5Q2UJz5bF zi>KDl18-GRs`D_A@5s4;)&((cUhhmUFOg!ccy{>(KQU;TIvXS!f-t=7CAoKc69^6P zce7*SVAPcW$BvK3jqelCN-L1&9g4(C301E5-wAY>JdArB`*2I_8=UoB3x_o%@xX=G zBqX|s4tvXUZK)|VdFLiaAfgRb% z=^iIHiaT+cSQ3tH3jxV-@A&S+IgC_0Bru%Zg!cL)=*f8F_{dx6n6U>&Ua{=g(=)lB zljYg3Z+bxeRXWz*7yzA_3)x{^ExwEV8`A&Du~CK|_%TbJt;$nnSMj;zA7h_DO|&XI z=ePyVQJn?Rjn9c-O(Ct7Gs1zLR`hyz0iDCowp%^L=_}1p9H09D*+*jZ<|!ra{>PVi zesvcfkY0ve+L~OxV-e(Fih&GlO6$d!7I&%Z)LTq;cK|=9%n|%`QKgR;=HMn_#B*9I zXv}+1Pn$hMFBea8!!86zLmlXZor-8sJc57fU*Og!k5Tx9H226U2fbGL(uibfa9i#R z<$veV%YWL+A1vB{B`%s=q`@#g{jSLk)YxO_4rdg&2Ex9HIrv^Y8+Q&l;Hmy!)YXMS z$#E+P>8-^0&d<=O#;}!*K{$SK9gK7P2Yx!`^yadkFqAX^!Us2?`K)SKUn9=Oz7?n5 z-Xd)4Bop@VgX=iP?kdQKjb&5)#*nlyXa1k>0Ci0wXr3p5<-bdrm*Y&i>}xgX(bSEl z6Fo7npoYIAFQBW^q;XsMM%1t~7M!{!&UM;EqZZ$Z$ZE2oE)yPtSIl+(4fC!1$qjqb z-F^k6`L~&hkP&QjNu@R}&4QM9T7b%taBz?#dt~2|?VZ!$(LV_=f2lHzev8D5V>GB!kF+LblZUxx<|N^RGVqR`Ayg01^>1VXHxljZVsH1 zkj2yQYx%s70gN4rA~GgQFe^ueF0K#Z@4xe5P=bMbmkNpW^y#-ld?teRc2!LKWr6;= z7hp`)F)H~_jMQ1}2XSQsV*G3h{@pVJ16vgsxdkrFiFf>572iUP23F&gX`%ELhw^>QoGrXcR%iiD;{Q5B=oGpEpF0s8r4;f6OCmwtt`OjZc)6m&?TlgsyS2siZp+wTfvtK5} zh_K= z>VcC~@6T!yFs_d5h_j$KuPDL}_h3i}&Y~x+XM(%RMRG4v6;kKw!PJxU;ma&NXkBUv zeKT*8!of6V?}TL1eMAAS%i4hMJxMtEs}o-N%Rt|OMn?SbX1d#30h^YeAunaTQ1s6z zy{Eni^fOlCg-rpZ`jsc#_LGFS8MVy!m|cLji|M_=6&R?M4s%!9fe90Y--kbf&ff9t zN402>@)@C3t@(&iF^oiIJk~1+L&T;$qH|~wiE|yLB=bHw@~aTC?kbS4OYSlr{9R{W zTM87ox`O?+JJ8K%MMhQPa7*7q$kp4*XL7WmV8W)d=r4cG7q=V2)&mo8we@5e`SXn4 zG989>mZ#xwQ99&FeuCXU*T9X)2%>zymu9zEgZKRNuuSo~!0l8v#54ZzaBnf3mWhRl z#;0M7$wItWag!RaJp>KO4B7EWlaBeWjenj<34VrNqNP)P$$U-zdpqa`doRDFg%iKf z|IA;(Z}p{cxTcNRG%sbEm!2lxqhXZ#s0-BNZeg%jE=I0hfD1lffxR=Qz#2D6xc5(y z?_Hb2&W?jbHU0#Fa%&j9S7EL&`w@*keh_S~Zvrp*cxXPmo>X61P5olkkm;-?Q&%m5 z7ea~9l(z?rKka3pB_4D{Gy$Hf!oDr_M7df5Cd^g_rTR`1GV}_nou2c5l>w*Cq`~;j zcrcncOfq>^X72k4ob1HmBMDxYOHJNq z;mKHMJapO=J+qQ9{zc~PiBEIL*9qN%<+_LII`=MO;IRf?XWyrNx+kcQ|5u3Fn#((k zD~WzL-$PY-Ny~y=P~`Fz6m(}(>&>;8bp0RBJ8+F!;!f;|(89CQ$;@3LN1Q75o7tJ{ zg_Z|msH09j8jX2{+YB0Mz=?CDBw~I!t&oE`^ZLNDViNlzT#fYAq_J5SEZD=x`5fjV zALjBAJ*v==MAGkFf+l4>c3a*p*gUrYhP+xK<>?nNXz@qkR#P%%fM>hpInuJbw=w+L zJ|@;19H!m!Raf;!QKB}!U0`ds4g~O zZ&^=dkL0*O_V7k_dg40vJ^$7_74!hVDhZRS99OK*_MpG#2T!|$Vwr88 zKvrrjXB1<{YZGhPKYP4k4THD=JbSd)`+-Ht;i_}$oLOKvpG2U2u2S)DV*)ZBD4aY(bm z@1~;s?Wi98jK-pDRRZqV_8*pt1(lyP7-pI(PNM;y#`_%yP{kz;Z$!_;zED>>>su(Z z&aDgAy0(+k1O8Z%EJFX9@|+CmBuuTiNR_?$o9KIA+@soCzJ}zIzRn-a!`1(AbWU*Vt@2L*xZ~5GmCtnd<`Yc z7!SN5^be~N*Px-`n_xlsKkB{q7am>nQQ$n|EtQ*jkjqS7$tCuPa-}$(`}oj;%f82R z2BJ=3aaJDfUh*GieBQy$e7A<%udl`Z9lwloIWNK;;NKOW{J&t@@MqMr9i@VYx#f*3 zm*a>1GF|B6GKzTtrETy9Z~0%x{#I%oCNiE|$4z$25VaIr6r;pe`8xarVWWW;QE4|W8* zq^5+QVZvGAoyF{&K`D0CVG(wUYYf|3CBydjRg;5+l|6 z(%gmR$GG_LrQDi#>$rd^lQ{1e7jWHP{{KX78^?pCx%{(xIN2-fIg>b9?!Pc~?%3XE zX!qO##n=}ZXHfwjTH0)9#$xs+axgZ^fnD_aAnQ2412(+A1642d*fYz$I3HBt9)t^V zmv{%FceDtnA+N$2^Bf!L((M>LTbmPkJ%h85u;lFG7jxFXrf`XC)^m3*^x~_FVfaW) zguD4^J1%EzxPlo&xP{+?&0;rk)>C?Lx)STLleHT}9 zl5&XJ%C~Trg9f)b}|WL7$TYu4-Ln%K0Q4+ zX8LxFI^Rl%$F^g%ei)q<$KT)icedfn3S3gU4EvKNbN%~vaMsETxwPZvT*yInE-J?# z10;&@N{lbx<1fR%{aT!dAPa3XThUB=GZz*ai4UA6aJ3pQa66y9^)D3Te3_-(755!n zW9U1c`#ORn1FBq9P$Lo_X)Zo$47cIVQ`)?73@7`I;T{=3LpkG>oacUVPWQkuoWvP$ zI-Xb1)Ts&kl|P_f$ajp*s>HH#F|N3K1HP#m%gK&=i_^rP(p_ix9`BaN;2;*jhW%#( zm$&M%ZRw7zZu~sZteeSxw%p1(#f%V%FTSjD<_lJ$-{_HeSsFMNq#64oo z%*V>QfH4<#pxm-#jGWd<4_fW!-|WBXdw3gt@1l#P z6LPVO-{nt_ssfez8azAxym@5)O+G`j8Ny?<@P)n&aQlnta@9Z#AEyJ~|3=f&A$@Y5 z=L3E_X$}t?%b72`*W*x04-t9u7e5_S<6N7TLwxZFT=f-ZAAJ4-g|0#@yH1@gkd1>} z=iiX$luid<9HY1Dg6R~QVkU|kqK-A~%+amFoIqR?3om@e;rGw6z;y`@^k(7s*qb!- z$q<$0Stc7S)wp<`V`QPBgv1-76#!7 zI<&B)M9}QS`vtx|hiO0cc;A99J1PDuq)MdIdgBn{_TMa;UEheA_r=(qHY)5^^%^KJ zehMX>;;c!d3lwBFg6|#)kV#qxqsQ_f;56@xnkCN91u5Vn+ zmN#m!zl(g?!3{?2ynP#?>-82~92!MsuBB6 zjI2na&W^X3mUwsWi2E13R$T-2JdZ=))(0)`N^oCY_@2X$Sk&D&6TNM}kR*HzyNp;f3tRR$+f7bgjDQ;jUm*3?E9lH>f}5ij z?0mjM`(W8zcG;yZ>?;1<7Btb3Ey`17Pq}S}{W_D_-B!&oq+Uc09`~jzPsLzNtSEh@ z`;xY=-j3$30VHA`&(u|&OW1-sbGx3s)Oettir*=P4!1xw34MiQ77Potdi+u1bTHqq z=esraLQpCiMVj|Tz@;K5%Za3=KEtN6 zF!Iu55B{}3jau)b`5xnZTz65Ez8R+r5^H9n!qV9&8Gi}SH1j*js5&BR!r+{9>e$=z zhTy!(g7+Z>kn~r8Ad@oL>Pm3d{q0!wClQ4(7?VQxF%F;Pp}cJ`>`8He z=!9fU98sh@gFMl)d>7V6y70HBFU;gKe+8;8H8jwumButk<8IfjG)8MN?mNGPhP{{w zHX*e{tM&mNs4B-8ZyyYQB2IK#)}z?evs8M?5dCem3u5!t$-l@0=x(2kM@+*=j+Q(e zD_Vl>!=1EqxQ&^xI2IJ;55Qd;086)8!8FGh>Y2G8U!B(>wWY5a@$)NDtS=rHjqq=< zC5f1CYL9>aKBm7CH;|QnDr7kBGd-~JFMY4Y-@#AULLzC#v&&S`i@&A+_|w3c(i8ag z#Cfz);P3bnZ;8sA%itfVBiQcrjPB>V8apMOXxh#uteTaMi%t?Kvs0km@3ML3hA3o& z|Dm4!+pz7v9HvB$M|ZicydPsW(V8G`USZ3kQB*GG#3>125-c!uSfFKQIL+of^OyPtT$(S4_-bNpshQzn1?5WpJ#J!At7CWbl|j zMlzxFpbgKUmA+1Q{W;AnmfB3BCM<-sgm&|zt|cftq=iiq+em;^1n#)JQ&3kb3Y`)c zh*Fs!oLSXFj;TH;d@l)QKCYyab%Ex}QpMPR$Q@^Xk;90A3ZzrpP)O`K{%}5qF0uPb z)B9!kKH3Qv`S`$5xp(A+xgIKiSpqE;%7mNxh;(d?z`zGNv`{z_TS6qceCyZ93J;d2 z%!x+vu@C9ZXa$y6@P83)J4xbnWNV zWY;VbHg75lr}>$S-QG*GESr#dQX*(D5&{*`IGpuj5uNYF^Sny~Xr7e=lOUo8i9RtX zW@?8+OZRPp%C^K`_%j}h+T=(l=ZTxt=IFSK-UJXj$jyZhrluWT6kIG1W0 zA{_3LVBzo(?Nj4_x6>=hXzWy`@Kylo=G-EhvU73!qBiq{f)K{lK9a^?`aq{vwUysb z(jd*nZ|UoD8!U5^VhV>T2<^VadkXg9{V6fb#K&b+;{%7AlkQ^=&;3-pyYMMpyH*%#+Wa_||6}njI74JkQR;DBh>u_xb^J^u)uN9CtW+06}x{C`7cL zpxXAyW|w}oU*TCg(ZsX*%fAqV%G*>*d8?P>_NB=*0=uurFFrPY= z%z0Eu1KaMwIp6Q3FJ~TXyD=BOFNlQ`f3ir)+Mne)k)H*2zN(!1-dpJ5){jGNY8+IY zz_ieG{5diM;zM@hSXT-B#`oY9x5VMc{bRWPtHNB8ZY36FT*8Y!A>`xCQoJQ|p(cd=$qjV*?|LTt71?j7(5V;%mrJ877{T!_4`CP|UccS8&bPRZL4sV<%IC*^p zW?#&P}vQdz}-I@*3lwyYizJvQ?C1_fe3p+Olk!HSExb3|RaaOoNSF68; z0I6o`^0d>&Qh3ofPAX!~a+zW*h}rO&m+KY60uXpJ$B zPtv77%)5CGaX+7R%)!Gsik!ZXAtxa>4|@(ta#@)-@XY#iSoeJbz@QjTUc411?5HrW z@S8@Y><dC7=D! zVPptHKMsqZ2G#F~&>B&o7fp}zKT8ME?9@$+rUke{aTu|+10@Y* zxQJdabR^~R<^v%V`AChqOn-COP-%76g)M2%hnTQy zxlrQ436=%`%@k=boe2r(-#&VyN-{Yl=<2d>C zETbHm0`AJg*xmbGV3zg^jIOt!2h2A_r!oEXdi`-XCg6EyFpN}rkO5^^}+FC(Ku9ao1PfUa{AoQ%xGfzp#p91iE?Xpx6p)V-$CBJmM(h#8FDK`*rg8ERCcZ~+jQ&| zWOQ|5>LwPyI4=U-!cRCl-D+96j`Fst}ZrxKw&E`G9@t3EeJ>i{L6Lh#szISl9 z$!idk{)`_r<1tO97>>7Ao$t;G_>0+GY z@lYzuo&)u6{w81hiCP>E26ItG^!zGEk7Q4THACI#W0;Lcro8~qYhO@7^D5o5MU6;p z48*{u5IX-`7hFA4#WmJ+0ltsp*bxdtwbP*`Lz0x#^irEY|Kat9O0r^J z984Ryjk9=uTxL%e?YS?HN+K-07ZQQnHoP0gKpaYMPltO$%W>l_3tB&94U2_xP^U7I z8abN~ZH==yI_$&ehYyk4>yDxSgZVhfMUoRzE09~XkarUs)B4NOoNCe(qM9xWGeC-a zvR)a>#G`nQOb%Y@?qkyCoP?YEcA!nW0j~bH2dn%dXnXBq{P8jiPt*m`ZS&^i<}=rD z!ygwKeq$$@?fi%qt`*=w=1H<`W)=oF-=mYij={!p7jdmgr9l3DB>p)$lTKf-k;p0k z#J*)B+(_U7*hC`m!v+I9qZrD2+;ZsR$b02S?fr1$i>(4j@d!b$$b4)ba}r;Fn9SUL z(9P$K9I?Y@h>_O)z!=WCgXQ8YF#fM0_&iIamLFbXbX*&{wngH#A9wNY5jE7)vc@it z`)Dz*30D3{Ai}-JFnfU`$ys`Z3ckIf^CO~Q`2k6|WS&K^)eGKTosTuEHsUSU8#H8{ z9QWgTA-1@-;v^$s4&F#`rHk9~Kz{=*b-{ zqeQ%}g-mykB}M5Hz6^%j8RFT=4)|=r7W!sc3%+*VLAHt;U~xed>OJy8 zou*cNy3q#9k1NCSRB6yQY9KOmccc41XG(5~W5R16qASYaKg)J!_=yY_}`AmKs;@NQn^7QAd0z9JKfGuK!n6^^^gnulj8j|V6e<%%tH2op#(^3#0 z8v|Ewh!Bgdv&fu&4|GVKfo=N!<}*f%h=uTRx;=d%UOp_wEMGMlUks<9bPb>VQg?@d zFAgwy$ytydV+#95mGS;f5qK!Eo~hWe%)H^11LQwUfK7EZkd(KbPL|h!qfx72g5V-_ z&br1UD$|J!!_ z5Fns4OgXyzlRrMu5T-)M84O;y1-3_Pf{wlyZA;lp-Hv7AvfH(^C-yG0*~<@)kL#wb zH!q^y$|}@ZF&0ZKIa+9yM@;3UAWg0koAvqy6Rv!v6GlGJpSSLzq4hd^m%;z+DxSqQ z`47~tbu!(YCJo7J18G+7D;gpChgb_Qg)N>rXs|#);wG+U`rY~LxLO!3v+tpYvy;r_ z*7=Y(Jlp)+$+Zja+*>bTMGNWR5e?Yem`-Dw_JDM;8SMHc4kpcah)R(R)~^@BSqY1Y zm%TTls4~8BlEBQ7Q2w((4dWloBW+7;sN^?g`b*Cco%W_+9$unX#GD}pHbU9aJ@ncM zN{g~2*~z1d?DoQm?36V(p(M|o&DHz`m0y;yJzfjom@<%%ohJku7FuK;6@zT$Jo>+6$pKu0$*I7L)f$W(r#jWUhgl4(d z=pwUDY@DQze>2S(FGG7`_dA08oz}-33SUG_o(W*#G%wIF*b3o$Lg9u)5!|$?qE3sN zu;M~5b)Oi3cSP*)_g%pG`^RBlzZ$;$@PPLB&7xKsUV<@>O@fKOhIo;_M$ZBX{IWY3 zU4OdaD0Gknxn#6jR7)dmK9h{Ihj8xZd30#dm{^eGG&lR4V1ND+_*(0ZQk{;>?*-g3e+J!7Ccbm;3ji^L`>k+A8Ct-C14L>j@R zkYxgQ$k>4($!DXFUD*!ixDQfpUWfleYhm>YEhfr0mtosh2{v541m{@|{64CU$;D30 zxse~ZK`jI8oX?Y=la_!^*Ga-y6hgPC0sIq*;rDo(!SjhXv`)DRkIv>mnX4!GZ;7V! z_>8F1X$elKRuK=>55V>_`MAWZlF0Vfz`WGGcyje^Jf43ZT{mYS$bO~+I~UVd&xx?Z zQGw4l3sHgV4lFp;Lj}_(qR5#LMsbobF&UH0+}hQ_XtsT#>*{xxk25}pI@UHc?|VMY zuslc4U9-c>I~s`efIMEGoFKR)<(IAMv90LvV>mlHokDzM(6lhtggsQITxU%LL(OH&)->)9P znuuszbiA802fD;$X>IM(6GkQ1(MyVZMu5KJzei+a==d zoTE@Yt^oq>wxIg#^LVePhuLNofIYuBR0yAh(=>|A9Vd*#&vkW-Sgs_e_3jNeS?i$@ ze=Ba@aTRAc1B$$!0LSjGhZh?bK{?M=p8IYdGe`3{*xs$7!(nfTS92;gxi`dolG{R` z-k}hC))fnad@zfq(gGiGE@nj`YHc0^O*{wB@l7=@i;%#QE+_7?`gm^DpIO}7dj8I< z;>cZ4Xhnx}8BEUUUyMP3I+oe|B@b#?=H8?sG)cBWiyM4ivCRrIt$9AhflJJb;2zjy zmdLCciUBc+3GB^?yCkw9iO5a91s`ooi1G;u@VFhvXM{%3?iued`|CqJzbbPls+Q8d zl8$)(;7+D`b^`p+BkakC<3Y)0D%5P7&aQA1;`uvsNw(2R_$ca0XQlWcQ82_0#_brI z;DZg4ulRn>1gy#R#C_2`lXUEU%nsU3zMo10SCN-Ec9shk8HX}&+J4}+TmjB-p9uW6 z9e*}$f|UnL!3z|y?#f=lXR+UO_Jj(|T3e3|=T(T1&_mpIZ!J1HZKmHwccNKo0Y2}k z#CrK_IN(%3H8&1X-*=|iXdx|d@k^m@)p0mO=?`lC<#TCYKJy;Yzr1Va9GXwBMHNL3 z$A1dK?Lo#|$?>;nuNy(Xj2du75_~TB;{+;+_t5%920F{|+<|EV?2EgGbMg&w!{%o= zSu+zmu!q!{RKm@5Hz8ZI5nMjRlHV>};Qi`4EU(Z26`9ZGx*LR8dy!`J2+SwKn*HFX zq|F@=lg8ibG1T2L6lLBOp{V_S(C-YVX;n4&j}hTo_vY`QF+_AUY+*ATI4R4tw!7lL6K!Uq5wppM z)L$fLye~f6%eyJe-1vEAKhINcf@Pb2lMlhRi1!KYsl!EwlCV$ZBktX$$VEL5B0Gn|Xhp9jG9A}=&xJ6aoZ3v3 zR43wvX`{$&@x;b`a(K+Q(7ZTf8u83;21je&KfU}py?gm5qrLJR?>-C1vmz0KzH6m4 z{q0LqJgFAskA^eXPq&loc3bex6QIwsRNVZ8qnT>m5Rf1b|2gb~znSr*THYF~F390T zesAq)f0it2Rm3-|EHOW)42Ko{FvZr8bL<$;6+8R!U7Ix2R-ersof?m$_U$+1?M9%*1wzv^?( z|J=r($JS8S3SWG&e?F}z3&HnA2d4ffjqiVMz_Hdr_{#eiT}Z7#Qs9HG`*fk_RR*(b zsXlsaeMNKfZ!nRCS!ijspNf|&Fa@t{P}6w{o+2w?^`|5%Hz{0DZx+bB9XN^(;U4(p zpemj8Pz>!IA~8MwIgb5&4LqKn!rdK7C`i_2eXDyRe76LX^m;4)_*Frwf83(BV|=ND zffG4saR|KuCv_5wtMTdRt^>Pw0Zz0Z4$-ICG}+Pg}vr) zrIqQmw`b@yF-=ff5eW7d454Es?}059q3@Pd(-XaSv8+b{kM7ea33rsp!kbgk)F_%> zQJ+im$q_RX+ilo=-H-Mim`Se(SJBwWUyAG%T3xi-+;#Wk+(|`65Qt(c8PeSz$(}3;OfQkSbxeOU5>%{?DB3h zN7xRv;!dDtiUfT1izHu1r0Cu*A8I61Pxr`$3rshEr(PewmJeT=jNQ-P5bvcbFlVqx z5IdqOh?;Lf)>;bVo5lvnJUBqc#tBH8@JD*{y`3P$=^<_t!zw=jP#2HtNo4Fr5>?L5v`2Pe$Z8rrAM`O!PN_?p6gLxRRAdDJ~n~q`nmzmfP z_XKX+TF~0J4QsAU#cJ{I)YijmQe>8+ z1qk&W1&K}f(b&F>R&V&sw5eNSaFqrnk0zs{{1#B{G63VBb4lCXue7cGH%(jYOhSc> zsIYbhy*6opX?QBl`-5T#s*T02T{Bzey8WB}_ zj-OK_K;ua$%pBSbf!{RPybG<+*w6{y&h2s8zbJ}!u8COu_6F^!e@&Ireqdp(9nWJB##H5CeEug90rEZ3=uAPRP-=TLdrMBfx&2F%dvZOEzuFT{ z&WHQl@4=S)U$M{24?vq|A$Q|VGANkAu(K<-!Tf?GSZ8B78=BLAO^f&jo^;fQI-fvD zmrr9uB15=NXl-8hIKb4tM-G_nc@i*N`kMw<-UWk$(fj7ZH-ka_U$ea$#RKJzV*6D; zH7M#kkG=5jC8#}O6{!97XyZ38JDXNHZ(>hVVeqS8=Rnr1gliHOL&Lb1kRDVQRz^qg z6}201&-Pj1;N>>-{;G|z(rXMHt#IK#QjCK~=~d8mRt>&hpIYpUZAZAnip%ibi8iLF z-i=MgLx!8`4=DyEml)H&35h1p;2@J>LOHOu-v{b7y2fT4+sb{J))i_VeFIyqFN3y6 z0sMxH#<1(XOt^7k6|CM-2_np;toyWIKxBO{Qv>J#^E|S^*~Pw~d9zdydS(@H+4hG0 zs^=zqsoen%_Hp8m>2g8U@iGv8pXJ@^grj={HiB7uXts3FQaCrfK3o%-685sJnzMda z06Q&qg=dcWfVgelxJ&C)@Vfg?@OZ~W*d*8kTnf+NMviUFU+TUN-hdU{uuUN_@sS@~ zP&J?1ZHs`LI$Y=c_tu3yN^@XF?{KbS+zQzL;9S^uiwgQX8_~6r`SANh^sbnwZ7}7@ z6WDl7caZU@9k(xY8tfdC$&K+1h0kuGYv#2z`HRsFdFK=#=(F`YylrjDhfd|WM+;k< zssnvYZ`Q{E_h;+D^|*(?zH2=Ay`+jAIAkkm=8LXd?%K}y!|V|DTYEO8|QJc*J5b zdukCk>xWw)s7@)U8Qa%xYCi_9Oj!)?dT_AWnshKAXgVluy&O*KI~5d6eg;}bD}bvp z35ErD!F(StwoA|&m_7FlET|m|N`~x$PtT@6CdCOhF-C#7W!+)O4+ps6$yRn=NG527 z-n;mCytApvtu^4pik%=))fvWKb%8(9ySSb13O2O#tZ`616Sx_j!Mdz9gNjxs*eOF- zz&odU@nv3(`1_YN{K@8hc=eJ``Ck)^{L7qZe&f4f{=xwpc;T1B2JRkgpM2ESls)Mj zn}6>LJal{%c%D}avTd_qbYB!ZANGfd-fit$V{|Y%vW)ZjdNv&Fv>$9rSPLlhPM0Hr z`Nk$gqqqmFSHaji(?G9-tLzy@f3~XO5wJD$JJ6xX7ufHkXKY8Mqu8m0^*i;2KdiWA z5985;hxeQgQ~Ec6`S()c?ZPZDai1>ZB_4!rLZ&%ypj;O)UAF_v?gwB<|9vZ>t zz=zzqzU#Qkz3aGgr+Q$SBg|MM_%-)y@C{G`AA|GxuJF{#e(+}eSQyzQ9?tCgfIWE> z-G9EQg58^{1#^eL1YbWrz)ng21-!O+gR9Z&?5(zEgEVyi)aBOW?Cosn?BkxTK;n5D zY!%Ufi$5OEjk**B4~6f5w;!&8Hz#+8_k35g;S*Lu=kk_t=-B$Ey-~Gbd}Ic9e!CaC zw|y#1rfZv@ zv#F-H?C}Hh*|e8hz0lnQ!^zP*#rLiwN@ut6VG;@w^eA)`q zv{h_V7oD<+?K%mKe?lsWp$2jBixEbt%6Q{T{mjgiZO&@T`%@54@y#&;Gu@208 z*$LF_c%Q4b>EWeuOW1QqcW^O%(EEHIHevhp31{1_e8oQ5^N{@}+7kxPyu~qIq2SPj z<;D(YzBML4UCg!}JC*z8(K2?)tr@^?PYd4t5XHMvp8Q4hOu0eM27XjShWEU(62^E( z@t&WA@wI3B^8O7x_yOlz@f*ByVZo>n{>?aFen@-<_hM=kKcHn#zU}-|aAM38ZcA7y z`}6)?u;;yC*!f{UxG*mkSktpW(dAd%hH&)!;|)6aw$38S`MJL6u2{EHaPl;_mC3eEZ(c{NO zbnKuQ`2QX1+Jb@$>qma>jQ&5tEZv-hFMn%T(W}@rzL!EFm{RzI==e*~h+&h4g(iGC zMq0X7%+r#iZVH89UZRpm5bwj%?Nv0b*J<@SO3E00t7WX<5W&O@M?Wb;tci zrI5(b5p*;SKAB5qI0le(=xFLc_|!3w#9%1AF7oY?Fo?)dQKOqF2_ zB{K8|TI!E+mP|Q+L=zbdgVm*^`LukqLZJ}M8`(dHW0-`2hKg2$4hnPXrx8or@w}-Sc!534$;zDwN8!sH7z8x9T}2N zfauYXp%~03@=APSaV2_##=y|nsF8=H6CezdLE~Lb9^w;+D`9B8p2GWyJR}{5=v0(W zr&0Zf*6|sMDM1aR(y4V=kNp=VBnZM7@Gu|`@fn3H(WvwW>c2QPod6MLP1S!=GFqxc zr84L>Y6_3?^3_SlAvEeEY8CUZolQJt`NT_==vB0aQfV;8bV@t$uQbUMMT38ibSXn; z&{BFDj{|438~3)Na)OBw$~O`jIs*#vDit<>+b2%kK~|xBD?#Wft;V3$Vu(lCpY3{| zYN0$!tira~Nt_euX|0OZ;oalK;k0%#6-kvMG-?FEgUE+jl~{$+CPio|ok5RJR*BD) zPSMDff{797I0A)u!n|AlAmz9j6&Fm5NLYrcpfzd@-a*&B-jZiU#RU^1l*>s7LS`4x zb{$Xzpz_Ehh!q$@hZ0r1McQO5UYHRLyq=?pmW5%120>Q*83JC}l_wea;NoiY}+`(-nm!7k!M*qWypmiITRMhd7?lB^&g#}UXC)&ns|g6ScEa45 z(zc7Uq6_jRGO;_AYorJRrO~0ZR@x$b;PsAHL=a4ju-(NFDm0hj!>swCP+!GIs5~+W zq69~v^coMp^21D7MM4l3aFaLIJu6f~FtLi=I6|Y+5C*$^2e-YzRG{=xkN3_u#c(pY zYx%sy5h!fo;a7etvL(AndM6qoS{mOVm=xpeX-0k!OzaEWLJWZxZiE)ePiyRFMa2aZ zBP=Nx!k|&ncm%(?)4Duo}zrDTvfx26bL3(;aGyHP%)%M!GVx_UszFb!NdsLQVc;G3_5&q@-O`&6+@^Q z10m!jd4FD_K-(&UNmSS{gob8xdTbJy^=--~Ga?8kMkvd0ghtKaSc9~? zm0FEQaQTt?MLDJdA+-30Pw+iAA1kVaVB(4t5)df+#XGosi#UG4RiIe}AE`x)8pw(DY^@C;&+N(|0zyZ~FXXcv+aU~r_NP#jNZl#lB2+GpV30R4 zM6e>4wjw_WCiaE$Fae=g;}hb*D;Ks;v-!J&hs?+if{A@$>p?*1RCv@<%@1%EiVG%2SbCBW8hjopeQ>^^6%`ju zj8OI>AkaQ6)~Fwz0+AprBm`kQD1NMK3|Yl)5(1rfz*LNBz9q?wDj}Fyg)Nex!l1_8 z*=AvN8o6IsdgBNcN-r=KbK7mHV?_!C6RU9C#Sy4u;b)WkRter^jDvlQ6&TuS0o)n&}cP6Xw7*+U;X9BHBt&q1WI$2i@!XhLRDti3qeq zCvDXFuQ#`OzhCMn^+oj81Qm=L-x{l~u`<<)Tq&5?osKLVfp#nLrEbym=6V^#MjWA` z)cEe&(;ertWDwsG5Gq1`ai&Qi`~G^7npj1$NeHyVCUvKL@3ic|5R8U&v4?#4EyNK9 z1IpvEGm;-(8zgR#sGXP!gF%a~f00(?!;5=7P{aOnI85$;PXd2lQe^4o<`(kjCwyJn x{r%a6e}4DZ*J}Sie$l&w`}=QDx%b~#V*dEq3H{d6&DBl#<3jXL`1~KA{U7#0J`w-` literal 0 HcmV?d00001 diff --git a/resources/testing/lsp_xai_maze_4SG.ExpNavVisLSP.pt b/resources/testing/lsp_xai_maze_4SG.ExpNavVisLSP.pt new file mode 100644 index 0000000000000000000000000000000000000000..16751e05458421d8967987825b8d830e54d6a4d0 GIT binary patch literal 484272 zcmbqbbzD@<_XbozECdxBu@z(4T^4ZXT)|erSPK(Tu~2l!YZnG~U|@GAcEH}b*xlXT z-5tL(yUTi4*YEqs?|na>GiUBI_j&HzIWxDGhT)kqJ2|<#JN@;ar<0dc4DHaRYv0() z9b?3pO1Y7b+kvSp*(a3{SH8Phq|nAy_AqgMBxF=As&rH3&~R93_UsDgq6wb~G! z(KX5y;|_f~##B)m-6A(Ri$?cG;Z9}4J;O8c|3zcgvf+iovtk)Hd5r7AvN2*Cf&@t7rt=Hy?xMQ79UPvf)V?W3Z})F;p~$8I08&Gioy!tN+ay92{({ zp=7Mdd$g9dM{DyQtz)66D;nz=jNy*Qpw==5BkT!uK_NlfK%FsCNl>2?G_Vph5;6yDgM6E<)YlE?k<1zS~ zh>yXxfAa*ZwZ>>APdm;NW94bjc{*5lI*P_vgRzt2F{rKNXbg6?^8Frg0l`69WbC43 z?8*mRH)PBhaB-rsyTRDQcKX#0r_Fe~gVE`r}1jC~z5+9thz_KcbkojNc;ZS1dP9KgG8ptbu3@$MUJp%@|>hZ>B-Yy-~jpsbT# zf{nnMpaD9SP93B+4p&l);1naR6r(srqJ?6#XdGiOjm+&CMRWdhgg0#rEd zjaL#);6xLxM3XqtWDC(0(U@c~PPGlWe-QB@H_e_WNUaG}VUkW)^332o$yT13oM)DW zXSQgZV=&IO4Y@yf91Xd7R=(duP8%E;gyUkql5qhaato0$W5_KMjf)M&C5{JxZH`-N ze=xY}X#;|E#%0P~FE+Bf=gH$1WW>~Le z+`zjp#oB!vdG~FyP;3^BTMWjnj)$Cej@xEW5Tw=yYt$;^b|t|MPO#HTu!|FlB)Ko@L0 ztz5FMnUGI3UcsH04KEg+$8u?R zwQTsdjAiwj<>0Q1#v2CXO~;hBS?<=~lsL<&jJK7PcfyN_#=E=&izOQG@eaIi;dme# z9~z90Y-7&uu&mSEV;h5c?$HFPbin~S;}a#pQ%>;AO7NT$ys!|w6pgP8#@Dtn_XmO9 zB=^Ri2p8}W4d&}xCDA)h^xjJJffIeS5PcGjpAE(@wlVh)B0lE6+VcbkYcwjnQ23_g z`ObNMSb2VOo?m7j>g4R?BvNOz2I_*=HunA?bTHe|Oo+E~+lF7DE-+XXtfHCuzJA{T z&@33^Af&G7QHFIKQa21m>WVXjZqs3WJ9T=pe*?40GUv`Wmol1%{ z2NsZ!kIiD{u}O1cP1(p|&erisb75@h3{NbHG&foU^+M}dO~&*{y%AzlW6SrzK$Vu} z;jI;N@?wmqfaXJQISbT>S2-ur{OB$81+XO2f@lr25L(B>*fMp}!U(XDn@4h>N*#=o z8ZE+`D!7Yc%(;EhTe*wzD&+PeM}TLTV$S_yG>67W(?6&!@8 zpfcZsLV^loE+GKDRf3vVp#%+jiv%r}L>h?JKy_#xr-Q?(mo6{i- z3rMI)hiX`(Oo!?iTRNi#mPA?;t%24;>sU?3)J*iU{-;_DC#=v_4t`ZGhI64R(EDnbc`R1lV!&o6A6rR!bZ4rV4HY#+@n>5cC_?NHUKSYQi5Q!+p$`_2P>~INu|}B<{V=w4 zMt>}cbO2fd9f;Pk8r$M92qE@r_{@k`W^^!btWYxqV}2@zqPL!kVY~`YMFM&Y`*19Y zbOc%h9f{U)Hdxn&Q3$Z-)~az@RHr!PjWOpQgWk$LmRBM7IP@0o@mLb+1hfV^ z5v}8F_&qP1*M><5{6m9At>$ynWWEc9hA9|x4N2&&8m96p)G!UbMZpm%4}GNv86NCV@aeN&>Cn8TE}W^Yr{r_ z{GldT6R5$tU=wewP_r3hek!)0x1Nfvyb4dnHuM(u?N}1&4zvck6Rj;9?E1pGHta%x zJ$Im5r@`k9G?h11aHnC+xlQP;+!C)sZie2%En`Wf>1YjfH(FaZ{K0LvHta#*9~!i3 zwFb}rUcL*3hJ6@w4g1ksH5}kosNo=bi-tp366s;I26_aoEgSx!foH=}#Mva+u2%8E zm6jgkyHIF2jxpD80=-qkNnV8-PNBDGIE^Kdoi6 zzd~;%f6c3q{0({w`CBZB^c`9QeUH|0Lj0bZ&CA0F1UeAGSL=^_9|{qlFy@Xo?`RG52U^D&@mmDXh@Xgapn(sYDI zS_932);tC~#{T2QAI*sn+tHgdA^?W~KJ%rycw+^hC&uQC$c+UgRAht~)+jT=8)Hjn zr=k$A!c$Qgy@kC9 zmPA?6x2-lCy0mPD#T zYoGyW&FSzzH1Kp#Bkm6gfkD9Dxuq09gS_5s2)^RRa7l$SY zu;*5X;JpJr(rL<@D!7|r%(7f01 zV+CJ-j3b@A@TM3GNXTC~S)Z{E#2RHT48qvb6@#%P(jjOKbSPTKYHaJmFof8v2~y+C z9HOHMys<*faE$TA3LSx-p9s%HI+9o6i5P|6!k&mFk&Z@dpkvV5a>1@Itn0#91lVy0 z;{94MzH_7FcvA)Uc#Jvs1oT$!iM$HAC!x1+PsWl+r=T^^B(%0%_=DSSU6_hMI}JL1 z{P+@vPUE{!Xqb*M*DwRURYNkbLJc#~TQtnVl1OKxHPAU|ZMpCd4Lld-BJK|f0V>Q! z6`jZTppY;hV=iFaZ?S_55!*74}GtqW@rVt?p?0V=#Q38w3KV+G%O zjQP7)x&aGF`1|!MO~IPqZ(!+03@tse2}>f~jMhN6pmi+9wk&K#$RA>GGzJH$={DY2 zA!a+q{5_AUFa?BsaO(e8d?K2p>>=J)@4CLfIYX0-#OwFCB~a7xMhqv zcRG42_ikQ=+0B0hcMHAPw2o83@v?9U@m49;RKQ37n!rFcz0CKdka7iMo(fmd zqm+zPxQ3xfucI~48)$8#&+g5iZCSX9kUtJxqfzq<)LXocyElJ zp9l9u`ixiMd3cWA!u|qFB7KS0KwqJ?rGi~oSXYJD2>6p*r{yo+-teXh?zb3o?sw>| z-0yi6a(_T?;r@svk$ysJpr6s&QsED7yH()}0&N;Ho*&>tExcC$%J-oV@eN}x;yZe) zh#$NPMf^l>5%CL4B6Z5dML46i<-$Ki@LX^~oK1uI{!xdw3u=6#l8Ns@At5uyTtXJ~ zRtc`W3MIIqw@7ful1Q_nHBb+?28{(}}tho@N!AJji$&#J#Ng*W%#yl5t zqDLtixsVG(k$R#v(A;Pp4?o+o;Dr$TLl4jdtMQQ{_2!Kge0eaA40XX9VJsja&jokO zYv_DfQ#QO###?9~3@ts8A4?)FfYv|@qIE3Bwk#Av$lqf4)LfW1R){HrF+UGQ(Ob`h zFR#M$Pz=3=-49D5EsoYeOQ3a}3)W?!Bm(TY163NlLQ&CDys3h_G{&5}40vrfF-#5BvAJO{pE3Jha>6QJXhWu++ggJU`z2qDPjpIQHGcojGqk ztl{Z^0T075v>bi}mP8tf)XtMc6bx?7RIJn5@|EE2HG5LR8C~<+%u+obo=;>Lyp3Fd&(dU&NA4sEqDtB zWlN01G38sK=aepqv^B3n$~NdNlx?vj(rB~>+74}0b_J#R7-O*ZZ$kWjmA2=21z`t_ zIblciR>D|bg@m2ZTL?R2Nu*uS8faIvQF#=Ec8g0l-1;{$PpCNFPC?uqV@})yy_Gng zS0Qmv^cLb?SQ4obt$|XsQQi)Sc^37?jeqf)-&%^inS!?u#+X=flff{SdHzHY9d1H)dZbL4UQ``H zz#rWB-AoA1zejmf1@|$GIrnk&R_+tL3b{|Bw{V}rl1NXZHPAC?9cRPu3mWr9)ma4o zp&>X#gP&*9b9@&H4d*fD8ZMx>YPiU&P{Sqk77drNB+@Hr4fHBn$Jy{(1J8zQh_jb~ zUzP?0;Hn2c zmvz5?4oKhQ7JCU=e8j=u!+qdw6cRpS9FBMSpV0GO&zwj<^D6B1FX%0#U$G?8Z)gql zJ6iLV)o)Vsh0YJGx2MF}pTCKuKY0rUg-s;FOJa~Xil_Ic^y*o z(VYu7+n6)%;5Fto&y%-QQ0K;&Q+uJeQhW0%q|SrhLY)^&_<1o}1NA{0Rm6_k(Hx&2 zVO9wlqgtia;5QLC(-h#lP-rNKF(1{1(4&ToQC%2AkrqK~pheNzjVasI?u%P&$7+63 zfWM~1x7#{ejJHwH_+cFBg!f0qvA~bDSa|4YS^|Uc&~WF`v?P`+$6E?ZA}x*9K+B-D zW42A>WpRr=vlgG%@h`y2@iq$P@)+|u#2>wxIFVN1RoKZD(OXC>VM(Nw(Hf`Ked8zPcEmX~0C@3`;b4o3GD`gi3NKts^ljppAIrg_q? zg4_S1#u-FK^}MBmnqbVS0lk%4;8jRn6}^Qz6iXrvLu;Vb(AtgW-_(3GSI5nNF{^nB z*We8m%r!CQ%(c*4nQQYZWUhnW!dw?ic!P-6K*Q164Q9tvbOgez3Ni*WzCTy%g7I=X zlJ7#Hp+3fZFgHMt8ZriRLkvaQ2(5t{(Ao_tUB-Q2W8CuBq2k@Inl|BW6f{jSj&#D? zlxA4q$BJ*qM$_gP@acIpjlz=Ucw1meq%F}JXe+dK%t0Bflg>+L9YIGA-o_?WR1 zZ=s;(7F`_+rO9gc= zj5)Oty_K5sDx~g>-a;*6Nu+(y8fag%c7yphH6P6VaPwcx=GX82c|!&B0E{{FK=fAT zLA(l?2cx$z55W?C+>6#ghoQ9_%t4NRxk?idW>t_enDKf8?}+e;(r~^Dg@zFr^T9k4 zJ!;4p%%d4tPCt}HRxRbCX(#dEIbP8I#VHIK-R!La@H*GL}>NJ(NP|!}pm_NRmj^0e0NN4aW z?BQhe7Rs4e66q|o209yUpCNP(I`iKnz@OQRG5pUb(79N}|Hc5FhlR3HxI8-1`B)r6 z7jQ8D0|$NaFC*ZeQJ@R4BHX!mR2Hn`H%tL^kr}ucZMTe#{PM}XQE_ummzZ%&l{ha4 zxJoLz%#2+ApU42Z!i-#LL%Q^ia=1@5U1dhDwjuEl93nMzjTyQ2KapCx&Wv1dL;j0B zkZv#|Q*6k8vFqqYGjfv>nbFm1y4k#Oi*jQ|S1aET)2(LQHYG0OV3j!R>g{Iaj{igk z(4A)FE*nyDuy*@Y(^NAu&4yGQtQ}HAO=hI@pGYlbW~6LG{);`3rkjzwZODJI>*yXc za<3AZ(bXEd&%ANJa$`nUE8n`%17_SoB`%|@l{oC`LuTaR|3n7RBWC1L8&YwwcKcM* zV`k)W8&Ywwc1R69VMd<(Po$QfG9yphkpE&2q-V^?vo_?v*md-r8F^lb%;;(@yo%m~VD0v)rZ>#Un>M84VC|3^ zddrNw{hvrJy<Oa5oq~FZA?@Ao+>OXPV z)j!P0pZ|#rpufyWClq5@lC1~(*FM$M88Jhsiw$W#*uRh(n#qjJ{GUiI&0{vD*yP9S-Z}d=Z%;-SnGD5SNaoLr)j1E-dumf|Lkvabp89;NHk)AfB z;t=fisiwKjNG}^w(SdeI4fQr7^ZX}LOY@qM`E1C4u?JEgGcvyospvorEnwbQP`NRq z1C@&dEo8I71EMi6${ZC{7^)(}l*^r7uu-m7a`k9f%ZAe82+95Txgc(`# zKapBm%8V>+L;j0Bkd`qc%i560&Y!|$yws)T%-hQ=xAUuE>kCloZ{A$Nwi$`AY`*r@ z(Te7cm24Yv-x-sw@~s!GY{sdSxQxkGiNpR6FeBCfi433`Gg50qT6^HHR~%{@Xh!O6 zNNfN9h1Ad>Gcx!;ky;vJMpm&Q|HU3i^=2foA^*j$qhLk~N~G;f;d5eI)x14axt*UW z>jPC9X5L&)xtTv&v^{U7)y;q!HUMf?0s?4FGoY3YfKrtJHLYz1)cF@cL+hFW_5KCW z(r_~%!Up(5Lm-Vb1M1rVe`wIr24+CRe*uDMBQwBY1N=b|OdFd4O>BTaC_-pcGoYCQ z(5H9%N)5x^+*_BO`Km_)Cnx@|;XnU)Up}W?c7MFDvhDBU)vA_F`6v7umHR=ue~t$~ zZBDt%ktTA=!xnOCj>5#vsQ^UxUoL-m=p)y7-$mXerLxq4h2)~m`^mvEBjw&>d&xI` z43d|2ddT`l^@SEn=ytb`e`D!=0 zLfNe>OX0gPuBo$p?o%*J_8STnZg|Q^7Yt|j#?N8$h*4ztj7EBA-7dCo)_90K+*Iae+-vT&VyIyv&kPy_)Bl9zac{|Xyl6>wz0J5_u2SS z1xTNOGIG6N?d4rP{p9HPGlbRRCt>XTvqHaGEd=>=5uw*Yt#E)mhYvp<3$2E)7nXn9 zFZUeQQ?Br^u3R#64SC1ClJfcQcUktMW#!y*3VT<6q@0(!q@Uc@LcaffsO;q{%b)sG zVm-WCv)2z2SLA@BUzLvFIfRh}Y`fvGLLWkDY%`;}`WPu)L4 zK6S-QZX36i$;HyyCZVZ3^3yihE{Dp#b7si58$D*b)4uBsOQ*;)Zj6BSyEM=!Yd?9N zUl}=iU@PMFAfLRcVI{eL$VBFMYB5v~y2Db7HZyH3I-jI?gvy4;KVWx>K5S>Mm+aBR zqH?WPDROG5l5(y-&MfbdOYDkix}4?YKIR-yN4|7;w>-;OM80y@TYebUTpsjv7klk} z-XugN$UBY&%f%i&W@i(p%cF)oU<=kgkX?#AkQ*hfmcs_ll%KWPB7e)vHF`e~Ey(O*vwn&a%mq$){w@j|9_m!VKKF_|tpCw=1 z_?!&+oKtr4zrdb+668$VI>|-KSC-G5oGs66l3iY~)|#EY!_xNWeNOlO}LJ|-<5Hj*{-hs&MzN5T8)CbqU?081S?lD(S|XPVtAQ;v$BYGpR`b_DmzR+0rDn6l86|~{!GZcU zVkx1`r5LCR9iY|RP`S>DY4U_u5whv)GZQRxVj&iahs6l>B*?TJ}3sSuQr{l-#V0PR=>^kvwAE z3;D*hf$~iE(Q?A4k#fDFD`f4ld2CnMF}Yr*rE;zjVXS}sEAq@@`&sRcqO7ZaU#@Z_ zT<(D*M4WZ8ABSNi##f1Jfw+JVT6_y_djgw1s-zr_& zc%H;1>*X`Q24GIkhKKzrRG)cBdOv=uJl&(0yiS-e>k3SeSEY54i@jVb`x{%x#pX_v z_8d7Zdo`TPO4a&AwpMS)Lbu*yaj#Q|%jE0Qh~u-_>+03zfW!6KtL1y;BJbwPKA+jFMN*WAM8BR7l7DXUw{H>X^ZtIf*=rl|`h=XrI7C!_X|IO9g>zigh=ruluA z;u}MT$sfRf<6>~`R7yy={YeO|enD8$Y^`v}d6_W(asy%Cq)yP#&;SxiGiIecYvDcl+K^y*+m3be@hth|3ypTjd`awIr*@6q_|TUB`(H~U`D01Mzm8`9 zX1P|iVC9l%_xEl8E5OT}|M?%+x1p&=fntc_|NfW0!hh>Czmcs~E&o6DO?!POv|xkf zVWXEF42vUE!#H1KmOGhW1oMCYi?71peCEFvSF2jtfAam=A77t-3)}H&M3|>EEo|N1 z@1YYn@c1;*5wIy^+?^4y=D?AR3&bKS9+qes%1&19Ced{+mbbOD*P_}DOXqTK* zLb={;Zn`3&sFnZwUwR#!KOO%m(*NiD#cmn~x5qS=TBZ$Vhu5u!hQZ0?Vy7#t!kMkm zZ~G87yO*AgSpSTaoElB`bW78J`@VslXz)ckKesUpsIi?j->;SD-M+?_WmQATPC3cw zAEE5I^Gax4cM6msy-Z&B%fO285-i-}b`=uu|+va}CS% zPz&vPjf94(Or&nPBji$^0Jf#*3NpL+M{=~O4}+%(EWs<8#jbLLVxc`*`-bUcX^MfI zDRa(rZqhh-vnG_(ys;VD{Sr-8YmEl42hLFFq8stvx)j6(nV@*KFcwkrrlc!Xjh#;w zq>>9;$d9+=lSiHRkt=?=$6k0x$fc9A%SCQgmggO~!L&z5HC&$R2euu9(& zq@m(R)qHjPCQ@3^KEI^Tktp5h z-2fh@tssLsm6Lj%9Y@-o^I)O70M-p&O&T08$rfGJNmoZtgrJIHY;)fZY)f)e_9k)y z^X$}%Vvb~60@O2h;zL=3|Hf~`ZIvr(=4qaob z#%EZ#{{S)7!(7$n6@EpAXT5y7a-OtyF9Tjq0| z=}$;zY_PrKW8ExeE0NA~O+4C##*NY9o#3!z6Y!tH+W<<6XPiFp;IBBcwmd3$%8 zDrU(}o}S6eN(@eA!6!SA#S!gU+)Ou^@vs)V=(iN|da{ zhjcci9t-(W1gchU$0EliRw)>?6H)0cIs5W*Ul9fkJ{K-T!@gHoBdLeF03;PsDp5PA0tY5AiW`7|LMrmTuJ zwVCjirSCe#Heb2J4oUmc>c38BnHE%G9ZF1+7N@jf>Pz0zpqW#_S2bRr@9h>zWgH9Q zqGcrSh!U{$KpW^5@q@S)@*>N&b|hC$PnQng7(kx(FT@Pf29rwe%cZ*ci$ldqJxI&0 zOQ3Gnm2ArHRubDVk+pIuMe;S@#s)1wNFTSE9B;at`PE;+($;yfF-Z?t?V_XEyB_D+({mELb0u8gpj9L+c;+uT z`Gi1@V~<#IuXy(S`$eYSHHCfKQIH*;zK(5DuhyTvK96}7cxCG5HJ4PK_<}@U7{WSF z9><={?F)@>NgN~3n-Gaqqm!XX=vElJKM(umVSu5D*U7`Q@sRM%6BgW_ zOl}Wn`lRMAupz7^+<*3k3`mNFMw>!}J_QTHgZ?w2_4*KDXv^c^QXvn-Y@7n`bT=T^ zenHS3xep7bwv-;#sSb5!<&Y}RS`GCNT!%c_u7(&6AAzbZJ`rhN5c4Mi!A-lUNXr{D zAY1li==EYG`1?_36!+c1~))c{i;{wawq zKa#4YPDo$E$4gm<&4Ep2x=Wi|?baXraTWZ-P0%|f50p+=3(cFMHEBunc; zLZ%0Pu*!cnLJ=M~T*zX_BH8p#SZYs1{vmS*>oC$aN2RL><6Q?H_VHtv(#J{_b9N-#pS6^ioeE@2bEN3sLp`BO*iC5pq9f$$ zRDkJr&tN-h7G|gWzGUq`3#?4S1jsz-3OpO^CNwU89{k+0L7@f`x!?aa#55npjvW0~0wL+%dVN>q*SF}LHcFsZx;8*ufe6x(x_bfHXt67%L7yK~ALPKCDt&urIN>7(tW z$fH#1cf`bYv|hp*MP!wqx)+p=P1{T^c02&-+Fh{!LUUMla}vz|910`vPL&oMtPH*p z+1SB7D%St-NcOVNSJU1Z;cWi<;nL%kI3dL?zfoK@c1J~7R;=RU%+=%DC>IH_MLFG1YUo$dTOk!_qa zkg25MRcdDng5}8zpl!CikfUN&leBy?*=M{8$Mfs}*Y&xDZ)2yxeCJ?DYv=+Ci$stc zLCfL9!a7js^*2@qT;(IGd#ufq%S`R>CBLk;p1nA8waVdfOIfw=8(DCJSXNV0PTtjf zH#>ISTV64&j2zag9V^hxRh}BYhiypmlxtlZDOcFhRc^6wfV^l%Upe$cD|zF%CUUzh zBW14_ZRBJ9XUbPDP9%mNo-AsGiQQb@j%<26SlZ!UUs}^SjTN|%B-QvNu*NGMkP$Do zuysF6lY7VBO4r@9!ftktT`!)%+Rs}cm8w-rU$rik^iLYV^wr6%PXCp-Hl&!Mw|T+0 zoDvJ~zKuog+s{@dttPLEq(J^j3BaGv_V;BS-xpwEk-4NN<(KQ5Phc#%L?`J%u_LB$ z5kpzYwJRkRwHQZ8Zm_!;nFf{En& zHUfIQ-axuuzE93vdP_Xt6(+N5Ed+XHC#j~=!?*!CC6{cInKo^@e#W#zZ0WIi#HCMu z@T)gpYOt_ANqdpYH22ClsL{+t_|*0=#1k*6b-5)_ZQpvB`Sd7!-ad_-&r=@0x4)}z zS=k%L47mVq$p_&Z^)o@mHPCj#Wzv3DApAOT33_k4PP&a*46%LE;rOC;a5?8|Qc(_t zuig#7%Vjoux_m1P+VK)JnXa&PhZZnXYhTtS*Fe_3ZDx2jWR3LZ`*QZ`^j{hpL*@D5hy*+A0lOk;Ln2PH?c4JV7|ZkDEZR7u{+GRte2#^x>< zE2WP~s*-DQAj=wAOga=fiuF&cNk%+*L^Qur*mbeG{=;Brn9$`MiS`*zE_GeRe11mj zozCrMzgm}v}@7oO~8l_oxiM!LNwU1SNC`(`0n zeV{K~JX4bOAM^wo?!E{`x)o(_n~oCb>sCVknT>?DKiUe_o0kz<#@~dkmDa(TGv{Du znftIra};Vdz5@O|(_zo%iqP%MM@b*Ph@2Hm3;nWAfDgO3kqf;|urhHgJQ%%|H7ZtD zh|ir)Dn^cF)85P$t|se*Iwwsg&!!h3JMlX)?7iwqX(-SC0ecl_kr^%8{fJN+T~ z*Cyh<;5PJ~1@QfR0a88aIjNJm6jV8pEG0~@C#>}>DD*7220UUe!?Ej^A=~Ro>`~vd z(4}K8@Cm5M`UX}KzGrPgG%IJb9F-@-Gv*CDYdz2}8&nO}?5o7i#Epc((?Ia;olO{j zc@`Xex*xtoErXnq*#*D;+u-!FD5$vg5Omq&D&NukVxDv)R8MnB5B!lmeO!+p^6`p*?YqO6e*X^GlUNSUJDp?+$(x~a%TQSPxHfZA6&ISE4S}&mQ$xHz z6I9Ibjt*plg( z5Z(5K;QeZaQ2%w3(6sCiDDX4~sbA^}B+uU~<=Cr+nFHcLw=EllZl3}dza7>e%r=7b zS`h>7=By=g&iAE=<5A4Jy@rK7NRncnt%s@ui%74^_k#$+ zfg_?>Sm_z2NzYeGmz`#?r030vPr)thQMG$)z{69_Gq9k%qFpY?Kcx}tJ?|=!=AV%s zRC}ZUG~q5AZptpt9GZv8ytE7g zbB-eW%8VhNzK0?DW)Y#yu)R2T*Rq_kNo0b?LBiRyLvA?uFph=O9EJ%PQ0nT0z2(Ua(NuqW>P4 zN4UM~3e0}-0SZn(K|&Txgv2rFQ1G)1Dd}~=*axo}jxPgw?lLy7(@xg0L~ZHm!0xPW z<$J7a@kr(ZRY-Tgccy30o=GS2RbW#idXa8H2~}#xWr17$1r~a_Is4eggH=ygLqNlZ zus7fWi8(pPbhBe+RD_Ug!Z;weX^=Csxk5fVY zhwo!OpOqnU?ar*wynN89b`7cJ^A{xh<#;y!N($sV90jFJx5?3&yJ^%g5&+ z-P|8S)pjbFHtH4(@pXb?-R7|)4NJ&tW;@BwQ*SWUoK)7Jn~NMB>n#85QG@B$4rhbh zFG+VA%Y^ucks|UEsYRW>Q2*r7wDmqWq&jc5=rfNSRwe%9X-RHVUGm+1P+w_NFnjlS z9Sf_WVjJHUBI^&gW!nmOf#8p$7&S~GFWkOMo7Ey2G^Zn3f8wxIYxoJ6)2Eu`^{qI& zQ(z9!*W4r(KV6g^Yy6DVa6c_o**peHb*$p1AyGNXRRfc;b z2eGNGO)NcOxvA@ex~xj8qGV_C57IDoF3W#Bk&%}ppnjdNQmv5V?9q=aZ1~Wf?BKau zK~aO>OIhwWVdWb4XDt^`23=B9kXE#VDTWuM#njPE%+-$_TYi8=)Qo0h`g=htKI?0r zwHhnbb_LngC5c@)IiIbXbeHXTCQ1EhbLQ_8FHLHF6sk0v&$bH*5D|AxT6IMxTN?|P>9tmmT!vbJ*hbhvxi+XUseMZ`nFal~;^kNZ#xV>YeX=rE*SmLfD zm#2)Cyqzzb?yejQ!*^td2d#^f9xel*TG43872Hp{t=$6$429w9sHM`AY1gDY{%LFn znIMf#eM1W7nq#WiVj;`ftTDSWXek@8Y_F8-MmqFq_e>hq=DBpYcN93c31CCMwkDh3 zy(eyIwb+6Eo2AT6b3wDWW7xjB&rOqCZXoAJoZt1Oc`VCQ-aw`_8qKO~-Xo2vkc+vT zGLm(96Uf0HQ%!|t+$Z(kT+~;7zZ_O(Z3h#MKY)%Miwb?#^nx7z4H z0gsN3fE{}tLel-G`ZJ9lOQy+t(>DH!f=#It^lNUvC2O_0rSP$%B=@w(QlDO4tYzPQ zEG4{^bYlNmR%6&0R%1|e)4ML$SxV3gNo$x#79SWZP4butXC}I`19_XU^|ybLiV-u( z%bi}Z?frWa9Gj$1d|QHTEu2mgYdDc;%~-NN*p(C>nMp{xnnq%(tud7>@Q579be2T> zpO8*pNMtdt-q3RNXYz8%2v&b#9&nGV4524Bzy$v!g2NcHvAJ;d?jv$lx(6qzuaKkW zXjoNQOWgF8Af?>q` zR&8ckP3|z>KZN}V&d1Vg-XZR5UJ)HkF=Yu!Bu`Z7(ygkSA?^J>5_I7cEXXdwyB*U= z>yYhmGG;2MMi+p^NeLw0V;mGV`oim&C;EmSd4+dR0?CcIm9R92!2Fx`WD(&LSbkF& z%w2biMBE<-ldpFoi?);}k3LOeXIliZ;z#zw(7iJ0S3eKrZ?piexOhNP>*3Pk+Q%VJ zmxHET*CL2t@C3M#v|KM0(y12DM9;V(q+d-X4xmfP2Gfh4P{Fz6-c}x>l z4Jy2kgSC^2NG@MJSnkDDfVo|l7I|G~r{g}e*~|Rp@4cI_#0}5cgx5N@A$dLP6Tgtv z+K^TD{E|(0wofYzXOAG_u2zUI?Iv{A*MZ&*N(;Fs?1!v@RfGk>HDKh`fn<1xs;oit zqA+dYUHzQTCBRst5INS!S8AiqO=2fHLI0LV_3zv?`XR>}vpf|B!}x)r5HMVTK8p&% znQ?>kAvp;2xbz*;HoFS9V(&rfob#~uT`m}>S`Sl?t(MB=%mVF=BjId|Dd0D#7&IL` zm6b{AXL8Oqg(OTEPO7$BE1kaO1A8vzCrf-ruy?wvrtg=Ju^|H|;{EFv)4^N8Om;7r zHahQAwqV$L_9$Q+(_NlL@L@muxNK6|lif98cFThDhWhi^_a%Qbd~5Ba?i7 zTo(Cd!Hdjw^E_By;5;NJEr85{%OU^dV&F7)kp62+U-m(JiFCe?*Grj$rE|}RF?laQ z*$s66st8~!Xt0_|rEx;zF=9EhoJI<0%c+1~L4`(^X zR%4BCXP1Y}3@6RghO=i)l37YaV!F{S-E<%#fz6NX&t{Zw!1C*gvwKbO+1mak?4^G) zYy0%GNw^TrK4ikR>*sy4r;;lyZu--tI{sFg6@E`DtM!Is>s9Q+J(-MmIZujToJCY? zXRz3kJ=y0Lby-Qn2$py83u%NniDfHyfUIy$BM0hTlj?m6ogjK>advQUPQj<;7dY8@G<3dHKuF8-fi=%}QD6RJ zc2oGFovcbpEnBaPGd0|R_unhFNjZltXSJ3WNR5~ht6v}7*OX&(DfqB@864Z@EaZQ= z9qu)5NjA29OqSJKAf0kr1`|F-vFS%9vaNxx;CwKI6k}Ui`#BoZ=g~{q&L^Ju?#K@& zX0HV8CJto96CcCS2j}%Wc1&cWK1Q-d4YaIUT7C%GaGjj=`5}3y^<_aNT7XaU;xORm zC>UB}3@ftN69P>dcoQ>%omx7Do&J7G+PPXBx&tyR63JfaujJCJQGx=ST; z?dJ-XR3S#1mW{FJqbPg#P$D5u(@8s@zISp)^myoB_0C>?= zEmWPFLs)1kE%@ek1znR(QpAJ7(xwUJ;Zp0lP`s#t^^a(+kM0%%ey1C-l$m`=p>N?* z@(f>gzFi_an=+o2IJ=d#8Z=INqo2%nFB-_kt$Incp}w%-suwhDQ(5m`{*Y9>#c1hC zq=z&hEiY@}TL?k}ZbHrRn|2*69)ri(&=egvlicjv2;4^Bg~)mYrxs{Kw9KQz{nLmqg-jzVsF6 zd4!88jw3(DIZHchWRZ;pF0rS&9I|tZ_CyXisPDh28k<&rGx;7djMN|IB45<{!`n6U z*xvPdNJ%6c2@sm)r7RZ*C9 zwzWFI{>|^CgFfe^HBCL3)TtJ`QmKekF*!f9-INHUH@}ji{A%e#jcufN1)9Q}%EQy@ zy($j_AD4gv+jfyYU*fmjdRVQDa}UQsYAMTIm~4L!uszT4>s#+ zJ!qaY2K>8iH+4_0!$N+2HLW_@2Gn;vOm}7{v2P`Rk;P>bCHKRpq|{+oq_;WuvH15J zSDnj)>`-%{m z$4V$eg@iIs@w?n>J!?JR@ALeA-{=0^&sz6;t+V>Cv-dgI*?XV;dhLBi?M6^b$90;F zaLyGG?)<_Fc&=8Jd$1*w9CCRhP??a0&G+JnQ$-^A8owRqoe3doYof{8VeKUCf+O?^ zTEYAIPkQ-*4;UIgAjzdBkRh^`rmOFQHXl>$tQ?M;AJhwuCf|kGi>3(Y)qN&o1Z6gz zvqa#u+6*#h!Y|U4Z3>=y3&F0+0G{n%FZi)Zf}8#uaGLfkJSD1wkLNd{-K`B&<)9vl zx+W04>K~*svK=xL&eQr3N)Kl?(L#v~y8G}9Oxk>doa3xOFF_24uUPp$Y?AxP_7Hn z>m%_Bzl2kCf0Oz8havW`2f12v1#CAS0mH^}{w$`zg{ZfJ8+*!d$sJD|95NJ~hn^v- z%|qK&F^J4_0@2C93Kq4(?t*f7r=7L8vH$2NTtzHmK7nry?syfXpf ztahV?JOWT?al;?G}X0$(0}$W9Byl5yg||n`qvw=ZlJIpo#NSrK1Qi>qu~`Y!PQdR@lq6?m)7MTBVBL{} zAHHv=*J`$swlC$N<)Ma2#{{@q_cRPUdjk5mHIrrGrQoW=--By2Y<9>?!Ni4K^x63V z61F4<+Wnis@2L-6^t})+6rY9WwNlKS71E4i#vDiL#-NpyP%qu2Fj{@Ln~ZPR~z-*{OW|7WS3+-BClQ;xMpQ zcu!IzQi)V)9F9HQg#GG2$u9mbn|-)}yuX|#kdp1Ch2ylKCt)(g2L;2{UB0;Lb`9(- z6@yy$u@FAzGnrqcj>}SG$bz$L(cq{)81!DU*=s)s(`?*8NUNu<#MgaGePj9~$75zXZ5VUjgsbi;1319ekA2Vx(sG zlAcQ5y5k}tErV-ky_}cBFAbq(EGs04n z_*uR{$Hx@Kvd427=*Fqcmqe}8=Gd zC$~-bqmhtDG4(iak_!&zb7Cv_9LMyB&v;5&sZF6{0TyLu3j&{(<8&_*{2ew7uWy=+ zTR*x%4Q%!^f-wS(QEaCIIuu2E*<7EYtCAv?ju`-I?Wu`D<7 z%tuW4`H@as_!Ymp=5pZT$mLhA!2O~{IO&=lcVx*o(41|G(RX6-P4iT4E9h|H@-w-w zcV42R(j@MxL@JdIx(xD@f51lL#SC}Ff;<@EfTo`>qi(_zv~NwoXGI+L6wE?RjlB>v za0f*7n&^n+6_}K#ib^*UNMer_uB)96K6;dFdvykq7QKVFgZz=)(#19x4fOqfm=?aj zLW19-e0Pdam zKu?OEr$@|U;EBZ=tSB1_>zb2cAgu~_BlrJurSVTD0lfrdrry$|%Txd~lVD9ZN zV#*KPW^zuSV5ZGPW`6^uO0A`t!e%c9KO`}I+M&#m ztYjwMD~)m6m&QyQ;SU3ag%A|HgZcKTkT#F$CwEh=!9->_*ZZ*%AH4UX=_3r7B@f0h z9mBqZbmt_cLF& z?48U@&uLgUxJuBPr_9LJr*dh6VI*(+Eg0~93y<2Kg3@9`=4^sI*MG-Is5B=KzP{he znMGWtD^=G((}Tb_fU`CBS#=YK|gr;m9J$%Iq{XK_sH^c^GZR0kkP<%9VQu-TQ-msQQ zF1BMl1?G&b{~{YPYKgPvrh=Qbn;?9oD}8>U7Qd+^;@WdMm`z4;`oGIS{;e4kb96g% zVO9)x&tMmP*I&(SKGwxuv75$~^&9heYymViGjKVo4YpLtQQ4m?w3rw%t_G8_XQ+^% z)f7l^R|T$oA+vF;KI3A~aEFVV;gfzT%viFFJF!_2gH9_kmxA`d(j_L$x@+!?Rlfum zIpPRBR7!`&%10?upCsec;3O`&{fMNZ6Xg{IOILIxA ztdtG#^X6~3{G^zu&A(5Y{af(Uk$pJG*ABDhIN~|Esa%rC2<~^980Q&TfRd~9xx(t_ z=+h?09V{5n)%T3%DuveE*FX`j*uaBxSz*P^IVHlW2q$sh1WDZK0!yx3BAM$8T*nZQ@2-M{{pRoI}lT>X5Zs6$anhitEioVeg@dAg!T`+l8&dsa8td*}VI> zr7n$Xi8VpPn^m|#VIjKAc>`14UZZwb27yLl33+P!9A91cChlb+(0=X_-j<4@mC+Xj zr>l>V>>qoHhMg{*b0?8I8&{8yd($9ofi$OcaW(8oSpdDZlkn6q4;-;&CT^X-g^MbF zO(d2WG9E=4=oK~vH#@w4}0 z%-+y%I8`tYVzR}F;MHARW0ocu%HuAo#*)m@)qaq<*at^nmj#P2RbZ#yK|?jI=<2X` zV(k@GR~e$gthc@eORgLzL!{gw)${>8a^6Wa3al`~_bZLzl0mdGh zOC6nuNoz$x`on5Y`HBp;aBweH%$4Uho)^Xbi4sg^Q4!wSsg3m0WoXrn$Ier0VC^Xx zTq50v+ACJ##a9W?HB6Q}ch(n%8+@R97lq-*;#ka?o+c>Kk>yzBO~hKi1iDh6;&V$6 zl#Vl_6C2BL+UN$%QL7S2GVvH?6anVJvhXTG2fZy7@TQ&``Bc0c4=VnkYnGSb!02@# zRoDiK&Rw*>JB1wnL5Sk#Q6Q)v%$O-lG82Y=hjV?KFeqv`XDR;$B_f}oP3#@~I#i!? zC_jaYf#GP@K8(}W$m3pQ7jd@tgE*H3E4a9Q8Jz0eLmW|>#=S1w%~_b2a4%dh;^XV9 z=up*9I3k?qvIUvZ^yMAYT_PGkJyGCR<;!xDqo09Ebq(~d`3`AHgPGa|GeOlNg6GnX zVG4%aftR(0%uAlfEqBHiPi*tWITC8L$Myw|5Z{D@50qnaND3PL=*F5Ed&%?M*?8q} z5%p9{hee}j;of&;Bw{{CT`XdR9Utn*@*%OL^SUAS#O|h7{EiXfJ}I0ZZbwBIi{p6D zHtK4ZjGq=K;jtDf_#ie8y&lG5+??_7#-s$o1CoR{@16yjXInw7ew71?R!WT%FcyKlcy0+tkfS>63<23r8l*3*NKGwHf zPHfavaqU!nJhyIurV+%H_3P*grHjJP6DCsk0duOuJgVfYXA-&b`yw3+^)CsfLX%M0TOYlWIc&8rKz+Nzn8(_pZHI*L%C3_%=e~>0rjQ$$S8fP7 zL$?9hn+X!36QQVnFBF#^gGJ%$5b!Dn!d`_z=RH&UcCKXYQAaP#F33ic=rNFNuoeTG z3&B0j12#Ua0;3Pg^vsKR{9dvcf?jTitjOEMV97@E`OFT1$d(|0n|a_>8-m(%8?pGB z5~24aVMTN+{jp9Igu@#sqhXA)C8Z!a#uTM5gdkIJfM#3{!}+g`L2jc0PRj%u5wwB2 zzl(?N*~KV2p$v^oW|PJcJ@WRoyI_a2F+M$Hi0gd5BAuL%FQj5|$a@cZ;QV@YSlC;; zD6pPC7x`$ez8_8I1>lAI`viyAju(7=QVMSi?6KzYYC&OI3>{5fpu|xUWlko*myc`k z5D=}9?GobpA6Aa9EfjRR>LeNDw2ng1Jg$sjm$G~2qTkb-#->K1?23H~U-FZRb zbVpb;^?2R0+{0k5BTg=i-32OvP4M0-ALd?Dr=KJf>y9_~(rb$Pkoj-}9X2WzGNy76 zq-+UekIFOB?q|VzW+`0s-woRyg@JqTO$d1O1=9KtgMyz*aY!gWqEAy3S_-^hr5awAb6M$z0l%~=eN%yo8Dc6@a|?9r-cAKbVuD0f9P4!OQOm?QzV9k3-@?&a_TYciWDxHIQO@ zHp)V^*if=;a2N!pXb6vaSAbtKp9^j+pa;8VK;xNxpu5ctKiXcWsd;`VxRZ^`t_|YC zw`K`%%N)fKv5T>(#}d4p3UG7gc+gEgE)4bFL5uJ5+|Rp@$aT*uvT5NwGd%w-loJT(RAeG-^Bf69nXFL&Ww=!m_1N z%sPqRuruu~U0a+0QtJz0;)1>8$4qJPK60CedvbNJN2ilRlgFU{o^rwJ+a=(&>=O7i z?}W{V7nAC@mGCKEl72CZ!qTXlsMaaU37AfNC%zrIPFrr+J7ey%oH6J1VHPJmI+`0< zFN;3b9(X8Lk-PNW89j?z>BL|#c@3E%OeX-<@(WjRW8ald1GE-1p3~5i?U0fpfIeP{-zPJH1D(2U9n{iMfkxG8LYTyZxJgOEr7v4O2Lv!t3+N@otT05@qEJhio zCTgzsHo#M446NH*;g|jj@vJ%Ck2mSkC_t;+WMFtA5#Sv*X08%7787s zMEDvsY3B1}J?8wb8nCT)rypOhhK;j7k~9?#-Zb>Vw!AdK^-&w?RYwKx^(q;XTdM{R zn_uAdjCHX6)n~}j4Tceg=J3^jDdsO!gDu;4!m1fYSXrJ5PtHft+ii~ooS%@IzZ?c< z4WHuagSkTWJI;cT-;R)Th6<{yjta}(nUd(93fl2_4P87)7lSP<1c7sF$%E!jo8p&y zF?3KO-BtBY7*d&!JrYT{`ua2a-uOQDw`LRP@m45ORt@2sUO-HiBv1!w#!8FFc#M+C znk{4Ly38}e3VmY`kL#{0__7|3w@JgO#%17hEgaIMW8lu{-_Sd@4N&oLj~7 zmvS$_tD<*c=EcE`42E&AmS9dvnlsb*n&Q)9LCpBgW{iK-Iwng`o^k812E};=V3`vR zcRpw`FD-!~l^nR=mtf|29)cAovW^!^SBw!p2q5dhiP|(xQ;w_6SJ91lYG@ z9+Zjsf>>_?tQszl_f=fr{Znt4^*NP>FBJ#7sWG(r`*G+m`6@gzUldFI0iPTjf+rG9 zAZ-128fhK^YjqlIN^4|r*N|fn(;A9femJ1N{A$6zb~h$}RWHv0J_7~e4gkhun1}br z!+vXVCN$;B=}0FZu#1yr%sp;`&b%DZnX?@B&D0>5dvB0eXP!aP8VV;Xw4p@*5d>Y) zgp8zS7{;svh1+vst+gJ}N~|M^x4P(vMbj{7r6gl!@lvR|q*u`EU`3;d0nE6Y4^Q~N z_Z#-X*{VCVB(#gXnk0jMdDqDmwY{jj{Q>P!tB1XZi%BQX>34rLjokdW9X|h@2-jVC zUXY#&w4JIFF6Qg0I<#BpSfL+m)tL+G*OgH3$5w&TetoQ#3x#DIY6&qp2C!RN)I!73I zHA!$(+mMX1b)j)3IXHTjB4%ihhFRh2%#Jss8QDV*pyZVl)7Iq;b0+SDbw&Gy!(zV> zFXi)aZmBl2Y~5}!UceId$|z7AdJGDaYC!wq1G3R*8tA=O!I0PpxIge&5U5>DTD!(F z#{$ej?~5a(9?TY$@E~BpG<|X=b_mYDbP!j5NWw+e#W8QMANU-S6WrcMr1M^Bqko zeNSc7V(`flU91u9NA1MVRDCobx7o>agJzE5hRdV30bIYuU~bBU`JAr&T(1885H7iBITzD?5F1@=@KT;P%{Tmj@~3o# zslf;Et5O2p_3|Fs{(1#&v_DJbo;}0a34>{0%YGb4P~$A8=AfL`R`l=5!LRQJaQ)zq z=#p^~2jr$=rsPsgQPJimCg!7!R2g}^?ka|ON#SdqK)U!q3f+Hg2n`Hc4p%zf(Ocy^ zQEyuaJw0hJ+`kixkNv7JLam7`SXoZK&fiJw&ue0Xx+9i8LQ-&iBTh(l5h_Uc;Khh& zj5~M}=S_Wz7E9H*QG#n|7o-BG1_xl(ku<@w9&21T<`8~*kd0~LS-3eS5=K}zQV+u; zWbvsaxV2l0`Ce3w4MkPBPY-a^DNzg#OF*}SM~UryH}oj0!HbtXKuWHprob-|n(Go^ z4qumb)6oq^M(%^9bM{kV`EF`)=Q4`1yHLDL8a_-nLg}w!Fexw#MEAwgp2<$2?$iOU zj|g0i8pH(!`f;9Krrg2!k=%$&op{mp6uR;EirLe*LtHxxipAE{|16>@XC)9-uz+3{ zFM3nKyUwL49cONF!?Agj@r~F8lyz;RH++9%|MN!lb~%rW-;UrpOtvrt^1(u>hg8hi zEm(hJ9eH)@BptE+DU~`FLZp*-qu9Y}!J(~wbomw`SZ)?a|D>%bxPFw@eEv=YFMJ?J zyJc`8eurm^e#5Qd@=Udb0{n=`fu%(?F z{$?IOtrY}%&4EceWAS&DDR?+bqqwsO774>Jwa5{d%?%gC4+*BZNz?FQYa+~g87Bze zT0<^n<`V19avScK0^_wt2qo3>Ok&e~=1GVeGkdK(vv~mr>zw8>*@-?(x33)Yx^W%j za%mi6pkT{9P7h|1b8Q*2-h;8YD8@`5n8E0oAe_xE0nZW^RaW|eTg4hUv#LsNK>h>;+QEPQvn_}*iBo4A3)GOT?WtIg3wg1oQo+D&G5k2qI@mFuAi0nH}=KVaDq&Fq(3N z_NH$Fb<3Bqhi|04Slka*9@tCr{7w_KC0=!-KaPhLj3Zcz3qjn_1cVN+$(z`rRC7%X zc#j>%EIEVl`!z!pKE$Fz|5<4NF+p&~;2W7dRR*4oj~7yn2_T%X07gCXBOl{0z*GYP z{IV2*G*JT>{78<8O?$)R|Ha^?cLzQjcao;~bT~3ULnyfRiN2%<;kZ>I*`-;7vvp3w zz8{i|Ns={V>U0^#*X@K`gUX<)IS9YYK;60LhWx!o9bTB-BqiskLhWg5)Y@>FZh8_8 z5`t~?L5~E=kMbt^FBUL~XEs1gTOL&WIt+a-3|OulL@q7a4xT)hZu;&zc^dTg-g}z9B&+~+Me#*(|^h(_my5rJl;`HMY?08^~!zXXVd$*!s{-Su?KB62g zJ=Nhh&utBFHN=Q}6JV+!n=IdE#plFqxQN}avF>XU*1XQ)?Zh@zTb+$74q0_E6d$f{!K6E;F zX2ufk!PO}4j?j~ff0E3}w`y}+H(6nOyCk?KO5-$ReKMmCaB6o7`cKeC*(3T8xoZj9 zRp-+g12^fg&El}(sUiB=SK#&8^*ET%L*Bn+22Vc~lh1Repdm9r)?Lx8TNhY|i66(| zuO}PP>TxCnt}nH|S)>DV_&ofrZL-MJ=b_V`V!_GB#w0U$p)h&+!T`ym=0lUd-1Tl28aS$QIPCl4g!rQy6nW3e^v7#g&b}(MQu?0No?-UDWlu zbLA?+&&@HQD|P^4B1VvX!<@-=rvp&;H4ZM@QBo3l6~v#_5gK;^!Z!YbMbD?e>7glb zmoKGR`dJp{+ttyjMSXO!(-5IRDUn1mrr?&JBiOO88MAU9;*Fu?e;oFj&hvj(2#t4{_{9TOuDmUiJQ&;BP^f2a}&JOCipdD70&jYDLXTjyp8&HW9 zWgd?GA#k|)jc8PP!@kiH#K&_Fghn<9Q`hXp0hNoSwX&4rx7TEY^bjnv@~jbQPp2)l z`fyRK4k`*mabE;dmqkWMLKdRrpmWgS-AcW~GleO`cfinAC9+UONcPI_hRhAwf&UES0{Ym8G+a!MuE?a{%;wg#O1Y%BFv6DP)Xsc38Y9fKvMxdXEhj|EC|%TKl7 z+s^HD&b`501kvEmbXC!claa!g>W5L~nonC;lXQlg2dh1(D7Rq zz70GrkY4$fI4lsMvYD}vqiBair|zV8EbYmr5l3*A-ZCs}ABJ5^weiB}a^CLr65}Q6 zbZyag67kWU=C7g{DeZ=2|9%p=S%zaG`s%igx_1#{`=B9vmqcXX)(@e1P+bBG{KnMF4mXoCXpY%av3zj#_lgT>K zxIC$lxZa&hX0$oNy`Wi?D=HO?%-aOsO~1&uDaTQ;GaT%8SkT6K6F~G{0;Pw%(BW(V z94`wXtdu)8z%CekJrmf#>%x9q4lcFHd>+OKi%(8~jUNJOEi)dd3!Q!E}n)8 zTas{V7|_6`SJ>FGk9>TUgUkA&sKH|e6w$j(H3npHh`$P%x2B7fy4k_$U|l@C{uG}5 zw4LgCjE6*%RGe^o57q>UgX)Vh_`|&)wCIPp@T#{7;vXy}Z}!N+jzBfWTJ{r+e0fU{qt{Io ztcNgRljWI;23fTKC?FSv!_i`T0ywOh%hv%(f#Uds^xTGC0k!AvKOe`zWQhbgl^k6c zoH`s*P1b-_*Pgn4Rm0K#bQ}F;=?I%+AA*>v2R-4R01JP2LEpA`SaCiM1Tg@|6TRT$ z;8Oatu^le=U4w?Qqcz?`5%kh-z>1F#p(6JH)bx9hb@neoq%RA#)w~5&LqF0KpKUOtAZQGGBlR+DONZl^eF2;I1RvCYC) z&Jg2ZOD4|cdDxN@>8_s#VZjb*W*^_vL*#uaJ!axdEN`sA9;ek{=2ip4PMUy987F*H zdc02W;xN!^`9R86-9?o}8r%v48BX*`DlVH5g|$Ou@m;~AI&I&5*jc9tq{p0*V4|V< zpcS*HWDn?_JVhGSe!|*4ufZw#22?gIhITP^82we2CT+9eYY8@3Nli+HOv95zQ}QW& zeJKGoGIMd+#5j1>_?mP#*HGh<@zj2F7Io%v*F{OS;I3p$FBa631F=UyC&3sdG=>su z=SH&M-4-gg6~O7Vo6vvJoOGSG6S$=)LgC#O*n6yi?vI-W)xz&kB{L4%b3N$V2Tc%@ z8w}4E5(rBv=l3}ZcHdWLLRK4rrm&J0ej)oaD^Pk&4h~Lp z0BgBmnw9t5rZTris5E7dAR#r8YHo9;Vj_Mpxi^3uHabi)!^Yv!v*j@Bjt8IrT8yGP z4rH=Rq2Tnx9P02uUl=K#K@Ivh<87Y|a#DU9b~NrMei7;DdFcd>n|ML+y@BU6>yCu? zn^H-rUl9)T2_?Nvm#`vz9i~jZhoSPvaKL8|mbGlf{*lU@(|BF(OnVQGdhwpt#l4^h zTSAfj(SSY5DrDmHgVa4f2X(U2XzR}$a>9Vm^~ctN)jVeuI4FbtI7PTx^O_#In1XsA zPNBo4T6_@KhnW z&(q*GGr90(Mm;JA$Z-K)cVSESDDomI8!sPz3d6oNlBG+sFiX4w#HT(LF4a7SjfcLG zo|W48qM%BcV#1NivKTsK>koSWUJ;J0Orc`Uopg*ulfXm&E{>n!COjkNL{@E5gxzuH zY0pq4syx?Jd=H5|5s&d)?;-?|NnDxfSWfz>CO1D) zkt^-a!@;fB@u|^d#N!s2{z8Py4f3I&h`7jdHTuQR$Hg^wF|j@fr|#X%$Hg}>U{N;D z&5ptkr>DXX-yR~nKo#2`YVt`~J5p$H1sm-3smYDO+$5iV(q3ADGIEHscO`+#>{wj? zdH&AIPL=y|bprQTsK~TLsxS&Z{^ZFwzGhP882D>>gOe-=BH|6gs%N{w(S0JFV!H^p zpUow@W%AhCCx@)mb-Mm%DtS}J^H9UR$m6l1g4xs+GA1R0t9%Yr%u<3QU1K22HW$+J zS$OzV8IJqRV0@++n4j0lg)y=4>f}K@G-?+brI-n#QxdIjD840Z=M)s@YbmRL>toFHBm7=@Lg|_N zWcJRLm>i(Wt@%EjPW23-A-kG{(mbE+@QnGwM89d|=RyWejz-aqiRpFu3I3$w3F4-J zXtI63fV}!q2~O)>;Ab>nM{qD7#Jw`;Z;u9$JsJV2dsjn4{ZZOd)=hjyhvKWrftY0E zkAl;#*s^;Vcs=`Cr!~WoC~niiMd3MutjH*uANGKptd-{0>RiHAJ7cJcC(_JQsu&v) z1AaM=1$zU2L0-vXI!G8x&w6LUEHO`RxK=Rd`u;mEZr;l69W|dbz%Wj^_6go_)#RQz z9ic5hX5qBj!H_*Gk#13YMDKQX;fsKFbZtn$>K&)B!LbwPAK8wqvpPx~^Pt`V=fKV5 z197>g0`Kf)@ONnvYWFR}EsNZ6uy;Q>eslxoOz5%M7-|PIl~u1mU5nDY!h% zAIb+M(cOYvRFznQjgIH)`YUp2T;~bgw&NxZY@Ch>&p(iduKG|o?F+hFCSl6VY;^FM zhl(G~QFq}SIKJUUUGi>F zJL4w3qru~h)@q>fAplks&%^ntBgp;^X?U{A2p9IZpuY1w^c;5;n|CH)aA=EQ&WHd^ zv1*`i0-|wTKsZR{oU@6!w~}hh6oPe}D^{kN!>>MFOv8(4p3C>l@ZXEUIlE|Rr3Ahl z(?j+d`U#I))lnmvRy;BBq_E)XW{k66fHxN_V*I2~bg0`;h>ZrG477+Y*SwCkgP3F^1v8SE1X^5Zv(a6TO}8 zL>$9z(DShzkvY*q$3?rqrO&Rk1N5={^KiTz(1&I{nOK&w74OFX#42eI92wt;v0pY} zqV{iMX!;cCZVAq2*Fk&{7mi!5y~H~0GBowQha(JiIF}C+T%G(AVzj%Q2EIu_?RTN* zI4cE$rJ^9fI2ny^GPoyOmS%XH;GvVff;UrdqC@m9d|sJMG|t?mSvTKPP!Yp}#UkkD zk&5H;HEBb;8)?$^6YQ;!gq1py zxN!(Io4(U5GkM`NzNX1SJ^>bJCGvbhL)^cn2v3I1hL~-hc(1hp>cpDK!MWq<nR&;nKS?`R&buLFPNI)1QxFoa3`CBp=aA^I6Z>ldLmeL_C47p zm`fc@4`N8y39@%ooe=Gp!|E%NkgvOo9xE5XjOR|mELC5LBPQc;k?$a4AG9dHu4qb23h~JE( zaEatq{A8bsN(uUSw|6YcCeFpssT>Br*#HYio`em@CZOD47ijE|C1R)I@cPU7m^MNR zIC(vCz+!;z{?;tGCb5ua1rFx=J_~TEh#Zuh`-G-vj`R525OhAo;uzs=sx(X$hqOx* z*Ntzeq}_5j6p@AREtNrWZ7xJUvV)I_o1v$?mR9`~5~WLqWQplLnmCj16<3x58%FV% z*!zjZ^g}0{IgkdUgbRdk%}uc*JR1x&s$rgp3`yMW1v%aaK%rFuvOThh&CX|#HsLB6 zUS19zig$?i2~OyESsSr*CwY-uK{YnS6N43%w0)8}R2etd`SG~)+aexY*}5M)zIwoC zpDY>?atQs-X^_>fwd7a-G%)I{M5&laH2#)|*9JD@&sTXk5SUfh!rR3`BVW>I3MQoY zj5=0@_E293N$Z*V8Z;l}@t$o24$*y1ucm9E*hVe7xj_n?hFs-y@Ue9D=thCRd;z@5 zo{4%_is=LG`J`lUHStrO1x&#hw7XeInoKXkxKsJ?Np=eC_0?tU9n6?*nd6zB^<&`a zH(e&sRD_ANGhn{2Zh%`8Wtpy%-(ldqJ_L5EP-~A4h?%Pe9Y=o&cSer|`K5)x?mr2` z!G$hsFBArymxnXE0?CiB3-QR+iTGNzhpzr2fsQ`%s5bU2>fFrv>Aslg z^-TxkUR}DuXEC-Fx7N+whUA#WahP-G7I9uO0w>PQqkhBB;<_AVWEl^iO@>xNA@85Y)lY@9j_dGA`T_ds z*;H`w9EG=64A2^rJmOhV4MDXjRB^)-!Ctxu+KxUXN=qMr=r9G+oV}7NO;?4-{d&KCO=t#pGNKzL`@JvWAAS8nLDKJ z_o!hewFLoKi-6N~1?v=H|7Q;1ksM7zN7Tm@L!52~%?nP%!86S8o@EA>NAZ1}7G$FJ zpV;Q48+~@Xf}RZJ(d4~OHp+H3bW=q+JU_b+J(w=*>Am7$I8g+ByBU0fKgr<$UEFv$ z16P#D;n$cN*w7Y_7KMR4H+>uWHtTV+J(gU`wQo4qc(`E8$V12%oe9aJ0z9r3M~nu2 z!m*4Yay2=EY#$jebj(Pu^lc0-Z4l+Ex(hJ4?GW}ZQ{v_wi$(gy9b@gM;=1r8MprbR z`PrVvJpG--tiN`EX(-KNBDn&lyk;u1YyVniX|Dk@a>5(1DjUx1d+f)gcxo}daub+9 zts9W#H->Smy$=_(WnjA~lGF`_(7(!!7?ElPuB=$>@EiVO?$z0 zWG|)Xf~o4`OcEiJ2h+#x$4PDnF|IM6jPk34iloz1W4KH3?Ys=`ap# zQQ`9H>@ehx4fEyPez4P<1p{B5si@8`atKA?}R!|53%-RpRgqSG|sn^?OJ7=mOHVNxq@|%cN^xmP zVYt5X2^{|Noml2vgwq#?p~vN&IQWhph?wfo1x-StyZ9xQa2v*y&z5BrPwW8Mcdnos zkq-B(H(A;bI)JPERZw|Np+G5KhSOc8%&m@lMXL|U(wa^^K?2{G<aC(bYl_DDy9~v z7?|MIdH$TOw+iPxY6{m^-wuzv9tyo34ub8>T0CDq8ujHe1dFF<%eEGai z&~^Y8Ha#GZ#~+0kIfIy)g8`=d#$nhh4SH~Q7#_>50xoPFiT>nBbu7Dx+3Hwmxps@1 zJywA$*-^k`)xp?X{gD0P2FU!>VLpGq4WfYx%m*nOXkX29JMzq6g~CuWbYL>o)J=yc zMSSh*{yO-5)|kr^3+MXWGPs-vmYmd=aIVwCp36A6kt?(;;Z)`w}H=Um$N}dKJ0<7;cS9_K07ljmHpFy zJ1Xo!b`-DvpYgZ#H#ai-C;hiCUWsMH2DY=i6E?FUkD}Qv4MD8qOCNUJkXY8>G<$yRLiUVj4BNFlnoX;X zW+Q_m*iHL(u@{Div*XiaS+U!}>^<`ccKp>yHc+#Gy{5UDjSi0dOaEfus0sh6{uX8y z|49Gmm$uoRyphei#wOeT3S4PtJ8_lW&#mpYpCa|`tXf6wTIvgJCzWrq^FKGo?%lH$ ztXB7Iy9%dJyC?gzZAb4Zvzx!^2YY!%m|fxFXSTgp#@QwNT(!GDUCHjMuRiPCG1>O( z&1<&qQoeRq=B=@lXeh8vUvtnd(c!&q#neT11wS_a)h~WbvvvHsR(|44t$fnavP zY&rYk(pI+EHJtUGvYDNy9?l*QjAZq8WU`}fB(Wt?Ti72J>)DaXTiFRqli1;twz5(q zx3NXr!r3THV%6p(v*E4LYI(Vg|%zhhNx}qtOwiKr}tvntgBJ% z+140#f&FIoPDKzqzBTHv{m&GR4f{{^w=}l;NBSSvLb}yZo*sCQf?G1fFWs@t z{6E&;$R7saCi1!W-U&PX5Xv7V;tK`SjkcO z?6@x@>+c$uat&4USiLj5xnqNC*pc%pm@_S9tkTj$EHjAjC-t+L8Fb=7{q9=PdauqM z^#dy+SV_5ajGTs5eSpqWR^`~Z`r|8|*%Yn)^=T(V>;LF~G^5$!Ki1#W(&C@kKOW(= z-SETS?k#^dwNk9@rf6QbmC);9Eq>0i+crgLd%*slt-H)fJN2*;c5|jF+SaSTvfW7+ z*tX}}vY(9g?Dk7Nu$>%YW%oR0qTQIi)ofy@k=?ald3Kvszp)7=adzk-WjC<$g6*JH zOKiJMqwRdpjI{f4^`@=%Xhplz-_QT`{=&hKxr6^_{nbST|Mk5H6C(=~6LZtQ7QpiV z^Meup?E#5r=KM2?{O`{`>^9fF_~*H?KjVMzhtx$(|GOO4{3G)gCYB~sr%e9aa@^tb znS;u4SELAP2EK#9lIcuE_9V{hMgq9!Ds%JZEMN|eSK!vpna&N%d5t&UNpNSoui@iB z1y*NO|6k`P;KTdrw!F-L#{Ws~|Ht}Sn;G%$^N$1hm)Fn2*pe564`lxK`u+d2e-_48 zmS!gWI{aJnn_8P&{4r$z*8FBx=9YgP>Ay0+v5~Q{g{iTH)xS2snW>3|xyipcznPgC zAIbk~`kPyrTN(Xp-=DDwfA}n{ta(TF?|gqImKGM4CdU8b{FcV%e+6>?j{fGBmS)CA zR{z@f&(CjZY5E`8pAYK)H~&3xlHvdCzg0!d|EvEtH?y|3H2UMcjsLdy_Nv$OU^Q+} zVa+1vuwr|6vis(^vXc|GvgOTwtf8ed>#)U=jjzdK^M9>jPb^x)PO)FYY6iNp)yFol ziXS)r760dr;@17o{##W9{+rz9Mn=Y_7QEN6{`+$OUty3Zo62^S`LlXm32foD5O&$} z<*ei0NOsisWvp$*c9yTPV_k+VV{hI`Was6qVM$~Ro1>D#?lOsIPnLzU#%rV50{$-4 zc_)gE)7-&6J`l%d-H&FKtrOX};&^sfLIfKc63eEnk7nKb0$Js!0j$^kEOxhJ47+3M zvcL4#{`u&B6d$|%8UOqE<^M&0V=F7;KjH5`(4U|3AN~HsjTSzs!M6N=`7{2G{FWvb z#%4zRsryIrN3s0M{cGco{*Ak}Mn&ElUHPs4M2-JI{>7;scF#r^+jSL4*nK)GYFnRo*S2ABnXN7-I;G>* zOWO{0bvqaIwL4WjZpwtOdbYuFO}1ToQfylujke9vxbT!gXDO%p@=*hfk?S}7C~Hvv=<=X?yKBvCji|isjPi2~s>HL8 zcRScl3s}qQw{cv0`WDu_U4;?(J)U*l`-^{Pvy(=qbilrg{`G^_F0!5JT2L?9)ln~> zZO2Vol2<=_>?GT9oiplHDs=1bhBp6YKRAhopeTOt{*1q|e-=jkwaxk;+Rp}RM06fOuPO`1fo%Kg~b-{R8`DVa$gt{1X17 z?>`{g5PEKf(w_V=#9nkY(O&6`?b5f&+iipKsP-&jn-)Odq+H=QvBl6kJC~k`(4vmN z9npEh0n*C4px#VbxEkI^6tCLgfa`L|@lis_$|+#Jb2NSaY8rHk%i^zc59%eom;B`G zQ5~$gx)ok4peOGdeR^i8V1DU1RLGIUP2aKv9m5-hdaHd=chq`=!=99<7I8k#DUOc)Gh>yl_}%Uo~@)FkKB z$ANIC3~p6>F3juo#<}+DIQEDqD4e@SKKn`t|G2m=Svgmt2>Blr;qUS zy+!c2`5-l@)}am4L}3BR6GV+WVDvT3DrTd?0)`xL`aaK?!9V*C> zYoPmAjul#r=j-%c0)f&Qn4A?)OzMo$=)+{(pfC>oUI&nDPZozb*`U!$TVcuUK!I4? zA!-$NTsbw zdm!0+i;R#}W?5Mwo9=VWvh}rhvO_{-hu{7C2O6*E^L)m2uIqYFTs8*Yb}7J1fdyEy zR~v`^S`On54aXBZl_`7UQ2gNX6ue0h-)$Tr^*}`N{MAiDdi-Z{$#LS9e{MkA%X1`t z=)}2iM$ywTzGr+OohxkQ92akOU z#CVq?I&N7DPrAfFZ_UnZF~uL_^1|4vEt_{->J2YX=kTkA3u*YmIx$dd8yxj{PrIMV z^P+bexN6*YuzY=(f3?u(h7T7DSIBBf272%AgBvawiRHU@ z3M-b6Lettjkj-5L23n_UZ!ai;zKT8gc$+8ApHw3#CO?A@dq2Z$yPhzs(H*0uo^_>X zA(&ToR5(8{fW!Kl3yPMp*mtxEPFx(q!*1TCdGZR-_;(YW2{1#~4N4TGts~Zy+=mH@ zyKB(M+EWI zxO9%pQNZUr*3;9Tmh8AFoBj0%k#&7CCN)cM|w$l zUUi&kW6X^wYp5%B=ScHGxM#8&yIgrjLUp3-eb{a&9vTl1O-jtfPJf)DK*QMgMM-&AnK>>+wnY+x$p=j4FOC(dUIjZ1K1d+hh6rl`!hK)CWzr8seee!+AtyC~kB=0ERD(xu#+i z{Vccly!behn=Z85k>cK0B z)g6p^U2M>-P7xn|SHqwXCqCZ069!gxp^AMkNq&3|uGdt;lp)Ss{o*BMG`xrMjWVoA z>rOY@n`rFJ5$LkNk=}0hN3%nZVBM$|sEa73%GF;)Q&T5AqtZ?CfmFgP$!nRuBb4vY z=)_|y7QzYE!AWvwsB)+^rzl%-tW1r=+pFm5`yXPv!w__rO9iEl)8cvCE_^T7k7zi$3^oB zaEz3hED79C%~r_zv&3SngFFkB;ZV%cj?anGI- z@;*0>^3M#%H&+^j0Oe!wGszY6K9q?z7iJ23i-ti^|4i^0oC(%Z`sj6_3vbq62G2)z zC(p7$Ty|ex?CAX%JeLRK6l)v4)i6}@;pbs{uS%HavY0ZrJHh+_Rov$7hI+ZcsV{VJ z{kmUpXnPXtsZXMxm;2#tRKXEdJE*te5DK}pMVP#&3%>cF#U@58sPuahxgFgC_H&VE zbpZ^Jm?QT0eMxnXF^8>RMenNmre1plhn2!{OJxx#KMBNQYl(d_eE@yCV26kD=ZU(_A7E&(9Tz&)iD#9~CEuMl zb&@)>TP^zH)SE5vY0wMM(tS*$muX8r;G+<_V;ViKAHq=^!zDH}aP{I*++FeserkJ4 zf6s1(PBLejSoxFW*B^!avQfD6+fXjbIxq2B_fmY?MVPmz8g9<+#Q%~kaqZe3I5OLb zwRd`;x0V;qoRR}I^*yC7=-*;#_%~Xr(*m}Ak5jF5E>*9v=d6gWg2sD8gzbOD`x6V$ zdZI2)S-wT+6mG>&I{HB;%g(r5sVnK7apzFy1kN}$37X?7$sk(`Kjn0xSJSh&plKic z(p@U7pZ88w@{H#fLuz3|PYZ52v<`}MQ}}CvEfq>Ui;Mxq)O2ADP4GJb!+M@1_ni0Q z2!$HTEj~eoN3?L}eGk4o{grs53y^YpC;ocUTs+#_gclgsl5V7cD_2aW(#$rh?e0P| zugs+~`FMU@5fvk=qti_Qlj*X0{>^NN-9HzW>+_IBW^PZ8q!6Xra&n;QN+^@45=^TOec zvxK?chHQSZJI>yni9he;vV6BekhQ;^@~)&~ecKZl9^feq{M;;5%PxthbY~OvoCA^8 zop}CORopVq7@tetp``!Rc)%EUJoXl7rT!gIQgFb4?5R@E{s^2T_3i3&3O3&e;ddeb zNa7=lu2Z|PX}$u5es@F7F9N2f4#s%JJUrLwIn+5ekmD0`KCL)|6k|qX%lsf}d^{Q! zPO{)%jrx4g>@OUgEamb3%fnf7%wX1i6kf%h{Wdq2Op zyY}tPSMcjq2N*w_MjtQ6;}_=vJnM59y?oS(%xzRfrOX4=BJs^%{3pi>8ABj8B%7^% zc#1A91KEQ+vCe?5g8P&oa3Xdf*_sSzEyICu<4O|iANGesA8aJfPc_)a+j7rhP5h)V zfL-S{!||2h;gsJiLD3=>Z~isGmIaoqaJNkKaK1~gvVKxu%L-9WQTmwwZXWzbr7#vtIXS1?WWO{L$L5)i!4X}GNf!D#w~B!!OF)8 zhnQExZC_QadN7DBG(Li6bvW+vYoVPL3&qDXQ+RL1eJJbjXJh9Tf}&yuC=Uo{rTv*= zd)P2^Y|v)4)(zr=i|0i9mbWxOI-@(B4500T1DhM|gjI^soH;)ljcXT@b3hz;r<(9& z9Rr>{aE;*ocs*PIi9KyMsdn5^N4|XU9n~L|2{Vstu%ITfdY`%Clb+`I`FR+}j^701 z&d0M>c@|!t{*orTA0zj1HP9!~71iSx(389Jyy5VA(PjN*5Lz4P^oK4uD$p5g{PMV1 z*8^ut9h|%Nf1tL1hpEDSF}R0(rxvY|+~C-k^(T1ql_Rk@!#xzeX2#*OPX`3sub&{! zSD%*oY!HSXPr?Cjp9of?qs6xEduaQ$V)C8iLX+ZZDQ%+;yW7j-)Az-K&f`(I;FT6v z>1tu@08cbLX28$uX5pu}FN{u#a};ODwoi zv&dBHIm~h#j45ZI!1IVT)F!7c_-t~guTpMee!oGO@KFU`v_BM&?vLahHNMbyK_@=0 z;Dw4!Kk4#}3*wb?Zg{R;8xKz1L?>1naaxKzW$H*wq%RTt;%iRrnQ~Rl{YyoCpE7Y*?*P6 ze5S`+;nVT=C(eevhp4g}U{dCUw=1^6^s{N`Z9vWjvac(ZE# z6Y>}zOvY!tQ1@mozMuG49C`3E1pVGi3fomUJ>V?)zWGkar%tD`3THU26E5XH?}!zR z1^6@RDSSKr7i4>VIp>QEON3PXrmuxR%XCq^@dc_Y#?Xt%0QTKF9QQ`qQ4iBqqFVSW zac0PP@m8NfQYTJN-ez@++&sdl{qzGWxiSLRx9D=0PSGqkX$lM+5Xs8|x}kTswSq#F zGIa^?q2U=_aoOOdAnIqKhr6-3aA5*}hvVL@iXAlY-dE7L54_!PB;^i{gtGr;Q})sV zZVp-@*dDax2gjy};g`n>e_z?txXwmADcG1BmTKa_u}8(u^TXKdO&ENC9>^D?HMz^B zpMufM^E3c`*{ndui$5+T_aD~m8h0CvdgyW8TB7DV7PvQhDqLUd&Q3E8uxP{{I4Cc% z4f`sgq4 zJbJd$+k!7**6Y*Y6Y9xcy3(F)?1P^kAfl}*KezEA?G8CetdEsxE!zvVCtRp}-W<4` z=gXa*Z>Jsk*8FAlC337Z$GUZC{OwvDUHEFswadb|pP4E?%Q zT)*uu_3pP`gw9f4=+=2q*fj{P{!0*s9Q33Y{)u=lBowm~%=qt^O8D?77cSdLIh!?} z;(sTa;ZTvQ%-P(T-haIal@{Nj;-))CosGloAIfU4lFl|<>6ieK%A@$v z92xZZZy#*^)q74Eh@Yu!=Ep^gyNi{Qt@YiKUdq;QuCG%^w~rnFTO2DTfb-1+kL)G??XH2AhRV}EDD|KN=`;vc}X zHAB%?sT&9^xCW5|1W>T1g42dlBZ z`xCmo(Fh7Ic%$0fCzP->1d@8G&~%BXWV3cZgk%lF&x4N9zJlKPccdE{?>!3oVMd%6 zUVw$4ocNvFTuRt$f$u8S(A9PkWUL6sU9Uq}*C!N@tWM>=rQPx8qV2+S!&R`jd7<#3 zbBZu;Nf*vP)s-h6mU3d&hIngz0`98(1(~s0G^zC!e0W&^ZkKe>R*a&zE{nw2M;FO$ z!adSIY0Uz-7qExiO>yn; zT&!5r2`mP66fQFPVD(XO82` zm8iAA5e;VaL_5pRVpZ!jSP=z0e7GygW+?H>og;Bcd?L@Z@s#w-L2PXNnFbehM)!sQ zJfE7#YozmH_R@`@>u$pr9bSRcLJx2ou!IIFr*q4c#n8TXlbBaJmrSK>p4DwVtaRCTWTIgWDO9s%eQ1D~9nA179?&yhm^P?WDJ*Gb!UlBJZ5n1qa{m ziav*X;$(}zn4dr+FKHzHh8XirY zB9`U%;XySM$k)phXNASHikbpwnt0Las`eu~mr4)k96=JEBR-WqADB0QZ|-5i|yxzgRzbS8wJ$Rn$il-%pl9yfx&Ty6bCoN35 zC?;31nKu%f3J0)PLm`ee?S=(GHwZKBc-9;%ynNDxRYV`&_09n1`Kpk^_dl?`AdS7l zc9P?U+ceg(oxpY$9XR%h`t;u|I2zmYgVh7jVOy(g>B(HE76zh``9j)L?|~mB4LEUa zZ=PEAnLdqP08Kp%Xy$|g7=Jg7TbF23$F1vPs74Z}JS+$QLGc*oXAY&w;oQfx7yC|2 zr`EwzziM^?#m=^bnGH!i&+;-w&GQg19_WUb9uC1@(|!4p*oS4R^}-WPdyG&WN$V#x zduw;|$EO=Jas6m>3>ue((>?sqZQ=kvH6cOD!DRCFMPr1AeWKXB>qGb=_2s4f^r0sX zjY3$vbb2WR8+0lJvNytG$(AYc3_@mRV^XJE}nS|#a4`)7TGTdVD8L3I#& z#|zlWdnt|VA>)Vbu^78#hxp)rB$?DnIV8PrR5@-AtcdH%1{bPe|Fj%VUL)g^tK+e9 zU?0@1sHWjB3en`7BS*~+!nT$-bVKf>@N0*;xUc^@Xt0ohOUE3zx7nCa+({Mm7WLq- z7rqN~TW$EKK`cA|i3Fp)Bl+*y3v?Z)k^Bm$Be?DVQg5IDqXp7-NIj z@K#xnH%`Z|Lw^dX`y;R=tA_RrGDiQ-q1dnnII+>K)^txl(Y32gytdX8Y%NW>i@i7B z-?2tG*ZGgc7 zt>*@O^mhxC-BIO+)dOK%L3bWESGp%J9LOu8oq6Bk74W*qSv+{R6~a#qVeL92e$&&Q zbtPTzo4XrdRX$D^TLw{IpKxr}-APRyVG#PH7K|1C(AeuuLWS!CQVz(&MTc)e(ij)~ z-r1PsX2kNmeWsN8KpkVQ9)n}O-@w5~3+S2CGa=}h9xs=KsJCk$LsKi_)U)b1VZtm@ z8J&-I^pdn?zsWUyu{dd_EA!bz+90N~Y~NnccW^|^&cxrnyl}z{FDXN;ETjh|gSNds zSiMe__L6&a`pa}kf1iyb##mC&7h7Sm_XApfOrQIEZ4m=o=D=(1t}Gv#!+k<6&}{py z+F^-VLYF70I4b)M=q)@UbNbc+IaTW1?4`=Wa&1BGKM%B#*qMLRFG244H?ZDJ2|HhH z7Cb!8LUFGUp7WNLPd6r`>qX{$zYr;E4tc`bm8zsu){iC-s-6 z<7-6+&}%fpsOBH={pNCE$<_UE-@FloiWQ_CX)1=^?2SG(#=PR3Gg}!)q4uOFR2%Jp z&rg4ZURHmE{#8>U?92(OPS0nr0}gmf@hdgY3+9No2PnN&(x6rC@b1*!Ebfpx(||$2@|+M@vlMnW0j? z)8PL-!R+_Q7>~NAW3pBV{UTtCroR-hO$Q&(-$RidwPdLM1x78h#ua<^fVYV){xw&F zPu7}zc7+L6h5tv&fiW2Ha}!t^rb)c!9&qWQ4kzdNaMP}Jkg|H5Q2t{DeA{tKbO`MP zg&l^h`kU$Y@E%l)| zxs!CRIpwlrixCdCjfErH9njV#2|V7I;$lD4N~D>o2E9I zCJrt;NtYFyVE6OekY%q9chwx&L)a<}6du6%qHD0(V=MJpF7SqZcS*IVKX>FR@`$ZQ zTqvJJ=5zCLN!KvEW8}mti&dydtP$d-UICMm4mdLG5XE;(B`ck6!XxOx?uYJ)4<5R~ zq{-UcYk4sou?lB%?=AHEwl)FyTlb$X6Q<#q8`d`TG>^^Re~M?G2gW{F_w z99H|frWbVi>dQly2VmQs0-Urzgcm;Pik+=3`Kf%4VE$|*wuF79Na;=G-tiFjCfjq) zQbTN8*^3W92*7^}i%I6Nh2%R1b18=6{d3P`h9&bMS|yZTI+xRqhqJ*j@+vGaa=}*T z1X6ai;pg)M&{a<2Y`(e$i>pRp(X$Zo(8mP&C~+Jj4V=I;MdJBg?aJq-H9?!y9egau z2i@Ps$o9O55zoFVq>`jes#;$G9qS@k@6#!mBWZ@tcBxQkrpxxXO=O?rTB&S9G9Hn- z^}2mO3jcjG!UYWnsqtAJ>P~jXx0h_ie}!pGZKt4qS2S1}XJf>~!=QPwf?%c-DfINN zwHrJH`*!^XS$|f@HSEI=)BtB6Dx&zN%vvSuCeVKGi{7Pc!7bwm zExOk%4qCQa>~GkIg1_~}yj?yBhJ$1a2AJ@^l8xZ7Fof+trDK@A3w;X$xGD9JjEZ)l z$NisE*}*H2E0>HqJ+m>*y9s(+{s(7wHPFJ%e)#g|F#NkA2A3A4!oE>sW%_fr*XkF# zvX7oIb_w1r>?x8ufVvICUpxQOqzRM7oeO*7m&PudFG_YNm}#>TE${R3m6jO~d!M?~u!9Dhw+ir>vVU3q?MIN@SxveSb0p~6-!NVO6+ve=y*Q& zIV6RDr_t9A%hy#EM8>PFG6nL@3bmjin2h~l|B z6vb`#BeCPjHn3LQO7nh{A1$q~gNFAqO7?g~nRkv+z^E8(T^CF1#%u7yoo8uz@+rzu z*$7YTo`P&scL*rV1c~Q@Y5ux=^zl-7@v9uX_mooOhba6nMGu!MgmQ}EIx5@L6Sp_Y z=&WM*?3V>sM?^0DQV!w5EC%&J$PJ<6WfwdK> zIPsDKcXrRB&*PSfGpptBr15HTYSb@ytW?17eyOt8#|y_b&J@s>G4`x~;wepEGFsdc zl>>+NXVrGuah;rv21Dzqdh+wv!a1`f%~@XR&3Lerb`^X9+bC@qkW?)?pKho33o^vq z?dF_0Kpk^Ojv@0O8L;b>{L+iBuMFZx zUw6^u?$LG`D>?2@d@w;##D$g#ORxy219 zl{iCb%nN#E*oke|O7|Z5M0QwhimR7L;--om7-!&vyEa7f*fbywX;!LxeFtsw$wv9F zKWXjuUN|8un)Sx^gIc)LtmqsQOUH^;@4;w`;rKkcK(jcOQB?oRiVMquf&MYQtjVX8bMlUOq8Xg2UN zXupf5=u=_hNxL-=EO`x@zi8uR(~HM`R*eG9pd47$;X?mXkT>*PN4*?#SoK~CPMp(^ zkJp9b$4gylj>Hu?7rla9dfg^N(VuiUspf;KBNcn+B(_9L5Sg= zAA}5BLvdiYtFU6523MP<;8d4Vq3)mxck6lpmRc3Eo93|EE#J>jt#>sQ)u{5e^ycb(|+V-bv-@q5UxHm8;-!yD#n9-%M_|;>8swoH<~z2Or2Y zBh&OWJZGhixW%1S=cw^mX-{3;ryq6%*x|45y?ONXIQ;0>hyNaVLfeM<;m7AD_{dU; zgKb>#(Oo_6tiBIa0)L8D{{NBQ+pW~ANF6PnM&mFgJun*omkQ@hhcv6L!m6&%so?rX zcq~&DK0MFn?#=5!v3@Z%wV8`WXP=8sb9zA8JZ+fxzDg{b?(IF`L`+rvm%c(!V)ZPxB{e7|PbOp3NB8R?bB_C6Omc$BKD*m~VjmLEd;rpDov@xw7 z_UzI^Z}0i=LTjef%aXzub-Xbn%abFFMfjX!hU%BQLzuG~8V3~8RO{(4$yk%f?u#~Ix*#NC-nSsU6^sggEx0`!@Ux(w@+;$&3So9SX+~b*W|iU zF9!$wILUbQ`tLvce7F1GzQI z8Q-}2vN(n5NOdjkT{|4sWcl;fpcwX(x>+x+R)bB&lc}ML6MkED7k0UxCHoCB{CD@0 z_rs3^@nl2>+t%B%{w`GvnQPAZiPva{-Z1F>TIx&xTn_h!wNb8}Z^=Dt$DY`XkQ z(9t*yKePO}Pkt%%uh!$GH#_mk1<&YmN;)7=*KsN+xyPY&#-;4z1R<{4`ty?)nf6QG=skWHHT;J&cVS$bj72GLd8A%J_A;y z^5fv4>}ZvO<%{aXQ72c5R?_VMQt@WmcgzI`78cS$sf+Ewnpb2Q*_}(GjajewrO+0k z%`ewar8U~;1k<=Juz$sBs=(&wHEcNBsTj6{~7SDP!CXxa(xAuv z>?kA#!SncVbxEZlw^cWq?iV;yJWfg{Nf{k+Rb& zYPJ1HKXMz$Dc=RINwYLH>F1vtn1@Fv>7eVDt8}fv2bb#^^1m=c4EvtLVfKA%?{Cz_ z{)gsJq@NooPK@P_Rz%`60!#Slmn17j+fU(Ik@)?_qiC6lf%7P>= zNmAw^tE*t=Pl*G0OC5j7$++FSooswq3mEQ+&*iGhwIFsm#HQ742j3^se#@9ypb0FRFybg+1MlQILNk);%kq6&~=h2mk$|AKim3q`Oy`0Jaa9q zJhg`OtGu}PldW*RQw+PWS_Tt)s-p63Nvm9I#nmI+5N#spMr4mnmz8w|ZNH;HRHOhBVuVpOkjBZK>k;6ug)!D;LXu(fKX@U5#MvxiI^ z9@q{0^}QgRy7xwi>3M|g{-&bFye%|q+G;Y~Fp;*5c_$9dA zE~#H1h!+da(Suv&5)V_PRa&tUhf5W+4)nx*lJ<5o%$2<)U&}J90^AmF!QEb%qH>TY z>Y8o#Zqv@^&o-Kqs0mF^t0-*HBhODqqi?OaHY!qRa`A9N2h_cE-if*kc2rJa@^7 zy5D`-pwXH3?>z_hvxB(2C|2~$l-7`^jM`1TF#U5LUjMnh_I&k2uzBANlhb^7SjSz+ zZ1_Wgv+_A-u>$M5ek8?<#_X|pBpmK35&ZskL8aX_LZxL4AIV-zPbw>^HK2mF&54pe zpKj>$A{(nVo`RkW`eKi93RHT32dp3cL)6bm z_~q7ma##Bzm>dE8aXpduEipk$r{}cJ;4Q4s4n&{N(%JY&A4{5sP_?}DmROpKC+2^o z@e*@qyU<-YZ0N$*)`zoP{x%_PUJj14kHhb7cHCoo9zKrpz>Q;+vEHp6w)pIUd&S|n zRkIft-N@%{_ZJIUQ;&%|E`JoQ!va{$ z8z0Sud)=?m_BHz{Xr?c=OjrP`@*HIu|7i&0KQz(I>CxQq`V*bc^cIi5*$v;cPr)ul zAAWhZ2U=VlFHEdc!GuGdxrfvUntaijTQ#;qphFycd5y-QAsKKd{wBEjNbAT+dWUY$ z6)wqd7GHZ?a>ha>Odin(f2f~_&I=MCF~=E`9p%wsc?@)I4d-FT$rxc#2kZO#^Jb4( zl&TZPFV)-`XX&urgzVazBL?$vzD>vUZr2*U)0MuPTDpkbvu+jneELRtg>N(*6WpCQ>sRui&=V9iXW=LM<#Gj}Kf2a*d z$@M2pDf7j)Vs*UkJ%Y~^tfwB1LtuX9VK__8a9(c#m?&uB;TNxk%As`>bTt;QY>dNM zk(PL%z770GjAGq0EpYIm58zt`5+{W4*7j56dSK%Tsd7@yUhao3W9yK2>^jZ=uwq{K^Jz$tMc| z4ZV5h+>?~5WyFb9H{p6^2YvrygsWb8vh!7Q?EYQy6Fd!M8*AyE6EYC{e+#KSSUg1B z-?N4^KlkU=HfyP*cR$<`9zjZbP0`;X2Os))f!d2hGMk73eiLlSR-Y1i&(b!UH*qL0 zn|Ym<4NK-7eFaXQT?bPqIEZa}!_Ye^h_Xv#u*|gyGOY{9Jai@Pib+G?3>9*_J6r5& zH5400=kn|%Z`PT41@wEz;JAY}SfKb1N+)<@XSpJn>Xs*Q*7nnA)0eO^F_SB1X2Zb` zO)#RH#ILni;|1RO@Lt*d)*xw8&U*RofdMM?wsqjkG@^b2yJNEK?(<&=-S>^a$D!b@guI$yE9kByFI13 z=Gav3H{l)pynTfRNA7{B$SZUCDpc~d|thu=FO zQ}H_n@4C;2q^`MwYnUE;&FO-R1ETr*Tx;rLuY-$JBA6YwgYhR*T0ia+EvR}Um@e)8*Bnkl!D0oP5m!$_Z5wzU^T3eRE~3ShS>nR!3&Bo7`}nDYUFrB)0ew~hv z-XE1o9tI=vV1E@#m~X^)D(2Fv;hnK?(+;?Cax(friDnRJg=rJeuu@OX|jkCXbW zH#dE!7|C1g7q3V=$IYeCPj3Y!xm;oD4=IN-AQ?Li%NAC?wZeC%`B?L4g>d++E^EI~ zV4LL5>@%^EYE$08r_4+Aqa_K?j)()>dGT1b)Sk`uSAx?zTM!S;pgE1-;m*r}lCP;6 zDm&Ul-OvWATPo=(|7qb|-Mduw$b^6LLb_X(!|>Gf93$-J3!Z0$+&s)D>2Tfo$g3$;7`OHX@2ipS$tdn^71%rU%P>jcApM8~P@HfY+N>LU_bOSokfD?H2tdm84jX?y%Pjqfst!2@46+1oS~wC+G&e%KdZEIk0z7xcn??mc)` z!b8C^*p_W*C~F4ym)5~tA)Ed1cW@4?4e_T%&4Y1AL@St>*ig}dZq zbwa3M@caynKfH;u<)nA_9Y5@(Zh=mFYr(vKB+r?84pdJ1b0jqjr%{t5r<;SZ#OB-5 z=FXGj?m?5yY3L!ntIA4F!u7a9HhI_&RaSe_*%{B_`jJ8C{%JB;)&-$ehcZ5zQ%<(( z^0?#WRWJz-=b++ikknlREv`%4vzza!S@#y$byi`uvUH*x>22@gi6`hYT<^58JndANWPXWbkQeCcD@X;bl*s{CYfBc8z7wst`;Qw5DxO!4R+Gcw<^m(DM)gp#q!_;p+azwA|j!T;t!>1!E( zJrhkXJ)0=VG?QEEd-FgiXTI=8(uP$A^3O3k!tOIAGL60ol;EPt3tP+}#BCqR$DW{& z200vlA_s3d58{b106Sgi&1-xEAwRJb=^DNIghH{tkjY)5g%oTRA8@ssU-jCde6)F3okb zsHP^GO$~-(b*w5j_{X!dhc#LmB+%DQC2&)-85VXJ;j%!$RDO9NZ_{B51#R1olr{&{W|yJpAm5 zN8UY`_1hxlemi^M&weioMJ;>Ybb zB+j%AXWzBN&h~+HyBYNSyw%hVDJr;NwTO)vgiSKv^{( zr(exSzo*iBeZ_Eg{nU*|-czHvMn{aB@d}PiSP8x5-Ee+L5t)?d@`U226!jwy-`D%& z)ZtkiutO938+YS*f(G{Hr7+6j08Mqi4r?-$@Nt1X+b1b<#y$cfi5_w$xtk{Sg-Z zmO4nbbY__c(5Z8NH2QirUznuL-*+XU$C0rxd5k-slJxe?23qtxERA)JcuCpv(_o&N zkN>1M>s_-1oc}tR&fZg+(@N|lk@H)P?w2#Hkr59)3CgUl=bb z(cV*0X;75*bDxv6heS)IK|?7md+!y=&R+Q%AzRdaPGm)hBH1IdvxThR{rd-=*Q=-J zzCWLHuIqYVH}1jqbyCMt)(HMEbYSI*h9l%^Gr!&ZHq;A4UZTNcqyPkDi2?D^c8 zXe@d&nI62k0WBRf;I_^%ewCcde4PS< zlj&kfFm^kUjTusA_fKMjY~-q=VDPn!R)zKF1uLh6?Z3a3BThJD{nuf#ek7`=e1+lNtx(lB7u6!HaqZ_;nEFbGE6k;HZSzM`tdYlfKN0M2 zMX-m?88TabkUqc3;Hyh~F!ReONDok!dd32A&C8ycIX#xIK9g806waC34v4qLDq!K~ zc&?qfRLpaal}r=|#MN(%aLWP}VbK?3EK~wkDVN8MCwy@3_Bd3Nx z!mxYi2<$hsRrJ5N1v2{iu-`!&zJWQs$mJ7-zIs6OJ^dlzWSuP2s7bINn2z7;GvI>9 zR&wsxE6kjf#IMbtKx=dr-T639)Sfw%Gvpd!yOJhf`ILtf3U3Qz;=V!u-qLTr#2Mez zRZ~|VPdF-Ngr-6ls8}d39N+O=Xx_X9Vh(%o<0IYp`IZ5k(AY%N&I4QR>MMB^d*P#3 zid;QapDSEmfWoQ1xR8{nrQe0hlE6G1@!FLKzV@O1l7H@wt~~#@(i9*}iyYkV(UDGS zXuUcC2b_;%rG{ql{Kk3oUh=f%`kF|7t0;W`LX{IH^yM=D&u}w&5Es=qi#N}v;**UA zcrwg^3j+t?*Eg;hkvItb#_balHrVmv*nw3CUn$^zhiT-dy-a#XhqKF?Y;+I5N#`b8 zVd_CCBR%K>3^|`n>Wh3}>YtCof^;RQofwImU3%hXeF26pu)vp#Pr~KKzZB}_isuJ+ z!}N!R6#mtYIxcI_cGCvB6$vcA^ex%YCK!CKme#)M!i^aT;$+`EoYtq7_Gzt_eHdE@ zZ4aN5%bG;V3z|>q(r>G{LX$si3gtJpnc~WT_p+_;e1$PJ>xHQ71iaY2AD4KpCco=j zs8FLnrw5wg-iR11(2d1%^+0^}*IVlSka7dp{m>-GP8>W#1^zTxv8wDFbsp{^^~KKu zv*|kp@tPB_75kvc@?yBBlY@Hl67S)O0iLR_r>PPTMR8+yw%3^?`8eKz()8UVCou+$ zEKQ~SqXxe;mB$YuQol@!8m2rgCJ!+JhfRs#hm|!DzM)(U%Rfv#_Z$?TAE|^tlGgcM zVJLsN&`1rsIlN|MH=NVq!lOFLc$*&bL+dQwu%(EEqB#7Kk}FKDA0f+)Rlxk7x_tkl z41~~h{PU`c_Sd>&_@hw1ka!QKYDV#%jJ-m_;W&)a(LgKJzTCP$+Ou-J9By%$4U?|) zV)xnCMAa9+sABm}8v1QZ)h3Cr5&F26bcRS8+f`|=dNP(C21Me2btSO)UtdX=SVPtk zd0bZ>AX)Is_=P?uychUE!hTwCaUMC;Ul-mN-k~RhGr0KnNGS6d zf$K~aSzce#_8w`AExSBmP}MT}AYTSeVYi@EFP+`;B;8uYmfuaQAiA8x=~qSYT9PBS zKkv=u7B__HA*!Gnahg`I>B}3W-AifM7&Pem72XW~0xJ%zqO8}Ibg6z22AF>q`xYor zkN6w3$5EO6BjtE=ZX}P3?#sU?BR+Z6A)EKum5&xi^I2(*_+b$#c|eD<-kI1cxw$1| zJM0^s*UzMDU5aUY(*W_;_5|!HxPZbHf9$h#Be}JBSJ`aq$4aV$dD(Xpir!QW%PvZ1 z)stIdxo#KsFL!}ylD3@D@Em&gbHx#+sobS^JpcT9Sa3oa55B2|ql7FR9Z?}%`E!}> zoR8ou)=n_sfC`S7dPOk&@(d22_&_h#B=fe?b5Q7Iik`a1V8ElrwCrjbm6l5$vIlMA zfjVi2pi(WEea*)BTvHCyO2=K_R#t767$277)>ZD2HL+UBmXyeZ|IJ%o6@-chA}U{HUi(24Ch7wDK{8PV~h7o=l%$(ztfL56>0Lv zvL&)9D@{>%={p*8@({TAzon3#pQ(FIUp_iv0OU6UCx=;aM~D>_yRQ}wmF%Xr7C*XR zVaH#U>Zoc;tmxC;B={trf|LV6+;H0&S$_x@-@QXyrCopP{a`51>_yHG7FQ)stb*v{ zhP+^151zF!1%tcoC2vhzZb;F?Bs)KP_)&`|+U2v#%OK8{G&B2WhPcW(8_V4OBh#EL z3|ydzjv=Y+Ro@?Je<*(R+6UG#U*NThIs|%7qagtb*u^7)d+jTv+NHX9MRNmeDCvRu z`dzuAv<$|L&0)Jam&mO7H8@`CgSUpb^Q^h1_|_nhkMFA_<-?~%BOJ*uyt1fSWiae1 z@&T)uAA@}}`C#~17|<=9(=tp^%Xcdby=;PM z;kuGlzEI5EsE#G&r4)2$KZHDw!TA}VMfvt@KEFnVUnpLnc{P@pui6gBt%AA!L@_b%;y}qByOkJh!)oY@a zPy)8?Be=`ZM4l-1RORo}n5PmuF9?nmGCzOqgkTP5HaOP7Eo>a}if_5L?+sy((^?kUL zW}tZgy$*X6_mT4YN<2f#x;{AEON_bphD^K$!eEyyy#0JBytzE1N_T27m?W6c;;XGN zXTBBQy(?)qn!dbk&PrHmH=Iff?fK6=cmA=-0ZW^{P~c5zpKG;R=$^L~EaSAqd7ZXE z$H-vZcs`4qByPg?wL@@klLL+(rpk{s`_b6F``~H+voPm&0FUo%fx+cYD5_}jneXMa zaE1)z74`W}gT$K~{ehkw`v4~*N?~A71a4MQA^TM&@b6+H^!q-H69wc&t5Rv*&gT#& zJ-?G%y5gfb{o$sI3F4j}*gB#GcIEkTQDC{w4`y&LorewH4xcja8ys z*h$z_C*#JPw~*SkI}Q^3u;jms;PSM+vado1eE-*jJLyNUv0gTIDK}@6cWa>`DS(ze z$fVKFd+@ahC2;iTaba455B4`p!$rR%&~xH1$m};2W*hd93YQ8nsAs7V?02uKqW>${ z{8Gxy4l?C0Uu!6AnKg7`CG@y%h0`arLCf5kaPY%$Y)*?qrQ%>Jy}t>1UCf7#VQIM6 z&JS-jz9vgeFV=IGJiUT+uDoc5I^Ex}Iol6oRA$qTAuhaXxPX^lNuI)U^TkQehT)JH z8|-%Q9F3Q<(n)_LZDGN8+Wb?SQ>vzdyOzB8dpm(eqA}X7(&6H{7f5|j5N79W0q@$) z^k=^uN4|S0%`q?OtH&=vJ0_Za2mPe3+>ZxV?t>NEJ@8DKCC9FsCXUeCLu!5@yt&kx z8^2Z2vSKr?ygCXC&E;Xn+%fQWmq>GL2BYREJG$8;gJo-{f^wxlPxg+iQnea@f!DSQ zr%x`B`M$mjZM!c}TY@hXr4QnRnJTDdxlgq0{hnH%hr_)Ox|lp*9duc(&6S;o(O`*X zHzO^LFLv$_7o|Aj$)(Bo>4D@+d*@B7wqK`uqjiG5g+CusvEjou2jPZGGyN!v;Ev7; zJTZ46EDz}kxtd+5;Jy{toL6Sg)SD1GVufh4YdsD4lEqc$qJ*3z}5kiRuA zu6nPq1TH-Q?q2tkCMoQNn-7Yh%50bL?rL8yYTp4@i=}&ev?1;VUvwFoieAfZ(}D>( zyirq~$3GoOeb+d0xy~pI9^IWYeb&SE`w{rIKAB3ytrR*w6=OHQpq33u@VR~ft{y6J zkeud=i=3B`--#8%|Je{DwxnbB=~g&eAn8pGFUbx@^6nya-ZN8!H>|o!gVRKzP0FhJ z@m6XpmiA@+LitFs355?IggV2#_=XEmW3fE$oa-U=%gcCJ=UwEiE%g=)*4WE0l+Vr2 zffsS6c+XinyB6O8<-LEXw{;qyv|CO+K1JhG%P^sOUKj^n(82tRiEOsXk5fWJ`GcJ{ zro|`0_Zoq_jUL3VpSr?+kAKj)!vGK24P|ju6U={fNqCrIgKmZaeEseR$eG!j6;Dfd zf%S1*XP}PhZ=5mtRT#D$)8ef4J-H=gw@iF;NF4X{kqBNQ<&%KLBi;)m^n5YCY5+d=oB>fk-ciE1vv9{n5j0Np zk!i#Ys9G^5ii;|}xb2c7&RDocx<5zq@oFy`CHbmOKC|Y>W(9opgNkT5$evS`2covF z#4Fro^p`rSvwkS`foK7p|r8nF7u~@6HKwYiQ=pkF>rz1donLs=^{qJZ>?NDNjw} zr3}J!JpuPf?8DzX-B=v@7?M`m^F#^z(Yi{HH`PUQW#knhWpe^0Jy&MMCu1*>D{1 zXn-rdLTLIYfz8t{lJ<-onzca{$Bup^-F1SYanU@OeXfURbb2Sjv}hZs2Y1H}(cfXZ z)c@Y`v>SJR*g?h}>3ry6BxgqG;l9nCpi9s#(lSWIqcz>DY$qqfgeuJgOfk|^X37gQQhW>SU=yG-`-IWYjtX69rsH>Sycz^ z_NRfdO$Fq=P?H_FosMr!`eGb)~1x9+B~3%2}Z0w zUDD3y#-sWQL)_SXA7$tH;Lz41RB17aE?P?d((-T|X3?1+@MDTNISOYD+ylC{ec<84 z6dYzy4Y5O1I5GY)*{$ABtCvJ`4y~iH7HUGk^mq(AXhbtjRdJChlC@4a^szn*C6P%O zI?WMbDt;TyJmBKaNQSu0}VMZ#vW^KXwdj| zqp)R(C)#{erG%t0>}q#c_$vRMN{4vUt`Cw&b!a+F@Asbi-i^izJP#|}$|2%E8w@IG zr+a2sA*UWw%*46xbaGPO8`;Eb0pLd!1? zT)V6Xn0v+ZWxGh8HbEvU-sUg)8qbIe%@#mcKNX~1mMD%kMgx<}qGqRQ)MOKb<R5OE5O^u6NxY3o!is|460dD9O}msM@!9%uYD5CRu-GPOOqvfm zi3xoA%n918eSvZg#q-1D!_;JE#6yO)3gv&(v4>g+d8>Khx#_w3)+>8XMYX zdRbT;dQZG`_Y7Rs?hyJ)?5hxqPVA@p2DS!{hMCv=xNEr$jOrZ$#;%&wF#j@O<`Tl* zFNK>gGgu?-0vw*!Ap380EbWfC2_LrvvR-C52fF0qTu?*TvHBQtd^TnO&;eI>;Pw%h z3C8UNxNL{M+skD^f4&K}rCFr9N?@9Hl0t*MFeh)FXfZR6XX*K|(H<9;mXSQRdnerX zqJy61#?XVKNjxEWtF)BUq_j=OG=91<_5QG(g0A<(YpQirF19sAvQ%^fY= z`lXb<&oHC5`k@@BF;Iw@sE4^dweU&NXYu02PONw0iD)?A5`&gEipJ^&T(-|#T)1U0 zM>-9}ZlwPMLqEO2GsX!MczX^wX*NGIH#U3Vq$-}5Hm<7kTAgI`eUf2}mLS{+MI z-6S>t*%YktnkFh=m2y>csCAtN7LKo!@>~-jLDd`k$c2eM=SK0HtCAnlW*Bc991CZ= zPXpQQEd2E=jK7>v1m{)_u-bo%EL!ZK?eYTf`W}FD>OKm4|6@{eO~ih;!m93hHh_ka z4m?&>;|EPC=1H7#J(kw2jC$mc@DjWRl@XC);3Q;{@pq&<}b(41C7esn*c5R*ok>p#)> zsQEN$X&gz24CofTR6KHI0i^oKL9Z=#{5!FgEU#>$pgww-6|e;6>FVO&PUmRT(rEU- zsf{nYyrwTh^7*qtJ|ELMLdo?49xu8}FD7EsLYhmI@M@+vzjIQqs!jXL=DEYlFzAKayc2D=>rl?qcF>sAgrMjdl z)wCIUZOq|{rmnnY@?s(WQZ^15?ZECA*FdMD&U|UvALttK0J8LlQ~XwAesVO0QxbA{ z#at~^R7=Ch;|wTcZw|NGpP@-9ZQ^vNUr^IM6=%1mvz(X%Pgi{eE$jK@ci#-{+@i_; z*kIJiisIloIdouk9!G6m4s*P(lT$}OF7$T9s-H_KH?>}vu~dx@do+M{A88)k*FnPb zH1_!zhYMUoaEhq|%r1(D#toiqyWJi0l-I(JvoenB-;W{R8#7nErnBXDXu>wc>5Dx$ zy2})pV9_excMOmiF0N!~?1(E5SfI}xCp7mDLAMe5xYVT=n%j=y($#~Z$=(_l%NEiA zCnr`>)uYKN=jqBoU#@6z#a^El(Tmd;sl#v(j13;l?|KG8<{m?|d+Usy_M33P+H|^W z)|=}*GkHtq+)j-_RlrK8F%~Po6nyh;+qoBTX0C!zucA8 zeq5!WeHBfpNQnW633z}+Z|Ok2FQLrVQ3l({8wi@ z9Pju*JF-Xf;n?#O`kyk6SnG&BBhQIBXKle-;!&D@P!g{#9>Reg`+(=|7hdEgQEJ&3 z>~cI1dlX0GzqmM_<~<(1H;Fus@xFFBg=c&qGYaP9lNmeL{PcZsP7u0`S1SJlqVe_^E>bpR`3Sv$1 zuaO5IEcHeWxehVnldjNrSw6qID~IXzbEF*TNT`(DK6xuxXZN548`ld)!(| z-rd3&<((l*nogL&QAJkY&zX1VW$~6A z>Ak;uJFQ-OShgcR3fF7>p$U_FK*CR{zj}}ihpd$0x!VC)QB)4gChL;V-{s`4`3#;E zjbXj^?wsPdj}op_Lek#7H0Yf=omC9yU%`D*<(nIS`0N1H4M7;9l8er}eZlCg42SPu z3VF4oc#GB+`tx5FJ+JA+bEcmWpI*|(S6=VMi|X6{SBSyl?1SWIx>DG=uY&4U zDl_ivf?wKdq05|sSf?E?E}yMMAG_wm@)SGXH}@>1%`JisJzdOwXTgUMLG6+wfEr-P^#nK%xg~KdIz#Pe|`{UXq z(!Ezm4WB;?*R>^}#1VI%Ew6{OoSsvVdWkSDaXGxcp2X$_L%3mtJ{z_;;_zlUzWywf zKmGBQCEGNS6m*6Rv7MB?R#r_I>`W6>6w&{EHK|7SW&iav#S?9+JjHJ{#N3c{yz%|n ze`G7!K3PK=M_VCew=bvK{h>J&!@sAiDOD1ba}wOCTdb_h6JT!w0goXnr7RVZx&>r-1#qp^>{m|YU|7! z<@?Yq)hCpsY{X})0{BHv5sgV$LjE@`(OJs0l#bECK8y9}zx2g|-56V*?KBFLMxUWi zf%oB>hCB?ebw>5w-^h1~#8mB@!l9j`cyC@5zl`gOxoY}&C#Qw3W*j7EJ5L_>w@GlZ zjfK|h!|=bJwyeGz*>^-AD!Kg+-cATWw~1c(!CH$4IppDVs~=FR3%p`w2Kyb)=G6-( zQew<-ocy^PJ~?kK^+Es+4DsePr=C1&v!^)dWOsIxo{{VNBk;r%9lm^^14eWnisk1# zFvw&T8CxHrk!?R|Vz~|a|2hMGzynluuao5gc|88^F}zJu!bSG^*fjGDEWe|Nl|BJz#>4A`NDn>Ls;>y#0v@xjFvFRAk{oD;g@Btb8T!WV4faKhvL0j((#V*OGY4D}UTxu1cDn0(sz-kvv$h zLL64`hUCUA7u6mcvxDAdn5huUW)jr|{ zooZBtAKufTr;RPBl^JpFSrc$LIh;3}By!lCEN*(Uft*%a@{C?`{55QzG{E7W;}iYMwe58)5h&44rF$7cw=)MD$9Zy4 zyA9si@Ec-M8{xCQD|WHU@(5Znn!ngfJrGxNG22|y9aeeZh=14UR7oAYrx(zs7J=pV zN2%pd9vjA#(fRv#sr#f@ymR*<_zYV{iK@S8#aCaPYUql+=bw@7Ky`K**_jO_Z^U~e z6Ir9%Z?YIEj|~gW*dU^s^hf4V*5#gir{TBF8v5?BjTQxjQ3mX#jvN2r ztBD>>I=vJQN7qnYWH27wG?4z)nQ_j*Y#ek?9+&=(rOX*s6jz|c5uw9CODUYRs-bF6zE}52KG2sD#YK}?3wyak5AmX0amY~+2n6K&AIYN-1ixH9A_Y|Q$x#z z*Qn=MFFNYvz<1WAu>F!K-YM_LcVQ%Ub@@YQ&fS3^@4s+Py+4ab=aR0$90>ao$~h-X zY5!9@R`~mq2Jds`R~fnx+&mN-BroH+g?qp}Z6~C5-v-^@XR!L}Y`n{M$Rm5Q>8xwe zf4<~3y?dUneV5Mc5gkMt9(>uYjtpE*(8bC=VzKnBlhH#Gdsy<$?J>Oc^r@<0HE3A9Qzmt(JmLN{kaJ7-XG+&|a^AFKnuQe2F zH}+eJ(G{yr9099F?S*5y>`Z-Kc^KK^_hjgpz;%Q*iy;04|j2(>TGHZ;J1PuPF&!4l8JlXCN;G8*I5< z2v#lYVSQN=4>_>`(hk>%R(oZ9a`0MF*?TyPMYimJ&6&TN1M3!~qnfK7>vbH2%*np& zRO$-OWk;dtoe%c(ng}mf{sQL@x}N&)MM%-VCaiq>kDdH%=5dFqDl3Scs0@!szC%7NPtw!+?921=9tpm^MO@qZ(uRRNQ9KvB-_%f4!%u zFN-N?t_wVjs-e{-#UQUT9)6aTQr)#4yeQKc6@OY{lg$QF+;pf?Wq&7{I`1>hHE9>j z59}5VmX73_z13i|r=HB-U#8H{W6*ckDN;Y8j(*+$(bB8AxTPTnebZM#eBoq4`EDqV z+tLO|tEkvso>vql3Mode?Ct2sU5bryjN(+!0k|1Ff6B3`q#xc$Q^3AfT3lZ#`Jd$a z;Aad6zHb%2s~ckDtQhJx79m_ohnHDBrWdiEJbaD~ zS_IV4%!9kBr703SJ-GtMlcQj-S3I4VTS?`$AH@m7oUygIO`N&o7R~%%fKOf1aE6pi z(>E%I>eQZi25!*Yh4!SeYcnnAq=MSg4%&F%2Ds?IN%m+@4(`8~NINF}BMHKSQ>LDQ z!AdV6aIrP3hewgl&}eL0A^AzX{Hd2;HccMqCNX38LVSN8y0hrM*s$sw{e88a3L7eE zoU}{4(gSe&QF%Q0;0kQ+EA6bLY~;ep7wL0y4@%D8O-*@T7^&F@i+YyQweioZ%BFoI z%l_?@ zc51TIldYnDtqMlfjTHV`x}k5~JIYq{lQL=nxNMXUZvAT{`}=l3{r;@UCycXZYT~pj*Xb+|#$w5T>pCe4lRy7Qhut5;o!BKX#Y=`8SH$UN@y3*9ChF{*_3N4w`ysYzai;;RAWf zAU~F~N`QBM%VnSJ5ZBXJ7txEA?0TDD=-(^3;poy$TlJ5moGcKa}{qr z)WN8IS7?Qt8s*lm0McGTDo5_nI5%Z38zbFCup1tB8b-+zuEOv?BO(0!Aa4CA@Q6== z9EG7Eyi&r(;vAkD|D06%FNL;DBV4#?5T1XK&*AS0w(iR0Zl?}P*}5*Y=ChVedB#1# zYa?D;0(MTYlQZ)A$)GqWUxur;X_U#Y`A2jFb(=}QicO>l)Ptu zZmaXV+ONV(Nye#rVZ^34PS6hZaq#1dJX$WcK{rwmM?s_#YO z$IK(}V$yhVbYinuTh)b4gN*RQwNP&GD}|$LZP9jlD4yCRG1#{sl0A84i`Dbu`J;O; zJXf@uI!bhS^@}h(YAaw~xYU!Tssv*?TX17SqQoDaKr?bT38lS%i5iVaihG=?d2}H( zeQ2j&)kR{!>rNcyIf}zh^^ntQ>ISh~ zv>b{zMv?A$Pwp7ZWcQ=Lc72~I)V=slSbM`m%FkQiqJK4F z+rmJ$dsIvIQzW0fzdR;p&zJ6I=^U+*h5e=dnAe$IV);omy7c8cHFtgu7iurTJJp5I zcE^!YB)>pxY%oOE6~LC(VB7w|csaWSW`^a0kuGwsl_-vMcm+Q?C-Pg*#bSBqF0@D5hZN==h9}ROgu^ea z@YH%AoRw1r-ltCqHRs*4qC~~c-GDSu8Cb{;n)G_lG zWHqK?h-o}`U+B)K-^>?&=RTx<*4ydmCUfd@&yWACal?7>zu{+rCWhI^lPF~|Tg!sk z^=B?2 z+d7YK-hV8t=3(ac@P6zRA-HQMZ(CjIn=JoU}ZwF0t|bI5=Tp zr@M5!_6n7~41+n&3rKCMWRGbW4_qzK=cmuVXkr*(qhbH~bLW3>!|3 zTsj;2H>==*6*UxX)Sq@lRe{H*kCg6~$FpsQ;D?1rVS23s&Z&@r`R#l@y{Qb&Za4)6 zyM}Vw;UN-N<0VW;cnR_vM`_C37>J$x73L2}5R!H);kDo<>Ne(vpl4lxBX0ZiqW9Oy zyvGn$duoWi-10fNHU4?+FaEpTPWNW42<4X3Uij$KlBK+Sx8Y4_P8%*%3P z-;Ju+YTk(r-22mmZ&tKC_*K;mM|IR3pMZblzKVNV3^+xhC)WKZRyJjL$aV z!++kvf=(T@s+R&D{2eKJ?FH6fyH_?bz7y0vIzmM`(R)z@;73U}mbkMeMKWR@EDdnzDQt=C0Tv{+0qK@U_^j@3ksNpHfy=;W~>xrK9 z{zzvw?55?br2EsIFv)LlAI`sW#(V3t@kv6Z82R@JjLKgMnMdA0opi2RoA0A1!xd3Z zp%+@@dSmqR7&J*V5!^>aV#<0O-1j>Z`}=ee&GMgtkg5VN6}HI^OPPe07iVejKqFQi zzKf}ZkG{J*D$B)7XL1W0JTP|v=uJ}~{p!mH#8d@`x`HGPPr?d}eRrj$_xIc)$h56&MZN0dr;5jS`O&2at z%I23#m%^}ufpAf^fIsIERJuoF@2$!#OCQZgdyGcy>Htbhxh#eqdqo}!->F{HnR}=C zNL@>Npj+xA*xOeJPTJju!ZQ~UotAA+6cLP}Doxwv>I%Dic?%$Ldk6@*oM-D*N&Id# zdM2)xJny;PtLXCYUQnH}1OCJ`d-|N)EI2z}hG}QxFril9iP~}W@?e4R*nc}+bvA~t z3pDVsfhC%L^@O!cums}}})KN8fYh4CPbHS|p4nwv>HL~C1Xtch=d;nKXm z)F1+PsD*IInE;+*_>xSuB~DY}ays#IAZqNYh4`v&bfUYbaB93U_gnG{w)c-h4@Z3z zE{x)EBE83;m zXP!4NZOG=yVOwQ$_r!=r^M4R7+zCC({?dH8A)FI860&Bz665`J`9NS1eQUSkFB;Lb zcYeOq-JnN(mZwtRa%WuJ-JTq6+;|Jyakgb6oF8b9*=GJ6zN|OfUmGpl2^#_3Z4~Ls z*~>!OS_i!0-xsTI9f3clQ>de79{Aa~@SJr4=o-9}BBbtDYePTI8ZLeQXm##-LF#U5 zj>Pe6S-6ty%~OH~(}W+8wqZXkUlYZGV?I7DisrE%cV}uA7ylJx|DU!T1sQg zBv12hWnR#ABjq^kBLC~bEZC@W@T?2;c=kDvIP~J#s5hk2t*hwXyC*(XwWEY7BcSr^ zMo%p@A~p4&@J*W8#vZYxXRi-PImNM_q2~k)(@;ZiQI6v$2eG@cvb@830zytm^li=$N>&5ACT2RBHkbFt= z_u(x+|45zmLvg**VB9e=ls|^f6+NdYv3Ktq)S5g=7%MkYur}z8^S7jP{ti2SVOAo>UpB^W zRmNDA9EUy<_i1#C7k1kh2rq8}m-O-?w`=;G`Ee&raK9)%EPYKkbJg*R#vXW#4RC2> zEsfgWEN#RkU1eH5*hpQ7E590G&y(j#q4#aLI{OPXJI1F+0q74>qTQ6YX4+^_Y(OCNf`Vor|=%E)SrW2+7)UVDxKwyqiF2!{m@0_ zKKQIohLB5rvE-UJb@`{u+75Hz*^LK~D+#k#r+3EnFM5jA2Xxry(okCQxddLU&j2}{ zU4oa?9dtsMA)4@U{hlzvV{Zwo3@x%^!&a7WAZFQV-p! z?)Sy=omHO78r|4F<2$)O&IPq^&jf>@o@l?sLadtcnz~I|Ourp1 z-@$R%5cQgl|EGtw3zTu(I(xC8ID-N#Briz3HTP`P^LHEpWLlz<(zn-^L0;%cYQ{GVm}GP zl$`l*%it8zKB-x9HOMor&ElvhsixKtq!P84IIFoHhV195lCBztdGn>r`__#VqjOPQTlE^o+Ss6Z))a|< zr@+}NCn#j6yRfkTGjcY&A=;kys3bwh3x5c9tXMMp|H8iVY|){V6u9 zTkyHUp_QA3&uCNSGq8BaJV z;PSi9n7C;;e_r^S9;!9a%ysoN`n)-qsUD?IN#QtZ!vLOcBgd1{eNitxkqstosJd^S z&QI^nr+e4;(av`lAh4-k$oMpd-99{lM&}juv1+h59P>GI&v8iDk%GPvQisr*emHK0 zD>|38kb80@w_JEG3tFbarT?U?@pB1TG(}eRSX+eQ%8GnQHx=I>$|IZcR`{xTg-pX> z4Jfet(WAlPOgT_5?j7|uVTnmvg89h3TRNK8m7fYz{|$& z6y9+JjHN8Gn3gC`A3KaYX2~$kUI`MVndp&4JiaxOX1mff8Uzc(@zeXU)1G_uY;g>x z*hKPTH62XfAewp%=Ob%-BAk{zjKxNDYAx`k*?)v$d_~nk&!M0Q=u|O>D*Fd8S zT4-K}3p%Ilp{Ac2IJuu2*ViPW)6ynEX|y8_mALNX#|NUDz0?CaT$7*e7>osV#`vdZ zQ`MiaWbF3$2ejlHqmn`ejEf2+ivw}^Q{9VC?D7pY7xA|WXw6e1&|z4zWri%Pqs zy}e)O*&bTjODXNNQ$Cf3-}Sxwzxj6@Za5A%cpI=k1??lpjKzbGboMFF$XahTD3S8ll=2z%ep5=Azg~ z!%RDN>hK5}+%ChFQ@6l9Y#^rfT`S$MoksIxUQ@x)g}!D?ZbO3hl!j~ zZt8b9CVmOOuKlH0Hu?qZyjN4{)T;ycDHol@eOdUd*pa6#NaQA)W`*sXcD$|KB(=tR(c8YaGaG-UUsR6S@(k=dAA-LlL(yqZ2A0mNbhRYQw=G%WtczRjZ=|r*f~~4%4$p1`v42D# zTxBbEE=!C#{827@zg6JXylgz_AHaj=)I-FG3Gj7Gd-i{7fo*x7dI7Ys$J~|L2q}V@*`Urf-ga0Xn1XX^ig4zwT%2~c9gO<4 z7wAP1UTSfG_B+}0IlIj;X1DO=^>DBJ*}NP4%Vly_`qQ(g9(efL7~o5W=+LGG9`Zg7 zw_AJgvQ%#h{n!#~JomxYkUVY*nV{VGx-;s`7f!?XCRn`13=7YN^ZRkFn2%hd335O9 zHgdYO!f%>%IC!;`|G5>H|8tkGMGHr9QnkW#uMs|2Ay~Wvt(4viZ zVBg_CWIGJ-&nZV%|JFh9p&q~m19xcREp7dTSv!{Y}ZB-&@oQ<|Hha`-&B zdg}z-{i=tN<8*OPVKlxd79AL+Bi>y30gCPS!;97hs9G}sV_Zw9?@ulK2(di)=qyQ1 zWt!6YSTxV74r8Y_j`;Uy3@PjHLv@li4io*)C97}3(Cw_q9nhBBTsBhlHZBH__7P%c zXN!kNZ3I1sXuhIt!jJZLR*HeBXez{lGij7-)dn?tAETJ* zJLCj4_SJOy>v z7hq!E4f?L=gm=PPbM_}6Sp6uO(Y-4^KhX@IzG?|hZz-rv9|HfZ`%t9HM>(UY71mjb zIZE;(X=;o=Sc?6rp;t0q4-9490n4dvxDiJ85YKsy5wy8RVhXZ%X(L+0FF>J0?rx|UWIp41>mn_&y#TJ86bB|y; zwHpdQduMR|Ia^$PdkCNR@uQLL+j2wRbZF~rhg&!zz$YgjZhkSsH=D!wd~4CMZf+!% zwPNOUGY!Y~NCoGw<6+y7bd*EAI6Kt{S6@%YiPwJ7u#Bm6sH{J3uGYloDLvRt)t9RR zg81?7Sh|vPQYookgs~3S>E_f@+8aEP+#f9@gDwj|H@h4(K1B1TEetSguR!{g|6rtSeNdq*t$l~rNztM>m z8e;amfDV|rQNCcT41OBTC$FlKla|E#*DuL+7V(08Yfe9>FOlXOZ;(Gn?}XzYd-A2d zvdHZw@xFiVd}p}{j@{H(6 z7{85ZshuI)Zl4ZcR~o{nMgFp8etWJPna#s1V(Ha}jby8DOcBo`aQ;(s9uVn>?^XKp zfVZg_)2oGc$9ex&sVr4d`QLj?FLezS6>V+t(f{*is)8zM!!xpTMrV2sP8*r#*~Qz( zr?YS8&Y|4{RFeLG-|oDy=DFRh@qPX-2!GWPmaNF2wAoMP$zL7tuiFd=aY{m?ieJKy z@K^e@J5`*Gwv#wh(QEAicqEQVUly+TcCmadU^VS*69sd#qw(=$FFgJ+k~?&W5$7N) z)OpdKnzmPyc1Sh{R;yFlDd7})T1y(8_EF@uwUVB^hV<8!$wsG&E443%NvoH+Q)2$` zfc^F7sYCfY+NqVQtZlQD-dgoS?QMhknbtDJ;9O5M8?VY2PV3^U!P`mqzkzsgRx;gL ztA^h+8>r2?SG2o>#73CP-L+=O2Ockg2*W2da)1y2HzO6#=9|#LS5f$-Ubw!xZGv8g zSLo`v5H=n?UAgg;=*;SFqO#onoW8SMb{iAHqf5QH@SOp#Ut^BV{Q_y=*glv#-UMGc zr*ow>;$*i)w0gXPgO<7Snz8+`{L3lwc=Vjc56B^xJ2#|;u+!k3XeQ3E{`~J!OVpV9 zomP~%VT#uR8nLQ?O&+yJyYgf{7@LbqYfq2j;9A{d`;Q{fQ|8Z!B z)AfNx)Ccc^{VMcik4Vt3cYNFB42 zwCxs1Kbx*n6l<;mx^RwFmp7t-IL6# z1q-`*?mX&mD1yA9QHmc?qW`&NHASy{3kP(npgM6N-PvxfoG~d7`_Cwa^F5uEp$C`H z^6Ik^_T&Q_q$=*@Dwiy5q+VS>p`wlu*~^v)Z!;Lhz#bhwwV-0T}hzyJFQ zaWhQW=z$^1ZgEiFItlkZoka_LBJjq3KXeh#jDaI6V5eX>WS0hE>Mbuevay1wu9>{9 zla^fnc{R-3`CUriql27pfUD=PhK#p2>FkMUZ0Jy<9Hn~+A|B_#jG3CezDFMJo8ivI z1rMQOQ5)W(-3ddc`f<=LE0|s}henhSgVF(aN`a7sFbtt{(?JA9W#JSuRDIAN|SIhi<=J{iiU%+izc?*)fep4-7sRUHTDx;nIm)h zC>$&M;65W8+=Nm1_>OQwlE?*pXbn#LOgR6!8=rgTiU))AvHc$5pLD6Boj<2S4cgGw zZv%LK=pX83?1Cv*gL#zYP+a`d7-k<2!J18u=%2g;styFhD;&!GS8H%=g%76YUjY;G z>~8Aeggve#af#@G#-*Hqm|ub;^{yvZjfla0OPcAV&mhbe^OK!32jW}BbQ-;|7DoLV z3!hz|LC1SdAY9uZ_i;c=!8)F|&6~UI?;&PXJ>>CG1fK8a6FqliHN8BZGok|xT;7&e z9V@4K>hl$c{KTD0a6gQEg(H$#4qRLV=d=6Jp0b{teb1kNM|VZvX*1}Is}`rm{0Al? zOY>u*0UyynPMquon_TvQsxHZMrc?>%_#3eMV8-!xjw(+y`SRC)1G#?De#!QVgv;~d zxaN(>Lht%5AGs;M$Ap(6-MIp6IDScV#H%j(7*NwmQ-9OKxx3>(rBr|2(~LLHt%?~}UF&3GF$pV>n-!(1u1kC+>J)Jmx%lgMZ23+S_` zO71>8itu}1K09ri>~k!auEYw*-}dWp_irMPE7rnSr=76;MmV3iq=c;=eQ4ja`*7#S z1Ibh5F>D4;R6KFY;q?bzLQ2_FfA#JgDOl5+4}i#E9v8Xw=4TM}p%1T9&IK|O%zG4s^MUf6wT*88u9iQYJA@614LE1@!qo0WM*QI_hl4gim5+2!}~-8-L< zgIy-BwS6h8d|yG^(xWjn`5^pW`UC3DRKotf27HJua8z*wYrA*Gr{mPo#_bIJnAa2S zH_m`))%O%{zV>k3v;GHyF099$yP)c(R1aGdPTvE?yPdF&efylT#^&gIkaCU;oSwH04^ zoJx;^wK1?I66ov!@bAk*Z#<=2_u}M`6DoY}U;%}>GSS-4%4C2D({#e>6m}8#Kgyr|v!QjD#_^I1Gdi79~J6$+R zvlbWeo&1$hHM$WRNB)6Y;ecG((T6*oUIXWZ+bYhsJsZCF#I=0_@!g!?(yE@NbX3P2 z=hmoDmzKNWTWm1z`}~JC501k6iS1a9o>{X`#A-j`%at3NN}rsDQx4;IN!w*3oLd>@5D~?&(4lq`7($XJ7s}k zssgS&siaNQFF<{A8V{cJjWVhS;E;T;U^jC3QEiL-)OsY;b8cj6G5$Jf6ati|K4V^&t89zM^39`HQCAk~;Bu zaGms%RQJAs2CG*z+p1LF5g3HyBM(SDdPLJGa6nt@!DM~yILvJERQ|5lf@eM2B0JcP z5j?U$tU!kIf_1WQ+gUm^(w1MUmIgSDI}Hb#t+d-olm|IQscr`f}VK!=LCg z87MHwZ5X%vosUZj^0~zoG0W)k72G;S^Tn#o@ZgrJv`J+cDaUJoPevf@Z?wX}!$wJ- zp@VQ^-9Y$pGoGqKmP_A5-Fd8YARn&t;)(lm`N>~xHb}iKpNbE_G}|jwWVS-C4o;{2 zdvC$)k~!30_=8qfo|boR-+Cp+JVaPsB?dY+hokH7lj$$Q<%Lj8-P zqH}*N^48!n+nveGtPr(Y=VIzE52@GU4tUp4A-x(_1EH@~`AEWPcsg$;1iF>MYvYlk zhmwRg&pTnC3wbc^`R+wlgg9-JlmG8fkMp*x*I@Z7IeP^h{Na<~5=&E%=_ zr#CUUyT*`5R~z!>emSzfZJ;#z<~(Ylug&xB$6)cGZ1&W93OdhU()^xBs6k|KrV2i% z&0crWh4R8N&u>7E`~hrxh4Xsn%cSX$!Y2dngUt#xZd&Gs6@!LKs*ASDS2dQBR9=YP zhu(nV-fy78jT~ymi4o@&DBdpD$WWeZC-%+p|@Q9B~m6 zG@IehrdgE^>yoh0K8*JdP+>do7m!z_#_83A@vTV+Zf$AA8=fwKDgA{9UNEIy-PHMN z{zLjA?&T$ITl1hLVt#SBiQIB+@L54Duc%v3^M|#d$n<7dv-ASxDdV~AF;&zp?9B&@ zE{U^HE_U>}1wH)t$zhM$^2)jYpy}9rFljss8^*Us+o=m-j+Ta8Bys{r{vvOPm<=`G zO}Ja@8d{@%M0P8fL6WVCVB-G$u!qzk>pU;2RG`b zVM@(q*gH{VR3H0evN(IyAOEOucDzAXAFe0!Pu?tr+@V=k>HP6)oNN&Hm9|`L$&W54 zq8u|ATi#da6?0>7@9|xd&BGL)=C)TV8Y}K%>x1N{rJl^kv$b?1NjYdXUp6 z(Mg=QMV^}+iHCkTu};frkn}?))A$g~w5gFoeD1*FkBPi(>vQ?*<(pLGc9P~j&&NTB z-h#Wx<-B-S0ozBO0FPeJDCI^3e@z-iJJ=lGn&8s z3&TL)HE_UIOZ4BmV$kI!!jIXVqhhqMjo(IiX<1IYZuC=Vi~fe;USnLkQVo-S3Xj~> z1kvTt;C}A{@W3fUWt$m-*QgNA=w>4vv$YgrueRon=3VjOXiu!|PjeF=$-b)wqgSHb#nclpN};ko5|G)~6^ z_lzD-hQDtL*Sig0UoaUi|0cL`i0J(Fdo=O+3R+uz0?O1}*t<)6UY_%;vJvwr)v8)r z4#`}8%u{~XK8Rnr*GuPEB|*5;M}2^vPt*luu06KtXjt5D(?lbIA%7?Hdo;G)z9R> zB{yLsjD{63U%no&30k&IK{U{@Zm?EVfGcoyQ*&rUc# zAsuUSUGVOYB90$e#2&%=@`yBoabG^b-c1jb+5X?8gspAmw5~2VutRs=(7(I1=-f(} zHRFji$@Kw^$rA232Xl^!+n^ls*bm)RPlHOJ3RQM{C&$g4E^Dprfv1bTxc7#k7}hBb zO~#4cY5UdmWLT8UQ+#>;oDDQ=o*(~->&jCq|YIPugU-MHAVKcpY+ zz|)Rf@oTs1@~%CP;qkI!DQRIgH7z;~JER&=wH_>ekJ?4078GjC$HT4ruL~7lJ$=za`|Fstagv&z>S)?`j*%$TB&k3HC4%0XEyCgpG2{54B>lS z0jyb5h=m*P(*BXZ>3^AF*NN^}=jw(|Yx;={W*DEI(@5QPTJf>lt0isW^O}Ct5X~gv z-BRn0{bO&^nmBcgsW#@?BZK+u(2d9Qmt|snsVxS*s8E))7W}-~3#84Sp**$CO(;Bg zA>i#kb)K|!9+16Ax`+&xhfNp;JoMz+5z8sRcYpknQ%8ogP4HQCBecAy$+z=+!M{$8 z3X0z5w@NXgdpD%+%-qPFV2^u}9imXvc#GyjNUqwTMRM*y7ZtDAcs{#Y-2uW87#5Ebjjh zf=selby+a4|6GJ#PPgF2DQz6k?W?q~TYJ*U{2O3s{sac@4S@BRy>NP{58o{@w~ zsO+|ks_Zw(5ia)v-pQ$u+8BpL=>z5DLm^!FCmGh;7V+)RjvTDohC_4{sk7#5dGQoi zIp<_I@I2_jpTfK2iZL6h|L$F6JA4W}9ihix(iYK-I7d91e?qoSC{`}$Ec`8xGbEd= zc-(%g7>qt&m-LIe!!(~_`qk+b{8Jk#Irpunwku3|xXlYG$0Z(3HV3oT$s_Pd5hb>*B(L2a!EE*d#kx&)?0hH^8dfEs{gVu6lkX#s z8hs9S7YPUKX${W%(GyR62}YL!74Bc!4;5L_yhZT+{&cRAVplsup8Es2TcABoPIt#H z3q|KiH=UbfcSr&8CYZm;lwEH4K}wf2yz!_jH=8=*kRME+wl0I=zTNm{@o%c}biol5 zT48~3`8o=pcE*~HJb9WH{u|ng-*gCogxYnmV6QHJlSJO?ZUi5)3&KA;efUvMPi%E% zuRLyzALl+W$B|R-(cedXG3Hw$dh10?`?Ye={X`(IuWWz``Kv3h-tLJqypRsoeS?F=Ko3nAUXB!%7UkgX~yo7GApTnB& zrfgO_5At?~%5_1OtiM;GD7l`EH+)lg);n|F7i5oq+f~r~cmjIgoiDkocBZj|{!!~K z1=5l(6%;zIuQb197#oLNAp4QG;EClpFs)uhNiEAD+`KtD#IE57YeT6@v zGcDQB6?Z#0;WlR@G`>&*d4fe~8{3iZ2|iZzm8Z}-*Z@c0K0!CSUP^5~O%(T&?i8l=RL+}~4BIZ46XTC3+)AKez)-Za5zajCqtMoG0{m*T5Jo1H(t)RUY3%+%xVxw~s}&?; zf$A{!n^MHJL-QzLdLdWa>{HgdbYeX*yS?0Mv-BV#6RQ68l0O;S1C0+wrFj9b6di9V z+>^}5&Y-C`k3r7ByYO4@s$`PjFD+Vs1S(V_xyZUJey|p~j#*-cgZriPmsRQ6BwcRU zX$d(GgTZXq2f10-l$(FuCRyzNBKC*!;-lvw>uUfde7Xt;LO#I9fF5iToQ5a1UM8JV zXUd=Cg+V48mB|~o(6LWhygJ5%m%ko_nFhVc&0n9j)$Y?O(_-n7a6}dkaY2V8Lxq?9 zy=-pl$4Ad)(c!3m@SO|Mq|r%gJz6yYkZw;|`SrjbZ4y?6P zxXcARyw^+>T6=j4{HM1T1`JvT=JC<;%P9kJ8=2!y2QS_`v;~DnRM4dWdrVR}qu3Jd zOl?Ng5*(?Zq$jno<7;oOZ9YzQY62^=Kaw}zxd0D^6Cvh>9$w1$p{(AU!S#dILu6?i zxnHMs^#14?YT@1w=N%Bv=iS0*;joU*2!6|qQG3X|zmqg&`wn=o6~!T4tyo>$fiy(- zqxZ8LlJ(?0B0v0$T3p*EUr;gP9%XTSWk4X(??H+k{}xGQtrhsOz8o&M6x@5k_ibzF zEu6(!*tMe(n&^Lmft%~7<;++v%oS(W!l|@qX*vv)H1X~i7uvDqp_J_v$7$h-WR&#^ z^1ipPeC3?O7d-6vwMQH-t8wCQLk!{d{6hq@KPtCH-;wj8J)!!VE521b0WX~+dFs{# zY~^&Ed>4mvV3)@*BVGkO?Yd%wxSLg6O_Wm{SJL_vYZ$U;KA3s;k$RkHL9dc}V1wwr zY&voQKK@xm8a~N*Vv=wHO&$!}Mej#FJd0BHg8)S|`! z2h9@x^T_XV@dJ(Qi^x-KT;xXWQGi2P#=j%^qNDsUY$=g=dflcRm z(#+L;u|ewqZQDN()gpWI+kaz3Udd?Ej3qrhxe3De4&}4Hy;09uA@W++ zjq=-I-tfr-nEB&4z2o9C&M7 zJv63OP|ZMB>JxESaWyuCpKdIMKSk;M=glAtPIH4NS|4G}NnP?baAnI~fWi0H(AE?q z+$%fLfo@}FWXM3@lLJhm=u7|ZDR@CJj)7vo-m{x2_hr}KH zR91r`u#ag#m*demVeWeAT6-JZm{ks0Iz71P`B7Louv8BDSBOPld$NafEDvz?pp-xH zd?_Uq`g$c{dogcKXxEap1T*NcaRDy1jG*#anzFJ*AB;Yfg7IR8-JxX?W=*MssZqxG z=Xw%$*p-NI)KyAoXUjt$pQeQ?HQ4szJs9@Wo^OdvTl#Qkbe}3o!(MNPcMe21{m#OK ziVMpvJY(CbT7tayC%~@&k`Pg)- zvtJBq*ER9dGaLNj6&HG#EMI!*jN z42-9#EkDYJ#(|VHx(T9^0CXk@TL-gH0x1m7P0$gRus>s1@nV zn*wf<=Ybz|>ir6`y7-j3>s+9I7QOlIs9>zyeu&h@4#3e@wW!!}56o!QmiI^Z<$ybY z9j#pWet;GyruyK?H~*3Os(MHnq>E-DL2~Ul!F>4;B27lYR2cpbCN&j@=}dxTs^55^i?jW4y3=Wc+1_!auS7x6~b4+^g6EcMKv z1f7Q$!@8r+6sawE+=IM%e0@0Fwh!dO(kxn)+m&k8{UD1kMWpRYkX@C)wJtJTc>YV- zK>T{~(@g zwo0KmXNkA|d{AiL9YM#f+;PBT7c%){f_bBsLg8u;_IuJ%{^hy@whGSntx;Aue{g5? zKYLw1nQbK%t*}Ek;Wjk6&=zBNJJ53R`TdV?lHE-@E7qv_@b8g^IO+a%y5sr=o)p}m zGtmle-&{?6&x0;mnsL%a;Vs{zs z_S(?snT{onA}<^}md3sx$a?VwOfN=CGfo9?xX5|liweY<-)uSMU8Ag=TtQP-&!@bg zc4)cmBUP_Wr>%i!!Pz#LJp#lowyHbnO*Q3&rwrv=?@(s@CCYSP!52u~0`5otk?Kuf zHuah*c1Ss#&}f1=-#y^d8U?Rf_nfR}9Fqet&yug{?;%x_PS|v>6sr37LE;dGoVMsSS+HFw@O%(&> z^53m!#TOm!a5xg4RtI7E(@K%kTtH`I#0&Kce3pwJoGmp6_dZ^SWtKCb(wVzJW zxja*8^Zb{@Lp?Bz1wUtq9WE4e6K_{Pc9tT^)UFB!XQos4zo+Ev)v2(3@gS5+R>3oi zeh|9&gY@80Ab35WMaQ#F!$0jjG~AYl7eqYz-xf>mwnVT9rcH!Fu`Mv#E<(CFU61Z6 zR?+wIi~PDR)uFoy!pYj%7FDhb*F@qR8l0-j3jKlP*VGH%X>E~L|4`@F{^A~F*n{nt zB}4AWIO+V#1~@$P4@@}lQyxq;)N;afs_htnjT)7r+kP87PEMzmV-xXc!*<0&k;h%v z-UuIQ^oGvg3ea-mDNR;i!mz3-j*PET9bPw9Y1JC@S*-FM;M z)MywmRyaS-_>tVl3_so|hk+l8<&Ceq${{B&(HN5i)O1#Yg`42^nnmKC(}8RuUhA%J zj{q73kciyin)irC#sgvMQ%&~Y5zNMA(e!zV8D{j~0a>v_dH0esrHfk?HRp|lV?!oG zW^pK=7*z>573SR8wgBrhi`a0RAKjX6Medbhd|y#Q&c1uW?wCIg|LVl|^mVZGayT9p zUYyAjMvx-YTbW_wh-=ZdWCS%uGx^A){-|i2=?#x>15;S52p-0 z@#cF^UhZPZ9wU9RcxE8x^t=k0A=P9b)e4=)nWO2C3b2du;gdJpveDzA@&@-Ic=eAr zR_|>KBgYi5Ug$79y(t8qtjL9i+TXCkEeNj0te4CS9+3SJ!KYIXmW;h)aa6m@bm_R@ za(TE=^-y2XD>T53e%ai0I#GeCV6)V|k&4fV43KUwezB{Vo`~~Wb%(X2d+aELPD$pm z&>8Pl|09hDz3^k;f6}al1z2?=j9#ef(U0@b0)}Pl(v)s~_}*u+)N6lSV1IcT{iit>y6-xu?2&x|j$Z4-jhEiQ4oi_;FzSbT??yqw97Bws>cbO#d$2?9 zd^#4=mh0v{qw>9uc=Bujj!<`2YK~0dZj1AA%osC->vKTq))LPNW{BqibyR)13wnHf z3GELpp$@|z(%(xloSJ%ATIZ9>JES+D@}o2REw@5t^Z-mOv=aTQApEp2pBMH`#gQ`= zyhd~@Jnk6anOlzRa48BaZ!}ZR?pVwaIfXKPPyYGQkuCZv*wUws_`b(0mRXoq=Clsr z$q5mtrkqDrS-zM%z=1!R7t`!5>O3t`2ezu&Q$(~o9zHFySHi0|yiyM<9(G|mYRHXN zy?9pnXGmV`iT~1jVy9bu@smw5+q$i#>ZXUV_wQ}#h~YCyRo$4Av?5?!N`$QA)Dc_0 zErZdq+Vt_Q1#b8$^7Z29=yElM-<2Do<*ZEnlIes|1IAPPUEL(Td$saM-MM1?s)Jhv zkN>Z&Xy3RS;)Kk8xN2nqn|?YeIZR7OmseiARO2!HG_dF6Rh#I+7Ecanj=+Y$#uz*= z6VJ`cm8FQO1hWve9nqyQ%YrXM5$JQJW)fZJK24ao!Fn#{IN51`TSLN6)|7gbEmh2f6!@tbZIU-g<*AGK* z-0a25H{ZhWY@$7-_@wdsgP+K2N)q;U>c_8dDsY{_AZ~IA;i_JNsP-o%x&8R;6;yLD6#`HCcAe>;@&*0?5!O8bUgD=20Pb zysT9|EGf_D_IkSPP{vH}?cA0)2Fs9enE8uL{Y{iSgnSA}rb7*L`#)&hB@X7J9SY%oX-iOuk z^Ql7=e>e{wD~xz`M?H2NrH|_@f6KQW-b?Perg+EJgNy48a7dLChg7_V1+^(0zr+By zw$2jVtYj2aRc=?jI>5p_n5|oRLkp3$(D|mr{|)HPC3PWiMmWVH15VI`sVBf?OqD!g z?J2T0+Ce^z9YHy@M1GOl0ne;GK#3K-VXnAC-95h(N^FXy+x3&>=!sp?THNIi^gK_W z3;#+M?`O-W6BKlaA1YefRKhyZb-UcXFAujx{Boy1N!!fPvH2d2p7j%ke?CH`tKU*Z zX9f29Vag3-V_=NVRK>YF8j6XQ)zXSaM;`eqmHu>#~z8hM@!3$bw zYu1Ub4@)MUh8@z?^JUcd&47=+H|6kM-Z*?jKk4Ufxq6zqxv@^Ec^XW zIrdhtaF$x2;!iUj>d^%+bpB85iqcu%WGK%N8K?g$>Y$DB7SLH~jB$Yt;CS5&%3sye zAs;ot2&pEGZBcm5DHY1n)bZnz4~m07K2qY)j`(I$GOKCb13kg2aoIT%9=~F>hKRYgReJ z*O6)X>S;dSZnYYeLwjMW*dx}@AEQ*nvmDkq6N0-1;()G>Y&60FSBajqzgHryu^7zv zp&QPjO3ko4G}uUf>@@vYh7cVZB#EKfp*npPMXdjf8W z^X|@^_E^z0lT}0jNmSNW|G4}FTD0M5mprq zwP+yYC4VW zV?bATRvU)6bZiDre-{p69pA&4h)Yx_GJd(b!@)8ogwul@So2y5jZeQX&(gRTP%_~y zMLFeRbYM5YjLz&o-xK2x=(25g3?EXB=Sg!m$&KY7=x)q6xZi!2@_JS`KJ=@Ad;1yk zs}kTAt=2=O)+g|*@4=x>iMYUe44ux1=kfm>I3{uhq&_#R z8ptwzI(!?tn?jp2x$oNzidfr$f@L{L$^8m&{;PNJK-^UyloW8A*X~@d;zq~6vG2@9$0w! z9z|q|=UUHrw$_~kzoxZA_0Q832G%Xmt_f(R=sAALzNS1E`CZ!Iu7Y07jzbM!HF@-u zQrV@G6)ss70$qKad0xpa=y3A`yo$IP&@+1j^oS{-z1oBDO2SG>vpx=66<>tk7xnQ= zdMJK%jl|J@sciRfnH2KqG0k=`#=FYt5{$=xw};{rMMCd#*MEMeJvFJAX3fxBzZCG*N>&~LsjKHnU|vP}~>W;mkO z@L*VB?~4gjTrj{-o0IcaLnpOZ96jkI+;GrFuQ85TJ?tTwm28#M?j4|0mp%gpZiaY^ zCy@9s70oT;I6ut^{X68-)g8{*ds-w;cRnoF`>X|ns1RkF9z}AE;O)7O4&(Z&XHt&F zVw(7@BdLyfLE~*Ctox^eRZ}#ugGn2l6gorRyunbunza`0{CP*3^Il6g?|9<^F+WSV z6VLqqyaIZ4;CqkWEzJVE*b!9s-yHB=c>sc1 zM&gvNhLnBOj2CV{DB-*a*4_L9(*M4u@gpRBez_MOZTDIJqkIoG^E24Z(Sc`Z7GaN1 z$?)HxZ}e|_8ydSQUODN%a_SYN&U;i1a9yk=pI+FWZxtBx-3;bekp<*1BUUG z_uuG0lR9dV5e%+Xd0cg-Tt0ZJCA`0%kKY`}E0)xrfo-c+z`Z|N-wf7-d z5qpo4z8PclhatRu!Vk*r?tr1$Ry1^6R~-H)L%0Vr_;XnhpWj{u2eWrj&BkSP_-YV! z>DU4$KK5qQ%SrgQ`#d-`@~U#~UL8))_rL@Buc7>8HjlOg{;x|d_=`PG-NLYmHsmkWTPWLk8I9GO3rcH0tlXT+t4?}i zO}H0wksoSDz7{jFZYanDG_E?H<4YnreZ0uLj*Fn2qOIVtv?n{x9D-%Le$&i8-6X%- zf#{=Z&N0@PsJXo{J|Au*tyrJUBTt=^cUX^rCg-tqY}9qp2S~?r=WD@c!70hG`wVz@ z_&W3&*i#zc_qaTMaXN0f;3PkVCp!%TuXcj( zV%h>Xdk6E7Pl>S5GZB@Ah~wghaJcNoG4bft0j_j$fFWzs8o*p_VGCeE0F_xcN8 zRUzJf{ejF5TchtRb=G*)lb6k(O*RYWD&5Vxqn*YX<;VGnJn>})@BjH1Mm)^H+VW(y zm@*Wj?+XWDK#CN!p(TDx-3$#IW4LvXG4T0{;Mv{ph~e`}Xv4~N^sB;|$G12R$ENLq zZ880E0)D0qXHBuby$8RwJuMxXp9eF)G)U_QxZtp|I(VGgojc_ags)6vJvAGcWgNoq zy8Gdsbg@%@rjCmZ7Sh9natQab!Ig7!q|VDM@StEq97ne2*^=$@a$9!+(*> z+IXlMt4{GHg>2lW12=x@$1~#pqtA!`z@v5!IO6OysIpu`rE^w5V`>|kq`p+{z0DNY z^s1n9cW#j1*3PKCx|Akli!;xIOSINfumipoA()H&Ya3fW-8-L*bB@T(BVNOau=ea; z8HI0RR?F^P-YIT;4#$Snon$et2r|Nx@r=J4F09DsbuPo$_G=6~XIzKXW4=MEoF@8{ zW8vq*zc5^C2a|Pg(UQ!eXbpX^G~gM$-C~NF{btA%yNDKOwqs3W1H6A@8inO9k`F$3 zLFYwpHg;JU`Q4ih=Rej^|DEaB|4A_3eqRVCW*_0tgWi0~cmZhcUk%}JQrN4?UeTOf zh?P}Fd{!CBdTo!;(Q}Q`&fNvnsfFP4yV#@A5`FGkWymd#{*%5A9KyTh=a3_^RV%#y zQcc+)p0sEe&AjH%(MenA+n!hOGt@y5F+UXJ&OW3zG5)O8sLt|4Z8VxG_!DEY*r|Od z)OfiFYI3|`Qp7*$Rp(~Ej_cBJ@b(AFxiK%OjrvV^J;8_T)MB~lkPgl*al(_vlWE-4 z*R(`HGxrW%45iOAv966O-pF8iJpr8TMZqNfoIb;QWRtj?2=) zYhM;f8`gVss6NYSf}{2->?G_;b3?0`p{Sx|i_?uPIDWG#&RM=h4*w^Z%0`_y_Yg>l zLx*CLp>SHiJpkE{4w1&5AZ{q$Mh<%EoHlC$c^4K(Q^g0M=f)sDc&7%`x@d9M=}s8k zDjzLQ70_|JR`epQNnxESI6x6+>4TviKUxw=zP1Bz%x6 ziS)L#kUclNgxsHcd`RC6&-kfe$`?Z_J!pqVhS_tga6zcp62>Dwh+u60_pr$0qZGU4 z8XU?#M;|Wt#Bo;x@m`}P+Ln26mWm$Q57|J+ePZzLW(VQ*vliViQ~27e1VWdz=7zap ze0M-08cRiN)Q(8`u{%a>EF)w8a6Gba4$Q8d3Qha+Xtj|pde~di<9Ac!QPI0$w#i$0 z+nWrUEcL+i$5z4Z)V6q8aILJe1~7)7lKMnlh1cZHYkGI(>!~wnoOJ*kIJH>$C(RV? zhWTLpJp(@YpKt)hwnFuL6;KnU#`|>=@&8DB^JuQZw{KhKgc4DaS)>v|*w^{ZkgabRjM85or#hlk7Po_P<*z3l~LwdNMo;|W7Sq&mKq872ph{HDT1-Y~Rx8M%Ie zGb(a>(k-=1@LWE?g*XhxWa@NJwRBgF^;(^h{bxT>?Kuq{G2FC((jd%fVAh- zZqNli&j>;G{?(u)m~MLGj67PHTfw}+4(iVJQ)DabiO!W=Q$Jw|*sVNH)S~m4zcN$n zU*48u`|O{QHN*)2)mo6f9%`ueLlXkV(x|UnCAsfD8Jbt6uxTrf5W{Pn59CN5*>c!} zs730s0nhf(;eJ(Z9g%1Z2(bLCx}A3A$GpE#nzmY zw z=M%}8n9SbT@Q9@gl~C)d1Ibr&0N$JtX3yhz)*$OLsmVwrvAPb#`!SE)u#970a5+N% z+Y&IIyqqGy%22>#Pydizrh7f8w9(`;6FblwA>xfwoH3VH`w#Y!vz*}{;?JK<@hh^;fM5c zlO4|f(m=b}DLBVW7@ek00ZGMd_Go+sl`_lZ){DX%yFe6#BtvMU@FnVR-AP@iZUn!2 zZw|K;nBt zkP+ZGHvv{+h07dQaqzRxqbpYpL4D z7_w}uA6cmGifcLF`jG)cHYv(qQy??Y& z-!z{FP8cEHMN{GKti$Z5HP!6kE0$x?YtX@Wp>(pe2FnvnBEJo}?pi}Uqu8s8&sv5_ zf1MC^4lrb&rait`SVWH9HN}bij;K|@v251KL&?JRY>}A(NOM_+xTmk_P~SwT5$4YQ zpb&H~`$Qe;uTe=)Pl#;VP9pf0Vys&kwK}#69_IED|6B>W#C9X~oqmPUIy@WK>YO7J zIQ~Ys%QBi|DT|9uHlgss5$3zm4wS3NV`rrT81I%POm-tHQ#S$A|A~Y1%O^x9a{&Z? zT#i%E>yX1nv+&uyavEj06q?=T@r=PH^5cssQti)-a*!@a+4_>ve|p%KbA$XInMSOawMeZTxp(R|sy%Bt+0M=8Ds_#qf}eZN#afU8lLeT)OAjL? zOwsk*M6y$MCx&nN%lYAgm|>M27|`#Hza;k3K*fEe(0viT-eEvb`KjUQP1^9bDx7pa zoQ|bhwe)!GL$ZW(S6f-Hg$->pVM@purr|Q@^O-(M#yB2Ju1y!U%`k(_X1VnI`e<^M zC%(^m3iWCs@Ki{SJ*eo!|}6F2<}XQa9fsQ$TIWNz#oDrk6xOc}O8i^1)% z`+*1gXoz9N?Z>3=^?LF%(;TLmZp1V9)=?OgfR0!{h;;~~S?lf*Z%;kCs96JUj@ZF? zy(=1Z?F0>r`_#h00Vh9Ff;n78|H3^(=1at9wk+lsGtW_*j;8zeO|m2rHUC#;zhO&gwfa4zq~5ODZ1eSFsgSD%|-r#iWd zd8(^RjAnOI{jx;XOXV18{XLVkEONjJjY=SXY9iKkQ6gT&JueR3U>v_iGIX;a%9!4x z>r}o|htr01dw4Z@CwIPn*@6XdRPP#H(a-tXRqdhdhy_kX1#)kPD`pBph}L$!p-0AN;p?VJ;M|+d80q|^3HPLl z>$@||*jyg${ox3=8ds1NzZ@aPd4LMct)q+6roqf&&V#<*gQP_@5h=0?b0(=kX{8@n z^hm?HBYdELc^({=xKCa_zr``2pPR%xpC__Sp14@4luYFu4nD5-gx#(}H>HY_M`gog zT}>9V&v%?W_Rk`5Q#f|S<^!aY3ciI%srO2E2)xe+fsaG!$6in7*q!wtr$0>NzA6ysjcb^hscP)!7*DK` zV~PB^*VID4fbFVtgY8dW(wV})h|=?VvZH$*>dW||>k|`_aQz+i=~Je&lSet%y&W+- zvyIyq%;cid{+N`a!dMKb!(pqH#P78@20M?^Aa0(ZU{yxE6=g{iO{e*@CD6WZJ&r$k z#O8HM<44#2W+?z!WHUH9| zWfy5n)K@lHjiKQyd>J*v`{eIO%6R)EaQp=k(dfCh{Cu_?ZiqYnNBp6MdU^~0m;9ms zA9D1c^Vt4Ob<2OiNB=qgyYn#ouN#`+6&IS!KE|D1yqv~ewwc(xQ{%AV7;OE$xc z?nE4~m%_Ir&G>U>8~pKZf^|I{!}eVgN*|2_%WvFsOzi}OPuPY%KHp8PFE*o0c?rG# z72)!ibI7x~%TE1nhWsYJ@S&_8BetvI;{9DXBlsrVR#m1IS=&h~9xQ3N2rq4%;6P+B zZq+;i=hsg{+ktv4Z+Zq=o1g*O*y-_;6b+W5 z{aqGTN{^Dww)g27F2C=DxmfX)6$hV85ieC#`b?WPfMpw}I@l*f|Z z<2^7rC7vp;d4sKL4`4K=nK5m950C9ijOZ4v7lb~#~ znHuV~K@NKZLzsNXd4Wj;#5ky;N;SaH4(E3@1%a*1?rodK|nSB}6o37)d>s6>^9R#lr z7UPX4-WVJ5mbAW($3N?GaO;=*_-Qa34>dQEiCf*V%ZZz%sO4kioiJ4RcpgSe50HRA zoFnz4H3n{-U@EL&1*a#@MV{+hD0tuoUC$rEuXm=LFJ&TZYq}4HL2H>41%7m@?;* zkNw}m@r?a?2%WDD8d4K+&C6hnn<+tFJ-kGAI6p+A{&Vnp_&MinUx5iP0-(qtxBjH` zAZ|Qz2(um-YM2Z`QC=y=x`yL+p+X$FU4ef`eiG5}0dmI91}6D@z+Kh_ zL@u_H3Cef?HJ_yM-s-FHa_J*9HcG`C4taDa_z*K8l*^Wky@AWqSo$UI1DJ2KfG5u% zqnPkH`q0h|2fR54-tjIxW}6Db9QSbQxm-}b`JsO8wG$|ztHB;iDu$gekE6}lV%YTi zBMM!uhw$=2#`l{sDpfCp>mRPc{^~av80mnL2Ks1lwI5=NoAJ%2wY7$yPh#%$S?IJ- znx=g;BlvC@%rBm#GN$)&(4oJ6b$bjP%ifG}a=kR|>qQdp@r$m~kH_or!;oU8&i0Az z#>m}Vt~ls6c>c77ZEgFpLrxV=KIq2JBIh9gRt(mznT!|TcA&!E4CbFk5}q(u$NRAg z7-+j0;kOM{h~qeTlSeRCDh5+`g+R}Y3%E=<9?SXe;ylGA^x-Xee6s&MKH$8XXU-Qv z&*m$5{+T;l@#7Y~AJYXs;l-x*6Gvh8ibbf>Ukrh-%*oSV4dl|C1XytU8HyBb!^?e~ zTcE=izm!Da#MiM{mHmUMFn)_Jjklo9Z!>Ovd>22dI@9;{?_o(dFw$D`%+fD0V4uoe zFN%A}v~q3_e=oOZ;;x5L0)qInI0_w@Aebo24_@RZb#e}dINLCqG`Er2A0&?FyPM&r zb|`+FZ~(Wxkiyz;FR{~n7GCn=%%qR9n3vm9@n-1`+;D6qNR)@tfao*a>_rU{xb@{! zj%c#rWE6_Y{$zuku8{*7_V6 zr@^>Euz-mim4tK2sqkT861ePa#JADhzOi!&VdmIDtXnXi5DmxmClWzTs1SOGUPIPn zj;|i(jp1>JVaKjlxS}8l>$RUkWx#7XE~bF~e)r(c1ZC1vbpj?lGoTLzbLq@m?J)mA z0cZ~xKyUOgR7r66P=zB7^Y!7SX$Nqo!*Wpfse%oEtl-oZ7WN4&MuUG1_~rF2A{|u@ z2ai(N`s)XMXEGDKV-BHD?_O9P<_42~7U8BZi^wDWA_xq8N57uy2cls{USAObuje=6 zRAV?WOZZV}Viex0x`^{66X5gTNT?mWjm`&RVCTZSSkLRhS+C?E%L~C$=ou=W@_=_Y z&!R=82yCdb!$mKG@oTFzPD;$AR(l@fe)W@h#V}Bhxrmw2Kz7?C!m5Rc-&ziW{x@;P zrhPp%|5rvTuon{TN64$*a(JX!$@Q*_aSg4d8TgQW~SqU7CE%zSX!zfo-ozY39iOQk=rwh zKqTS@Zd`T@*PaT7;Y)*b${t_v3m;+y@|NS`4^8-KaX5n41$dsOjNx4W^WVloye%RK z_GhAT)AHGj_W>8u`ArutnY4jXwF}uT%0fv@5>W2bJ{(K|v!9|cRn8LE&gQt3XHJ4l z)K+x(SWQkD&VVVyQ$e>)4x$$&pjc=Ft7~6{JP9W}eyE%nOv&al4%avl!UeQHSAe7G z5>Pwm3iTTs#Lf0=po#;h{&@Tdwiy?Ly=oPfOudQ<0rSwpKmopm-X*uvFPd(tevdJS zVqs25BwoE-1(l0JnTd1MNb{=d|BpX;{zC5ozKPtTi#z_ib=UvJpXAnE2D-ZcEB+)O zU(n+J?)cBTu=!K&S7q+>{&W0y=Qr!Wt_zKHjdTr+tu1E!zt@F5>e3DKZ23|7QhdX# z(<@*|MwHjGVqXItk!VnuIF5EhA|!El5f;|ZK;5mphStea4f{v7H9QWS-!Sp|Oc<(2 z$8U@R9$9JJ@GHr%LBX#Cf2d}l%_^$~bzi-PNY_lZUQiFI#oUGy_Zu2KJ}l*ppE=ji zqWpz1Pv6!cuNMmwxwo?GEh*5J;=n5!o7~Xn9nz3cajQXOBJvy-zDAe0B;EnxBHob8 zAU?jg5*kNxQK0)4PokyoSD~-4mv~+}&lo<3;PJ;zb9Zbt$6$ZR7|I(!8$ePK$&OZ7Po z^)YIVy)&QlCQaaP6zuy+KU-$=?$5mr6H8Z8x38%%LrSRe`~$1T1d&CH&ucGi@DB=Y zDA#V}>8l&?Zrr)wkf`vd!Jsz3;Xl`xqwe8AK7Q`v;*S6B`ueZezrMkuMaIV5_4U8t zuX5k@fA#U7^EdL03ozrp%72dk(fJ#h=o;$(@6P|5*di(po0%6{3$UU#n$5TxO3tTM zm@c2uNexd+)Q|SH(G>1~VXa~V+1HeS{)KU5`CfIbH;E>Kd8Z*(s);Qc+=$wdjV>p5_jBxt`%3uP){qz{E`W~x5s;-@%i)`igOajfsiI4GJTJ1Ig4wf$ie&U63TXU&~x&o^hFU5PmUY}QVOo8V= zFa|S!Sc3KW7KlzZ=0!H8z?HAZAy~?i^Y59_q!+p5iEbwN^gkhqfr3Q$-whZ&B*?iS z48W)GK9$s(%lRRH;fxJIpfM|uN{+|iQNwib__m>5MehdH-EkjiVhW>@*+Y`rV@c3` zN@wVM!>D<{8i7&XW-X`8hAdS8f7M1<2$_< znB6B2uf`*(NM;u4sNDw#xmmkR_|BKyVz_58rDA?a%g* z_wDH*STYMNGP)u0VmE1cYmWEpR-x%g9>C01w0PTYDq}qbLe&3|i|JcnXRJ0UZ!#xq zYgUj2MUoKeWe@5?gVd^HnDjk5OU}V=7zf=-&4@p9uv@fPr zkzwdOsD+nbN;8vwX%hb{tMRbObiBHM5^w*{m!w#?6ujrnyv|Z=TY_5O}6*s%ld?4EIoeZJYH6vz}O9DVUfK7`*b%) zUkpCLvFA@R#S89GpA1?2>gq$IMzi4I<~rbaJk1L7pMZbY)0uk(P4t#sC{^}81h>XM z((9%i6S1X-?y&Mfoty4hJo1+vzR2LA?}g}|;YB`ft*2hmobzkg4)<-gLGAN_C~{;8 zZog7W_8co=Qhzz3*-sJtT4Do_a}4OP=_)wYpGQxNd&AY>v!tmq3qv^1+^FJiVleiD zhF<0F8-F3Z;NXaCQVx|gJcv=kG9=MW2XkI4KyGb3=g`Q8!eU>JQ|bz4(>WLUx*_Jy zwi1p5F$<P zNqXMm9T9O4LAzO*M4&j7QPFRqd!6^8s%Rlwt2oG3ggZmrhSvIZPwtpjxn_|HDJg21 zI{`la9-;4Uw$th}8L+yW>o67^hB^6X7~_^=cH(?@sB#v@x6Av8#f@j=dx|yWO&_J1 zX@6)?(-rXEnF3B_T5!Z<8Z>yF1^%=Nyz_fh;cnm_u$pHGSN3cIh_Q#j z)6cAL-U-3mhKX#_OguOL1f=$!1J8?7;YemBoij-pe98pj)L-0>&GuzoIhTb0za9t5~TqMoll^ZLG!_Bi~ zrSUchxOovD>xB{f5_h_ESb(xm-LSK)5Wkt&(%0J8XxlDspZ4P(nq*kZNDnq*vx*RC z@nzy^Q5$?Dm<%w=?Vr_$U|uo8%cx^?-eWQYc z6X@~75$y2b4V){n8Pv3`pxjfL_$f&Mt!8HU^MrbB*|N zGlLBgs_-+fpXM50#z~(`@acq`rt1eO&RFhkx?bOj1}w?IX?lhzFPucm#>5cXU;K3YGx3AF$L5%?WF5V(uv${4NNo%Cy#^t zX^g`uR5DRRMcdUF{XHBF))eBDhruK_2}u9+WLi?bmxv!Op;}r2IO|F)hzV3e1DEO6 z=dwF1x2V(bmEV}{L7Peb#B7XuHT>M2 z>Ruk%sqO%ZANk=@Yz|qnV6=<>FIq`l-O^SgwbcG>E*~8uY<96W8 zGX%rZ4LH761@+VlsQA4VbC8|83zEIHM93X<(E9vS7s*so91gnkyu!qEU;O+D;9NSlerqAHf zxg#x%DYRn4Z5ymrc}Eoz6@b6j4C8b{!QD5PEz%Do4{ght%cm9-+fjxzT~h(^>U;D_ zX*T6?&faD3-N0s65Ka?mA=jfO<0ZXOb|teOzK9t>_UIvUoNpylm3MyOEUfy3;EBl0k)cGuKv^+Me5lL9>pwP99I9(#SyTYB973EMJnh_U^khkJJL5yQ|N z_E*9wGTG`0weE`|iVml!&%j*H4-(I@i7jcso*;-aPo@=~%DjjDs&J@O5cY<}!uGGC z^zYuKbfwoUuFqOX^&KtY!O<0XA;<>}gNli7U_Y6zJwhzo7QxWULdZ3irT5sga^Mx zhoHg}I!=YfU#@!(^g_W(uBh>?5}GMoFZ=_WG`d0h0?Y!o(sV3X_i~ zlK`%Ne`XG)$q%YbJA-3s!^XvsC29^M>9OFJm;f>}uYv2OAfN?TK-^psPIybg;3^>^ z8N=m9?Z@epiQ{x+Um^A9{4%))&Dbay&GAUrVXSis9^EYdAI>}NPuWG@E)_&4uGe=Y zOpD8;6cP?YM7~T(hZ@UFSdy3sX?JGRfC|nX9v4EtJnkizpKc%toZID^u_DHe|D=46 z+_C0b5EhM{z&C?AXc4Qyh%0u|?9~#K_brUzVqw@R5esb(IJJ+}m0E~9C~vP9zQA%=Gr zH`SNER)%+aNwl>V$gt}jGOtn#Cq;c>&t+_Z2lLi5y_;>goX~L)&yI%b+ZSnkVi^f+ z;(Gf*pXv3Od2lrSA2WLB0A{RTg16M|0X_`O~>7PKf+(gXU`{TQ`dbeF#d#(RhyN=UgsgrQ+@||7%9&KZ0#JA=}CtKjoDHwf8a4X0v~ zVZ=}uw{NmX9pyJPF@1=MR~ezPl8T_h=3v4Pz{tt!tnkIWD}^?*=X_5lvT0#u+!i?ZQX-9k{gT6Z~KR-f1UNIpy78R?qQ0 zpCw{&bQFy5k`?sF*DP?&2*%no|%mVqs zEYnUd2lJNafcY7Tctos#&G4HJY4b(!fVKkeY&M4I7dMFaIaP?6RzSUKi%6{rAC#O* z!KjTs%;REf+)%U>1!QL94p+Nw-LUZlbPcE;b>%Yj{4RX(Cuma zs9N7@_^C4$M&y3bJ{w9qJ6@A0X28_L;w~d?lF#H0M39ya9WdW33kSAm*2`-?!1ooB z#J9PH%*m>z$jvl1z2kV6$683%st=4to&$b2IDlmym&o)9zvSDbT1Qna8?cQ*F9sQZ6>0Y24dz-N8bs)Y>yF^}kT?NgJu2eZ#j`VZRxQ?3V zq<4WNz3U`LUyC}?NY7DvB`uSFlI6P8`#0c8sH2sh9bl*J3cuC)FuS#x^eM`s?y=ML zc53cqX_gw^lbQ&pEA-(0ushX`*oD_#NYM>eYjA*L4TyC7WscL;2s^Zb;Gq9&NZZZvkYi56&Wdj0v&odnp8AqX z_q383vOTovZZ++?@Pyow6@|4MmQnRde7whxTH#1{EL0uLsH;$^gVum8q`E;CPhR9$ z>N{G&$@3hzw~Z627pLISmS{5iL5j$Q_rlQ^7sx*`Q4rD4!NL{q;aiR*G_L71bucQd z_q!@aB-&!xPoI3@?73k!E?Et4%d4PYUMsG;dmi)5gH4Z=bYjKr<=9)R0y@o;acI~F zKRW+qL>Nyz7${D4y9emv+Fi^UgLc#NHL`G|T>;ELO+)>%S9rCf8n3>qWxuz2Fr8OV z(%k$ucBoYl<%+g4saET74mZb9NcczhH;HrAEo#PUlaI>W5rh}L;TNGXHg)u5G?6CKyAL{e=fxnzTwjP{;Z65~cYk48m zwSP%%?JLOsu8EvSRRo4_US}2^o&-vf@~AmjN`34A2SX|Q{g^eA;oL&&`a)6rfihZH zyk<3?{l?mD8faQ3g<@F=r~*N_Lu4=h`}>df?_Ex`)l|6oOA={YYX+$E5wr`Y@UHJ0 zAbaY3z$4BpzN=Us5|tv{?u_VrX^}EDK6NC)4onb&S!|qX7jKiR+F|UY+1Ol#4~Fr5y|IaXcJmRV~V_RCC?VbbUiUsC4uvhr@`!`S`^8h#C5HG z$hAqAfa<8=3mOT6zmw~)7jQg+W%96W+XZ^|&3+WvssJjZbFgWC9QVxNM{5st_~wv| zOBU?G^UiDVgUE6`w04LrvkD>By}=NXbA>SqQh|xT&Vi$|BF&3wF@4f|2Y$3k)1QX6 zWLFQ@>#6sI)up3!$+mvFb!rOJC^t;g@|x&&ZGF0BC&%-hu!2cjH-%fzo+oBp@1X7A zWs*0bN*&w7NzUC}bbsA8xF>m-@+PnxLtPTLO~_{IXUL(9NEL}~S^+oiU4*rj)zCkK z;~u7MhoMLrkZmx5UT-`6wj&VlyF?;UET%U;`=it`SDbe%msm8}Q`X=MeH@)jc-GHI z-HVyMk)Qa1UHL)OE4D$nYadmSak@vh$297U<4epyw$sikS9PhR)8(MUg`)pn32D zl`daN?#xL;iPv7ZmE#XBb=JW<2h?#WoO43x@MC+T4uq6cQ-Og5B0VOFcN(4XU4t+D zGoM9$j=2$ydxCJaS_ga*Zq`-T#Bl%XZ?lnmV(Y`3Z=&Y1WIR3pD!W@niYK;MfOjC= z05<#PLEN=660RY@9u3ffN*fg_KPC%*oBqLNOFuYUD+kv5Md?I&aY(z~MtpS)Ft??@TL7h|oW$ML1K4c$5qe*}hLZT-L^*mQ zW_me-?}x0q)hZ7eF4ap5Pncrw{Rg<{`*BQ;GJu?pG+e;-k|*0+Fue9Mywj;cC+yBc zJIeuBcybn%dbpVsJ)rD#=TNxJH;Gt#SF_bec90K3Su`Y1g?Dj#4Y(&L!hLH;a-`-X zIHqlaHE{(P^L`_`9T9`wGKWDTdN0U+I}Szy(@9ak2P*EA!C32kSRKw~4|;Cm55Eo+ z_Uu5J!)x&y&z+22j6nKpF2-~kF&2xtjCb}`(}!~pfp29q=dLlQS@-@hmRtrppq(F+ zQ|A%w#(YXHq~Lh!N7Cpk4mzD9bhs=64t2-T{q1rPbZfxW_)P@N|$e7AoA{;?>crk&@xpM?iDzJ!d`UmAQPN#z8;C6N(_A(qwj(~kpNAdZ=EF6C#Ny3)h zz~an7{IWcr9#%Vvqaf9g)mVcWb;=Odz|F=}Wat?;F?jsm4oaQc=`9Ztoc7oUMj~73 z;jQL`<>Q=QO9Now=x^xcKMYQ9yGX*FX4toP4jjy>fXH`tr z`E{d&Enw8ADhzkACwDD5KVw-eI-XsIAJ+aRVv$KSEp7>0b9*+7Ia{+1)t#tRX+t1F zn7C^{#VWg3bm9D?jIv)G`WaT@nIl&)C3FEke!jV0ujwwyK6s7#oeQP2J71ZO(|ocs zejZwS{35q6E{D4p+vw7XCLCjLH!l4w14>_`$=h@{r03*u#+p;~rH~2QTz$^v);1yJ zyfD32QfcC5rVE0%_^^BLJu*jb6K;I}kiOE;#w)YA8TINI`rOa}mCNrlB7Lr)_Tn3J zxBLpxIrfOC*UNzK#!Q&E){uD4&Y+bWEWmZ5Ajpa(P={s1gyVP7e^5>?@tmmo_z0u? zQ5sf9Hqy-tHsahPn&2%m2^LGo!q@EUFns(UNgq(c0JT}PEU1c3xlxI~+>Pbg=G_aUWA)l#KcS5nUbSE&`1XMBoFbUV<@5VSxo&2}YBCfi z58nHH7$fUgoRi|ksQbSI$+zvWopFGM8&hDOks%yZJ`G(RYiV}%9XeGd4OA96L1-^a z57v&6DK6(&>1qbrE60fD?(2-v$OYVgqMSHPdP>BbTAAqKERuMdC2CnUM19#TjGBLe zxFmM7Bg&JoQRE&({(ek;Y?%NlV~KPhw+H9qa-7!0oxm`@^*FHf9UK3A0i^UBUfu|)tegBM`MO*^c+9z~pu@Fp}8v)CgzoPzY#BibG zJEG)~P4DfR2qPon)GxyW6nhWB0wqy!-jzX<)K$-zBwi;^L zVuE{oCE?fNFVw6^5e|&?Q%958;IDp{Bu$N@KiaqB!|rCHrVxTJR^On4#|PLa0lS%> z90y>!`a804=NV?QP(C?4RTq3V2f@2lt#r?7uCMdWgH-QyGT{m! zSd_YvRhF)xe{%yS9JE7?kDm!&hAGK>5P)9474h|5BV6(134!V@=-p}#Ee0X*=-VV% zs&|KO6Ol*R>z~MMrAI`nD4FEWK2J~YD&stgp(y+A4y{lZBR8M#hkf%ocb&T!j@c>W zaNTQC$~gf;o{Uoe4Gz@guLJSW=g0bZZCp3t!>qnmhD-N9#FvSoc>l^D=76CSJfE&j zJIy2M+#f|m^ji~2b1oz`Y8mVkcTq-M<}sOn;2AU1GoB5M-GOG;WAWOX+4y{m6TVjr zL%qq_xcC62pOV8^{!;|>Z~tPphg~Ff3w5#m$21}x8HxYC`VpCeeHi@C9}hNMHVyps zhV*mqhPU|4XxP&%5AFjqO z`hr%`RFsl0s5Nn(O|AMp$)cH@!}IZXCj7QODQo>g9vTgh^Jin0}h9{I(L`Yl+j2 zOJ4B2)Q3t>vnORMC2>iE3grFR0(ztBOg^TPCrVCKe{U%jx?6zOD;nvx92aP7C6IGo z07M6aAXq{K4)NvE%rjihtwsVWK5rraY97;2%W!JwxfBfJPlA%a9GCC)$F7wTSma`c zA733NrNVKXx4?>3do>9elM_Tw(hd5KNjEH9@&<)FgE7m|p~1ydy&!su^x z7&qw*ZAtk+A6iD?_bhcB_dY`xPTq)HgUZ>#*Q-&5oe#;Tp5XRsh*aG^00wLQm>G7Q z`_48Ia-&azn6WrcUBnMoc1d*9QVY_f$_dpwyJ+NI9u}l0vk%893Uq~G`_Ef+mhLQE z$He27ok`@VhdkM}x)fi4A(XwlL@%2d;HbxBGOc-px_l0$;r|Yht6Ki}K{*-y?&^{) z?Yr1RA`>u`n^7N3qvSKkxt{UkWc~G0E0Djn1nu&M@rGw0u{xfB`O&K=Pqz=V^_Agp zfi@HmNz*Q^&$OIM;KH6|WPFw*{aE;s7$t0mu|M43uzChwu0|>^=ZvB+YDn6NVk#u$ zNYn4EhN;U<>2ax#>|~Lr^=U6Zv4Rq%XmI=*t&VOb(dYL-kGm-?&*De+*DdmMJpm46 zhW5KpU|@(KyIU}ZlvxI0++;Osu*M4N=S0B!&NZ;Ldo!HOibXx;<-ks#2+{o(D8BOq zdP~fLFHJ76>Wc=3yiF%0@B`7DE5x}Dkj4ah;``G+=*V#;Mr;bmCjotQ&p(7pws+~z zz*d~SW;gEGpG+Ja8R!+g&#?^eQKRFbrrj^I=q$y3P?I?YHY*+gr`b7V&+0QE?rH=E z%VRP4a4I9qZ;YA`ZZgHp0tlaen?4Zc*z4BXu*q!}xh`Oj;{2QFzCLZJy;RHy4Ns(L zbCl5Imo4}`I>pV^CqUoQskq7K8Bs0Jh4vXgiM-@*s;#saqi>19p>zg@=BncDn?j^> zQXOOLe49pae7{>mt1uxx9V1G<5C`caB)p)M-rHLVd-qln=^-~bHr_{teAMCR?ful- zqM75*EF#;Yw2`McA1_^)Ox!)j>9ZY)Flk3LQ}gsI%{{do?Lxm(+sT$hd*Xalwlc@r za;?mAHUM)zN#R)0H4J*eP*sZn?D}vL&wP1GESK(L)|BkyvSKat#^!M<_zv`{4|-ePk?Csdqp-MO91z(c48fx4}m(>#PYN|3Fz4hCM&K`o$FIj^^_54 zFUi5zhq_G`X$O!q_eC(#+m&N-%!46v;BM%y5CTKO?|r&>N3wvCP%&u8WSw%7B$g7MWeQ5|riw?3t5q+A1tte>;xL z2!Ee}*;}H(=>7vDGrEl`?YcqyySP1?_r;L)M2)m%at<(gK0L4|m9gFRk+^8hq&vSS z!$R3>^l5MzxryR|_sJ5re?+6v%O&Lp{1z!JOSs;bF}V zFbLpdj5!8sf#y_@6WR^7n$^G)OC=SCWmJE@9d0a1g7|s>&$$z5yZRUn4AQ}*j7)GN zIS_uT4tTAZF!OgXF?eE5zqHzbT;>i+q9tk1lBe)y%@go7e$NhX%plcAi-6ziGPKU@ zqt@59(uBhYAnEG`)6U+_#7%e!tzx&pk_vqY`F;)pUdEFs{&id?w~f>bA7Df?N z*5kgD1eXsaQ| zHCT2e5w+Aj%<*u>s|icc^KK9g{WQevIim|5f<6#-BaSYQl>;k<6fmB00d7jT!HG*% zXlD3|xp{e*`dNpghbv-YMi1@C>!QCVSE7&#$L1I-BT^GyQ?Why>`1679K*Y0hx|fx z*`9({oZlJHPam+Lyci1@K0oU@1K~04Ro)T5dCVR=5 z^!d8E_*bA?*c#s8B?zeP zfs7?75b@#zXa*~RoP;7T=3^$r@A8E4EsJXkB?87HLF-s*N6&X-k3XP%6>nn+N&ZGQmkS0v_&o!bp&hWdB31pV+?y zzFuEKib|#MaK>F2ap@#;-3iQn9S$Gfn1HYLb$C#aL(YjuKxn%IL|(hfWat)PhtN@C zdQ_F18lJ~FC@bnWZ%78g3%0;i576*OYT#188)l}j;~ZE?n6=TJ#^0Sy@*1t!k}KNa z)HMbDzr|w0s*L(CW%t=`Z8!W8-9m@$C8=uBJ(KvnDE3rlBelOKLOi$}Mn}>)+A~=h zdrH#Krdu3o`Zw}jy|8CCR`C|# zJ|7oI$vX*;`xj8CI$1yZTMZ=T5{dOf3HoLU=ZM~Q0=x&}(Sz&Xlt%kulf@idb;cX@ zZn)w4PZ1>V1&`_9kd5UA{KUY$jPdiWr(=f%;n7nh#Xnw>wS0f+S$kvlQk@r_p|q8* zFP{k}HD}>?cLO6N^Of}vD5S^3Z8-L323nuhKpyA2o@Ww;MlRRU?m`1;bvDCbm+N#~ zKcB?^ABxVyAItZP<95lal&m6JM%nYe&XbWODN4&KNlQyR4LdUm$(AxQijZ)hLrFAf zYKw;Yw)aq}e)sPW;Pvu6kL$Uwb3UK10qWt?{;isXHvhx(%*Vzow&rhS4n&1KcssgKp^Khv6 za;$Xrr6ZmPm_|w!S?G+Rs@$2V>m;zwUj$LHuFz%Gyv-EUCQwI<2cMbJg5bJ;2Ij#dSM_9$`Y7UvA> z7cwFuqA z@#nS|m>(7cVS)KDxb8R~S&;|&@r|JM&>q4z7qiLntD(px2~;i$eBl)z`Jh`@SZ2PP z(2uwZ#?L3Q(Zf?Q^yh9&{NO+j4NR!+e_=FgXR=>FtHm9Hd;HNUF#r>nS2SR zmCm4-F%KGww+ft`rwm(T2XIcLqpg#{Jm|Xj5c7ise&qQ>F!(|y`mR`IJMPXq9JcfZ zHIJ321$EcxBs9>=l1ln_azAt4CG`BF2RPR+(?I3QJ=TKipu6u2_x)Zc^9vfsnggU* z`wD-MDOhX$QQ&sX3do`1uFe!=Yk^L$6|kXXB#5o6M2VfMwD#>DcI}S9{W6$JajPdW znO1dD9r+A3S8ijE(`vD6!(h6W@&=!=h4^+$7@oSRjH|9FHR&uKNkt2m(*3M1RCQFr zii3CX);TY*yA;Pxzj)E8eKQx9yGh{AlL@$Z(NO-vJ#iTBU=4eQ*t6Q#Wwh>>2MoPm zOOl32x3Uh9C#<9Y_Cq}(DSj11IeN5SiSOF?#0wmWG(DE$I5J@=W2|)t|*Y$T$v`h>O@-c)ri)2n^R`9 zA+^ZuVR8}ruvB{*-egOl*TfB1zyVg=R))k|)AE4R`1r1niLU9U4d(fzv@;o8Bu`VV z$q`zv63TR5#?fNE?I=E>9s9+;b055h(h|whkQew1r^bEeUrp0uEp45k<~R{oZTN^e zfrog1b1hK6wG@`B^|P!|K5$;^0+UJ;r_IOIU{lo;b~s@W)Nb1d?YG-tGG~Zw)f>Ui z%Np+F?m@?c()fc@fh8Sbba-;J&{_YFp`|-cULk`+G_+{!q3gEq?kK3G*{yvb3R&1He!}^{G0;B#bv>?_bF62W*Sp%`^b%yID=*f z8|ar|B3_d`#x+cuB77eQz_9H1nI_B_ zjiE$fPsmn_!2<;!d^gIBt+<*6rYUh?vvVI#@reQtnM`_|Al#F@Gx#GyAFl607#pNm zfvy!3$y%8EkIl}+?V-cTGN;6L-4HJlHOJCc%V+qwTi`_$WkQyAEe7-^!jW!$R@a__ zkt>aHhK@Mw?TmorIWh3)@Eex!?FKCUe1WZB5(f+JcY@TNKm2U*_h8Xw4v*(I!%X2B z^mUWE0C4kykm5v`=ihsEZ-oWM2xiva(Dtz7W(1m<$10^VF}MU^uL>2gOJh&&CT zXtge!S}|7C{c@1V)8ZbS%DfJ7Z^B^Eb~RD9nH}Ei9KxA?awVrTmzn%rV{HF48gA;G z#`V|L8;93sW6;VskmH{XbB4#EM(|B|qx}rds3gMt9V21u*Ml|(40T~?(o2DF@dGYT zP6aoa9uPXL5Ye*~Y?c}GzE&5(HEn=@vT-8#Ejt6RhaG{KIBB-{;v>kPs}KB*FcuW( z0BxWBxcbvVKh!D&FLzIYk(FoR{A3N1UV0eoj!k5@d}o9GjstMIR*mJKpUNwI)@0)S z#uOd76{)`GdUyqe11KFpDuP zvt5I#S-?d-rambheg3Fp+}j!qd3cvw=4=4^XH&rFY7%U0G-SoxM97YtA@tPcM52yV z7OuA$hh1rAf7A5ggw||2dnA-XoKCP$p58G3sldtnb`6pu4#CJ0Z3x$s5IIckW(t$G zv7@0=VfKvckfz)P4Myf{=UgL{3pB+oji(r=X$tEuzhrI)$3vleGYg#f0VV#l!Rt+N za5(=E3_a7uRw^ta&NhZJs{g>&BeUS9^#Le;-Y58LC&4sVJNEVd0Z?l{3iFEUq42U9 zdvdY{4h~TgJrv*9_;JB)uDZII*Y1p9x7O&uxF3sQx3Lnll34{-r@TR{B_1AJ-;Y-f z_fdG%MA$Su0krIvvG{AZ1RBK=HrzvSRTdU;J)W8HWLhL0Fl&d|UrSKKNQ-TKxd1oa ztEThfJ^1@#9DFY>gvEn)!J9t;%=gY!_L&`p(zrbEdrt6Z$r@0fzLd?1-AcdZ=i>|E zE)zY%fSH+%=Gd@gh&w4m^fnm{hOPlS@dWC8tIx!W3&`5s2rE+N^9#zmIHMiKe8k^! zthkv9UG7&PFPPtb!;y-5Of>KxSB_P3=wsH`_ZG z1}|43Pk$-+8>~*DMGN4%x*-kewkMop&0DqxQO>%2+COost%{i=%`-6}2ft{#I_NV@ zc_{^pza2ykmnvN1pMbvEwxFz2!bU1+)9Z7Gm~G!2c%Qe7opBS`O%bWsGwUe&{Bx$9 z$@AdsoDGGjO{jjQ#aaVa@BuiIjuS6r4Q4o=Qm|0vu0XJWofo)YfJGB)cZq`TJOost}|K#Pg zYfl)JJqV}avx}H_wNaz@tmQP_Y7IA6)QkOEr))Kp-{Y2jIoPy46+0eO3f}K;{5c6j zG*XmhTZc{r{WGqxG37j$BV;G!luT)2MT%JVAe120Q;*d;ZOJ>aCsDj z5-*0s_aEz+imDRLX;^BzS;w+5%vUSTqk#C$Qr5~e~+)aX2|+(w6dmk>d@V0 zNf%Fe;zO%wtm(^TBWiP5>6Z7l6W8dHbJ8Qcwe2*X5i*Ewjx$Kf#)fG>Rt4>5j`qxx z$D7@qSY;|A58+<<&$XJboqwLQyr>HsML#&vGG&^htcI~>3M_VV437abVBduuIPUTW zQtH}Azkh^K$p&M}^%J{cCHz1|FIkj^$Q^VnF8!C_{yR= zYe?U>3pn!%m=iStdKG)2^h-L0XzNmYb{u^-uC#sObBR3&FX7kxRKe}r8u8!14qM}% z=lH@i0RvvFOMHbCWMqz_Do%bR)k2?Ot|ykHW)HyGVFf0pP9)@ zv(QJ0kS2I$mTXspAyc+d-t+UA(|Qnc*XL5V&R&u#t3$D+(adb^di%C%z_jle_Iz<1Kfa;$n}mrymOZqO>L1AsjO*-wKEh%>E@>(Px24^ z_wy+%86!*aw^rIdkTj>Vr4#5-%Rc73`yor4UrpmnqH*ifp|Gq)inE76jQ#qwv3hI= z2ikf3$I%k>tuTuWMh#%-%T;tfIg7U0Tfn-&$u!eDt zzn3^tRLX0LtZ&~3e~m}r=#dGlatNM((-qyf?SbdXPgvN_hb%MeCLj6AkuLAc!-6~U zc>hlg8|Y9W$%j7d*Nqg=99IdK-o0n>ewpl*SuA)T|IW5_JAjn1Z@uP~10Nl)v+?C} zq9-2;LC?Ab%AT}?&%z`yzT*Qkfous`kA%d zU6dnw2=bHaA@7Pa&vhBGc%w8h=?KS}d*{)GoPT(;J_=U#*TW2t>-fI!20C63rq_EI z9TE8SJ{MAPMTi}JTBIymkRAq#g{^o}Cl}`LjDV-VciH|qah$!ia-o9jLt%63F$jv6 zfEEmexn^yAXhR?$&|Jx+_QgY9!4Mjvvz~JQN{aFnHbVWc5#V5v0+(I$Vd2TMkdt!@ z()SN%nimd1`j^M-fpsxd$aTWt8TZiNr4aSU??Sb?zi^-FJsc)(MWa7&0ISeZRNg9N z7N(u#`|ZwwT)7W;2swt(%5%`?7|U{|K83Y%x7gtMagY*K4v&}jz|u!ijd%QhbH9cN zPR6V=piWUtcG?J#zF7^)KgC4m+Ka)y`XS2^PZT)atw09yY?F)(rY^Y5mt~(ve}8}Q z);z$rW~77Wv}+I*zX$SVI8bAfqCbZgL;1;4*m^*YE~bwc?wIwM_~I7#@k=mEp5lWg z|0LnmxlQz8XFPQzJZHaxTOf5^A8c%$zy@_XljRN5b+ADX<_(Q&c{^1q`2b!{(gZAZSrR@^~-9 z;t#0dDF(-)qu4L~i@0j68?8Gg?7Kf1Q1W9RIuN2p@ZB1H%C!Yviv+hprj)r$H_~*M zc;I6ZJ`dIc|EeVD2})zXucyL;#A_@*P8)*KhH-k?8Mr4X19Q%Xky@!NoUD>#8nWgT zw9|+TruX3-yg(agR>J+m;motkk3E~X1-4&{gr_|{eEyRk5cN}>**2R4pO(y;cSb_T zmZMOAr~=*^bwlK5DUszfCc0=iM)WP?3N(m2P}Qt&c(^@{tcy9})5~AT)5|D!OlUEq!VdM!%s-kF{>FQF1?R(hqTitlNhG9+noNP z2KAW>e!VhtG`4()k_k@CV$)sp@N8$7D@R~g*lVs}#TPs>$%dxf>c-sdX_R7ff$fYu zOjiWo)@l6`yuM{VCJOf{aI*49rNi58 z>F$mD-0GVL$?Kw_;P!flHD*~je$;6U3KnMSt0n^8%C>39bcdkORJy6Tll}P8#E+jc zn+C2Jz{qen?uJ$i`)|@b8dy`zG{=?kD6^D8e(2Fw_vP4?U4iRezOi{LJy_`d^Q_Zj z6GUiy6y~Vnxb%t~4E|n(u;U-+xFwzLms>Xm_@AW0>qWHe(Gi-kO%-73X0oZar-_2| z^YpYLw8=TnYU;9KW`_iZe|*J8z8-;R3p=rQ?GE8Ctc_zoooAooN>M5540rm%NSgRe zP<3=nWk-F|aHU8Y#*LSS8D4Ubyg&y-8sqSNW-?Xu?m{>hLpSFll@H3su{Dy|FyINf z1BSGBT{ORBY*yocWv3`_rZ|~bzF}*(on_zY2$TdAK$+(-cs^%1yg4XCH7mccHJ0hv zv`ZN_BrhR-kqem|jlemD5E3Aq9K@TP|iP;l!Fz!ooQ8ZI{jW0$F2+g{b*@TD7<)?4b%O_U8#B{WGqHw+oGo| zd>GrR{*=jF*-uVqC!xJ)GImu@K$8atsI?=MBHhoR{NHMPf8a37 zdtr=!KkWdmfN|{W@d((|;KkqgB?pfuj>3-zf}r=y7Al?rOlF28oSpQZX`gtC_D6+I z>Z^Q`|FEBau1`dna5eI2dWU(xcaY1R9r)nude$6shwa`nhcu)SyL!u5N9GFX;}vO$ z)KY#>Z!oxS%ZJ@smq32)5q#xO@N-r?R8{`tba#c(W{-{NnEZwnU(gvw7o z;Xc99dR1{cG#zt>4`YWz-0(m+y?YZ}nx#UIx|d&F*!9qC$q2<$OV zr4KEFQ)h-BmugeboorjpLVaK2_t&Mky|)YdhQ3Gp3_bjvv7B1YbTzhwZevR>kAe-4 z^zei7CR#r|1B2}*GjD^!yX)S-c%i5C_K-MzZBpbzR4!m!Z!RsLYCxZF)$sqa zPji)rzt-P|9~1Bv4Lb3Iz&W^%djK)ATu4Xy3fCxGZlX^Z(^eM^7h^ zT;3)8Tz!Pkz2ZTg%Qv%cH=G4_p9g#k-AlQ8>O>`DS)ySCY|zfnsn<1rUSvk4LFu^OcN)~pv7-XzQf_=&7-@VjqvG32bpQAB#`=sl_WsijG8{LB zPW##5Rpv(tStID`^FHolxG{S(@gs{-)Pn`zSJ2msp7iB}C2e16K^8?yq_?+-rrbM7 zr~VSgl1)R-`u+G#w26Yp+VK8+VsT>SJop!_ivdQ5g*ih$s~an@8pU3*4|U_&yi;Oe z;Dg{gaUEy2as>Tx6XE7nTJWef35&mX;(BRmdZRCikDmu~<9{uu--aF3|2-WI7KOw4 zo~!KdYk_acR|-_G3Y>Kc zg!P_+pVn?T>nYVGQEuTvFtc`LP=}XxYfrSrJuset#0IA z>yA(5@=15YCAzOwPj3z!MbCtUupv_7zCS`Pixqh}IhgU-d7Mco9yqU}m zeVtDRY6-kUhU&TF=)_B8t~B}-RR5};IL3VaKUV=7zi`C-v(*ticXVE42L z94(S#4jMyLXirMDZA91ew4r+`EhY?{{uqpNc<)2lBx7TFpLhm{{BkZ93t%Ppp^0_o| z+gtW^;XeF#XBpLooM*95cw8H5hH92NkgF{X=QkKp=7~h?UyzRD|I8r!E2T(0B z3-5gl>n{OOYrhwN=xZ!2c=r{7f!bFc-VBjAH zEzOaz!SO3Q_u@F4zg8K>uQ<$XH)zAmN`VQ~UqIU)A@e+U4g6{(Me_=if%6Q3aVdIi z@9s#D=;62_9x?FhPAxo&ZG|?)29)#ijJ3)5jVf-YVC)N)6kTSZA5?Uo_Vu2|qIA0)LVGPt| z=EES5C^&v79vYvX1+F9tesJY1K;^!`+Ac)hU=p6;@6gYtPL%X7B?q>T7T$fu#tg}1 zT&@N8d3O_gq&cW5Rl6UL)UL<;^|f^VgckMx3x@vol`!m)1hgwAz~luT5Nuk)0<|l^ z);|h-;03o}dl%<&#G1CH++|O1yu>{|m*}V5OByzAI~8`zHl=_1NiJI>c=eZ~VBBak z{PN`!8~1mxC{8&Cn(yw1`%FUgXN%CCwv`lpA6fv;`h!LC|B3}(?gNq#zH85T8IXMS zX8))EPpY`H(dZT>a*FRMsbm*$Q7O^)^ZM>!h8H9 z2JUqZf`KF5sGuAU$->{)aqJ#@75$E@I_8UE!;Q(p(vh!}z6}jRCgXwR0DdAPruK}u z5#8Tu#qv3@@52~69r2ASLqD^7PIefpSj;CJ;MAwUKYoIP(8sZMm5683N%aTaFqKxbo zc+$D;0_W)LAhvbGUvxNelpYs{kdymgR`!a)i;7}+l(Pi9&+dnNu2pcO_$;6EZ9F?= z8x1d#S5x%E|2U7w1vJh*iJjSXj{LneNL_9=L=?QWb^UFCy4t=F_HIAsmk2pNTnf2z zk71!=6O{OCaQ$ac(-G>ZU3=_U>_+5tFunvwSXab`Gh^R?Rg8q+-3NYtRgBn zYEEBW_cMu#&G=-@4wm}TknBEvVO5Skef`DlP(<$ebAb(E zpn%8U4W(aP3T(UH1+}5x+*-wxZ0q>#{6UnW>f=o~I^jB#_*O(KX*?A;8Ia0HKdM^) zonQERJ*#?cLhMBuc{N|dFM@-}Xwns$_EnzWwl0_{9B|?$1zq6`{MC3vGJwpxH~Be7 zQlZh4!LQ_(%wkV9nhZ>$oe@LWmd6LFSMaOj`&j(%&~>)rfDiu2+s@5DV1e(07qIG< zIh39GgsUsDqs`6d@bTMd`Wa)-)(?|s{;nr+PJRUc-|+8Dr@V=C91wb3bKi3_lBRRV zqUd<{R3zGW0i#ulC7_=g*fh9rg2#5gDD_Hj6BJ z7jI7~OIDJhkbzrPp$rjIrJ>+k9`>G@38k99n5KCg|KhhQ&A9dkzwO9mvMoJ)(6~f) zH^frQ2P6J!KR0Y~!pSQKHSjE{cUQ8E8NYcfv&HSn)OS+j=fKpR5;K=-v zMxWMIe7umQS}OGEeWZ1uRkIQ{2+UI1f+)H%HU^f-A7BYmJ7|%%Jc(U6fSN|hY*%|4 zJ$s-;zN4Zk>stsmTo@I!^0}-D62RZ zCskkNwHMg1VGe6aF>rI^O#Ny)(d~+dFW6w!Xj2?*G6x%EH<5;vKaG2KoDO@oqNm2g z#<%@j!D{zgraq0hzTacvd|3x>*g6@OnsRW&Xe=8zyp}rdNW-bUck$ULWv*>?6wUZH zoSyrf#9eKw;POwJeUH?D)$>$IyD$QC&KT45Vd=CoGmkSW5$@l^o#9SeJb${d0IK$+ z!svoGc=dKMv`kyVf)r=7`vEiQk8-TQm`enMfz-@lK>Zkmo~;!-H`=4{fE)uf{FHTcf3o>n@A(1W0jY>e1w_;M?c zeII+Axd=Su15VNSUd0q24OWKCS79unppDabKLnJA2xszQb-M22#^*SyQFHkKE7#Yh z8&(&{!|xi-n;T7PW{c?f7Eh}CSV2>LKd{9^%gM zqu{pg4er3gxsR|Txq~Hyou}P}Yl#In+IUv3!r5o#8DxZ!-ewJ&D!-i)MMHS=K5M}p z?g24NEAd>N0rz9{P?+E)0*67%=z?5`;%&LP_b>So0E|sOb;~FXCZX~%Y{cLobIhuCNyhHVq7t$KN67sEGOA}L< zVEU94nl7zK{*SL<%REUYYm&*z?mXZ&9>0mFw95G{Ypa-kTN%6VEzaG#i)4Is0xZwS zK+82tX`xjU8W~zpsrMTeV(dpNTf1=eH5W?K*P^?sIZS4!I!;l4gBJa{c=owF?eUvS z!`0(acYGfvJ5Pk&-aHkQD&;S~K9}Q#Y#8Ay*MW*oQDQox=A>20%xF^Ys_8&6gd~2eq_xeIsaw89Gnljm( zg|k61b|x+9RDwO>3oc)0fiR0;0Vi6=4tE0435%k=% zhh-J*%w*kua9itZ^T#(D_D(s)T@IKBp%=piF33}MZ_s@FCSd}rU=&Vkj;HwR!(oC< zBp44ngf0U`?AIS_^wK>@C2!Q=Mer@9=Zse{9J&#=q;x zM1KDs#N*bOn3{(Rlf2O9KnE&%E8@k&E9t0j4xa6brB`djY1zpRE>dPc?5fv;RX?vl z+x#&0p*aDH7X1W6pE_uMvIk}lO=D|omf=S=J@8Q7$;|(_kmN?NEi+gSOLv~-7f)Et zQEwTrn7yk81$UvIIl&jq%cpI0e&gql=mLx>oe5Buf7O(U)Ch&^D&^}s89F4 znXxa8>SU?n2Srw4%;(`ZmN5GoYZLrQlXHD2I?J6ij8>)85mvBnqmi)hlAwf?_xL(_ z1t`rB`XUASoXRGlujSQ_752NKr%DHk``*BUIBC(CkYS=@%lClS00%>aorTPt6|nmC z5ME~V4XoE{V|Q%g@hTsVdtGLrOpwr_lh(oMEn>NvV*rT}@PE0FQCXrYA_t~Su7 zAgKywUvPi|@Fk89xyZZh8wKl^xKWKuwbMjHELwDIa@S^Zmle2%*%r% z{>?0@TzHMdg4rzdlb9gmi9bsGuw5yU{dZ~#DSnG#SF$Hit*rxn{Q6(x?b=YX&>Kn3 z7xnQ$S_BsDdcrC5Zq&9n8xOscg1TcjFnYBm1pZo2edppa;KWJWvwxmr$;^1_6eW_) zU>B+@ILCKIPsC8AUCgW6o%UAFppldFEGe%QjP7>Mcut*YkL%P#xG-lK{;+ z5821`X3k{SQ%272?5>6e{`&S5k8bcFbzu%uwee8n*o8WD{Eh-Ce4S5zpVu{Z+_R)7 z`##{z53~5sx|z7=_f)oNNjW>QTN)G|WK&8;5{ZQ*a{6lTS;@Ih<}f9Q|Lm7Sl45cY z8^47dPc+d!?5uUtS~J`jV|6Ow$@@--|0D2GgnhuOGjT9&Ku#!; zWP!7*BVMz%pgiHM)a^4QS?kNJbjKR@?&W@pts6()(Ti!Z{daCmu?ZRo`R*;j0kBPO zs^EhiMk!Oi*#0+I@FQG4&xQmj!L}_aT-%1LT)Nj+E;Pqc;GZf%-z`=4RVjg;C=wjL zI$kh%n-;CUvIZ^Gv&h=Po>#Nm16OOMnc1SDa8@G?#tA#CA9gD2__ASOrzu8W{pGx- zF!RhW(1PXi3wXC0Rk~GL&8}*kf{pF}fk}oZY(BdM7dA*ki6{z|D*VOJJ?XY@9kOAv z1fwbLVN89$CP}9=irzAb4$h2a$HLpWTlar+`>I+wCnIe*Y7_t-;))b*s7HDa4DrkK zH7v#bGCG9Glj(%{F!TOf&hp;pMw#KwrOe#yfw?ue-(oLnnGqOHg9#?WAr@s}c1HxZcc_JvXN58;_j=FoD2XNTRd z@Y@sH@y%-?Zy8czyJ^KD_EO-(?8)2Cx(=>`96pD+bTmPj&1pDv@;SdbbPjju?Hv|= zTbjENc!;bEqinSj2UFAYtG2nD9XXS^0c0GI2z#F%hokSx`PDO&L?^BX+e+26u`0^8 z?XMa{ze`f_!c18*i`ok(bnM_mnmg}bdz!y--wLbUvhb8_FX}H$Jb!NM?`<({iBTtR^|Uhn`lW7OC>4VxEH_X z6~W6-Lzt}I1Gssq6f`1_u}fn!VN7e1F!z!Z4Lh0&vv(Ua-a(QsJKV#+qZ7e8--(TT z)_~eu>cQhz4Yr+Mgqz!bu!|FvVe(cp>ns}Xb^*Lo@`Mg&H%gzd z05S7j{L?FQY0|JZ=n?YImfe|f@!3HbBII`J4Cj8KnDVX@8nD?S+l-_G~l8v{|s7)fXXl-Uyi8 zP{Fm;)WX;;%bC{udKh=V0u(G)Lf3p7a1!*teVYDkpN9lpa(0BqJArFFY^tQ_X2%w8*uza|U8pX)_2~>q%j|)k zPgCj8+i&>ff+f9p70VUTAAE6QK3OS_W-ie=q#x8yjmu?4DPl6B?A@7Aw6%ccpMD5+ z&id#wAro4RpTp3QXtu6xFvw;uBAiPd43&)vVVlGw=~JyC4cnJTn|BrA)4X^vP34$rPZZ2~Y67?2I^f;{HwgNB z4vsu6g83umMHw+0q3E~*eaa8T-J3t*vTK{c(IlVu+Yv}leGie$y)bf=(%?P@IdEfk zJJ7m8M{$nLFC2M|M>UU1T+El_t1&LLYtlkC>d84dh>& z^b0djzrp8ren8bv4_T<@5xSjXN=s(0qG2D6>A})OT#cDrh0qJiqziES*H2vF701RU zUVsr64RH0^S+LjFX3kFOGP z2-zSr)*c3g4uZ_Ics4_9C2Wf{u`ya;gHw&a-#5T1If|gw-SZ-2DeTN=$^@<7whroE=|x&dd7zLE)o7ajL5`W za4|hUPP5!bQoU*ct@Car)6_~DIlUE4KXsCw*b3g>G=mDQOsIRNBV94^B=rXi>Bdzf z@~{wxLwqd@I2zAznLQZk7}A8uiEwyyny^Q@%Rfq~q(IdQ`np|{ugpIvIGbP4GSA~A zf60tSjGqM-rUP7&XDw}3J;n2KgJ_2D3;de&mIAKE&{jJWs`)DHvbc%pbCqFW_XK*H z@!Yn&@d7sugSpI7TDwx~T8|BsX9b9nl=!3Lu@GKI0 zq|Wq%_Cm`!!F}wvhF%tb!qyGzdA+C2?Fs$GX;Ee}Kws88TreyO|IQyp#cgpkC8L)a_)eg~nfCDb!)^8_xDxi=O2$Q* zC-GlL7B0MQM7oukY_UW>sii42>2_vNchY$3>ly)WJ2P0nqzbuD$b!OS=h^443Uuh; zS~jt5AJboOnu==f*w)5b)5FXMbh>LZ-9LW~d;eBZ-@Z)hyFHoy3@QQfma&l3u1@<` z1c3Lp88A(7*<=gP2whnc)HmfRzkzLMPIoV0t9B?XjyVcGu0?Qj<8HM1eVT7G_XMe} zQqa-s%0~1Ql4Wrcsr|GkpY3@9kFA^oUR~HtCQ#PuFYL+Hg|MM%4I6vmIP28i|NpxV z?cd-&*5SPSx74uI&8sbZEdy{FnhrXFeOR{ zEWV`D=CmMMvW~ck5`xEl=WSj^Q5(9tT3K9-n&5>lL*~8b{HYzg|^?z)kfu@tx zuCL7Q)rRq-Gdk(Mq%JwOCX(V#C7S%sns55gR(PHNFe@`dGL$&YTs2>C3oH9j$$A1< zd0J6OjRPcypI~dhA7X<&KC;E7o_yi+`KY=lnq~f&!i@ghWy$Ol{(E^H2R#&H)87^` zd-HmhV(CneY-U2cg$mpmahZ)9a|)C`{6!04rZatz3kChWfVtBR$e}kF_n!&k#=Q-u z0&yK2zuX&DJfb-L+$8q)+5+nRJD7r8ma^1;anyWsF3B`JV$)2=(8p`L(9mEIgnf6T z+tOFjV{JCJnjNIBufJLL%Xqq-s6!SmZ?JQhB#B=gL^jUE94;+kj++gUu?l|E?x8UL zR}dB1-sjdYal(QnD)iqQFNjz^7Q)vDz#T~qD4eUx>}Lj}qly~e-u6o1%UWPLcugG04A!Hd1seFSWH^NW-pioHgsl(Qj#}T6K;731cQ-Ag z!~0?>W_>T4`!$>9eW4`C+IicVIB{M!z8C2?1Who&1wpu-XjU5w8WFf#oLmm z&QF{oZ$am~6ls#+8ke2hgKNI#a2xtLrh8t84)qB>>S+rJe05<990u$KvLvS+f&nv4Am2KPqU>2EBaY6W{>1LAJ%gKz)`FpA9Np<$1&6Lbv-NP0r^z0}s3Y<& z%BV$x;_;a<|Enp58Gq(K2Fzv7OQyrJ1CMM|v@5tHky#jcG=yv_v#Bf``TWwO&>-~2 z&-L#CX3ocXDw{lJ2sUjcm~lj>151supp0rDfB5)m0o9C z!Z1q(8WVRI6Q`|ab}tr#v5E|}7&}7I`8Md>p#f%VzcA|;wOqCDIVR<@2ols&fL$62 zCqs=vaIb^hsB}1Wc^mFeafQczdUWvmVUlmp#usEp;u?BreQN|I`!6M>D^Iw!*N4*8 z-9rgR?1V18LwMQO2DJ7$!A~g=n2b6wu%jCkt6e~~NuQSgUBC_OO@R1L7dWro3YXOx z2q75okr)db&3a)TO59d2v>Fg3V<8Lv{ zy*wBj+q_XvUJm!Jsbxo27r@?YkJ;jk05A+LhtgfrbW$`0HIw$k_y!^ar%rmaCWAkz z5YFnJZ^zB^O7PI_I+CwyB{h|~Y{g){xxHJ_c%^eT{^gNK(-9c&6RoHYb0IFV3A@0#TR&6%~ z-u^hxxuA6a- z#Yd+KtlnwlC#icz#Y*%cpN&tff?Ry9V3yyJYI&7u9-2Wale zF1+kC(1_a$crE80q^BZepq!_}z*B*N;CcxI{q1O4&19%=IL$7Z8^fYMT4b^IFosFk zF{_QIFyiNbG%S4r8P1Dj=X^I)qcBQau-=3lsjP?p#^<0`^b*32esu7`Y+7uvhF;vx zHCSXH)>VkG~u zx!S^fvT-oyGBOV>{RK{S(_*kymEl)?KS~;3=W~4n2kBdQGCe;kFim^=xU_AP$^Y;N z&dcpITdXVw5N0|t}A>CL1){LZKXDo`H|-EZ@4 zuT>mmRj!r%blt&F`*=FV`vs$m-F6zM6NBrD_2}faGPcVjfjKO3f}r4Qm{4OvzsJrb zOHz?SwXT5Uv^j7yBD?Y6UD@|h2VYoR=JzUaw-O!32<*fv> z=ErPIz*Lyt@`V5QJdn=%pW>R<7crUO4NR~V^Bq@rP{?he1ol1vZnPX>t6PM#Z@oM; zrTV~{x6-h6(I9xx9S)0wcca4Ysql)Hk-6_kuo%cAzYC*rl9eQPc&P>TK0ZV9qhiR@ zeF*==_fBKDlr{A#)$`k4n}Jn}IQyzR4k|`^vP3aidevOSt2{}ehB|e6HmaFV6#59i zwvWRgjcD>IlZN`DRz6S~$XH|%IYCPC7uOOUrJ%+40MYy-* z9PKkO#Bm!xGtq}FBz0Z5qm*o-u9J({$Stjyv@V&=GizoadqRok3WKIYwfvRe$f-=Z z$}Qac5r4PxcvHwrwSFsSK5J8H*NYX9(ys;zd2_f`#dX{bJ4fC{@baxm6Z;=;Zyrr$ z__qBk^E?*OAVY>I3E{rZy_E)2q0*p86H(Hj(m-aBd5R)JCR`>h&WQcaQzRSXp*iN7*~#MbCw_`eHHtlx=}i z`c|Xsz;XQNs(}ULC!=Wl0(N2z4=wM+;L}m#$&0k@_*CDHp8NKb?mDCmZ`X62Wv9ou zY4=t%Nq$c?Wt3rEk0y;YDa55tTQNc-y6IdZLBo@?FsZAXnP)!4{tf)Z#9fc4((*Al zddma$#*tc5L^rV2Fb-^)bd-E{h1Og8F%SNpq}!h?VGRG2GtH`5q;!Q1tY37QdF!Jm+A-j|F(iPX=#aal}b&0#f4@#~MeLQkyGj=;9=aI!iOa@%CjV zE5Z)zEe^ttGhw9tH$%?-tD+{^&8&8l3Mq;IXsh7&j?#)ua=4Iz!`maNuYoqIJH4a9 zCK51YS4uB`m``7}jtA=Sjrtm0#eV%OROA+)`0(4v!?O?QgacQ}(iukym26^5KXQ7T zmv`Cyr)*)O_*|$q`^khR{U%?c45;zFSiIRTi4w`P$b7j1GRSF>z^Iyd8K&bxB1HMT zKFZrF#4R@I=qaqBCjv)Es%SMXd$gcurr62nuU?~wa9vhcvh zvA9*`C;iiNg#KyMv)!6J0e3EGC22(}aO@W)wW51r@9|*bylOGnwilAAp1){Ia1rh0 zbOkHg*MN#x8wol;6V2tM>EQ1*ct7|L8QI^(?)v#|nnsS3CY#)X7N!C=*{G5E-#lXXbd!W1{nOww|#P`(-a{ty9ayxY2lvP6JZR#hwr!(j-1rwaRJrT|d zvtVEU7t(Tr^DuFYbGyI}*r^=@Z^Ea8*`9FlZuNr)Hfzzx>L}iGm6R?N>!#3jQh#%!E9=w8|i#Ra}}*N3(6VxKgG{2pMRC{F+# zPi^E18Dxi}Gx`1IG^74V3rx$>X!_-4AaC}A6wv zBft`o3mB7}j=>w_sP?3@_+jx{Jh)^E7>AuA@)6FERa^{4*Ep-n=ABf2Zwk5fPYv;V z0Divk9L1WszKvWbj^T~Lk6XiWoqjLcWXIq+g9mtVod@bi$8bJQOIXOUb+`Ksay`2x zsBKh>BYfKw`op7SeSzLW^ABOYW@R~*yPBHBgyIi2mSHs27Rp6%AtPlB4nUk8do`3VWIw0VwE_FV{mI?XzN&x7v4j^ zPF#lvJ<5r+TrjF_Y9~S58nNnc3Ras%kjCg<*8iIm?2e143!00`y_+UbD|kS9HGN3y zU<8_Ov><8&Cs2N5G+b7n4e1)~bmF%-qOTRlhCF-E@z{ZWx}3_5;V^D)8^VLtZCFpF zg|n+fuqlE8(ya;OubpLY=O2JGVmr9L{xlMosler0CUZTPS@45nXqFm2U^ncH1g)Ek z;Lv3$`XiapeXNMI0*5z)jYZ~Mc;`J2HtL`a>(E2-aSg!v}iI>=~J zHy0}iTBHlRKh%@QpIeCApXGubo+pTHWie=SUcLu`8pMqMg4y{(k91|((E!<(G}9^* zJ>-|*k|G9`d<0~_ToIOX89=Kgu3&XgCKf*9boaw;c)n*4#e@R<^5PO+d}xje@6zzj z7I&z<>5SVhg_2;CViNUph@lq};Pf6tx_Z@Ta&8^RM>~9<931zQT1&f=fRgE$A*;dV z^yy>JY;kfp>L{5sqC|Rq-cgC6`M7&Gr(ID_z_0>0viGeCW~hdv!N+(`Thzjus@HySa}ze?Xbbsk*RRz%tmOP^PE`Sa-_ENg3&*4D*ju_P}x26;F%lenTVK=J*^s8 zw|^fTNfd{f`BCtBej@qD)ex0)#)Cth485i?hBnD$+xAtQW|Qy#qaDGiRJJ_~t9tI! zBQvGQp6lP~IEMfX_)y9Wm1MFT*SsdBclfYitS5WY=_z5k%&mJ#W-#0$i(j|zBU@Ie z(3?l5!Ie%&@cWofrn#iTZ>M5n{`@a<&GZrMzJ80XRF$LWF^{Z!s|{VA(IkFlH=`Py zO&+xK$d^bf=uc3Bk=^#J_2iRax>pMSefv$nO_HJU5gX9Zsg`42Fs%EfJTisp7u1Ve zl1tgj5H%(W|jy28O^<6Man#+dcbQp3Ffcp|I8CW?9+H`@4HOX4xNWJ&h4afaUu;|9zzZ85&b8vmp%mQnxY_o$oE#a+oIt+x zYvKDZq8zL26l)%El~{6TiRj-Ytfff?)r;Rk=Jl%M^Jpck`YlOcu!clTERLQ}JqcPP z9i%TY0G{Qm&~IYK)M(}>roh_E)@}I-@VaoEjN5$yOkMs_tFmP3vS!HEwaAs+nVtfl zM=D^Lvr^g5DPRJ_E#TV3a+cY-0sfpn4r#spbo!ZX@G40JVw3g}sjv-HIx!4ltqwzq z=RLCVTq*I%Y(siJ7SrSUP-F5vD){pS?WV89rvY`?5hzOI_9UYt$KibYH4nZ{NTtys zrM6#QB-4xo=c&k|mEgu@MsKqhB{HAPsfcAh#D0B8ibw1jna>&I?%HY^EL=sBt#8oh zAqCXs)l@X!9Es0YDq(=cb2`=EfbqOqOA8#sP;u1_y0jyg7&%PFzct&b&kh%GTXKnB z3dp9c(^c}$awT=VnM;2s`-9lE=a{iI0hKd9;OP2Nd?_`E{f}0m^wS9RNy^2n&5oGz zWI5I{gCwa+5_>XbVcZL4NZVLU0w(Cdt>0gWy~ktQlbNP)Y|stfW_qBxlO~Q_l7wbw z8+;t)Otx=)#CBR+p!0`?X!kD#-M$F1n`WSz;bXMAsD~Y4F`TyD4|68x;_Q8iWPFhp zO1ySt>G3@FZOUUhEnkJ4y0HUpCyc@lr3&W!Msc39;cvLJL4@os?*M(H{qVZF!*-p6 z5p15y@g`*o1n0J|A%{+Sz}gNi*giv@(Rh2G?A&;U$d1oOBh6EE%NbQ%Ew%|tZz%9$ zzZ<~u*vSxmhcJcCUrFQ4S>%cA98SMuOI*BGLM2zrF=}n+?xzXlVP_ur6lX$dn=AaA z;$b5{!59;x^myNPjpAt+){^@kAK-*$Fif2`6C@W@a{XQ-lnYOQ^|oqMPY~7Zio8=bH^6^QIb8ebX8TmQ2QLkeL+3RysJ17C>O9y^=ND|E1zg=@ zBgbV~+;E;qGwxK`u?92~XF!KsS(9sOIH5V5-u>ul7|q>FA02Cji<2&*V|*5lVoYFp zwF5g;dkZ&=?jf7rh@( zT26296|_xKpi!%x%gBAnacYn#NR|M&u?iveJPiU`&BtUby_5;4T^?&r!?V9yd#_p>Vm&ZzQNbj#oQjf0+yQU;JnwX z@yF=77|HE{Nz?7wdp>%o(54MC*~+v$Z3~u{u7Cz*Sy-uYoQapdPWrw{W55+RP<@mP z9dGTJj`7lvZE^?#YrjF}_*T%Mh3v{R!5}tMgy#}IjNWPIsI;LDyz9ROrz%`v#kD-R zx5kg@*moRsXIaDD&PaH6w}mV?umhw8BVeN-h8sOIF??Sk8Cwy6XI|~3mCfs6ZlQoE zNvGg~8aXU69gja&lw!}>WuU2)MfAD8d)%6DXmVDG?m8eYym$08t1vqgZ0}`5=4&5t zeBVMX2E}pJqY02%lnxfBBf;myLBcY+U~u*nUAARDDCCZ?(q})?!yl{h>+l#V_p%JP zxk$l{YwxJR9uM^Up-%F->?+x-oL0Ak%Ls~@ibiw27!m)~Fj4V5NSSxQCZ7Z_jEe>3 z^^f4xUoGCH#3{VHDXB2M$%D%%K@=Ix$L&dJ%lLuSBEVD zjpWMuCm=X^2JTcx2;PZ~gq4$w2+=*yN<1*fKksE=#m*SK`gsG+oKuXuyH8?jIiFk0rEs>5 zB=J1_h4v~}k?xq2#P*&CklU(of8uH|Zjy$|j(bEsBA+doZi6;i^`tXmGAR0bV(U}| z6nWZB+csz-Utt^$zbzuM;a%{^yAV#PB#~I@yYRA4mKQzH5AJjnQGKUOn#XSg`$#YF zd;6Gp*(4FO1M>Ls*<^UQ#}~dop{U>!fzNul+|A|&I#=x@)sc#){dJtqX?7^ehZtgB zmLcISdPnD9+ejp)&Y&k-A7P!{MQVBaElJdfXUcz-5hc#MP+hWt%OKv4L2J0PoU|f% zxX(h>22tJw#IU^s!Mr8m9!$ z$L_%MIIvFz+lmh0%|b;W27!36?=Su}9!)=s?4`Q@CZXB3Qc`y)A3OhvpjS&J`A{XG zJ4FrYYrmBS%CwYbttpvE3GoWgR3`$p>D}Eypb4*2h}x@8HmJH z7hCC-&06@)Ck6`-^`iSmCAxm~dKhZ7V~p#=Av|h7`Ow0#;uYt?tyU38TA)G8RXa#n z>PE6edmL7X|DZ|}1QS`wtGGc$YlzwZy2F*b*%2O2Bur3b=7}G$vm@i94Q)QHQKT^0{sclqqbX zpY{o1=I2ayvpA>!TX2j}k0Q7=mdk6pSw!-)6Ty?yp7)N{r|bUuqh3i6x^>qxCLVF{ zZ{2=sXv5{=R!%@`ozvhZs}4oSYFYI{S-7KA2Y1J;0~w7$I(&X2Styf)YA5^1-<>{~ zJ1>tU42sfcEv00N>{wKA$Yn+;*ujgua(eQO1eWY=fn1*OJNF2B zdgvN;614^4!f5={EJs@RvgGwO1$?h+fthByFo)v_t>82eyT5r;?amRV)jyUlxVpu* zq$ZrEzbRs+pQ^*I%Nv*?g#vP5uOSYL{~_MpkJuAic%(mW3Og@62=8R_fFD{!Oz<6L z!j146$E+XheU9FpMl|t9GObq_LvQZNz_TfF9BT;a#uw={e`z*ZQ@0GY_D#XLFXX_! z#v1nbx6*k-(Nwx7n2wl!rM64|F^|Jdq1p8U_2=p$CF@F{GUT=(O?4e!ZQM(=ZR_b6 zPhB!PBOHA*)9ISti-PI-`P5(`0b z0LR=qnoSf7ByqyOi6A#Gi3Z7kg{zPBK+$#!+`e27$z3PlM7SsXZkdmhU&=v!WFHY2 zM8KJ0ML4nZ6z3he2SZvbL5|-@J!&dwy88ljIWB`0w{oF^FAaw~_25fy53yhIg2+`p zARE0V^Rm-!fP}_ZE^8%)H8iLqlA%NF<0F$Gq3{l~@S`EokeG{$e@>(EA(zODj?p}o z{%}}(@)&sDlHgssF3o%ORhxG*LXB6R^btPzD)F*flS$&-O(f~4qdz}Wb_mv zDosBJ_YW-~_15?3DA#n`t9r9>{>mGym8U0>coIyqL>sGC?gQ(vB(f|t1r{&* z3SS=;(nIQN;OBaI-sqqaYJJ}intCo~Db?6V!yH=4I* zO&0|1Ujy?ygGuy2B*`hPgZcV{5IxN0NlVGV?=7oAv?mN^^~|A08I7PasvDNSSOd;B zQ*dEUJ5lgzg^zK?=pr))!B2!Vx-NBplv3tb(t} zYUr~k9mPa~(AT6B(@mye(&DSAYNv{Sj~=0Ka<@^Z8D-e4PzEF7%VC=KV`yXA0b3t( zIg&AuJ>do@&r#%^%W4IwcOCSAo;4eJu^c})DL~(473|zBEfjTaBliPlkxc)0)Hq)g zpK{li=hwQa_A*0wX&Obp#Xd$U{V06aG7TCG$8)uTH&FcU0kq$_4>dtNPk?RR+J(EuRpR6~`8fH`O;mKT#2q>bIH1r? z3c9t>Ol|{}=k}lU%gfQ;_6TVn$HNPj+fngnn{8;R5~v=Z2(M24A_vpXfk*8sSbO4( zZF86o)_*?)n;Umw``$Oyd1Dy9So4S;TF9;cX5QSMwE&)Q+@R1{ZPqgJE8!p;;J7!M z>8j8pl6{7d;`{11Th3A{v&K%z}qU#CU%zNAu)@X2XIdJ3-A=k9S^u4DYu5 zaag2j!c$)EOe2pCTOY$qq~qmi98-6h_F70n>Bb8BbWtDUqJD+^`ml#a)rZ2NODmza zmg8I=kB6GC@ivpjhM;a>A?-Mz2EQc&=*c8Us&XiTy>xLaz0@`a#%K!R_;U{uXC@$H zXXn7u3tVotgdqg)?IcRBhVc03L!u-ZMQ1Kh2cFMKtn`e+eZSRhxA__2kq58ojI86t zsCW?=Sg4XiZ%i?0Uol-Wp7W`kR^T;D6cY#eMs|<;ed-;1iuR@bCZ)n*a!3DG*=&P?7*dlQy}rT2%Bo7LqwqN2?xj^*ll zb)&(d@)2D=MnF3&xZK7nak8{qf*ui^VlLdXVv{C1;{99WaGy^usnjn*P4lZb$8R3~ zJrjZ|cf;{#_ALBr;!Bc7PQr$6J-TL_1;-JOB_gGb%<(A(sGp{c8##^EJE1bix=;Wq zX$5?9<~TkbUqYkeH?zyt9$*od=hLyV808dlAw0AW1UBZ3*y1$$mg6lf>P;u^wtn^Dl3gv6ieVR08R9NHE zjPvxO&RV$cY{2E`eJ7ucqv#H^`P9kG8g>jw2~XWYYE$@z>5CCZ{q0lex$50$^y&ys zxRZ!&o=4~{sjXhN>bpT_POzaIgzI&@IEV4f0q)ilh|)*f+dTOK$C_CRoN{Db1F0$McrS5pi65Q{Q)C(Qg0re-M<~LjOFTHgB7&b zx|f)GoTVed73^J!?LdxJ(G4#j5mv(%Ke{a^#c6hsJjsM@7*fDfAycWeY#Wxfeqq&C zy(Ag(KIkAbh;Nl@X^XBh9JU>W!}nK`ug-pCb0eouXjzC;KIEX~TZ(gcj25m@IDiA6 zV{!e67)~fDgBb&RXs`VYoYHAbWmJ#hWusiI%udHy$4=nfqs{ni(r0==c^cLkHRJcY zfuO!D1{Td)#Hg>&f`-}WNV?7x*g5Mu(LEalmq+V^rfoXDaE-++^Cg7#IZgCr#2^m+ zx_|-Ak*Hk7(07gpur!(vC;d`L><0%pw{$)##Rk#oA_35GBA5C^_b~IuC&7@t7so1h z$FkWn_<5HP>S-0DPxCyg+gXJL9{1>zcr#{^;TvMe)q%p31M!sW2~bjeN#Er>rX8jd z!0#Rf@6(Lw)S$zRf75uf@M9lziB)j?$04xkQQ>Xl?o#d3OX#7t0!UEJ1h4TIVB7mR z@T}BFJ;{5-Y-2wxeyW5dWHGhwQ-$hAM|Av@iLUc}S$~;-Y~Wl&I(FM?G~cqF$fT&j zinbPJjqe9G)u@*!pJ}6cWB!o*H=AK0=TUlJWDCj)tKs&`qqgjiK*-s4jVw9K!#r&R z{QbZMt=65T_l#8Vg2HpM@u@!D%)F#0SCo?5(HF?HO`)I>LR`&BaB|8cLADgqS2@Af(XF&$+bQ~HpcuNfACZ*ln;`nV7P(RONbvmiHIU89 zhK2V&(xwCpD*O?S2RSyG#r`UiG%Jx_gd*_Pl0}o3sW9G^lQVu8gFb2+$Y+m}{L#0e z^U)RT?mtN`29!eFS!;49KoXU_f3y8n3gqyE>oh@Z29fqiq6bc!;lPT+@UXE4`_x?V z)0-%GcJ3?Lcz%F+D$@p*s z6+~b_`vjc&K7r10-2kg%XF*m&AZFEX;Iz8Q@bBzBCiqGZv%c2^V>;(!7Gq5<+5>HU z1(NuB&RjSb7E7+&Tun?z53m{&rm=3$l2U(_%@~nX5t08qZqA}&A|g^!+`Iqw8Y9A) zsCKO1=lOpb z|IC>)tj(;={#WBK;2-8a<~3v1Oi|tyj{TL_o6pZU^ z6s~9-!k>2K!mu3%=y57V7`W&PjH#F;%-Isj)7rCMXmGX;SA0H!`SN1C%E3CEQII11 z&-nHXD~mL06ZPwsNm`p$ErYBt1W8%YR9^b>K_)<3A~ zq{wSt>@Q3$P{wZ0wOFw%0+fHdk+E@4@qr5w_?ZNO*0W?hGu{ckWNs3juGIe;-;5=) z<>B1e{`36b#`oWUzca0^XUwp&{$I_X>WpCi%w1u8wcp`yjZNaeFW$_rejLXC&-}i8 za`D>#aQv3m<`(~}@gFDi_{`=oKI_Dp1J7J(maeW5#yMKr?JOGNzg5iSPd8Pw%V>Dg z9GtM8UvO`T-x52{?s{Ave^baUzQ?G%=3-02_st2kTbohGA8;z;ZQfVaT=095oy&e6 zzhG+{ulZyhpFhj7xvQG7Q<$R4@A;)^S1H=koD({_rS0~}e~rKN@7m=5(fDmFEoWN% z@5bN3OC`n9ZLIF5`S9`Ebe!uej>h(pXu;`!!}&*8nJ-S%wc|Pce#{XTB3PMc+NnjD;Ej-Sp}(ALL`phkZm`S#-%k(plrA6$N$X#mcsb|+4^N;Wo|jc{C_q7;|~Y%)r&&;kJWC5n zpU)iRzxQ0kKcIesFZXCQU%TQYe?S<{cT!uwNV6ule&Y zc9OK?{=5Hq{$KvT7BgndH2+_&zoHwIcp?8%V70}rDy?!T?dyTz z3kgI@FOOqy#lWwJLFC$N531(vfm61u!B1vu$wdXu)3bO7)}_UQPr*^3ueQU!?Qu|Y zx?2iK6VbZG3jR00}sOi|0hJ^=V&rpVuUIz-G+ju zMC5y~2FYX>ejBRpq9j5?0yen|Sog`bbo;K8 z1oU=+e|Q)59{-N)a~0vfGaBCd9|5;9qp;B~7pz*7pkbB*%R3iK}Dw z)f^_TI_?nb`Z#jj;SXVk8;P!?2^o}mz(^-Fk=5;QNwQ@+=Gw=R`Xn1z=pKXalN*^8 zJ2dc`qmXRrl7++&pC<27>%m&^fmj~COx%-PAaUkfm}fW_?i59XKATHSSWTGxI1N_S ztcSk(3c}>QB-d7CV%y`dYxZAT`~T%2ECaZ zMVCD-q8_{769>OCR%*E>Dxn3`e>sRs%fqmyu9j?GF&#tiUZCFdR}tn=IIxCQRMe%C zZZ1zDnMZl#YTp28|Eq$Tw--Y9l5zC&kHet&gvT85t0RhQbr_N36Y1OJVsb}89T!j1 zfyS%FnC`$;=}y)guhrzx=QFRh8~ z*Hu(dGX@{YMcUT>HKq4MR>O|T6Je|E8d#xbgN}CgxNrXsjQl>9>fK!1P-?gcIWQWI zu6;^39bF|DwynmZsGVF7C)GyfM-D~|-$l7~EljskKB|0M(6p@lA-uYC4=ygYfnmRT zx~q(165Y#!j`IT2_BVlaoz@_ud+J!>j#%o<4{nzQ3#4%J9-hboc{3-vKtc{lBgJ&(7R9Aqn#f$N1?gG$y7zCXk zSHUx>br9Xx1QNFm!G3%U{481wMj8na%JF_SZi_-Y-vaE}+>7DYIe+=KU{K^6U@3!C zPS7KeiPV9*GB2}8`M(jFI65ZV;^K z3`=sk9y-cmPFou6mWUxmPHSOk`!2|GZG?C8T5TJc(}EfMJ4xG638_fgLzB+cfw%N! zSnZbrhSE<-*DiagJy%R)qdG`@xj6KG-T}R}&Gbg85gj#Cn(Udt5606u6p-XwAiZJ#^L!PgE1>X+JfY?DX-mKoqJk2>pQ2C8O$lh;c z@2S7^qFo3sadU%nRv$PX?Ox<1US(VNieN_BY`FVtIb66k4Vdoj@bQN-%w9MbOzy3P zTQiQchwh}18Qa{Uz+fe$y?g;Yy@gE9ZVK}3QCJ>oj2CZlUEjRZU3BDPTf4e{q3(6dsIl!oseNa5YAUB&9{e@;zHP4Y@ZQyc`Tq-cN+T zzXI^WzGo1={sG{WUxF@XD=fWt4-USg9Dl}#`b_qKyM2>!QRoZ|nlp#Xps!_@ZB@aT zL+c^KE1t$E3ZOcthKzf@oBE#?lE6C_C~qeUtA-mXZ}|=w3=xNMCrnXy^8>o@`&3TP zl8Hm}H(}()6FA{v37(D`!l>z79zDl^YZ>E&U!E(V+p^8jGH`9z6*5Zh=D>XToy2^UkCZ+0!9G zb&+uw`vFZafym`vV&$y`R^PcSE0_Y>(~gq9#lcWJ%Lw#eYk*rx5OZv30v=l@BCM0t z!J8+a;mr*TIfkAH&gq_uh8up;@vH|?v8g2|o}XrqAF3m-1&VAlr@yqjaF9L1^+FmV z!oX;G6vv#6VPAjF!N$@=9J;y_dKT!RwL&3X_PZJ^$~>8xW(&H`i)TAqsE^GDrr6v& zQby+<)dj6n#pJQ0H^wWiWEIm@Fxjgfm?BR55uE^^Tt#?M!&9OAfhbQWe29jPDgcF- z61*z!8Z@iy=ArB+MHV24%<+B~fW+sg?coNhu6(RZX^zMp{w14Ngp13yb}fp{JCq ziRg>*{``*Te&f~fP(2u<4R+zI4X*h6iYyxK+KO9hyKq!o4cOi?#FhRxZONlP>Ud=< zlw13vD3_PAMJf?4;1oJeM?im=*ptPL(rjJ^R}WENPE8lw$Az2E<0OxHxb9yq#?1@B zps*|ynP7ChLW@2KNOe^g#kYl+U!0m+;IE`8dPrV*M zc4#@VXRB$q&=2^VBr&E%3H*5Ba4&QejQti(!aD!ZPxFLq!)!U~%dt%ky-5JYW#`Ep z;~1(U)d(-{>O-U9Ft{eKWt=45!>EiuwtQ7-o9fmZaPHMAxR7uc02u-hfoZTAigsqu1L53Rqe&mdUWH>#QW^>t*3dOvk8^g% zOR{sqY~1GWP0m!Xq*it!NbI=J?w1m=iS{tXz?^V6c-x7!8@mv{#5@L@!Y|;twFI7j z@B{-(dE{7#@GGMU)yLG5+gpN|kvvWE>Bld6C(xS;gXJh+bPO$&7lQx|c`9n4g09=< zLU^+uo~@R`D^;t(VrMyx>b9e6eW#!s$MTeNc!YU(Pm>42D|m9>I24ZM=g`BH=i4qpKQS7CF@$X7SC&e^u8_uI^*PXTP zuOEfecdVzrIi}?K{y-8kxeQ-Vv}SEihk}!KHYBZ7&`0r&} zc$8aDCfK9&;)gU>=Mwpd>+w#18D^|n3g7oVB-Kwv@JC`LG2V2Cx>UyD?ICd#UvZw% z(wq)yE=Q?(RTBGddW-)Dv?gAqVMLf7#87%{|h~SYa?meT7KTn2W^7VyW-q~W@re8t)wWAkSy0!{hfmY8i0gBI+?%qLTBTE>WuJs;$I4M+9LEBGvkB+j zScjf>Gs*pDGFYV|i`pZTVazl!F!=Y0{FubmykFiI#IM>9p;ehwd8Ck}c`m1GmSxbf zf36VGi7TNi#2yA~#FMv~Pqeu5&;U zX=99ciA3t3hzTyYNm4)!O?W3tSN=N3oRu6;hfPb#idSLW{u+j_6}WriNj)ZfYCgSK z^nooC)qyp_0;)At339u;=vm8YO+E3kXvOqXYvE-Ar&i;{p?yS~3~y*J`luAlFM(J_O9+bXZ+~6%KPA zDw=Q*R`2j23Nj;5k|V>*SKkBGA2!oV8c`T>=`GpoYX>Sni)J$f4Sz?d757sipwUcDrmFHJFf^*S1oVhn$|%6R7jB}yxU|j zq{7mC>}N(q{1wqzqfEYjIYK72*Fa)nCCJxn!3NC=lAqkklqf!7%{HaO&f|lmTW%bc zX%DB@W=D~g>zmLhZZtD5@;4Kp)y;Z$4U)cfqR`HV_fY!BZl2c`zn850bCe_n_rdg3guzEop};8?j{LHK(awD&Hc6AnDaqjFiqW`naSi>w zrI?)Z*h5xbxW!~0>8B?W=0n!~S7gHKi%tGAW=zn821=(JGutn>kotiuWU6+P&G)Ra zSo1s?UYW^4y#8m>x%o2uUG);$4J5(i@inTo>?B#~Fa~Wt#^BKDM2u4V%03inp@$n4 zVd>(B2=8P_{ z(&_02M_8fEt<4IPK;1zUHib?AhdEZ@bDGmx)=HC0-@M@M^>hf06vCw@H~P*goGLHa z2qAWF$iFZD7&U)OFy*vDOGg0tI|cAuVjVe99f5k+xcb8eY237}8Ha0}am;k2QEL7;*1Url zXm>V6KlerNqMLN#v<=XEH2_WydPC>iwUBYt0j3sCgUEA9#6-NFO3Ij^>dXgByM#ST z_;irU!8Nq*cNL-k4DjhjCr}Bx%%0oL$1TB&aO{)&Y{SY3^#0(+cu9n_D;hI!;R{t< zS8*KG&n4O}*)jnaIER7f$4HppT19aviLjey&^wyIi#EJWhZLV~E;t93wx053TnjAa-LPk*Tr+&F?@xIc8T*s3ll= zAEPBx66oLWkJ$aQIc@#8M8rcn4?#K6_w(DLhAgsP;Zix+F_&=C+8CIcoBF+IuXknr zSKR3T=nsbKf5ymUF0XsW9!FSPn2)`x;E>qf>U4va-eL6|=-8gkPmLV0^PZnY%d~C)_)1 zqq511(_Nj$aP~3g9&W@@tC~?udNxxCk#y_kn;cg(08H{{z-zHzFnRY@@G8~f6+Rt? z)Rp^yyS0#wkEKjc^o4AhajqA1?X*1LjRc;;fhE)Xtl>7lWu@F zpAIqF1|>K(I~DJ^J*2a&n^ACUJ?M)S!q$Hhyl;27OvKt@xHm2tt~3;Y`&<@Oy=}-G zPbF}Y3J0I~66SJ7INNY~Ixgt3pkj{=;ps&~GE>7Kxw$**XkZ!`MAd8*y*iQ_6(QLj(8se^T|?ZfkHvF_Po zTm?ND-6AlSbQ#=G?%^GOh#L2>hmr9ua<`@oSP2^28e+02Y zH#lv}<@A(`@Ge+=fs{{L(6(lfYK`;3UzSp=Ye!?_fxmz08Jp)c=TQ{CmI=psrLaU_;TJdhZX~vGJP~p&2@yH zUbzeG!likYH=J3oYZGa|MmV}XDqvJ@EU(v(d4~mDSf^t0$+*Vz|S#~ zV9fc;(JYaC`kTmh&X2?w7P%Ncb3NTyVuTJ8Bhm4891UnT78v)BM}1dwl31hzb~$gE z7yM50_?H-DwR8DzcE@qv)1#bTG6lcQbigl{%9sTQ7YQ5#8ffj-b0p}|GMnpDTIkXh z1JpKQHv8ah7G1re7A42=$mS6pbPnOp*&BvwMDbD1HvOAV7}lW{{rbo|~$*JiB3vtKS?;KX#i-E9E%jWH-!@r>M3@de(m41BRX z4*z8t!-R@7>Tqu?KI@V~t52o$f{!!u8k3#UA)e2!VY#a-i)ebheSki z@BJjI{G=X#^rqm|UH$YG$Exf-Zw)+!MbJ8XHhsk1|Es3%#i#jGiMr(r+sHCA6t!QE zV}gjyMU^Pl;Jq?j^W6idMReiVgnpE?`a%uY`mpWRFL1UvORszP(4kjvZM;0({|`my z9na<4#c^BqOh%GIMOH?*ucN4lhO((-lrmb<(2%`n$xNseks0y5uR{?3ptS%dn7kpwL1lPBX+G8o9>L`biP&OV z&r{1)#=W~sQKTe?*`joUe9_tuBEK7m-A*Cudy4az9pgi$(t@{V?tHrIOFxsy{r;}l zC_`Jic4JFZ0OacAK+SxA^4{$*J14Umd^X+!@9}CVJ?@0dnuW1-?|jUjZH9Y!*(j2o zi<_sJl1=KAO4r(v-@fTV*$HKwU16y6|5k{WdZMZ#wC-=Qb6?ZGmR8f8Rz3|Jp|5Hu%#<*9&Z* zsxvJgai*JAWZ;8=r_k9Z2r==5cvhxBZQvtFnz|Q0y|#kEcM4pe^E60iXOiMZUrUM6 zP1tsOKAgO?kBWqsQX9!<@TyY;jl-UhA~6k^`dFjAKjQc+EFIkim5L#W(^nAINR8Lj*Q!*49%WU8?B!P#x#SgB4n-P!;pujfIPs4k#Q zB3RG+0XLiCiMhB0(W|at>^u8mG;l8LljFE6yfcs+l0{29CR44Qt~9T|mc9|Wk12MO z==&LuG2KcD*XYMnx5a(*{f>Be{OuyizY$G8h!98}?BRi6TUdP}IV6aM5FxbD-Psrijo(8_p5HM2xeF}US0f?KPz-)?wHvbjOhcq&l0buLD|nGb8EUa{4#2QcYj5-yU+L;mHGxFOUMZzhGo%5(lCPUi{n znZ%N!lVeojtu>b=u7Y+c22{VjaP4>#{!FZoKMtx$aMS*)a*7C&R(m(>4rpV8*mv@q7bMG_9`u@;a ztUTG!x*HT^zf<D+LaJ} z(}T$NS%W+`KLpA*GFgWU7<%mjTcdJ@-al-NA39GFg%@)mXz?Ijw`Mh@3hYApo;+MO z=t|#b8quF$=3q-v7VHTQWNw9e5zApZ-ZL5Ep1h%aayl4k zw2dCO&%iGni{!@kLs-!%3;|Wef;pw1`1fsb#%va=^s=pOB{|}E+^{^j*)rFUO0{8 z)hB8`q8F;_@b1DMRz5|UR^C2|cIJK<;NwVEcPr46&SC#r0aW)g^8EM6ewl0JNvjFr z_s_>dJt=t2@hE+&jIhbRo(vzoLVr7-C$BwKh{6^wgCF{xM)k|XVy`HYnO#Uu%;&>! zIeRW=GET2|o}k4tBDD5T5G>?ocGrACa#t~iNQ^k5b>c%(NGC%S=Un_7S3+5n4kB;P zF=^V2(5Fa-yc@N~ySt*H?42_=U&Jsb7Tmiavy?7r&nEYLgV@Z+j;Ptb6orSslfPj) zI94$kwm(atsd0yC{_CIIX{rJn6!Ng&Y7IVlu^w+NzfUWJIe*3uHz?UM89n4VM*Q#F zw3ksJA?Ew>>yLQY#tu+E^Deq?^+6&W9ghzl8e#8=wZu)(fQ(;kLYF{Kob#g+C;iqX zs)lu7J5LkE7g|sUj}m4!PXQv?S5$jNzh%b}T}aeihvrFvaQ4|$s>t0udDu`Er6-0CTt%IhCUlHY!Yr{BaM?wPHhHu$=N>duv$QBIjZwj^ z+y8NHrwY6wFOUDin`wCOReCw>jAcT*9I#7%(8$s`R$9ZxMB8K~3UZw2SdHW0RJ#~1 zJ8IFne+*&eFd?hVCU^#CyV+-Rk8$3LEX-3`%`8q=gup}bq;&5o5^9==+q?vMhuyWY z_(viU8#qJ+x0JzTR-6h=IfmMdBAAW((9jRVRC4Yks{gnf!(!(^#ikxBMvl_SMe}h( zggj0WUV@$PY-pe{=gJ$-#L?FR7@)X}K2OrX&)F3$nNvsxelDVU(~H^6*2R#;@q9=1 z*P`w@E3m(nj%u6NL2>pnm^RfJ74BakjPgY`xF?zwj-CmV2F-~6lr;lc(p>XMGY&Ms~hh`q+aqm=m@_QV1ygG`8aSQNgh!8&CSw{y;G@wY=0k=I{ z$do(0VBWihgO~UeSfCe0O_G8!XE>i(nmiT%DouuUREIu1cY;LuKB7a}T0l0bz>f#t zX`8D&@FIO#sj)tiv9FM^Jh>NK>yN_7>IJak^;VRB;R+Krb`W0DMTaj%u`(Wh)OfEd zu8z3Lh<~!ge;nt>^(-gqm9%ga($J~N$At-O^PG=lc% zY{_6RoW0$BOzL zxaUw2OIn`N?^hh@A$g8-@NWvrNbSS$2S@0LWgtz_k%tsr3FJ4=Cl{=Fthi7XtkEoi zm~=nLoqU3xDOyS-=fzS!rV6gbJ2Kj*%Hf7{CM~R&<~_9B1F2#0*ry^zETLyn^F#M4PXkJU^U^ z@>izfi^e9rkhO*Ru6F{I&j!P3-Jf*n?pbuadli%qx#4k+rB|pb2?Z7n_(8ahwtD{{ zb3StaUp~H|{i_~evv4vl%@Lq=H|Eow_a(@hf|)4$R+VgY7A6Y|!qB|Gnz#kbBk^ah zqW0@Ry!A8#J6fGU7Hc9L`OxC*PuH)A)@^*qZ%Vm*oO$eQ*LZlscfniu4S=09xBfa@?3&(;_J_BgKGnr0`9^}nfVSt|$Dv8lR z5{hbYH~ELAczXRKj-kVKDqqdO@3*}1?TjJD)Z`u&O#X!C6^n3my)gdqd5HVAuE(E? zns{rtjOtT$ci73!#Fsy-P$Djlta-T~|7FHu?B5z1@#YAxoS6ZBqVm-7&~K7y97m#S z0x)rW8#WpLwPGI_!`X%hByZ(ksz{5t8Lx)kyCi|_QzXd25@W`(tbsYue}_q~&9Q1b z)IyFAwUFyoaiov`81}6iU>)DrQ3;NbzxSUzNnF&yPBb<0)Oy#z^6Ra1bJsEy*mjxp z|LdU@LHt;SD<=GGMpXTKqWof;I#KO5?h=K7t-WGZL=v6ZxaLEUKbG9whx=v@}Y_$ zfSK_K@p9C|jUDRf@x>cdhrQWdIXl7fi91e>5rF5M-$JE`%LVgB$^Lu|R=2gAN{M@8 zvC3L{B#QI0x6FiPPV%@)&>3L!BN8G*n5F*m?2FO)B;D{ZO|G-RH?P(}c10s?^v|IB z;W}_=uPs@ya=J=a3G|eIi#jR3gp5duS6Ta&7VbfC7)m=);f}z zf; zR{TM;U~iTi?hwep_8dQ=H(wp+#hF4}h&=5$+D-hFkHPkzvq;FoT&nZVkX%sY{2_~{ z<8)>k*58{#Rs{@`?&9gFdRzjn3X55B=Z#ph?HO-({spr5mR*${p9@l;dvnO3rI+efp0rmP*INMThazf85(jX(o2R^THJ~ zjIj7}DFz70&y&b@ZWeD=VQu;1&>d`OxYop_b~@L-d_NXx-gkmek{_!{)2;b{zg938M{f(TMd#Dp_8Cp z+fAx9WXPuccjW8XI!LnCpcN(u;3Bsx`L?C zA^b%HbMG*hm+AQop{q-vbK`IF_Ea;wT(W}rwZ9;*LuFv0dMw?QmI8)+8di&zL_vS} zI>vThIk~Z|m|VCeX)RKHnzUJ+CZi$(*5jRG)}amVAlujv3(s+UgozWd;j99^5ipf! zWK+$$&T?Vi-YaKLY3t$>pUF7woCxL@yFp050`?VNqFe1a{;y6yNvqX^RpWW=At4uD zwXg_oOB7_aIi7U7?I{`&+Klbf4PmcfIZye%B}PiREebj?_MAIFyQeY3+-K!z z_Aat!C4;8^X`JFP1Q&1eL(!EPocl2pU8Ij-|129|^8T{BN)n-Ry)3+VsELoF^&xo2 zPA((uOPyOZK~;gDJnG4W;(IwL-D5*@@;8b%>=!ag z2|5_ndK|x0cye6SRrt!HA3qr+q8Z_GI&PYn*t39cQ%nD4MZmr! z9PCbpft!jMF?F2_8ASbjx!~g_h|VtOK|C`FbuwRKh3<6T=O5chWA$ka z*qcC#W(z>oHG44K|AR^K)upj9GnnM4B@p;;I^Ct{#7O+w30tLVAo0gL&Qn(k5xwqU z{^t(&hI-4`ewDCZXf(_EPvTM<9{G!C?d&ICgVJ%GUp2?qiNkP#!|40pRNP>jf>)f( zU{={9Hqw~F`L%C|Wm^ExXNCeJq+o?BypmAu#2=!Qm<{0^8x9yBkTzNgv%`*IMA08? z9BhL%zCX$KtPdz}dX7F;SPW|SV!-((OSgt4!*LmL5EjU!TXXwKihDim^46#8l1x$l z+Dp1vOA_8C>*1RpA!z69fXif*=#Bep>6Y}1cvH*+Z#87mJweS>XW$Xt(Qt>X-mZs+ z7jm$7n|PbU12g!o>IH#@3AEl#+`4aD3t7i)P)1XOM!Qs%i>m#L!GoQsCHU%^TPlU&0YyQy(_RR zM-f{F(@0IT3F@9bMhEpi5Y?m>Hs9g^HYy5||6Urvim(wjM(6;?6D`?a%^DAKp32gqPa8p`A|> zinMB(@9%{0f@&6Ye?Lx{a8cx2xQM)-^_#u!G9640DxvyOcW|$(L<^HPcJ0+h%$kV7 zWr=6N$vPXW<_OUPPcM_Q1b=$>w+bq)RK=zmF$}qtk1zRbAjH-M?cY}sy91kH>{vG4 zc^#N=_B9@KjPB{|c1SOG~%X3nP4N z+|WC^=)Mo&ZKUQ!NhIECI^7$*5e;XZBn5LWQ<-h)p!Ii{DA=n&Rhc)(b{`~PqW@C! zW9fJ|IvL|!CV~DHE1E6mLDmnu!26LXLW(TlK=WsEom3K`OarK=XE_(&A7cN?nQV_W z#UzE9FkWi~Qj46~Y^!VZo1`~L>pVe8@iJ!fwy%sC=Of-!9l`B!q9ByZZ7&W@f!zy7Rh_byLG>Sa;_eo1UT%Z)C(k%i|%daypBCi#|nfxn86KCdt(2_G&y`QpNe) z9jpYTf0G&WOUR=Oo8fhUH{5^6x!E^q;Gd<_P{rU2L6LbRTiO8lWv3v2eiYWS8Dx@e zEZOnFgbaN52YZ2ZoWdL;e6`c@y@nHQROb9;+#Brr@F2OVUP5KJr(vL86Z@=a6{=sI zj_27b+?FTLl-I4ssjm$2;+&b(?LivLyFQll39NVWuF&TVl?fWJQbBe7tUzDcrtp1TD4!hai-DP-WatA&* z(7<))3xT*QSTA<8A?>D7nwZpm8y}(54h_zMW3i zc?{6bNAZwf;0%qjk6Y7CEm*1Qjr8yKK{jfh8|5iWqwtlMmey_oXul>!&beB^-bL0Z zhOy|QUyb}e`gnYE2MX4wfHg$Gv18ICwDK#cysDwIT{ghVixuE$)CaC>T8YN28KkN3 z3guN^wes)SMa5>_AOjz-(U%R}&eci{9DG>PAY4utTc$(hsn4v~`mK=h+ZeQt`M_+) zIBL^<7LGh;p@q+uScxj)J&8>%br$kfWUXC)M?g?yX@m5$m_Z!)FyA{d|jG*w+CYr6ykAF3|yldNXj#b=G{T4;A z_q~>qpEVYc?_h@F!seKu{?@92S&xP14WV(36ui1!NDdvHj`D`7Q1wU$^g8>=r?4E@ z&>aUlk>y}EeFqd|7?Vj~*OO(O7s2afFKijj1@AG2M*KAc;{Zka^Q96j@>&8iBWJYBWSh|%C&W)|u$@L^LUJs;G;`=nS1O9qq4&~7bg5sHC8 zmxr+TTRv#t`a<}fo`H`wmxHNKg??3A=uF#9&fWjQ?BKi0_=s_wk)Ls>osv!^AIn46 zBYk-78b{1t#=*)B9aMZwp1rB_4s5>d17TAg(%HA5kB)L=`#|%9n*Wo+VO&o$Y&v+Ors|MfPVfLu;M%c6NE_`q4 zg^c<$#9;4C_%_c1n=dZHGYQ-tCDIt}=g(#>x2mDB?^^tdD{#fcQTC>UAmIypM!Pe@ z(Rr;b?Rh}3equJP|7eRlCtt#SQrzr)b%F@|n1YrvJE^h(=TFHvi{S^)al$fl!E zobm|oOkM`CVxFK}EkDFDOhVe;&o)I-LeAt1Q9t+$8E>TtK%tdf~f$#_Y24EV{WT zigS>>rZb*#9<0GyTpy5x-+sQQt`4!hNZmNNa(oHVFAgHXY9to6T|WLr#8B0+bf8?E=P)IR6(Qr zJnKzLCt%0PtHf-As4a$iX%?9C|o=x#w{-HxyZ!W!5RVQ8H@H43~=catiW*AS2W zklt6p+-sRf40b2M>Ni{Ai{>J_K=>B97@ruzaL>G#tUh0;X0^U7Xe-lDON*T zspOLQZ~E@CG}!Y^04{DO_YIT4V?YrMHif|a%SE8|Qw|uBQfQyGiT*5F3p*#8$-^Q` z9N^v&3cKowRr-CVUFQTE4ot-_;;E>Y%4JcW)_{ka5NY3Z7*}(C%bzd_7q=e6N3ZJX z?bI8@`r;gGo7hpJS=I;P+KHgKPaFbw|Dyd?x>T`ZI*~5tn1=!_tp5~M>`6zmw5Ja< zwGUHVauBl$dHDYIG5l_J40SAjkyEEm6A`1+aC&z?DL*F%a#238grD09DT@-@=iD4H znofF02FNp|SEN<ADF89Cb6uK|1BRi^XNZ$t!G|x^at*gFMa|1ylJS~oUi$&4MFI{wwkP-Yl zT7WaeOE7YDIm~%#i;GnrGD*)_GCXh&I;)q_2Kj1`|5nfCkdk4n@HZ7*XMz&SmS{XZ zmsmZ{BEk7-bVY|IE-1at>?rA_y3Qp~Qj|dF4c7pu{vcW-9EwkYbAas#$DJEDu-6|f zppi$XfOyI*{5CZKWh)m_&EoCsMf)Y>vdbJaAH7c3{?MmGcjW=cxtU^VD?3(r79>X% zz^?iTthJON&z%S9fK?mEf|hI>*%6DC@u~Qr@2jQe15Y@yKq z=xd|G8KNIqEeWZ#vJkpKD~le`-W1M>9W)(WUd&MYR zdl`DJRt3YsKG5ZFg37r|P^L`M`rV5(5Q`9nosTa;*{ zZ9SG2Y+#>1x5m+Dvj_)tAziO3=_~H`elc2t-E;i}`McvYE)MQu^P*P3w2Ni9YJCG{ zY5_<_?n1{VOO%|X2r&i*pkElk&fYE#2~G#7*Pthy3R9yqo9)S?;yxG|+5%Nw+Qc1F zVSI-zB%aL!Db-O@8q-N{N{K<2KR|@cBzD@9Y|yYOqhH5aLMLkAYnd+0d+0^aE9fF` z%4v3=RtEig;VfNxdKI2j>!t%ji$I~#5<@O;BF8+VAy+h+`4-#{mohXM@3zB?PwE*s zJdh19xtZ&D1NSC9>5sV)HqPJqp%-t~t`LaA)mjdetD zffT4|EP>9zD^|CS_^g*ST!U5a9pLn52=ZgUL9Y89IDcXbY*U;As`vN6PCZldLNJ@Y z+L!7j0Y(n~PiFPooa>=x4K^H^=`bZj5Sb6&ymxs5-=o4v-WMM5zZ@ov`UtXaHz3;NZCcBV*{gj?E zQ>6ndj^otIbkuN~MElODU<0oNx2)WOkENq1Nra}u0jOMJNcc)*p+e#zk^E*) zS9efi{OxN?zB)sr6oZL|hdLbi@r(V@d;pupPhv2HA#eOEG}XMKeb#p9|Lr;49BzVT zhUdsTI0MI|r(56s@(n851?bYlt@y(BKfL&f=pqNz50^pbij4txR3m&>Hfm}&I< zr7gtOtdf!ZDG%TOq~iGU<#?jgmufFCL_L)SFm?M%d}dHVlu}<3v%3LU75RzGU(w1w zndt{pCX6BZlrP0Q7UXM_E6vW!V=Zj_vBKgNy*jUec0EytGiq5>Kv^8WIUK^SuC4UW z(}kd>f03+AyiYXkl!?kM1#;3$2-6=d0FX|`ll#8Yibw^FD5%8yJ&Wm~eR8;2ZYkc* zu4mTW&ccvw!zA#}0ju>cVz9t678{Pn;<57g^xug>`kh{6=k9sNjE1o6^uFbIi(}AE zHte8N-=&gmJW~QXjusCeq z9)W+i?88_ANA8_E4TL#<&zQ74y|-JRp3F2OC;VrU9V)pbZO%RG}Q4smY|3mdW5grUqvg=R)qa6Yx^} zDJi@t&XW&c0-DmhL1d2z{7igIzvo=0x71J5GP5F%H-3@qn>B|>WhFtDW*s#j>7Y*s zqVZmS6MY`3h2y77P-iy&87Ono-`?r}x;H2o>f}Ksn89 z7Nau+lc`~^BCc;0<-;+%VRlruCejx@1B#OseUKz*%zk*Bns){F^R}AEk@t zL|bVmyU>RCMesW$i6)gAPzM(tQ7ha5Gt1_*s;r8_!=W=c{zU~%>uRE=`KoNRg)VH; zG`yhEL}`HIkjBiU|Dx5|lo#_+_U|k*kr0d)Cz5f-M{k;Ypp-rOBpoay zzA+tlfVz)fVE-+CL7z0n;|_U6P}EK$aZ^{27G)O{AYJStF?IF@y};WrPZd;xxV%Z~ z3htJWLE3i3!pp;=U@cKe%JaJEMC?{*@zVTw1cMXdd^e$Ck=`-+Q~I>Jt|eRhm_7*ghl2ZL}SM$h?m_@D!g{# z-?B(zGECqs@agAIaG%&8mPLTLI7aR;zqK{^4V!82Dob^5s@0a9}I=Nm}T+9yE z-kXAVW{6W>kOPYD;rKK|-D9>?1ivE6MGhV&q@78vGYIg_~#Q;ToCyZ0?rLxMnD=wRgCHF52%2cZ+qwj{CXa zd{_!c?TzrG=r?Lo7X&<2Pf!`LBTjX}RP)#+Huh91ZXXh+0S+^8)`T_9k7nrMZz{Ok z=>gs08w0sb8ZdZd1JkA-1rL4<(j-55Q#tGP zVMmB>feg-*3Fh21hU^c^6sEB)4zm8v`%xiFNNiZR#`S! z%5n@G`vjsZ@(FV4rb5riHh3~=7Dfvikv|`6c^dieiL+faN-8OV>(%YB=Ai|X8h)8E z#M$_6St-;lP^I3oIw0}pKF|Ac1wA+Vjt;BOgEqA=NHR^QU)7(ogKc#r=J7_De!&aB zmd4>9$vGle9jM_2!Q@#f5bhoWcb6U|4&3+r zhW{XI;$DsVT+XCgsf?VwU4?vphjF9aG z7S=1pm%@Fg?ex3#2N)Y`2gO50oX2=E-0|E-`weG6(fpIN!t4f#D!M`IC2dI#4aXm2 z=g`!l0X~|3h7)Or$j<2*X!E_AWTup$;}13bYA6rvlkKEz^bLu-(gQt?Ja&eE2P^#> zK;BUvB-ORx#p*z=J7|s9yu-=MSAnGPKT{ewBFHM_J*2F*6cXUxIf`LyQd|ScmomkO zu3mPD(Hj=0QFlZL|>+z#@%cY-kCCm#ujK=zb@u){d~z0dg?{3$1=R&hHecaCwZn<2#p)~;m+TW?Avo;%sMYgMlR_z+@5HKI<xo9IJ!b3*1m(l+pd-5$tb;sL$RYd^o86ujH;Fg_vp8*kjw~)nRSFdYq|~6vI8J3=}uwM9C%z4 z3}+S!uzXv#VCPaE<@2`Yom6Wkn-g28rRhQ@AWsA4PMJ@lx(hfzZ3^&xcZ6u)8Mr^- zABpgPy)Gj<$_8-0`6^jZoKL3et1=&si9<$V z2}!dkhS01c=E)2Jcq}~x`#F|3U)v_0kVOkq7b($(Y6ke|T@QXZbBan%`41C_2F@_+ z!> zKN9o#N9k0q@<6MrqZPUfZ-!B|fNE&u)*)Ocg8vRWF+Prc1lniMd>?zQlF(nCh* z`9iD7Gp<3>ueWq9ALl92Ngxm5A2CaGrLd-ph$>tmYc~`?vimUz?6PEity@Wqn*+xG zR>G4uy>y#m0Y*spa5;=ZvSHdV4GA#>cGm@VOKu_x{|Us_djm9hM+xpUOJMwF6%q5b zt+ayfw|sZzH7lK_1-hT5@a3_eyw8vA$=-j>AZV)q(>ivL@hoX@f1FD9PH>Er&`IRm z;X_(})l7W$y9^Fp+6gf;WvJOdZSWS!r0$YOt>S1MWE3b8 z-4B7!suy@MUiXTkHmC-dx%DO8kb!|5f(G{d-si2bR6(bCJL zzWx(4-$ol8=N6K-{#Ovt(?ZMHb<9-q1x{WdkU5eHB7SDjX`Bu;btc)fSsEIT?u6k5 zmzhxgJZKy8hni3?Xg`vT9#^w)^X5hpk$elDtWZSPV@7z?DG!tt6hNWqJC(J3#th^R z5xlAhq^=pE1+Yc_rZQ%_$}R2@IIcm4`(+SLyrd zvUKP4-C)<22nN>RWp4g9hEK zvIG+RM6i3~TG*{907V@P+)u3}LDs3vy{q-i`&YpbEdQQt*uqEoe_|wCeou|c>==uVM0D~x%H@R*z<1I> z4-IkM@x9g{XR{YhFfYJ;)+*@K)1nK-e#5HlEco`7%fi|4!@EtX@W;`D9JK9Vens-Z zr(jtKecRh=>^%kER0(o^EgKxMP{-DuM3}lEid5Y-gbU}BNk-^lbn17+{sJ>RVG)c+ zA4}1-d#Y*ifHTA;yOW_4?p#hW9O^2p;B$;1c*}C#zI+jAko(1+8gwLNE|;T>1N=5YfE9WVGRo@;$Jym;*b{0+_tu7_KrJuyJhzdbaOEB%?&%Cxz<-=TjNU z^JIb1N2*iniSB2_;PW;fO6WLY*tKAy)z^+iH~)}JUK-@ra?UZq<(U+`Ka&SXlE@tL zyLB@686V_WHe<#YN!jE+$SKYtA=?jA_v%G>G(a8#M|ZH&R*5vMRt8SI4W$mMyXYi$ zZZ{asIh7|Vq9gwy5_EDI{_WJF?!k^&WBZqEO>-atSqq`EI|whyE=S+4cGf663iD2u zaQ&<%>S7v;X{iD@=}I8ksXGm*+ftDGD1f`TT{{0FEj&10Onz3y&^b07iztb6rL33_ zz6CK{e#;fb7Mx_$dP0HQQPA%1!R)*(M`%~qA^PvHptZ@22w18Z2Ls*|LQ3R-Z{|-c z^V)Xiz%ps3sQx`k*jGpV<1^7#+nBd;lM}Q_PQrm_+tDc}*h=A$G^TJlHD8}v_|;bn z>moO!pr0Ob-^5Qvx1J!Za31mas>vMsE{p2}^|(C6GTiByjOl~L^wdNFJo#Jz@?sU> zEF@rEbYlzfIk-XCTYWsC7eF8Py=D&)7nFK?2pfLHbGKPxJbYajwPTFnw0IVTIy8dd zIs;mIFb<3xC9N5r1Gv25di#m9tZ%!=5zUo$*jt*x&CtnAzd;W!`+OC9-PW+;AD2Vs z;1@>N)dZTO0Ou%gq`?loWZJWSy1?}|=4rAEbKmDFYA2O}yH14T@`KA!^sO2W{g;W}n~&3e^OKC!@&tJOAc9^9(MA8Z zG@!O>usF98Hjgi3I;HM|cf)&f&$h@rI8M3_u>O7e)*WJS#uNuHzk1iqJ1Rw@gg|p;0L?1p92iMgsl?N)<0_ppv?Lw zcV|okue;|V=#hrCt+@!y+x`(&D)C$I*(rk`exHQ0@d+|0G93;mEke!t-0pFoH&KX` zM5oE781_k;8uhos_k||#n9JBKpRt36mqep|LN3NlbkfWzGnq3&lGf)BAEc*>l4yRo zsCDs1X&6ZLK)-R0+2|V&fg3I}Pa3WeG8{+?ReuuIIxENuS&X*tHc+L#mDJH(ksj}w zjHz2bvW)}2w5((?{(c)s)Q^TzlSxNuoQpaAur!F38!e~I`J3#T&$`%L{T_YB%W&C= z*;G>FJ}TE=Vbq&K@b-ahJkU3d^cu^d;h8D8tiu2%Y^CUto0W9mA07;bP9-%b^q_Bj zE8X)Tmwvlcg4dLeaGb^X*5M^ju*Pi-`WyFSX_9~d(HX&%a zK%s4s=L`DH`V1Cz@U^){aE#B&rR46&3=n$C4z%pybVXMq6GZyis)Fd zhSeIqME&1sqgB8v3=v$5%TJ72RU9&h;?itz3Z4YA%nxwC8v+ukZczMTCU_*aQpXPx zs20b)g;p;{ho$ZGv0F5)J6K2T9~5H0mnB(?IT&=m4z+Eck^EJ4SoY!}Zg30beothm zdi{Q^PnrgY?i>Um?|hu~%!jAz$T^&EXpnu9#SqA4W6}Z)==B|qG%2*75#tL(-FF-5 zVV49{3Y2Rr_nnMkOd9Um@Cx&%ID^f{X41~Fsgs8`fy8ho72dQSU+08isFNcU)fr*H zYJSuRT~DX~*Femky5at~KDssXC#_!jm72|bL3jaIC^E>>tSxDiR{f7$upfeJwX-7D<$(fecNkq!gJmmC6vw5SmD$ z3}Ii(P${KC14Z*h^Ps3m|NXol|KHx{`S9Myu@A@nac%qF*LAIRp1;$in%@5?i1I~- zkYjiR8n4UZm&1l=mZVR9?pcW%?u2bPm;f79GD*(eDyUj|02B)q*}i)ZXv%;$PMdiJ zqas(}l<4{Rozve6<%)ut?g$msT1j7fTB4@O#3q~T`q*$$4I@5ip#6<(yfrHUB0Z-; zcWE^#+NB4X1*YV{=t~l|`7AD=N7(}(it+mKBzD81TzsEbj+u$)FsoevJ-(Nq(0gYr z>$*z^ji=GTBQcF}%2^otd@|G0zYI>7U$EOBwUS3_hgg9x=eha23{H^w zKnvEJQt>te+CO;;xQ0!HqYv#HT&-iFCR3YUyR-rpMSH`!sKX!==7eF!MU*pZ;H!X= zM%Qn`c=x~)bfGuM4(lQ+E9%ASKJ>uGuch>1wyiZeQ5U+8(^(w(0{g? z&<&m>@R<>){5F7nGZQ%WHxI2lShDu(KQjJ76RRF^n(jH%@cX$O&eMrAq&=W{`Dr#cl!7Ydm!Hey}3Ps zU05-7NHRnDD6Qp~d4*NTT&8+9oUudJC*! z&%z^67JeQ!eTjq`k7dvro(Q^5&%or=Uvh8zLNIfoWO&hW@S4Mqw%XfhSgbCV!!P!3 z+5*f7jzBAptvDmpnFL(1fz*n{9NT^(hQ;WbEAppduxAXJFMOC>(qBzyG~6TMTz1)k zct!Xrdl*kj8e`Cq1imfi@(|@x=qEWP5WTV!L+a1aH}8${aZ4zxB(7kjor*Czl)}4j)4Vw&eEES34te0d|V+Hlxw-zn|Vs*vEMT9>a%^CLlVT3i_A3X~DNZ zd~|my$cM~|^MX%e3R zf8XQ~vmkM}rnMeLekP&a%;WI#assaHt;F`3f)@2tx5BXQR7fc(g~_`U;X|Z3^>9rE zA^&>%TSfqvR;QC78xxYm7{dMoTKM2bv3a)jd-T0L86K1!pk6P>uv#?(Cbd{G=S>Re zon3Fp!864mc$LAgJ~Lo~ZUNlR=aI-w<;3BD6zUBHq2J^$4BNdNN}E2wcfBJJVo}64 zJUa!OQp6!i{1gZo-h!>6FPPp-T$aJ`L*_HH1O9FjK*JI#oa(zCzzg(_b%xToO z%YmTU>r7UnJZUbJM~U)4+&fy1ZXcWRsq+H-`e164R8>Be_)^H;kB`Lji*A8NzcXBa z9RtUNA3$m5N;AcEOX*9)HaM(s5DYsxKi`Vk*n8CgH!X}ICeN1Q;jhb?3kr{EquNsj z#O~9%N(}u{c!qo(D91xC6*xBMH+#FVjkcL8HYGmh9F84*^yH{KuI-$R`C~8Wvu|2N z`&}aP@fBg%>H&IrtqS!v5P`oNt`o}nzUDbpL7>DJ`c~2l&NR1@9`5XYVx>AL2$=yJ z;{nOGdq7$EKIIjxz|M>E__9lZM*rQ&!0vJS?F*L?dGRWHsl5!MOe*2w$NjKx{R;?q zkpfOHIE~j(B3#=v1m>sHse0%M+PAnJ$09hz;MqIWGLc*RHCAE7Dnkt8&LD#UJ@l83 zIy^``0lPLhqpRL1J)s`~(wn2%CGpL~+rO2>nRwv_fk&iZ%_SnCR7H;lzJkeHDXcv* z530(!9!`1=;Pvkiwe=qjD%Zo;9GklIv;>>AE&xt$oe63U3ba5k7E*KE(6-(M^k-GU z#@J{mI=l=lQanIg?-CVUbqH+v%89WBfdrv#kiSxjo-#XzORUuK>@iVLoY>n~_Adl{ zmrR8V<8z>}-3w}-Y=y-}>eNq~zj0%_6;*YdqGnXGTza0Iaj^QpV5xRj}W3!drsQPSf-q%%1vyxQMHct3VtC-8TfYeVfU863u>UZ-CZY zr{MJTHdq~2PSWGJyvI5|i=zuWq387tx-2>zEevmxjy_=+U*|?`w(P}iRqAxvpg*Ln za0Gv;%k*l8IrAtv9TW|&ahc;gK;%Onn9VYPUz=;-!I!I$8#D->C5Ic6wLQ=wB$^~g z8iDkJs|53kAg%W-6+7+?%J;-^>+}@Zaw;8KolnAmLkbzl60lIKa3t^QI-#>VADqJH z!BB1xvF_ah$v59Y#2i&2H3ISF-~LfGU3F>Jyw3#3)&FwTJ6Tl8!O+m2i|R!a@?CVy_s8NSa1YsG?|o^|6> z+X^rii3gddvtd|v6&?8*Myp;=205>%H2y~}K5fZrY>96nbH~+)shKG9_DzJ;Hxe+p z$sh7w7IFRYjQX5~g{0KGinZQLaC2Bb{q^n-ZFD=t-2L*9dfYW(j1@)j&|ncB?QTS) zXgU1VU(UW7%_m)V2B`R^dg@pCmAJ&j5gVyRDF1vnydKDgRI#g|?mCe;)xCz#m#=`q zPY-i99S^3up&FxymeMPe-Eh>}21mD+M1zOs0sFU z+^13{)@XTXG4?4IkbwR&G9@erCXZid|CA|{gsN0B$><+x3A_b|l&1o(C7jdC=yDk( zcSuxE3S5~i1>a(=@j5r7v>Tm<$74+4`kq4e_v--KYVwKBVmqmzK>?lTa0Ao4)bN|D zFusu$he62|czadKB7l43qg5DPV1*O(R6x$%!*|D7JGE zlyF)yGka&SR!D$fG0{+WaFD1SH-;l(c`)bKdn%(P4$e27!26yloC|nJv*(GUA$RsL zh><{R`yTkaC!du_sstkV1|}_*vKaAyN3K~ofPLg7(n$6|NMHf35Myyt&@o)Qr~spl zgHU723k7h;3WWyqOJMkG*pROk)WilK%lmRYo znt12&IigCk=|O%I*7o3f_L-{*J!fu8sQY|4A3R2l-p1qJwf*GJ5I@$0s^Q&t`|hM5eAsM5v5mh^yW)X^IQFe=F3)3rgUQ-#{f_uO|v?w+x8du zQI5q5ffX1*Maa;D9gzMo7_wK~<@gd)P`yk9ELZE%;fOG-P2=`H)B|^Q3B#`=)wr<# zH0or0Anec-Tq{#fD+br$tFiUCL8ApD%eMh8a=^Y~L&nzd1aY0ru^1+1!|D?{m~z;V z@ba7qJa$5-$qPwqObTVxr-8nu79NeD^z*a}v??u@NZcG|Wnwhgf(C!w)@6rRRzxyJ zs|)a-#3W3Qm7>dY6X}FK61dR$2l-TWhg8|Vq;CDmux#c!`p;}1_LO-NA=`=QGGIjzkQ%Lx=YNG8t8S9EW$@IE>oZ0C?Lz*oh!?FZJ;P^D&4*0LR^EYZXIGY3({(*@sNJ4(mIgVCH%w6S&7KJ-vMLjG|+ z^4#-Z2`~Bp<~aJ|nUkrw+RvNaYSzt+cMdjAnUz9@^QK{$y+2M*4+2*O&VS|_!tup_ z6Vprc@NN{B`*CG9)td5xl96_pKB@-$1J1D{72ePuUjcr0Q8b~U7Ot8^!=9)S7Or%| zLr(iK+r$}~)K8Ih54hahd%4)L(TJp-tt2PKb~Em-jGqGuz5KJts zqV)*@AaZ{PPPPoen!-M^;PGO^ntlRT@th!ohCa>VxXsX z2lL==4mo!;m3?OM879aqB!%m>E(C{JF*<8X%Rp6)FN{U z@<{MV7B)F)VAt&{c$KPRc(VX*+p`DVkF}d$4NRnMyjDi8XDX_@JEKqV04?YE10S}W zVXkm_jc=bellYDIL1a}H^!_!0M%~M>W8fTBbb3NIiu3RoXaTcq5?ok(4s?r_pyM#d z`&zY-8DCjX7yUSeQ*VvXt-4&++OQ0Y^fc21&)>xGx+}a15XRe_{ybO756*ZvqKIM$ zy{EAV<4wPltbwy6rd0`$1A6}EgXhP~*f60&_FB?x zl*#qPj2Frfxb!wtR&DFR9Ml#?siD&maCXtt}Tz1OLG+N@!p!|DzG%|k8EFI0DIyD!Go?0ut zy>A+q3tfi5oqG?|sGE1*4I|P^mt%L&Q)2j34_^BiW5pUxFt8EA4GJ4^%hbI%w7~%0 zFMrGO7b=l!mM2O6%Q!ZF*FvnA%94%WI_ZqOEXBatx}>#o1;mFHah^Oa zbg{ZldrUvmpywYM^}=Ti{~;~>G4VDLZ@x`TS8^Ol4?R3J#|6iBn&N)HD%LbImN+;J z(kCO!aijN6eC&9KK6t%}tq?wfByl&&YUGnK!DKFn%MWHKO3~RDHPI?w8n;-e;F%H^ z+;ZOrPVF?p2huta5otmehsn~kzBVFpfzxmWXEr>0D-E|f_CQUsHCyHUiCET&(W_xL zaPf>6U*mcUTB!e%XfC%Z=buu`G_3aC_a)5$v733~uhkz%%#TL`LKUbUu^8bM9rt zf$t_g(szh_sSIN_9ts2Xzt7kcEs?D0r9`H)z!Kum++vwi${6zK9_==5A<+k}(TRI? zsKwG+CQ|trn_fK!1Bzv!saqZmWK6NI?-A|Zdyf=y%z9OiX_#~5CjD);7P^0GF*1|$ z=unyo%@+~__4Imjrc)L_?24l+nl>UY@HEX?RE8eU#_5WI4MbSe4{p?}Q28I*@tsI1 z(O6W*OuXy?XOGq~YuaKM0o@J6doRc7p4dyq9rr_}?;{%P{gN&${l++$Na9XzPM|xI zPYrY@p~CbtOy~3!@I9)6u2!vN551d1Y96@2x}BR?<dtIXfUG{9FdaA!2jkC8=8?isAABbaUZd z5y&;$*4ULi6&I30BRZFa=(5cZz;BHMKm@w-qQ8HpE%{G>iQ zf9Neu`cg)O&TZoQWQ$Gb*ezi$CP{!nPB^U==cCrg!{PPC({#sO7s$++iA$PuIfmqP z^k21=Y`l|=)m*Qn@?|NC`iHSoExyv;v8q}|QT+U2LgN<0thl!YyRDoi2s3@F%|DMB@W6)eAVl8*IcVesEL61KDg4;M~E zee>niQYalg{>g&v?o@hV7ndcIz7&#`6X43DL8!sCutB*JmimjsvAxPLx;_Xpw`L;K+LL3~YoGy*G$uz(aO{SuD7IcnluS$HCW)Le|I+cy*-;8eAaF7(m zzauxV7efAuZs^F#B$vjoK+o@c?0LtNq(3u}w7)$}tb!sN*~KOFW&29_of|;E#|W@$ zyKj=zTRP0=!`tx*&lR4P$kIP<`|t~FSeLh3A{^#b=HA|+F zCZ#ayCNT@={g#Kq3^@>TN}|u!oCaO9gY>@aH|i(SL6R3gZ>%Y@Bxah4aI~zQj6eIz zdJLH1CeF{ZUc7|bX>uOfr%iNBX*O)U>3|WljuB&n3_MX-Nxk)zh`GZ-_~N>sd~pXT z9Q;f96;@FHds!76zT&^&01=igRQe*ddXNPiZ7?fOY8 zPnf{A)D-+6-HN}yh~geIN_!i(kaN>!HXe*Xlvp zCziNvdesTNM|S&ON=Zo<VX&$> zg>6fi45?dBfpXSbST!$${u)k2^W}@E(C=(|yG9iX4=JI`L2nTGJRe%`NkX=SF4}Jw zfVoqL$TzVW=#&o>Hsuh-N1vGQ*<#@6<^n}2wq%RI90=mGXG|wmkvFEEcyHcR48Qk> zDaztf|Gr&-vLh8V&ZM5~w05Twn#G(qWQ_diSViSS521(FB(SD4px@7d95xWeA0g=w z_4*riuTCb~zV4*qjz0dD;<8oS!!hsf3{dQ9AURH9AkFoQCt0s;R9dkfMnYvlfSa@D z4{qa-)cn*qx}4-5@q$>lC$v0!D)CcX4GX*aY1bcpT-`VmA6qNYp&NwqmNe2~-DL9D zJ`pCaG$$THvf#7l7Cr35-GfQS7Qd7yScKP!6Uh<@i)y=eD3VTxGx@Kf@0B{-Sv{ZB z9_=L$S#{bGxf0wD%E7ivL!>}q2h7_hKr1e<#Mj%d(x)$#Ngnf$+H4Rb#XVlY_2a`ImU$oq7e{j=33z~l=q4r%J*p(F#Il_bD3@@yW-Uh8ZV{!cnIgHHU*uck{aC-!o z1Dq1Us4Q%P)IBof;*L@frNhjXr${@0TxCAxz9;+zD~b3!CwL`&mYguKgRccv@Ug}P zXZJay%eXMpD*u_y^6a6BHLD0w5uhfa4fI;{D6#&`k2zrru(kCqWm^w}x!pq=cJ?`a zKR*bsac8A8?)=fWbUp})onQtJdO}aQ1WrujcpT=YT)v+#%qu%e>$*B5Cb7#B(#AE!;qbCXN%E zqMxjd)Tzd2c5mqrH&0riECiAIp+r)|jP4TMk4X}8D0J}#jqII=3F{)+DF;^(_l@p& zIE`c6hUYfs95rK4FMS4m((W+ZYk*GB$%DWLH);Be5^DOu3k5z7n(q}Z#xveFK+E1T zQtJxIGAU8i_umeEx1JEcAF1e*dYOtAn8B>19(pZ5mig6j4CfTDqpO@0InI4EJw7dx z^d&dY&de~{E}8(F##AA|Y@F2Ca2dMmjp6th*S8GMhadALNpR41y5-nz%J_-EyNY7^ z%s`*Zf2bsjhnC@=if|fJlZ8ggoph+gmYy@d&g$IMLA$7VWM`NHd*W3!=jjQd3QpDN zwzr=d2vuMs`tnHeT7Sl4V#=uM?xY@zse7aDnf8}8yEQCO*AnGQ4yW zIR9fR-K!9YYBfsOJ@qJv{zkgBoYSwaZz7ysfZcgVfXmIBLnjppqLkJk_csiC^gmI) z=Ib;dClh!6UPYF*w9_pc_3?(uJ^b$0fDT$&^i{SF=gnj3zL#<2&-EDWcMXRcO>><8 z*%N&aPsdD~tHf+s0?l}Gk=zN|1>?)q0peGJrKB#c{L8Uie%v7Q-qpejNQFidDY*JD zhCDkS2y66YP_3|^n0$QroX)C)aViwNjd=s{_e4x187Ji=% zhS}Xf7D{!q<($Vq(s3(%dTveYT~yel+XGDbkt{Iz@tI85*bT-n__Yq67P!#O(^8pJ&9h+E=}zyLcsG0ls*GuZ zg7s9C%6UWfsP{5IzSV%>w3np3Or2?adXoMr9U-GSvteY}N;p{Z2yOmN#!dE5>5q37 zI2NpiX6ht+ZTs-RuLCesWP})%ye3L_x6(&8 zh2}p?Yl-sHEo7lj8hJnliH?yYH~Tz9KTY7_c7+`@%Dtc3pQykk0jnD&XU3E2x+wIh z(nrheo!GrMhb%mHi*2p0XS_FCk<`IAbkp+~I-k?zw5P4*m^m|memqN(H2aAM`jB-^ zPl)NwDDcWtg=cv;U`m7=yscJ+<%gqj*RD`H5}IeW>;5P+RZ#>cW_c3X=ae|U(I7wD z`0+K7W5>H5&@#nr)Y_#0+a^WRQnOoB_|H`Hg>fRd_;dw5>h+pDK4XMiCK0e$EroIl z``DPZ)3Akx<9_|^;B{98&icl|nN3BkQXwDiIr`bW)hZAC6k(<5>|IV7sv13b#^4FuNBxHiRQ`5;6P9s*bjuJbKDEcsL35iVI z0kzh0uzqt3NxC~mgkpc2_+00zFw<(W?KHo==O-q3fZ>BT*M-QPx zW-)t5CjxFx^Oz!{&=K&j8OT*N@_9Ci>EgofbkU(v^o1IdG)>m zl%58{hWC>!MCA;iMX!l*2-#0OGaiw(Mt3-m(K%dbx{l-;r$M2N11Zsb2ANm)gWQM- zNJ!1**nk0KUs4gIGO64;xCV|sUJ9((Eoik!A`|+~Lj8F~xKVr-9&M?GI5mIxFk=Cc z|1r@*?5-Y3&ildT*uIConXdTlQwlpRB_1jq60qoNH@z5poQ~+;q9dCLn!eV>#ocY@ zGczrz;qe(zV;{)`@A*c4T{z0Ntq#YBEnnF~+o$0(O<9ZO^NZL&f^NvKy#(wpUnB{K zcjJ;@e0bkG0rpLp2byYHxLc`&)e2C+vO8SvV!j~$mH$VcKOCojyn_i(?jP0v`kqD@ zkD9IWh{WG-x~SmDO>&?h0o%_1CO^3>6aJwZGS$}=Ei_o%TKA!`?t&nVP?N{Ge-2^i z-E8Js!*P87uaX8HIt7n&-JyQNbY^LVDjRi42d2C(AwOiCVDaWE;&Gx7FXl_a@{Frg zTrLa^f1Ra2R`KJ7RAF84MP&HZFw~kz!sR4Z& z8Zf5$jj$$j(CJAn_==`dr$tkk45=aI!s@qpbW@_q3^c+;LkuXf*p z9Z%;%neQIBRq+wFNgjh0ZLe6blY5y9E?o9(v_0r%95a76HqKuBl#IMg2abuF2Fk5- zvFEis9{G?-jK@-8`hlmg^Tbsmb~BR5hGu|BR4WM7z9r7W*);!rJNTA;As@AC$;`8& zWO&X-N)1j!>Ay7chSPPF?_UIx%4<07g#~nTJ&WHBsf?$N10LJH3p6xzz|}5+PUQBN z(+gQ=#7ch@r41P`S?Nfrz+iCDrd=imcYzVre+&)+H39Zz;3!c%> z;hcUNIA$7geI_2cwf0s0#?c*cWTq4RxabQyQ%{fw{ZYg&D2ra*m<0_p=hJcF>olI< zg1EUK1ec4Rppux0e1l8zYw2cem8&3k{5(KXn%i9%%-k@?XPtpq{xQL z!{hvEIUHMcTNu99y-sFjc0$ceeF*sQiR8L>H8yd4G;h|7Zg)?ExkdIcda@c1HpSzz zf74NMVHPIyR%1Iie^2zjP1V-aF+ZMsq!YHr()v~gM;$tu^5=@UceXejxE?{59=t$h z{=K6{yAv4i)yJ_xECJtKet|prl39(sKjudxG-=WX{{Q6SFmtwR(TXdIWYV@s4tKvFAk=9O z?UIotU5W18dDH_lr<}ls(CP3|Llm@buSZjR4YC1CsgU4K)SYYs^PNlC3y)X8OZ_B> zwtq+bgGY#OP(9l=r3mE9vgt7~Q#@#TlGDEok>|5?;GK#Di-Q)#V#a!W$sA< z(3JB=PvUB+r&B(i@aGAgJ+6x76W3x{-fXOomBFZ#VsI8DMHb_G|l2GYxHkny+0<|XBVEFk3Se)L9cU-b@ z^M<21`O^)IRyD=sFcJ6~bdh}%x`*wp4#ln9+{$`d4C_0?3+)C((5EDXd|nY_dVbwh z{K4@xr*)mC`+saBvRU%zyXuyC)x|5c!SN>N(J>=`K1QH#FH6pUT7ps>pa1?f?mYP< z0k6GaV6l!Ty|zZieC@B3X!hqZIseZA%cZtr(z|1%s;G_;kG;XHoOPQzobtt*L@uML zHH7%cuEr-lhSa}@hfx~-c)-Vs?F?69bT}UMp!rd>T^5Z-pO-RQ#ok~#-lK0uPNIgS zGY$W%ffu+uf+Z`DVdIZAbRoO-SqvmT;Ce=1x`~uV1+)4e!E2GhRMSYZ zQE-J1dG^PM(_y)Rxjxq;bJ_txO>6P_^4+LD*$-EK48eP$r!Y|YD9ZJ^kY{gQu;NIs zN!9aY^UsF)RB@cays5?z&*edB?iR-<+w##nSOS(8dxPK`RZ^1ULO%{fV%EGss_ORz zFIJ8=KCC=U_HU5GoKpt4*M%@VlMOaPfYL)@^( zl^hSS0B6B+=qr*2`L(j>tL_aFXF1*4<})xkKn}AnDv(3X;_#r(8`e(9LRhx|%kOEC z8$wrU-8Dm+tX>AL7P%n%Y&v;dOlix>?Kpo!k~u>&*~WJ{WNfnqUM_l!jXXE*IrzX< zO3J{weIta4aYl>cBu=x}La3$#Hk;?s$9;L!`an4Sx#J1z`<~+iS!B|6nSSv8&j&JQ zumj=}GT_+$9C~j46f#Hq09_fGhq-=Qc%Snz$4!Z*O?gVFu05NqU*Q7#()NRb{sf|M zsEN)m*aYj{Kd|;2r_o89ylHvhTXWqJEr?n7#4|lkPn;nh)NRYKdE_1Ux}Zj*Uz4%o#AgtOsxdujsN1- z068MkGoOwqIAeCLBlg9=CvQCU=zV`p?wOf_x57U%wFjq?-u#c$Jll!7szhNK)kj0W zogCv$SY%B2xF+9WKED54u1*sK`S?UcxNrZz4;RqR=d*qNhK)P@7x?+?@L6DNsApzu zW~Ohu(2URPzx^y2m9=_bV`t^FA;ap{!5h4v!s?cx=WkefHMj6`*O~K<$?oG_Gc@G+ zrK(#!9iC+Mv@6+irFF8^UPm)a_xB-IR(FMYKd;WPDm=NDM@-&YrkZD2DO-N!ec6y` z)${PARj%Fv-U3U0-ouy@%k-pDUfV?}s|Bw^t%eHttP&I-@cvW(n)&w0Fo%VBg+sii&4+l0c0}{e7bWnz-um;DebRaA`6)a!4C1|< zyp6XYC6dSQ<-qe>y@gl3dLOU;ZU#^91@NX#&*X`VmGhM6o#d@>ir{tJ59Q4~WzI8n zaO62U2J(EK@px0ja(GJ7aXj9O3|{P(G~V~8`~Oe<%S4~{{CD*m>l^Eu{!jn^ANeu7 z_J_N8k%BvUkGey60V}ri>VF3F4ryoe0&d6fuFekO6(0)Zi5SN5o@fN{Zg$7<!2_%0^#s^hlvq??!V-p!BYP5v0c^VZtR+dm!M`i9f+ZDH+bXhIHk zn5>BFXRN2X`PndhBb!_eInDMsamLhvDuZM$r`DnaPeiX`J(&C z{O9>kE3vxw-_>tos;_VOKh@9u>UjSzum9A4En9x}e^tMMzP^$E|MvVBJoM$|^u_a5 z*=^;8R}Wb@r>(Up_)%z4bE~xJ+x4qW--<3atxZ|l9Mh}K6a2KU`RT+`3#IDwyn_Wk zbf42AUSa&wrj5r6cu_frn*{Ig=6MePw&+(>Zx&NH!prGM;|Yd&G;JHzYo4GP&tt0j zc}sRk^X8cb^9=Us@lO5LYyMCDHN$(P{=51O42_Kcx92}jE|vyv*iRY}T%gZ0MX~?$TJT&Thj!WP zU_qWH@Yy~l3Lkk`E_astbF8Di{a$cqi7=E(ZbQdS#ng^F4_q4dh0S@3*a=?Nbfaw? z*&Ql|!6K#Xj6`QR6ZwP=-4%tR%na6Z$$mD{<^kRJ+mQJjI{`|MP&U<>5B9p-gP^V+ znSaRyPT6ck7s)9Qa`y>ot8)Us9DDrHBZz@+@7d48-2CFJ5B4_B!&>1{DtJr-H%a_s z+m~_su6jS%SfCEgF1DEPVHx_mKR1m|y+^N36~|+*GU=7OKe%;Tg(jR000*V{5RoYa znNoA1_+}3wA2-6z!UERNYa3Pv$Z&o1W5j~b9}Y`vpiaFJIB{O{xkBzV<$E;|NMDHW z11(@8zcSR_-G~XR9r2-(JSqF$n}^^aO>F==Al#o@#eFoX41#W z4g*>I>amW?#rnib$1&)nG#y<3sjwga3c>E$3g+lNADp$BAEmyi;n=1$=J)AESXMg) zLc^?B|7(&}Ie?-uubn-a8B!UmmA% z`bO}s)EyP*Trk`0&KM4?gfMF{u<^M;)y|bsrBX*&6*vVSt)7Y@Fa2T7`YguRS%>g{ zlZKko`6w|tmDJW~VXArw@m6`+SYP3TmLhW@(Vmcj;HZuXv+2E6JhC9hum zB5(E*nB!1L_J@Qs>9bv6!9h(Jm?TfuD}HB38guB++ZG&?P!YmyRNy>Ml3nbU&&u#F z(M`ScF^==HeOkJbJ_IxL<@R<7Z=MnbUvJne!p(E{&4Au-uSi<96H3TCb8N6x7;4~) zW^vW5@3w91n1&Z>NGLLfUZZ5%s3C0SI0YR$XT#l!5~}~u3Pg1qsrb)>be5G1Z1c0m zBFFV8T&x1t(q@p<7evx?z7dPtHt;yl78}FV&>E+rYvN2`J7jU=sto3bv=!`L5JmpI z@&#KtX)Nh-#v8IyI3ai;$bAz-x%c16=Py5)?$@!zd;0`<;p#^CiyRSNOvCH>D(LQI zMJKp-(OpOMG4i(~rtk2hH(`+MbvxF~$64$h*$B4T=jpT+H<)?Nlq$anrfzfR zg2+TE-}KNi7t2`#}pD`QrVV~nuc;=cQR|99rzhsB%dA% z;vGj1Qfy0N`TSO#7Av;U2yTpKg!^ z{rd*6UwVY%hbSVKUP?k1U!aRJIQ`*wI)AwasO5E#Rl1Yl$e*R; z*z!~4S*a`MO?ys)4@+RCP!&zOWK4DSgu!Il5_C-v$2X@QnTHm)P($r)Oijc+dQEf{ zngvdQU5CYRZGIs;|En=J1_|T6(dBro+KOC#$Gs2fQXHA>2ZuRbYP+#GTE1*!%r*$Y z2ghIZke(H&2hFArAFRe#yw}Vc+o_OT8w{wo7+U1N(~tr^*!$}bjla}EPETHfSI1tE zk@@17RHH=Qd0bwdk_rB56CklOyy)P|nNY6W%rsd~hx$q0%$fTu!B|Zm9*exBi`ULV zcL7yQ+9`$B3(QE<*fcn9s!x;WaQQu{b!3z~SI;y}r}2HBbp2~zJbLF16c0@KBD&tpeu18-cU zSVDH{CvqBBeJqW&$M2W9Y|`Bi$c7yn7&aJ)<6Nd9Yh(g7c3;Trd`~QYx)Rpu>!Zf9 z7-}6?O$GjWU}Yyix>cW}*X>?1X?qK3xY1)W9H2rayDk&esb1tm%MzG4kJAB)ilJ=? z4`rSK%xW@$Luf!W(*MwlE6s4(%yUG4_+I0lQ2`n}dkMbsTSnMXO0+xN(0#Wv%-Xnz zQS0*s3zo|}tun&QHGhcdmS7rnX*v4M^@c|4PkI{%agtV|8W=!P!p zopqjwKb=Om9TvumfpcMnqabJ-T&LeJ*|Ep{xt`3w_jD{s52N-Mv%4R!!+M?y{9f>d zDSQyhOi}tuTB_bsbB-nVIZ%gsyn9A-jt?^bI=D<(u7}=L0vwrWD`U^jCTBBNz(=#oQlukp{n?YFiVmdC5_`=?6F@V^j61H~NBC3%>iQ%KCUvXSJS<_!FI+7{#8wds^rC%nY*rIbX|8MS^Pl$<${UGrrEwW)B2>eNK0Bz!sU zzadRNam<=)i}*R+wF6u~&xd9|k<+SPAd)w_=+27O<+EKvE0zb*iOieI#pULG- zZG$O%YLI`vm)_sSalsBuheKO8L8_iA_kz;>b zGQQP^`&u z_y!%pg3FmLW!E!{wbp^Z`xCmpC6+Fhoe7y83)p}?uSvu?L3lCJKwY(LNzV4Kq^Yi! zD(RnLI*z^}bM&@yz5Lsa565p2V@EUaH5G<)VLkNBmx;KeW3_d3MqdUiIXj-sU+jZ%Yf6}F{sj#;UbK?R zH^NZ9Q~=i;aD-DCvfO+8tpPH{f@D$Vt>=7q60q-1bf=}H*vNuxFk z&as&r{?WO5LL|$`17=ilb2QFkJ6_OBmYy~wDNnV52?_znl5a#lT!|PbFUFN_(;+$S z3tew^ggLZrDlL)U!|1jvQ{LxtGFf;ogcWsD#UF17Ct7sSC6z#2yBwTT0bCvyz&sR7C;RH2ko`khq$JG{+X~Df zU}O(9bb3mb$8-{_LPg5B-(j2QnBiwhGt9U>58mC-#8<6Jgv(KHEbidu)2#=X431-O zT`-;UUFLKuT8m-wQ48FCo25|ym^|`+O+HMu#Z#C4$$(i4t+kbde65L z(wQp}NTavt!DekO5E8GXQfp^mQUsTOQZ7ZhPE`}D)SKo*H^<2ieO0t+pFlMey2O_dZ+B>65|wS5jTvA{Nd5yW%uV$n*AaWz<-()Puem<-F~1fy*@LG~`)*`$Ka3p?p(zW@@B19HB-xv+Y{_VRD(%wVQ#&OsO>ORT($rGgX$kGEEh@kJ z`}^0`b-6CR-}n7`o%4J?9&G*WH7)V=lH7E6tLmqwR`nb}Wcl9(VWRqbdeGU1x`*td zcPE}uPGA%KQ`6xcz0F|IqWR*E9ZpO&op8;~d~CYqi}TJV@b~UIY+#cBpQ{r2bM^>6 zZ|}j?@~(n+fThX+A0xX%B%kQg}fltzGlGy-(tTI7jx{ZhpOligzJ-gMUYTq$TK{G-B{Wc+a> zmD4iK@VcWJ_rm=`t+ZpR{nU*HIo1h-$4vvTYKe!xPsX8+`dmG`6jI_8aE@F)Pgn7! zKMQV>ZPR6OKEn0ak@#_jE$iKUCmZ$OCTcIx z#%|ux9Q5Npth;0)@#cF;t_T-#-bib5J*`1K{HMX2mo0<~4Y={cKstUhhTj=g(O&PX z)b)xZuJw#zF=!@4MY++|*F(9|sw?(x3+AfStrYVs2aPKuu-PJ#j~>b9pVM6=Z(a9J{}~LuQ)^KCMf}g_7I*%Q9`;yHmRF z&kw~yHGg#cFC2e=*5~;{>fpAH4JLRVqy;6~RXH7A7+BGXXZ*>)yy|3D`w@ZX3l#bI zU>}lu-UQ!jE=XKFe-0iMfX6OKJ&f9H?rU?3`X0VS`KC@%KXoe&8Q?2s*q)a{0$SW> z-Zx=FSr%^F;=;o>#iG5Y6Uf@Ux!=NVbXVO24;alB{w1oB>EvX5Vp2}$f|r2e`-yPc z!iYDox8$w74%TKT;X*TOSh8)Jutl2VxSxyRlO^7Ct0IsKhaRQFKMO(4&YtfZdE-wZ z5C5{j!{SQB&2LV)Ejt#1y*gZQ>fG&B+nWP%!|xz&`sD@>`-ebbe1C9zV9A+hB+t*a zr*L0Yat-X(=U;m3VE*4{;Ez`PGe%(7DfXCqaUFFD{UYki2JrLw?%X!>2dF>y#9I>U zqhxCbx^B?=lF@YF5GL|85Ao?{(%fEBE{8=Ub)ruCq4UHgQmW$T4p?nROi$_WZp-*>r zzHZ~o@d^6ua=sgvE*Z@STg`Y^lQMoZDwkMI6|lCvg+BT16P+$xr9!JL&<$;bIqknB zUt|)8&FG*#wMqO>zbn6;x>|@4rL%li4twu6X@IM#vVV(y6w!0706g$CK&5>Af z(}~BMNFIlE)8XW~g~C>y2t3%a7*<^Oz-LWwA^WwAMtyxEELt2caiZMtl2$5MbRSLW zhC%FVHiTUtZ={36V=?<{8h#l#hk6%$ucTQPXc0Y_e;+gAS5kkAH8jzDrLCaQI2}G3 zmkJJ_`oiNEHvGtPhfsZTJBZqL9QM%*4YKZ1(fTM}wx@)YUj^{|t)p=NcUP=+0L0}Ur_uqR=#LUp?}787XYxI`W#h@`HH@&XlLL;v4E(6d5PM{F#it`P z>AK4ZPPV=Qb0-}Xx-FYeB|*DEZpUEs9b=E0F6Sv?k`EnR+>?8Zj9}$`J=wByCLI?o zNiON7)ai7k=ff&#i2hpfnzjeUdt~8DTTQ&POa5D6VCiC&Gy=a!+Op13|FD#yYhCVq(^I{7neAKZ{ z_AVkBrmk2_s}GeztnyPB@P0E1lDEsV;yB&5KScpSMbMyFfGd>eiz>Ae3$@!avY8}L zm)<=TrZx8A$pdE4t)C<5-ef1bxjqe(+pMtHDw)_4GY>L?d-Lx3mZ;TrGfkcToeob) zLa&X;7tEgs4`hg4yZi7~A5Xp#Q7Wv;xC9~E2ZVCdJ@EchSk=GzfxLf+58e`L#8WyC z!MFZDaZq#!cTqVAT6vw>!nR0U`Ot<{A~w@jT^H`MY7m;_`SPs$_Ly>VIj9}XM!!CN zV1boCAFxW}kvqn~*Kf|aH$IEQ$BpCxeX{YhraQ;o&*b-MM=0^199~gzp>qjqX~`W` z_IT)szq1Xogc8MUB?tQbRhh>o3mjMejdBa)v6GDk))t%LDv9})ZSRH!by?z?lhzz; z(L$|Gzo1p}oE|@EfUz;!r%uc?vO?u=2c8*_7q6nqgWoLw^W)5W?@S4rmASKnN+kSlh39}{e<>N4AvjWH8t@V+u)C_ zV+Y{S4GUqRW*%25Z-E2i)!BWrtk!5Mzb*%LwhOX*AW6|Y>cMs$vr?vYZ;vQ;tlNy znXGX5mTb6(5uBHLG2>r%0n|J}WetfuzgCYQ9$5hHb=PQL7gMf0KajU}&P2KT7AWfP z$adAYVMbtoTqJ$&Ul^3bl|~=_c=HqOc&3gf{(AU&Vw||lE(Wu<4aK#l3n)3G1sZEh zWeW#oqE#lMUFdl+tsw<3eAVRnOC4xW%1x=Wd=+k6@1mxbwZgjUPP|V~1_#e-b4B<^ zIJ7tyKbc>lA>#&fg;Nl=NSxfgbF|^ecOy`{(kj+;{X|PP#Nrvlb+pM?8#Dfx(OlhJ z$#qdz^`TH7FMl=X#2ksw@> zFBP3IExv=!9g|$pT^7O0vzaVk*9~62I!mP&5@iqGOBsL3HQ;G)%)28KulHO^e*-9R1BUTX6W-e5EGPo(u0UsFpE}0!uj{GDb)wJQ8KkYGRFfW195L! z4_@^5fH+I%1?*KVrYXhw+}Y5E&vqTjB|0iNrz(uk+-eeZj_svxzXrp(%Vu2NJ(wFJ zC9m7}|7gQjD?T3m1av=T@x)WE_%%2REw-4Vs(vz?d~O8IiYKDuidHDxdkEGlWI|xz zDVjcVAg*%Chioy7?-d2&+UDKVsYf5_;rvioHu5l>chljvm;knH>5SQv0$5RXm$0z; zH!bdRTx7KyU?tk&qI;XEpUxt(pDno#nk@xI%g5xdsfhXgdvpDsG7?@%8SQPgl4o9| zIXkz|ORFEWUN4)yBIeUAQsd8hX+odsM*8s`F|%?Yt@Kz$6OL`5nz-Lpf}$a}$K4X* z-}#}6P$A5c_CqUIRzRlNUeI^-rj6ZBLFTV8kURa4jAnuc!zOa5w?L1jp_E-BxhU?bf?ebpXe-I4I)xCNt^Q3|X}u5xJ|8_X(BK-!3(~0hZlJ0E^pP!TnDZ8t*j3vWhNfQE^pxU7HF1pMr4vg6Ea@efA5ji+ouA z!hHHKJ_*#{M&Vt}MpDh|k8um*LFsWK`+oAkBd<1yt5X6i2QM=dCw|ky@j3l@>+1v# zuIPs~)hTS{)D8D2B!Of35uvzH9bZ*26?&;kjIYmR=FkIm3f-}5R4a4e#aqH_OJl@YACoL$V!lnXF&ydHWj$D2s2w48>3KgyGOzX$qm+ibOhgJnL zJguUDKaMUER4vrFtY#i{%UT6a_08Zax1Lsf7|AD()(~EOOl3i}WE19&pMLh>cd1K- zuR{@!s`$dMf5Z7!`Xw+Kf0Xu5*hv=yufb%aBp$rTk!@^@`1~P7!QVR(FI4UopITq5OSXR2Kzxu=)O_>x+wXsfYCNFMLVQ+}%9OocxD zdP5UwudgPz$-C%!&Tz~O*5TY6XQ8$4J)!HP|0rUe5t=@i6PvSr@O_{&UR)K5SNBgK zwdE$bu1Ou!H}>b7c{zMzeJj1TLo$Cdm@Nutybr?ZoTQDl>%GT^u-kq z!}xq+cj_vN@G&C?SJt+Oy)R_I>H01hDzk&0Hl; zAM9%H#1AwwE1%STpwfu`WYP1Im~N8@o+-+3tk4#{8zdgPW++x>N8-8kQGE1P8Y?Z3 zdh#Q@@X7jL@X$M)>-WtSdPp9%E~|RG)a?q!anbpd_G~+3n+D(-sZ-x=mj*8@420PI zMx0tY7vzQ{@?K13@SXyG8wPNFA9b$y+k=M<7SQmL8f&+V;*q=N!J<^6mL?h39@C`W zBSIt>fy8;G?ihYoI)}Br6{1y=@VbQ#kBC>t8DCSeZB!2Qolr&%T?+VWjxK9u=U|;- z-6?4V3(ZYCsLR*@EGEJXTiA3u9wSpri5uNbFIXT6YRI@3+HyMcw%1!||jwWCd7_`~cbUM*Q*L zVt6w^iC6lm;@uajEKGkOYHA0w$!KldzXagkR}=IymG1Kg25`@A(hg6{1IMfzjDxzB z!<{?1Sd&l=8-k?HM1?3$Eq?$dy<#w^XEsfoH5!|zu7Uo|3Vh6sAY*15tlM-`oR>10 zoDC)j-zG}@_irlvvcQ^CJ8gheDJvXyWGqd2ABb1C3KYL_sqoj=9n*6qf7!Ac!E4?Y z@VlxbT58-8OPg|W*3E%9X|fL=sOTfCpX$Jt6T4wy@H#L$l!s}y&iH$<5gN>L<(FpN z#gS&Q*s6Y9Y)`x{PP13Qe#=JCbB$0oe%hBq-*?8X{%YLoP8jYjRKj7Wf4fEgnnJr;LUXfzBq0+kqh6{S_t}R>S;wY2JM`3|G7Raki!{-ntopi%ukQ?dz(@S-4$yI+pM$6HRp&7+~xyy!3dF=~d_j`3*Ow}A@x zucT@}dEWH$4_Wm*4PBv5P&}}Zj>Sgd{=a&V|K=g6H!PHeCmj$csW@Wj`x_zrNboBkeUrI_u$%k4s_X%{9WG z*hlnOsTlgqtOWnfGG4PL0Cmqxd#{1BtNOfkL2cU#2;FGIC2ynX_|;L^wq+|t`paRb zQ@|%@^uYn^x^anXYn6Jx-Wb-oC%4x5Nxc6MT#)9>5AR;5@|<+ZA7(&u*Uw76C2jW6 zh{gk%I|Xm|9~AQ5gjMCrsBDsS{$vet`_G=ZB1xb@lVbQ&*(AvOm(QIZII-i8z8q3+ z%K7_I$U47M@^~RXZQV>B`^v=tb6{o10a$+QE5t2$598mQf*U_ogog41f_|wooX|W8 zN84_}0VxZA%@8nIwF$y~B^T!zPpK1R&SlB{QNeuxCnh8bPF_o^%I>>>TuKTGOVW6e zw;#EvoPp0qDbfzx9mjYKM6K|vpj+7o^@|RGvz8urSD7dKXs*I5D=$;+5@}u<@LLRW zbd!1&U&+pRlW=I53=jSNMFx2b#gPeB;`~$2;^H6X80!{AJ!b_|j=eGd$}FW%!~l!CD#l8bkX93D!2E`E3F#}4O< z=!tJ2Z&_|n#~XiDPO!6vct<&&w!0k6LiA~Wa5$~)_)E7QnR2t=T5*R~EM{)($+LqV z3O9>AWLdj&Ah^gJa`zsC)E`6eq{dlzWYiZYdxrCC#SpC7bBV$=ufmDdSA?w&VQeUu zK@)8jLU|{DxEOo@_S-}eOh+CU?1tq-9tajsLeM<1D=v0zqC=94dC8?*tS&F$2&wxy z&B%+l{3qq}XQyDJuLkdEo&~bHdYEW$i07uoa-4-C&WNg^i3zj7cjjMOJ5cJN=dS_N zVpVpm9l=|oM(_b6K%ej1g<nFi#cKa|Pbg>lV3Rs1}0y zT_o+~V=&_oKxnNdet4OL{r7qCna3%-$go=c)FI7-r$us~0S9P7cU{I~{m{kOoF@eN z(7E;L_;^YWUO#iLtoH#K|9rNdHoY|mFTEgK(cy?z+g&mBjRH1L`vfs_g2j%!&bWDP z2rKL`r(vajSXb3fyX91H=R)ZYvtT7n-r5_l=0=JqkJZBcF=p(TnJ%%Xu8`_^3$g_* z>?F+#YaI>X{cRO6Rp@{t@840eS3A8v9*Aoq0+ zt|ZEKI9{ZR3*PK>MiKp*zQE2oujp9PU5Z{~jP5P|_;clPs*>38aeV|V^Hb!5PJuXW zKxbi%L`oh3HW zEQ2wavd#r!h7TprWmDla$UQp_3x;hn62LFjT0TZTt)( zw@BZ==j))bcn4g1Spt7PY@>@iXTvScJ7iPhOn%b5qtAl=eCCQ0gr3*oz0xyk`Kb%= z&%_)ojtF9sf(3t1@60nz9C`o#k^Jmd52+*Q1zmpUq5qjKxTjd+x=rau^PAi$wtpAC zGc}H_Xr%#6C`CWpg^tMdn?EN-w^ zE?n)|g?Eh|1DP#a(0fon^z(P+-McQ)_#|hH*yYIQGMXv5FoTBAD1wqK;15QQXe?!c zZ7u|(FV<4kqa@Cx~vu{VZn=>DD0J|5PMCt#}IE23qpk<_FNe%!7T`)7m#;3t znEDVl`(ww8sx{DR;2n_vn9I2RH1v*Bp+C0*@ZY%_VY+@X1?fJ7$V-Q0bzY~%PkF29 z&$3)Rc&J#Y8@-qGdP|w7#F0GExPcbjs;1p(%LFI&H*iNur*ciDCL38CC%+Z}Z8ZX1 z>(YSUe>+17v7y*y1M=x3f!LAXiG~~rs7m&E0(aMRCm#)Ouvh#{w>6Zx)En{VW4Cbr8 z;oLN48C@8f%;9&pLqq*UIyegO?yN+#_w&I(>ArJ73?YqLA2#axo$}@-qF4QTnxNYO zSI`ZIuP!HxyIE|lFjAb>HBktETSJormcgk%CUDxV4g#{?!&>hfr1z^0#+qkyz#Vx$ zEzLPsTRHHUvDw%*wF90VcE!IN0`c9-t3o%)h4X5bC9GK^Il?EZa*sjdXn(#2UjJGM z9q&USTCGP%H4RH!zJ47JP4akMdQUpFZ|@$ zm!}P$D^73ghZDJ0IBRN*KQn^)KDhCYMm5~FZ3KC|_)25y_rV(}+q{3bk6V;uFUqwI z#lyQ^yQK{@rq+o4-^h9vEsoOqcPgU2{qPFrX}0War1+2V$f56 zeiC<&iuaDhL2i4vGWs-F|J_AqQ`NBFg;nCAd%@hQ`Gt<|iDI`y%V~;Em@xiXKIIJ2W=H8fcw)03 z?phR2{%wZ=cK)J2eLHhhlssjb>=KKYjmAB4)!?*3%E?y8OZWL|w`m=NF)6@~9Rr78 zj9~)zTHwMV=|k8uTI#@NNgK(ti^1o34LBVch)e90alDjsUE(}Lbfy#Vy4?=Dl?3AE zyMgE-?HA^19;VA@QE|Agei;FI*bJ-Ffbg=sZ%fHo%4R&YXM$aAaGSrZjI^Blx z!}2)O#0*Yd*h<#A=jlTDYU&s^jE@FQqh0=4yeIX6*!5FqbZTbLEX5*U7bJIg}m}@RO4_UTx0csXIEeeUUAfBtC;J9ZH<@JQR(6 z7LwxQUO4vfApH5QlMrnFo3uZsaI)GenpU|K3{xw_jxUD<)xTfqyRIT{w&+JO;zLj< zxC?z$2lD7$uY?_E{|Sfgo8q%`d9-1lI>ej%@Pu*s{Pd^?EDM|^Y;}$Y+du>U+-!$s zcQd$MFO4tTSJHu%7HIp~fTw)X=Hof;qH(7%ZYUXr>!(+XgUkBkn>uqmwO870p59KL zcFsIhBSXq_iD2C85M;ktC8SF4$MvnwJQdc9p;G^3RjNPqaE`*GHjdc5#1}UOgwlfb zh8Q*_fD1RRptXN{;OC=D1@AXGsN883?Hd)q8o&KWeSACYt~bPid+tL2(g@W4Pz}!p z{HW4Mo&~0jGPb%l0I$vN$6NpVNOu$mke`Ex@cM2V29ERMM(0)3=kp5Ev&-hRUP(M_ zj~tf;81b-exi~3I@|}zb=5;;PIm{>>k3Y;uqlPF{**=q6ua4kOCtWDT<`UP>*^EIS7$&&wBmQbZ{9M`0NrH;%RcsOP+i2Zt^qN5K#sU69qq<(hg z^S|PN6$Pjp9f+G2%oTDxqG{O75Z>Fxk-MDwEPQKI6z%>F!}F(i(2{5c>T4^Jq$w)ppAmVxVAIw>x2;SFP;Y6vl z@#^8m&6EQQLI@dD_r*mgqj6bRcbw8$6~}uWqNjbN+!x;!mCoC8oN8a(`NoI6W+Y&E zjnpykl85gm?5Wyyd?+b68Kdojq3rNDf#*K70D?t?Kabq?s%zoxFoV|c}X!*F$K zcPY>EK*(=5!B@piRQ+%j(5znQ>_3oaSP`ms{-qU{|HW$mYVQCW8ZN4WPc{CJf-pb<#JO9C; z%S_eQS0MbQ0mco^;TgAk!y)mr_@}f^T=Fmw&L_dn&8Yv6E;w&jBCeUHjOMPpr2Bs|SFSae{7luP+>wRzuD=xuu1W5&Va>2qI)^;U zvBMRIz4?*tIQsBG9W5H)!bgih$ywQ%y}z8GBJ;nnQtJ;8q7Kh70~-8>3TIUc+$ zYXm&D`3w)sr0>ndY&KF-;CZI~uwbACOqHHHF`?QRcfLsU({QJm@A5HGZwhSG>x-tA zUm))l;+k9?Derd;UY{1w?`V=3Af6DHtC`?cvp0gd{2e&b?g*b+WKiEA`4>0rrA3E4 z(L!5?l+3@wdF6ES8c_i&8gEj~8yk-K^x8$CQer;pxCs?$^xYK4u^l44S_G|y>(2aUptMHv3pHaX;ZFabJZw9VC25ew<+I?DA=@w<`0v4seLbjtF@GEyXK4mdwTQ3b#^#%PB+*% zc^}Bme1%u`k=)PO0@c2)2Zdep$ZG8i7~&+c0Nqzn#piWk@NKv7PiqJ^HTA*@dJi(` z-gx2GPa5>u!gXJP1;5k}hBNZraCMQyiX;t8miljs|6^l4_QdQ}mnbr52+#ZdgRBQA zK+41tn)J0ZZMfV(^CIkcOS4Gh7a75e51nz(k8)oX_GZjW@n#MylGOTRN3$Bq<5DWV9_TKHrvDNjPEO-q{afJ3p?>^p@^Bc} z%a+fs?n-~88BsvuLHIo8Jo!vr4et(iA%~w?+j{iiYM7XxRii9$~#1ycc@$ zK(#NB-Z2u5oy}-s$qP_iHJS$gm%%%4?FOU2zk~}9l<@XcC4Swho#uV%47#H?LghIN ztS{Ds(%tT$aN!>Ob$8?&6&6C?!cn}q=Oh^Vc^%2et5DL#DdLZ${jd~*vBW}|r=Qb+ z=$VPI`F_3RTpj?|R%r9LK{8&Zn$N{seejcgXWo&iD3pEB#!YMEx2wK z4?))l@UxKp^yc;u?$cih2BkZo>Ai!LJh>B(`6AD{-w90C{)VXuDQxI=hbC-{ME^gQ z?6k*$-QXL{lDa*zqv7;rB;d(E_E>QK3~l#n2hV`*F#K9>Rix5E`lf5oElWPq$#>F@ z# z7vD>En(pc};LlqbGFk>LPn=Yk+Jlo0>T=oXIpo4q z>HV@yUb;pkh4={Wun{xg3GJuD;0 z^JXaT3Ee5kLerck|&E4%eIpi*f^^z>Xjo`33$(Bvqq#-vr+&rc=pt-{h}IM`&-HM zUc^!P=FY4zw1C?_4ae|@y7(n<7*kaWI?C+uvwjUYVgkCU>eHz^mZ+Rzk2qQfG#^|O zbxcC&?t=(+9~jTI8x6>JbZ=I_u|U?fwl`Nr_a{qof>&pk3R-7Y(~1=XQFBxS^i_@! zFPh2Ygc+9TD0$kl51E2h%2*-4?@vgHj>7+nJ?M+PIax*6^0t0gV4_Yx92V!ymeRB3 zV9q=8xP1%W$e#vX{|q`B@5FpCk5_ISiK#y%$Jmyaq%RwYZ;mr0C_ba%ruRws(Lghv z)QK^eOrtF|@Igaw)E_;Zzps{-M1}|G)pg0iK&ikOx?S9ObeK@pmB<`9T zAhc}}a9jBhGVWeNQ~ur;qg?I?gPuzXe1kY}aF1Y zfd_Y;p|tS*LY|8QmrP2>wx{}7RA#^dgW9VMPCOLuTN{XKr7mEU8jJnQ=Tl7HS~?S` zkMXJ&yl9yXJ|6l6l1USnhG%k_QyRLS8cx~`^0>IUmfF?YD5uIue7{?Rvgbd83darf zuZt0{$Xra5I)`yDOHI80K@{8L*3-T(i)o+g1-G*i!(mjU2ba&V!?q+P;)f|h!Te)n zD(%&RBwuOCmjJwRO`09%n9=>-);L4IH%%-~guS;lIOp;UaZc2GdMmGpEi<=>I!F8R zzp}|R{P92zjIom4JMj`=ZkXiL>C96V{CV>J?pTyxMh{ay2!EA_@WJvhk>Bg^29+nG zLeLrTdR@SeM%;pe`S0nMx+_1mn*|kjhT{b5K5Ti#mN#e?aMGW0dS9c%b>TyiTsA}I zuAOvtzO-McF~F-PDp2xT>T1qQ#_l$n{7u0CBc++rH8!J-1;!X%mP5lb{(x%b0Nn3y z!v$N%LyW~B-ecPgHew*|s2(E}TF1$WS|pYxu1Bc??S**(2o|gNBbNZ{@eW;41X8QGo=56;u}ZckB1JsO_)dO1HIwdR#ytw9YN{h3RA5VdG zh$#=dI2^yZCUDZ+W(r@?g*7L;VZQXUx9J9)Y%-La)~_Jb#wzjp!KYN%FBc8QqHs{< z79G^@j<8@iL=DuWhWDGG`e6*$wZ5QU?}wwtO(!gPcY;hx4S1Pa3{U9TORiG4tiiL1 z@?R84d+S+rUuRln(2yXE`65cZaCLYVp3YXWU*WCR7Amx9gukCZfX*{R%#C{l|CDyp zj%~J(;53~+p7i69zgAFMh81rA))kZ0lv(A%NmyrLhob)M%AR&MIPPdZ8@@}yz@Z;S zYdJ+u^F@A_wG-~^hvS|!i6dTYDQ1pP!r4*baP5T&H;zh|g<57~dQ~)CRm>2)&n%{E zbAd-2nc)amsq0I9SzfgqEKXU&-xUvOiFY73uQ7t~(3zlUVTd|YL%G(zyEv@j6Sa=r zLAw?_qc6ehq@1uGbyP?Wmv)pse*rX8>V{POc_V1}NwXx6#o)2r9>?_3kvM{bd2yuV zGub^3#+OK)g$3nX_l;lP(y(Nrig{?twP{Y;c~okPaIi1_Spykhkdr^gLmL`4SUf`?oERXgVTJ&{_kl zOl6=sAqi{STPZ=kAIF5nu&U}~A=>FF4R(@ph4uw(kz-0lzr4VDlP&A|sd38F2N0M! zlAmYy!e5^Q>3m)q8!Pp%nldSoespc_{P$W}*R|^YP@z6(nr#PjZ(KkIc8^0VSs?VO|mRTBCu}-e<$< z+P|`f6)Qn+>kYbf&k%1(&ZEOix=VM$e9U*#6ugCII?{a&G+EyQU8P#_pVx5KJT{zN zZJlWN>>6Qq^c~S-mN!OTSHz9KE2X}CFMesNz`dsj;9lv@ym`z}?5`aPtE67aN4as3 z={|*SF9?E?sE@SnvM*Xg3Qrz5O-MN0Abyd!$C3Sk>N=$gM&m+o_0F|$%D0+U9o2)M zN^ambV+vKQl6HTxU!-BB&H1PX`=hd8iIN!(yp)FzEMj?6Q(xh3r6rynRSAndm%JyGQHmnUe);WP9o^n~Pwmct&UxwKx@guBhP#S0%tgCcqX zBR{S-~K)B|o&QJ3L;fbpQ-VHZlZKt95%eQ+eq9sTG$@-Vyvu>xu|HtS&O)@^Ho%Illc-z%3QM zNcGVxA$#2hSh=R2Dy+j%bDJ*5ow2~ykYpUae4Wr-I|!}hHVdb!6wvhODll8!Mt3(L z?k~2*Zhh@AGgj*7Y}!K{8iA>)zo@In7O)$C1s)u-!PUDP!L!p*u(B+KY3G^LZguB= z?~M7LO|Y1){E;FvQ!wVf0jvBO&i2=G`9Shu9KU!eb@6SZP8)J~$}<78CWW*AqforF zOO1n`%!Zw2&2(v{ACI0mf`1(@q8C3F(!1{$;ZI8h40+?q4dY+I9mNV+lDjFU`g`Ib zJzY*$jzEPMUBxdGCBOUP9b(h`EDj!%goiycg&S)}aP@?H^wMkuKJzk%7iFG!uH755 zLqAjVzeF-o1U_sUNzS=%;pYwwuD=i_4t{h;7$7Rr^$J}I&{yR%T4y0QP?c<)-@+8QjvOFLvD%@Mv)oM8}- z_N)iTnR4)PnX_;?VV)AR99n%`L~dW&XF8a));V z<%$f-etVLZ9eF{qao*_ZHxusa?x%BWcZ17>v9w}uo_P11#O{%v*KjZ&-zIm$jVhhF zOI!*T3V*1}hfgy3<<9K8!&KlPKv$d1G%{WGQr`O2~V5RMpL6Y;k6sO{4sbg=>ND34Q3i- z>ZnR3&(*o_Qbj(0U_6IkLg?(jf^L@jQk|(BHU}IAZHM7_yURDYbEhBd5)&X^{sCmj z=gHoxYq7$T8DJ!FL`+|3qZrpH9@;Y+-#8j^$i*#iY4~|znfDCQIk>CXG4l`H3>^+d zo&G?5YY=`c`9u*Z3n9DcHofWU$S-SF!pZID=~PD(O#fz$c@E?7O?ftDmp6m*vp})` zcuP>2D?^h%Dm?3BFqF2=B=L_i&TEu$+2-kV2()E$3^oaBHJ6~*Tm|@%-Jkay9)j~p z9&Ic-)2gTP67OLR^_+YR{t9vr(K6nshc|$yAOW*7i8sr9yPRy#)Lc2Xe!p+`YN**;R>+99{WPe`{KMyazv+vrAAs_?9}NQ*f_-q+oKTOq`W5j8@#s zpui8tJzd$^&w%icJSp8RfbyPo zVEiPKBDDfwr_=*&+|^FO*8Z4rV=Ddqtu9W;`vCe&B`5kUH@4krjLi)a&%^$24C@CBOaIfB45TvVVzkQT04Aq^%_fQ2jk(+ zg&~jWOV5{5E_w*ZeJlXYw-aD>#suQv6zqD%4sI51q%Df_Y&BF5HN_y8=J zyN(oIOyV&n!I%|YLrWyyW8G|HdNpDIj_^*FdR1dcVY5BnZW&tL|3-gy&5xlqp`P$~ zY8TkqaFBLAu7g<%08@uH=sAK#Pe^X+ z3X0p2D@@KTg1#q|sBZT`YF%tYEx{A{;q!0swstu@|K~=}!k3E6b%ye#hwBAlz91-F zjK|Vt-6*Ri5myu_;g*Pdl$adLJx2ZqSJey2S2q;%9}f~!f9Hxz+D1_Eze<_OEy>HV z+Fbl~%GI@{rkSox{{g+``H@mnC+KlNm!BqdWotz(ni1n8W$eeZ{wIIDCiSbI%;-c< z3bkm3LSLSBql#9SMq>Q(TF!$mc3@{tb&cXl z`iE)3ntno*QV`zSSuB{j%h16s7ELUh#YuEpnlIfG3YrJfw?qF4MMcB;z5EntT3<<7 zmxplwsdB==POf})RX1|6_#}LmzXh=^Ryg*s1CLI01-}iJ)y@{rAvhv{BWx3~!elt^ zo@Gm3qkLKElf>q^FNX)8-yxSrzoa~U3V#=rI4&xl-%0t7?A>!=nZiIA7Cs(+_>bXr zQcgj)M4t=ezra6MrhnGK=)Kd2?|$!#-8EK=p*HpOckfY%mS$%%&=St*ET+9}!%(^L zD>W}YLf=R2fWA7?{_2GpHe`e$z83i6f%z2RF&J0vvV@VdobbsNbyNv9U?bzdaPgEP zrv_NCqnax%lG|Eov9bbMLtev#^67NL_kiqvr9ZGqG^(8Z47;6!(f{56=r$w-Qth2F zJu4P>c9g+`7m|W!UKDNDl>Biu2ql%4k_UAS2^EhhcS9F^`Rq+~ zdaFG@9gza9M>fKnA?AGb_+xkzxRW-k2jSW62?%Efqqo9-%KWXxxru`)=Iae1G3KnS zt!brT5iRX>w@DeOH*JE|49T~Bb3Qpmb`UenY2UfhilJw#m8>GeDRi) zzl`;UgX<%3U`d;6DjX89R#*I?p~w{rpTO%~=6IvwEy+oH*Ypxm&^~9*VTIK+OKqXB zE4U}Lx9YhLy`KO@+RMeGLz+cR+d%B56pvl(d@;bHuc%h$KrbdMVqSO^T^>?I!CSJ$ zB7Di!_oq_(m*pg#Qog(+z8$BiQ({8JbFI_MYJ ztgaxrzL7ZUNhyr#G7x`^31a7yhsi!j@&-uV+nUWUXo|89|99CRYft(`D80B%T#Dl&5|0z(>_eJh#tZZi>Djodf{~2UKn(C zG?qUM!FPEf*wSkYO>27qT%pYU_T3Xq73H|;p_E}b*9dQu^T|5;I_j~wMhQnB>I&FMMtZBQa#;1n9I9z{)4 zvPBE&j1TU%7-r~s@al+xoHp4EQ`Ac7L(E`$kt@vsZcF<7k&^3=c(gIsyk;hNIf1c+6~BTwS?tl_)25 z)h=sg@V<8mJo8up;+km8eN!L~zdeRq|5=GQNBQDi&rv8e>7ahZY?2?d6FjB{(GSz# z6kO0u4y9GFBJe3Gd_){9{k(Ln8w0c5enDKk8*5JcMO{qHg$D<9u~P0o80R97bNst= z=M(Rt-}1+xbbU10OV747+xE!fH{GO_0~Da3K8mxI!syd$IsP!Ruhf(E!KA(hwC;Ws zylwQtRa$bmYs*XVm^cET`zn%;fe#M)xQo8rmAa@AU9i-n14hh{oJro9)aTe^csjC; zyqDOslFSjq-d})LiT&aD&k|HT22;Qp4YoCTE)>P*k*ANo_-?c_2X1&k+uglLP1Te) zO5K8Qank2~b3Zn{;m^ap10`OrH~x(40=bo4czK5-44GL?FaGYNc;}(~ZBhW2m6_t? zjq~8c^~s!SFo16kZKG97Jh9-eKd(~of@di@xX(EnmcKp@>u*@o?~VP$xy|GG^TlBt zyil2Sx=Q=)`!2le(LO2}yn$Xn(WBWe$7OK12nO>)_;)ijVujIvpUJ+ustcBt8GNubpI-0mFZ@1zm`=K!qs)d=)q1`c;oQE? z`1#E-%6aaGS5vw$t{%@uT|ChCT@VXFpM=qN7T7!UHT?BlOIZ&i@%^xVxO}@GcW$nQ ze!Xhp#KQ$tF=GPsn{$ni zv=5pBPXC5-rqfy3x@*zAL+bFotm(&V91yRZybrI=oT2pL665v3WpPfQe^B-00z|DI zfbKhy{bu!t+GWaU$5K{#?ON$>&_Nn&w~6lB(tWp91s#*@(PyG5s~V=_*MCiLr`;c$ zV#ec-2VGfyQwA5$a^lZ9A8Gvza}3LM^K95_;K3oJVPo4SOnapkeE@WDEio-J;pO&9!xg(IXr`>%BBbjSmL zn(17c?KUshTEM>fRmHT>-Mn%eJOm0VWWpgnqwY{N+nJoD=#ESJvY z3%#ZLfZ)#e8+&t2d?Igat#ExW3Sx9*IXS~<44WxZ-f$bVUq{sP@ErN67DM=uZ}6?l zAYNdkfYcqf)-i9M*et`kmr{?gP!B@M6+i75%RRa$@j1stY<<^@W5!Gs z)|FX+rOpId{FJxQ>G%+MzFm4xtNKdH->vb}y>hrk=D7BjHvWs2xDR$i*`s0z&K=za zSKjE1fd>1;^miv_LgI{ z2i|CBsR8yzC+MT(LpG6EUV0zS(s)xT@0R3e7b>I-uKsLX;*=?{U-qGp9<83oA@aa5gOc*FRB1>tnwE=(A(4#q@vSDP1 zDMYI1W5fCNG*ZW!?R@dJ#sBb6ha)n>^~As{q@qB<_Aw8y_tg zNIIrw)xSbx7=Av17k94+YrdOe^Qao}-CxN)8{&wMFKrOHvmzVJ)0cXJJ88)%Ki0Q6 z1pV8zc)!V8$ao`VvO4**Rm6JuFXV9~OWkRJ^B9ge)E)Kfr8!`MA-mr+ z=j9&KY`s$tu#j)7p3=z%6$8(UJ=~>y^ja@8kC2IOBS+G)_3?N__Fa$-mB$6n^;ELE zp488WLV&+17xiR0+SRdL4r*}l4qmDQF zN?Gy8hkWqeus-6@Mn8Tv%Ika*&fYyqX05m2*QO*4%6Ubr&+Bpb>!)2;x<|m9)x+`i;9rnA=(j9cx-0b^ zagA!0#p8@KaXiX;Gj-jN%sUiT01E`%|QiPTe`j=tEVQ zrV7uujO8`^jH%CCXP$rZ7Aomn%xaCP(@i8MZ~X z`bY}*?k8~w3%`oCN$L2^M*)2L4&n8CBJoGh`xKww8E4yoO#aM$NVw!J%(&-`UnWmv zm8NL0+b40p$0y^D;wR$MF8w(;VWQ*{jleO%9`8k z$q{?~FSBc(fEB;9C`hX(YOqm-au8sgK8(aY$p8Gb?C;h?v|di;94sfIM0^{?fMI5zE<4TX0~*W zjo}_?;hYgW51LKNpksjnN5`4M{5?5TH+d4yJ^Ko#kMQAX1~C|NUzx=MeXI%|&tB7N zVU$CfxKYKDhuviI!`}$-ZhTQSiZGWVv61bB@|bOeQP#KXFjD@wN0mGI=CM-+K>p^S)Ee zpUa@{_!b^L|3_lhLD##j*I;H#2|Xz=;O|PqxXsmz-HycJ$EN`>{6bab(P3fuL)!~i zH_PFlc_IzR?l9A*J9pf76cu9BAt5&g|CJeV>k8=^8*v=!AGxrk#zyCY;XL-YJY2cj z81jd7JnpDh?hM zc9Oc2-|5)_d+=IiMeB;BT<$?_)R7n#!SA1ftHhEJ5+nKAjNhWr&kF0iu7{WDLD*O? z&6F1e@tzJ_?tQL5AL!i`>-3ay3t5w)N+b`>%!SEwz4>|MM!|bhG;JHH2Xp4wv%Zv9 z(XLFu1v{h}!#%M zSd)gmLmqE(1w+DZZ!U=A7(5^K{rI|4XX8&MQ$5}wO7VM!d!;V#>Tj4 zjx`5-)2pf#$AF8~d+JhSPOpZyNVzpOIXB`(KR;(hMr0)>0cs%+xc;M!|FXGzV zJz!ziTJ1esn`cb&CW~3WD9Wl?9Q;Rz-+v6nkfJzpQSXaahKE!4SB22h&Sf^UN`t*T8{aqSS99Qh~2KTAfNx(hHcs#5r|z7*;` z$BA=4tbh*G;wgG*II$=d%qu~#-Ea*&v;5Keb_wYV%IIhK9F|?y=D)Lw;a%SK>K*3l z=>Bgtpk+0w)TZMXPu6K zbdd7*H^Vu>dN6jDTpP9ODSSdp>XC*YB7^mvVZiJAbk#}fU7j((!me_7KHQr1Uf+W* zwJD&YHeB@TdyKxcs_})hyM;X8`9jk^4NNfaj$_q3@w(%8X}e7)ZWdhFZpZ+z)tW_5 z2Ih%LVN0stWhVkTQI6(7VtrQ{(n%eg2P4nup#}FhCBuR{Pw4kFiSM~(ebr4VSG=RE zBR!G}mDxYOMh@>*R(DBtDaRaYSdzpbH> z{pIlL5^c7adzRj_KPG40q;5YE*Sp64kBKM#?qS0ISx@O&%<>26W|i|g+2rU zzIw1%JgN5&z8~9OT~(*gF2N;mHMX2ym#ripDKjm9*@BnZucrYGn_%p!%P>x7G(Xp0 zLc_}?_R6s+-txi;A0N3*TJ{w*OnyAqj1T2MGu2sJejnJKQpR1$bzpn>0rXwkOf5Qv z&}D@&zjB!@zAxQOu2Erl_~KjXLvRRUEB_>zEb|QYLQ42JfpBlB@mL@CgPM&Ls0wo3b;7h39mLOfbGBQ;(~EXe50F& zaAeIR$e)7vp_dPPZkM`K`E_7__b#nTc0lEie%!BAMe27w1Sg&0cz>@7sJ%Wd7;SD7 zSM*cn1Tl%%&vd~dBjnLOv=?0R_aOaQ-l#JrkzI0o;qrgdxx4QZylU{LwC&EQs1boF zPg7`cg(hbXl;LrSH=VaEhC{b3rn$Y7ag2`%M=NiI`af&wN_jMIPqD_IL7Qmf31wa> zzMx(=jB%W%5qIgD&OJ8A;diwWpk>>M12#57Ql&L&=CbH_m7OHYpLeD>zT$fxW?mOm$XLbqbIX@l)>&J7*kT|Y5FUQlI zwQ$LYZfID)RB${p5S%9k@vr4MG;4z`UbN03zbX?>``|@uTfPXdj@rm7`Lb}`)uP&R z$8&nEHh~ou?h|Q?fHk8mWvMRFWN8)2o0S~UUH=S4jmf65uaYFj^Emo1BV9N>Xe50+ zKN&l_Nc;lDOzz^4L3j7a^8~#(Y*4YnZC@O*i}7?}@OvFt8)$|~hdYb9#oIcAPJDJX^-|iSZtE$`5dI+BKM=IS~DV ztSBrgS3GT`$Su!$iYHR`lah7_`EPK-3m>)7JTQ@G?|K0wM1sou9Pqp#qYRa6q;w;M zlNT6r)$1U_^5MAcVwSM)N+LF!H^aW0Wx|XJD!e#W9ZSm`c(ZeF+;GN~O79HEOOa}L zV!ak8N^@-=2Uk(8ldz!)J8|4g|CwXc&{HTN^Af0KG(*G=$y zq9VK9Pr=Ql+4Y`ka$cw*H%_Y9NmH`@Kj$)-&;tWkM02d{QRNW%$-%Hg<+WPV$jldB;{>U zoN}ipwy6&0x1cL|+WXK*zY6i_x>KMT@66Xn#BlA2-?Z$DZdGglEUIi5tr^^7Vpp{J@kd-Xr4MPiOre;PcHy(sZ^>G58}8}O z0+U6*X@JCCQcV*{^JWmr0w;3l;tp}=_h5w3V%S#oh&Fd#MBelF3h$pShI1Ohr17O6 zUwUSY6}D+;_4v8iqgjXN&595L?N&i=*<0ydB>&$N8fsuF zPE~wLSI#!kq|47_dFSUqwM{g(zz5+^xHBd!m8`;9VD6L@VKzkjBF*w zbz-U&*EH%%jQ>?2Z}b61r>DWmH-`kjV=g>;O9M4l5Yf4B(r)yLFmP@H_)49|NgKfI!i z2gl->6NQwVc#VWjSHReKFq(GnB0K(Gx{FF2^e_Lpx^DjatZMx!QFzwZ4CA&&Q1yK~ zlxeM_RrH9it^Exag-Ou#^SdY>NZ>UZ60>ucyx2D&7VA>S&>5`? zNKZ}1*q__!(BFU5*?%nOxqpQ<>$~tLpP}eAV;-qVj;A-Oz-oiX@%&pd*tXsg4-e2o zhe=vIL~=!lwvXZEdn5KRJw%Nk#_=1&-B8-TksM=_Vb-ak_)M=!*!Me*(?@j(inE*H zadjA{M>L9hcbh=&eH41H%Y~&kS_Jd>RCso#54K9K&|hixILCJck20SCOIEFgy92yX zb~cG?j{FqP&h~}Ft5h+fTPs*5&8_}?sg9J6{*gMSlhOL+7>0an@T}|0!@bI(@z8nE zd}sl^+WHFyoIg|jU|%p#K4ZXRX0D+ATUW~Nm+cqVMjWQu{wd__=YZQLjlt6|z0k7L z2;2~@gKuuFtPJ_4Mb*nZTyH9-mA1$CE?JMhg+nZF&C zL#6#`sCi&N)D=&mS#}I_R*d12QF5>$^PE_IYrM?I;$O8_$~yYDwm;|J*TDtv-C@`+ zfkop5u;W4>o_WfL-D;MKUc*a4{%mJ1+4cx9b}6_Wj}`)l--oYWndm)i3@@7ZSO~Z= z2QHN9z#Pqb`i~=ooXjp)>Jy?S;rWb?nj(al42{LZ|IhyxY=}eQlZ_dc; zpTSjWA3SdRI5e)hK%EvJtM09F0eYVZ6Dv>X!=|V+)hDI>{`rao(fj^tct`VTUr!^r zK#6EFX*D(6p1{kkB(~t6!?f;{HoaJ4BDN3k;a+>=*-ot+ossq9`yE%r6A3$QbmTR>zM+r;iG3 zHA@}7En5Z_vIo>sGY6cCow0QL5Gi}s3m@-vkmj+0>~ncCSN*A^*NePawm%jVI#y9# zvJW`L^hafbt<>rs26aCid5q+wxGLSbFiB$U)fwQnUw3Gll{0?6IgSsQY=zLN`aHAG z5}<9D;B@j0D$oqZ<}bcDv35J{T4V>CA(D#2E1}#&dOrVW&!3OEv&=$?a}v_gw zqi%dC;6HI%Vn;Znk9K ztux+QHHsH@9ssKOo2f>AH1-|a8Er{oP^}EXLDp{EWbl~sXKaTP{S@Frz-ZLYGQ)w! zgYapwu5eIlbsw!=1P5C(IJ~zWE?iU#HNte-Ww44&GMk|}Y#g^9mu59f;?Wsu==nk) zo^!*4XEk`iq8?rFZtV_1?~N-~a-|q_>jUUa=z|HtKWL`MPWal>hPiq?YFVgKh1D|f zyYyBZw!{(Vq>KS`Lwnx*^#erDpAN+hG2Grd66X|DQtGNY(AeJxJ@#y+Q9pd>?|=uO z@_iItj|>6V&;a40(QX*Mv=Od{4&bR@O?lyu1;WA~nPRKQT$28D)Eu>>dYXdd0E^p9 zt4(`x$t-J570q}}mn6>p=f+z5lel5W7<|;D2kDha4C}u}pkq=)ul2KGSw=cGNiMQ% zw{&zJT}XEoPebLyqvFuui$Yh4pO}>Q9me!3B$LB3mu~Y%@U)6If?S;umkKQuVLOSV zUw(uJiTzRX!k_=FiNjv2^zr`GAa*#A4Us_w;CI9p`?`0gle6PV+JvyvG%casYMXHM zS|$9EOsW~3Glk|SQv|IvP3#vMgfG0^N!L9Nm)ZQ2`Hi&Zl}!@+z_CDbL%b4;O1hv+ z^XAHT`H|G!qd)(8@LBMwHo?DZm&2}pIpmxAN$BDDljgo#OoRO;Cg80gPVFtdcm1mu zC(9$Xg2-7UvQx6gqm*Ms|%pJvfzumyJ+c*w4oIs8PN~vBf0Ph|;&?L=0 zvriR)=d%uSxw0D0Um3;+uVmmOH#1%=optutI#asq2MBL`3WFjgKgbU^p6B*h>g}pv zdhSK>_>e2`Y*z!kd=)9qDRyTw&n()uCBOPym?5XyR8Y=fA9QHH>?F+{j0LG*c>e$mE%^-HW7mRSc6Z(}rBtS{IF7@1{DmIHUAgA=4wy6{ zfwL~0fZrqkipI0wz{!8t!6Bxe&W?Qz!d(T9Z#qL0rY2+enZUz_zo9-&GoZU?Do6X? z5Hhm13i@YdsCFp=E!J3a@8jX(U&DAVy`_XFP9);9gDO(CMT;LuJ+2yQH}GA?1t$=q~#H(ZndM_#&bAtdw>MW`!-cgzjh%$ySTxx+Ut~-V3E_ZaBZd93%%PP59cGKV6$8OTSf16JBi;hDhg}T4gf6 z(UWpOS|Ql~nRLE|Xk+5CWV9{TMz3Ca+^_FAN>Ck-)78gw#)(_dUv&wL7;nZwJ16n$ zASIj^RYt4!^d|k~1JLZ_d+F|@$!`W-6#ag8;txC4LZy)(%GF0;Mve^opL=#9gbGXeK{byl=7(?Tr|t2cP}L`xtk|;PBY{0_MV*eA_dPclktn2*9kgVprOKC zGHW;D!y(?1za*0TUNuCG6i@8x?2Ua-d=svyOybT>r8II}uFx(f!~A<*to`gcsiW)|En9O7_7BV= zq3#FFmsnSpQoqpu!xxe}qR7@|6U7q;=7Ya$A|A9Z70(>h0O~hjOPQCmqWg|ZG}Kz+Rk5RI}N{4X+abx)y=H-ZRx_X z_aZoTcL+zNoPdN+Ghn*h06O+02vv@)p|e4%G_`L64jZ%$E>5yym0%BiKi!i}auFzyUi=$ z){z>@Gtq}H$MVH>XH#L~TPw^py-&+eN`94q6yEoFB2WCP$Y+jpL+6K0)g1={VDRk* zn0?5S!o8P+>Cj@=AJQGwDrF)?oOXc*;c#_FdS7&&qJ>F?*P$(0UbH=9#41JJ_;6+# z&W}_SBv&5hZ{95BGWu}6;asui$bHy5z*#)7W-TZ@x2C$Fi?k@M9BR)TBKv!~IC4t8 zC~PvK>NoqySXc5Y{f)=<65lA{(jzEKT?lu&Dhna{jn)23J$Qx6C^FGc#A(ZbQ=0d} z1Hlr%3_{*?ehFk(aC{)n5Z><7!ol(DsA{(5ZdPqIge(7poTgRu618=WJCg&`gcO?L$+z)bbZ>{XRj6zHmfrdl&&v z()S4?9h|w3m!`NxPDVzXC!)pS$vj0R7ZzRgq3G7zWc9uTf)q;oP!ykNbV5Yu)XB%337CKbTo4e|JC-$^Q8H;j8E zIPm2U#@tiig6pe~%1X2cN$*`tVZk&HFgBP=O`wBW-Ay4|YoOq|*Q#peyIT6!dW{aH zev=#-pWvK-cXBkA@$e!W@#jJpPP+7rhESt0JmD41otFplUI}1g9!)=T6~RAtr?B_w zHn@~M5f@w@CS}tmVClbc7`OcewGBT@&pw;u+#lgMvhq;1-uKVq^!aaYkQ~#G%xIp3s@0_Q>=IacEs7cn` zGj%mMT@9m#G$nX>%N--R`NxBwBHFbwzhiuvrCxhFq)%0!2 z5241w1HFU$aDICQ{kdNPrim?Zy{jiJZ}}|T4!Z~0`Xv-2YQX(T+rjg9D6H#};i8-u34+ERsO^=x#wVSB+=8x}j-#9Jb4u^6}aaqRPUfWO_gj^5w_k z(@hq1dwWy$+cUR8(O?f0m-s@y!z23k=qSZ?x=gMHli+Q`7``g`J)Sli<7mA;gXQ|X zByF<}TEXYxkF-nJ*=Y_0M*W7}6S65PFjrV4{}uWf-GredJ-Mv73tI#kve9BqjLpr4 zX%~HY&6T0>MOFeiBV&2Si3A?lTb*O86kyTP(LDKE7@v#o%g))0g>RQHQB+wGxvZH@ ze*4@7jRz~~16&-2KsMLK+SPgzH79f&gxEqXq^}yeK7#KdS?pbKYkTv2kV@g?Y9Hg`pctph8kuR zNiJ7NhMuG1g#{(s;mKY*o*1yAYTMrxu1`Mr(j^sb9+t8j^0xF79d>uG?tLYU-{okt z`@m%UUgF1566gQU>@(1F6PW|=Hbsg@Yu1z9HeN0W*u7mVP#b_1ln4G48fJ0MwMoA6%c3B2tmlk(!eI9pQ}BWE0?Q49ZyV_z8I%`v5Lcgbj6 z$%D9Db1WYWljlQgJaAb|HU0dtouXc)@x;K()O&RjPao-yUmFd%U9`m0e_ueC`Dy%g zqc%Sqw@dJylgyt^BuEZz0Rms?!MnM}IPm;LF3@@d<4V55h!@$g^x`Of=%_~(y^quJ zO+7I7NG!hHJQ%+Q=K~FxB!)ad40)-GMt`T!lf4RPRo*5sT?OuWeg{OK>V_9IOdvUQ zI)yIp#gFgXqTzlWp|Ht>Rpa#NXM7pGnmdS<$cTC5bK&?9XI54F3iailI4@)}*LYu} zGh;r|knk@s$#NWBm~;s8H%LwxYg=Ao=}o*k2~*2n(TvZ%ID5YpkLd8jEz*9p+k++4 zQo4cGzHf$Z>pP*#5DUReBNU5e3S28QL#KXEX_NnYvB5*)Q^`f)y^<|3cDqpAa0i@nc_rmKJ%Hs3id^63gE!xoQ(E_A*sEj1MgN}DZ?hky>r_ug zN<;WgZWyjA58G_3#4C$d3oT1kz@bMf54Eu3@&(7CMpg=&BM;G> zry878>x>or2@ZCcW9+he*%mW_E^K$BFOqNSdxitIpX-C;Tg>@)To5Wq-sJQR=2*XZ z5F5(7VW(%`;qVz94pT3O`~n9W*xi!{x4#lb*iPhs^;$UcODsK3Od{jf>i~Zp#h$*V zICg6sM?Tiz=$*l+HKBzbpRnOUOMb!0;&h%_vqrr1;}{%1JqV4i*rKQ51HsgCv#@oS zwAOu71bGRk$o)_?Y?5|j*)Mdl$A3pj$Jw>hTL|9rc zabC_&0MFD%LZ?Of^kHHvG#Z(M%PtxJ_v=4681KoMM{8-5>JHjn+Yc87n#13I-FS9L z6z{K%M>p?6Va;7b{I%#17<5nT-dT{w0YgWjNV*RzfF*wgbc&73Jc0HH4;gNS?#h517 zGftY+=f9t1w@(p#hP@Mil)MoOmw5Y4}?S#nI~dZACB zZdiWoGPUlqLVLentl={Rr_K6Yz3ssPNNAleEbb$RKm4nNChbOHg?L*S6&8Z`U!?JA zz5PP*2^T(S_C^e!V$KU{FVT1D@3C9lg?}%;B97kqgf71wAi7I?ZdauN*r=OFP7Wie zh$VV)i!nBPAEYZI_6t6H?1hKpRN!lXnmFjh9jFg2qng9b(z}p92d^5)22Tgz&%+IL z=;HTfvBt0am%$W0HQ~a?K%vKnaK6&Z7%lSCnMGCX{V!iAnKKccT~|u`zBah? zTo2Fz$Tga4Jzvx04h8OZWT@oR zJpwP3q<6+IA$>0Vb-U7$_k9+1>FYF2-i2Te;;t+sZ{75>WqFT-LdBDCs2tv;reLA zU&{2#rg;y`AiZoHht4h&5`Nz*qm+>IN|=`O7d{s2akSzp zp&dFPD)l}e7+j4r4?ht{7bT*#V-{@R^@>JqvJoy7=Hub5U*VzN6|u~@7Oec$(RI#9 z)Y`RzANv*wKlODfb!-hOXD{L8`TJQo)s3$^9c6_ZeOa+}I?k$E2MG!5rC!D>ToAem zOMNCo!5kG)LA?a$9J@-N<7%mU&S0K!?-O+M?e6w=hN4?1i}e)qDFw?1y~ju5N$8Rl zjR(W~v*_u=mj5|$s+J9J(|XJoZq|zNLju`));B7jc#UidH<8?o!!#u$7{`WcBaK`P zkH?wt#!M45)rjPsXWo&?HVv_>BpU{eX|VldWTr~V-YkBzK6LFmZEyE>!|i# zL%gzV8y&D{L3$!Ni={qVFLe*hH1p>r&sM^dtgZZ6>S^t~E=O%Dc49AEd0w48fmLks z7+1w|Cl_5_GPVv@nd_oiQ#GsYnG17% zt$rWHZWBI2=u);eM2l=YO^t&vv^|A-GpW#f_~Yw7dqW1#c;R3@bWB??ybr!Q)D?{?jlVtUHnyN-U}V$Nae4(n7xWYY*Sq5-z#T z7W4EU=lH<9Tw4AVJ* z>1=+t_%EwP=TfKgS7f;DZ1vyyt0AF%ojCRFV<;YF#{=(ohUMxZy!=gXZoX@aD@RDX z;xB83&&T@XYHJ5!W^3jDQFI>eSpHuemqfP6$|^#kG|cDz9Az{lX(*J{)Q}QNQTB*z zMH$I1*`qx7=a53uBJHWAp?pyqq<;7BFK}JY<9hCMpYwjdUaateY`D8k4C;;=Kw~;L z%kRI!GguJIY6<_Ki@A)^G|?p_F6%6FT+J1`1r5nsQbv|<@nmz1Q;6E-4tAiW5pG`2 zp~v3W6Hmz{uzP<9W}O21a-lY@TQ(UYC6_|Egb;XTr4vV;Kk(HdjfkzPr6**oP-M>} zP%@B#^k+yP_zO3!u>A%%y3fG-j4*g+pig|cEMFs-o2BC zE2p&4e5DoC+D$<5SAsA*Vhw+cCkkh_B(lcej*+1U6EVkl2J@${9$n*wx&6Hw-uWF3 zP%RFdgC((}cs3E17$H^yT%OWm3IwD!(oQvHY^Hw1z%vkPjQ0T(cL0BtrNSd_Ijy8I zg$nj@w{C~;)N#HvY-$l8&kSeNu`lQ8o49QJ^s1iD=)c=-8Dh&|A(MHWiHaP zK!%tEXR_;W%>(stG14EBK~yyFPzl>x^p0(}$?$AJoI9w9%_Ds@cQ^&l4Nrm6Es?0~ zIvp0zx1x^80uZDAi7I`r!XSy0z0YnicEX_eKeYP`07x9w~m5 z%l+mbgsNTXG(y=Hbq5RRzslb};Ym#v1nK1rezWH8`{92X((yjTi4!kn_?( zXf(BeJ)1n8T8#IR@pvK3J6OW8wd=?=-+jokNj#GqS6GK+H`-ishiY_hM-wGG`rZ0B z`|jH~X;1#grYp@Lwdjk-{`!*%ny1M1F-@Kz$LSZpBL;8x2*WU&k1eB}gg+w=cc{Ii zKPK$LpWEdy>(OSa#AU^EFLRD~w_X~Vss&eLuTUAq40>*FAYNIU%>TXG8z1V%(8lO= zn%sK?7jETpezD4sn}3)rKe-GZ{$7JOr`#gFV#W|vO0lh4JF2-_ksH%g@?YIC9Q z;8k|;rw+8IMwt?x<7(ESd@+{cDK@sJZ%hr(@xHLG!u`rETq5P zLkEghWANWBDl#SsscMVyPlyJWBZ|g*8Nqa!(E(&H9Kc7$A>>DvJM~+TjF~euQD5LR z-pksE$8N@w%JN=vU1m9~UFL;)Qxo`;MO3MKrx9LZd}m*jh?KfZiEiC6!22bP8I zC$F6@u>sN!^zraI+In0Z7R~h~oy{f~UYA34a-8A!`)pFn^^F(3TLe-MWzczX5jnGb zI#m%_z}?-$;mZU;%qs|IXKpw{w*Iq0+ejf?P@YE$>;mvkU?GYw*hf@1x-(y#fGjQw zBpUZ($*`7{dp-9VCQZVf8w!bltr5+d zXaYM!Hz7Zwp8PlI6i&FELO!GfqtVt;lDYjI)piKuzuv71;YkHl%i0%>WUsSh^&{-a zZUJ_yMI>5?XJArgF@O1RGO?A_Sht_O%&C-bmnD_iHddX(j~v?E-^of@Ib} z0Mo?A^RMncK^>#H-m8Le)4-+8cu9?qh886_prNcLDuI()^gvcG z5L}`Xv2wmMUawzD&)kZm?@K$#+=~S`UU(Xn*Sp|=c`vcv@|AW=oThb-*&xjL(1~$? zzV9QTZ>=8{zq=D2ICxNJE>A8U+)G>U?|?^rugN>V5q7yy9L%3}jeKq9ysnmVz>b(u zUjH&kK5NR9yKvbNZk}0x|0d{M6a>Qw9&o@gA13|iW6WaSm@m<~Mw{H`z{lkV&_sn=&ft_KJFt{A~>%y1fW-&W8I{oCC45 z3iTf-fNsKlSgFhHbN-mZo&IE&Mg@bm^HN+_be~?a8zRS#CQ)9>6QVEH%rCXxN5fm% z$od>3+!A~O;-f?9*IZAGHVfpssVPiFLIsLU9V30bMp9~Q$~V|!gzsK(4m8L|!`?Qk zlQ^Fy2S-rPnGIy6{4IXnr6f8@LJ=CHC&Sq60n9nC*WG)O{@s~N|*IN;C)nF~1ZXsk5xBDZV8eK|za{bcM@5j?okEWB8Zog!5Ct^uVe+Y& zY{RTDh(6Ur-Oqm}AFLeETYD>d)x*^bX|L@*wW00lhj&0^9>{ z5Yf7LwsBr29Cs<8`<}()vUv$4E`JZbu24@4`|N05yf}O)xj}@4tKrfZg0Ay-vL{Ou zJ{af1Y0lf@)ffuQ@AqUV9ofF|4v5^$gVsx7xMWT8fDTAZ0OhvX@aKX!6~C;9-&^dd&4B>ADCHcH{=E`bt#HNc4Kwk- zX?E-izpbQw(=GUPtByvOUFLGOVNBDpa9BFlM&1?}Hja1jQSPS_COgE#+uX(qeMjY#Lb{<^^9Pec2M)qE|Q?^%g{4)RFZGDezA1B8lgEd^_krD&JGVv0ryWThn>6)6f}Wy*fZhA%L0T zdXH4D@+9AG@#)JAdr`Jn7iS6d{hx<`!KJG(R^SLi-wZ)E!hq>xQW%eC zJZMZBBZpV%;r#sR*gYwe+OCs=(beZj{HX|1;aCIWd<8IEewvHk`-Hub_nA?=uga*+ z`b+%Xf3V(LkB~`^gz%?P1^Z|Tx2IHgCI<_Gh)wxPW>0=LU9s>oY_Up&mbzx}S8XIY zC4BNQ^8nuDa(oM|12Mp-0aHAy=({?^vHo22*p>wDiRK(jT?{`fzbEpVhsnC~%}m=1 zTbN~fkIh(foGuPsM6yQh$j#P&jC7GU;=Wp3bM!7*TaZj#YBK1W13&18zm=fF^(~s4 zSAlEEAJTcewyTSEVtq}=kUC>Kb{vm2wBy+oV4j2abIQ#8NI6Hs$&NGiJwAZwoc%9)C7FA z9+K9C{qRCx8K&rWP_Gnq+e*vo~%y}cHwbvK3Co`~$6TEchu5 zvTx>(lLiSLraypBi`qvRfmjpJ^QomH6T6|e@(%f9ngR(r9%Nb4ZX$Ze5#%#Pu~<_M zgmeu^eGJz}Wzu2!JZaF&j^td9nQYd`Otd&W5svvw<4!F_nCTcs>r0~WKG!2SIlGu> z*1jVrwiuzPjyC!Wc+*j@epYu;ACaHd&yW9+fZY=xlb#uRBqGwB`n`4s?UG7f+1v=s z7<>pXpFJ`AEU*s4s*>2a#37opYXzPSx1yiND%qVc8;IfOD(HFWK{l=9_EmGa+r>)G zsXdubl-@>>aLaG-^t}M{<6bT}6bo3K_HBap9dD`n%X1`DMu2pAI-nco(A5vhNa~Tv zAYBv0%vdUfd+vuqhLsQ0<kAfq}-e^0VPwPs$-)K?lB$*h-5f8e+)5p6 zMdzdXug&z}xi@TW#!=vFFM?Ut>4=`Sc+x}@v!4yoaMNm1$uSh218U&smlT*Xd;!W> zAGkW7^LL+nMlBkq;eNM0Xjb%|ZrZ2@g1%wo&5C!hr*bV_u;UrMt1v`Ye~m@!((8Eb zL=c94*bLu%E|WKfW#rL!A8bFTfSTM*>8{*)RG#35^WCHH^6P0huz~v@<=;kQ&(G`{ zo;Ue@M+EPk8=^t+Kk4783t*cs$3Lm7W(?KNz=(hrHYTQ{Nqs8L?yjMSdN_vp-+CH4 zUkP5em&2aW=kR)n4|{D=iNTsq`boh8d-|erb(;!C2n3;0yD8Nj;@q?=R@3%ZAIR6v zQPT6J160l8U{#wHbJzSHeOz=L9-D;29f>JK`Eoc@<5Wvl4F4mUzf*|g)Oq--G7MK_ zpP=jpXY@?(WUIDmLurs9c1gRSgPtmW;#dXp{?qX9KNE!An#4M&oc6dS;$7!%Qg>+y zO4zT!$7XA(#k!lYapoVAc6%AzKA}&i#3exH{d+Kj`r~$sgxvWSkSu!|_)y z$*686)NJk~)(NqYIp9NvGFZ%Q(xa;)d|`Wz1-$=N0mi3C2yBcYI4hIfdvcU>e8tga zk?%;aLMmt+sD_HB^RQtbB~xeLr@wcO)988Ysp`ODHpX4b>{pu#@YMIioz2gP(!v|i zuX_XD->v|md8cSvS{67>TLUM1f5TFTMwtFV6bq{t0c(Gk6m1AY`+KcaN4c7Hy6MHw zGuV&DN5|+jSsBo|s|!P`MDbYoN-!F}P3GS>gbtg2B3|48OP2>hsq1;j`=y39J!fHp z^L|(>y9DXviLhTj0rVx-LHe%OV0PymO(>s^t;^KORwG^LeiTKnH7I~dR127{djt=z zX~U3W|K-Q$wlc#aMEZ%v zkvu}O-2RbM-Ybd7hzOancQXC@%>cKXnPA2nuH)H14|yl25sMWZGqFq_KKG91rC^#n@lfIWCdoTsl z0pSz#jra#{gWQ%tXur?RM^2G2_4#Fb-GJglZl=EcM-ILn5QmQrv2gXs5B!kuk@Wql#1-b?aNYFIn&p0Tf7E7R@yRK9n5f}Ne~E29m9XYg81tFAa03_f$HSj zV7@bvr}yM4Q7n?i7fmyWighK*9DK;?R(Fty&l>#c8y%tLkQyjEr4lQHb@0o{9G7|a z(2LHT^GH@2GD@XzByt``iGCon8Z+6!E4ftp+ZUSdumY>Q9@FQcuV`ej2u78!re;hz zmviD&?v-1JjgTSZ+J1ydY2Y00XYJ92?+P+KQFOmR4{6#UixEwia6q9JTm5FyJ0>5< zTx%bWGsnY|6Mj&qmrlSgiGzPzk&2d>fa~+QAp1lePY)DO%}=qAcKRw^WG{lnewCWMuIl*FEgVzILCM85q3xB1G0JPEH;pAN7wXZT3$L4XY2W6j(!*(kBY&V_!4~K z#`S25`Mihis&wNAdr*HPjd$dnu;{@9+E6Y-6gsa`@1H7Ib?P+T<};b-$f-c&M$YTA zl?S^;f3Um7MbXl72C%0kiA~{oTKjheJCHFG19$HO!5KPKy;&WD&j~}T%4E=?8iXGP4i(XB~YY+Uyq{30Q=qdtNYtMOC=)b_O%gB?9+n z)Zr!LM3kz^CTFgEq6LBSX!)$0T@(9_?GK6~HP(x9>p>N)<#D%Lfp}DMXO} zxjs`=;TD)Z@W9+K>;ip1_>9?qR}CKR*^Uo(EKHli1#~w(DH_S z3_a39OUvS@s(%fc>39*Jugt>CIeGZD-WU$wSO^g?hr2bNq$6*RvArIL@rdCzv|Tv? z1?Mk=@(nJ;(Po@P%_<@qedgenLEu9^5cMm5xYRt2@T}{pCWK?m^(@{m&1!u7XbO&X zM$r2UJwW*)#B0aQ4Afo5%| zcvk2MevzDw^L#@wY~p4V);mW++H6^<>?9o3THGsjm9F3Y zg_3h=$X?t^6j!=n69}_dG6t`%Wh<*>Ns08D1`NEAJ7q36VNz+4|JlMsQs2RXjamJ(MwZU^S^qu zEi?vR!DjOK8cVP3;d})TUXU<>ZMZ~4wdqdgC|3C|!O1x*sR5104mmX(zi-dlsm^M8 zt&|GOuGR1k+>-~pC)eQp_%(<%yARHTb{Nz#PA2|0PL^fM(Fws)_`SA*NEfZ9f_FwC zaqs|`b%espk9VQKr5ete&tOzix=G)k`!tmKPXAM=#PSF;ytl6urHX9$6~EGHX;c`< z8Bd_!HD;0fwWr98EjMZ1k6bGJq=I(;HG%j;ar9``0uXlP9Ev6i@K~-LyVl;t-ERwU z&kaTD_xKBmdY?;|c%?w-d?$Eym`{D|PU7pTY4EXNDJ}V`NbOhG(#o6SuwveHOkN%g z8-?1)hCo%w6ysb+dv)-QK^5uoxllbn`p3JwFAt&?18JOTfW=)iK*r%Be3dJL-!hMxx7*y|R|v&V&ywNEgd}2qZY>eI zKZA-zQX;prg6$;qrgmk+6{82Nlj0|ywJZ0T-hEFNPdSZgBU|z4 zQ$^@2_(7!)P6KQ1w&)Nni}NPTfz>fwzWUNxa`k5x4eXu|F2`q(@Z2cswj`I9!YHlJ(+N%m)xql@&7L%dHp@TTZ|* z0C>GBfO|{ENsyBlBeLTGw?7MpoeryrqOAkWUD{|aw%42-ryV45xh53qBHeT>9R0tP zVf?0Ka;4A_j3(wo&(UOr?jibnX&}i;90L{Zz4)g6Ly&5>CtJ6Q!0>P+(ato)H(VxL z?`baf@C0~2lf$un+6TJ4e~b)>O2XudQo8Z!1-dZtIr;KPh;}Jf(>>2Zxq65n&%!hW z|E9%*X@Wldj=n$(f@g8>$s1XTN(Dxl+xs6+UdFD!IY9caUL(z=u@L)h0Xe_Fp9HKL zrWO-R*iWW{xIU-?!?-S! zJHoMe;-95~SIH9MuR+5pcaa3btJ0lQg3W`mi=#k7` znlLpJ1|CcY>#}U7gX>Ugo;wQ>2QujNfBWHb@(X6)QwO}yyaDIHTlB@B<4jeaAQ5zE z(l_eqmV`@hiQ=VOws6U66?{3_4%^+8 zU{`ZDxLucqg>81U+g%l|cZ9$*&R4snGy@S!m9GCE(BMFH~ggqG< zv_;h)`OPKx{BIQ2{Ne7%x9o6%-D_&AV2Qt98KL07B-Dx70{wHhkyEmgRDYOdBi}B8 zf+3_=R(~S?(iK#v!U@mKv&XS3I{X`XnfPGS3p!o14IR5(@t59Nx*^Y&vW;^g{pdlm znCqjtD|o?y$%AyyCu0hcwe*+z9hSdW4+o9<=x&KoMy<~d=Hy6nzF`8U+ao~D-kB`k zm`vp)>WDqw~#i zZtD%Ad}j|#X$XT;+imE&S1;Mf=Q_CC^b?ixIzuA2C(=fa5x%fzEo|i8)h;QqBuKTK zXL~XT2Jc^DcK+~yCr#>*woeoNwLX$I4J~^6`y?1#TmcI}1ZI8ppka%zfK_1*YzmqO zJJal;judm<3>CO$Cr6`3^htVL9jD_eT>X!`c|I$}j!I2j`e>AD4P;V< z#iMl1+|3Z+kw?6rZpH81tZAA4nqErGz=e=Rs)gKGiRDMY+3X;h^wou4ztVu;g*g4z z10HPP-=-~VFEfAVCBVz_7+9qIgdWxZP1b%gM5XEau)<&hfwe4Ez#K%yM^gA5Exqnn)#qxWk>klQ#<&I!x z@Sbg3SOAw4zEI6AAIPQ6R%F4zD>lxxhCWqxxz{vhIndZNV_bE9Zs;}$d#R7F0 zv3^dgbE@d?!|wcY-ydWsb~feJ8RK196K1tv6WyXKiZ=ZbWUxmM3$>O*!uwM+Z~hKg z)OrmZuMb20Pi1g+vBaiKL)cw^g|{VjEB%_6jHd2^c=&Y$3DMEx=EXQFonb+*a!!-` zr#0dF9TQsZwGihwFG11VFevn~!LPp(>5QlrT0g}QM0P8Z;)7pU>7(A98*VaW#ixOM z_hHyAt_X~HD0I2%7}b@yYFgSs#YqFWmtnw^d|q)_bBXZBBnW`w^@0&$Rxe zA8d(@fR_$`N!05QqEXht+dR_6{Vndhc+o?K0&;L9KoqYfNwR)?BfR-Y7$tNbQ>?y& zSyp0Lx!7Tng6a!Y; zmAEB;ge{4YWe?iOpw}gqHtbnKGZlv^aLl1)rR`KsZV^8Bc*1&adO>o(ZASgOC(yq+ z2A;&}VT4dLZI^W*vQK8g@dXyxs5PCq-fv;H`V|m?{`(~Ft1bN;OaqQxT+Gv<-XDd5AJ}Pqk@HAJB5ia_wn;) z{A1q*Y=NGbr{oW-0bfSO8Ix>oNAtXgE)B?{GoRRz@TASeK_dy}OPXa}5R;^+mt&jov78L}KJQ|j>fEsR*I8VeQ3CbCF>FxBS9)CiDkvSA!}_P?;zOxq za(bE%$vdcrVcCDl``OWW?&NVaC~qNl#~#q-vWm1xzppB7Ci}W5?&5eq-thh<$H`Zzf>ZKu zAx~ri%G?bm>!v>>ueWbQr2-ZvMF^9RVLI5QbA!0Wa$VA?3ot=npPS9>QGHVm7QAeu zlj3WcB|bYaXv%D6rHCqA)VhVTB@tkAWH$MwR!iER@5diI2kE!(0Z{8y$##`@P#tM0 zc%kr!NEoJLkXr`!x~B8&JiMsgV_SHBW*;PpJS3m57K4SIG&WWEp@yF&%;=p3`$U6a z=KPIx={HSKt1-mA+M%rAPvxm@#=zFSs?-wm#V#yVsY&d6c9 zVkXf!<^xjF($JeG4R_KTsNb{FWjL{6pdT)?~TbFH0B2XK_XB67^ z(=Sbn@S~g>NN>Ict7jRp-!DbML6L|2FOFrv)HKo|XBX;Luz-TQCiEUjApI&F7fpRD z?lgYL+8)@=@YCl(?T@#NLdYXlEwi4U_2V+S+@43QH5MP$Qw$55OP%M;CbKTiZXJcF;@A+=3@OcKjNGpdAccQ`MTq8-oY>HmHC&KNE!L-P34qg>l z4=4ZSz#6+b>{+fClpKAHbjqKA)!K@%)_4t5zc-z6x+{k!H$G55VR7c*uc@$-JxCm? zV&KnCt~a#pEz$bw1s)Eaq+H}6*_GSHtM=G|-oNjnQuGw0PGj_8NeZ@qG=%AM%1BdZ zGv8&!P2z3YNv50>X2K`mr446av-vzhSXg!&ZJwpkOsN5KZt4>{)~tY+Kj)e6w+&{N z*V=)l;YV6r69KC@cIoF$3u*C^hMu{o4RT>DL9$ULrZ z=mlNg0dKVfM2ySsB`@B<&CBO--V>oq_u>cdB*vR8#FOO z<}}z>`BFQ57Oq~ABJLkkn0Po0S|Jyy{rnZA!ODf>e`&y`&~ToRw>@h$sR|PJ_t7P# z6)?=PYI9Fj5>u`3Z0ciqvPwi6&dgf^!peP2N9soG;oEWV5);sESs3NZMnh}daj;sE zOq}#o;QPB$_*;63%2=PK+g)1d0*?3P5==m1-dPBu-$+L2G#HLjB>^_VG)dkWwVod* z2a4X22bFyC-a(b0Z*z!g+vY``qK}Z8ojUlsPaVeKvk(6l&^kH zS4q!?5x-u}#ZKvRJtuf$SPBmhgfxD1<`ez-`@rkFE^3@z$}XDa#n?71L=|T;}Gu9h{mn4h2z?7N>t^!;I`+ zn0(m*+SVq5md_}Ap?48ne5nKEs364riABfu0ebteJ6YAghcP^}7%vn*C1+ScC{wjY ziE$Hra3_N_#FUc2RIY0{NT{qC zJmHtH|257dLg^|n?bQxO$t8rwm59=*g{8#vS1Xat*hg)>k1{qdoXO|xMp?vnT9w7V*?W_fVv@GWvNOdc!WS-~%l zT99n~ONDpEK$k%xJRFUuX^0EWF=$1XP>#zmS`44G=I|GSa{vmd`6Fw^2 zghhw`(S3@B*m|sr78xGG8XaLevq}qsx+GEi-W2#)^^KV3?j^RdawsSq4|Dren2W&% zw03J7*P(A`!V+~b?r=3c3fKu#e4^lm@D|QHxDgTxBFUGB`_Nf^9Srw4Fb!7m?Clll zXukIve(3Ds`ijX^v0WHHu$+&A4TkuRxn%2vOcL;57fwvlM~@f7^w&OR^sU&0@KTg& z7UyFgsizU|H0jSrVct7KWROP7 z_cBgv*Fe5VJvBSZakTTd!VkOeyySR!_!k@wI-^mf;7m6iyi`W39ymb1qX+VD3B$ss zvsk@d*y3fuACUa=fPS`mPS#d^WH-J2K<+eZqtCVw-p!OG@-!h2ev631i;xz)Js}3t zG-Jp|QCSFWhyj&FMli5d6+Uj?2WM@#XXN{6o|udcd>2Z`=`spT(Oi8TE%U@J{&l$X zzhpQa7z*io>cOn~G?!hTf?i)YLdM`lqWEJ1T8wVQn+-{1@ZAF{Q9ej>Pu0Wf#3Hi6 zO%bU;5Unso_;pi-(e+M&SIGoi%%ib>+kRMZqKJ@5b@XA4J|r$3f|~p)2wLxoYu$Ru zVUE-8vLKEwdbxs56Kz7jpOZ1lF%-v02r66z=GLA>TKCNm`Xp(jG5XZ(13~jm)hN1m8@;z&8J>2EHj$ZAplq1{b5EzdUhsH42{F@vp=gF^wMgQ! zLsGa?Uxgl7Gsu#u-WWA0iF$cNLua)OqiwJoyVA-aW_dRVh1Wu!Q4u_CmrwH3GOu^*nIY6gXVvKJ&)jY5rb3GEV zj>N&?EA?dQlG(UO$&gq(*29q6b<%WG79YhFuz9)7SaKj7RCrIxB>4s|ljBbwb{E4s z+lf%wJO>(UhG8xpGFFAOfVl!r(3RpG%P}GdZPPhE@y$y(y1$iL zetOMpdlyJ{tUd)&@zFSWh6$-`7b97|Vi2FY99wpnLn!xqnKv~E96RHohQrgU*p4zH zV<$i;?i%Fe*OSXh+Zz|93^8LpJYs#@jBcHlLEbEWMAx-u!{%!TK|COjR;Oy>NQXPv z?K%(NovvN7=LbMgsw8x6i6-S!HAudKJQa|B&UT3%Cuv{p*?AIyU^y+43ykj2 z4SFErEoY(P%JExwd7_?;0yEje20YhUL0Y{Z%0$oL9a$v`c}{C!Fm;ehtF6PgU+2;# zdJpK#an3&`x{@y5mxV>gZc-O+rfW3Mgx*|5Tp6MX)8#FRs`dqN%U{R)XKsc?1~w=a z-9fdu@1>|Tk;Dho!)gB>S~zrp*InsM{I$aH@YkI*;C2Xh7H)$)E~mP{9_O^IGO72yvx$rF5rCR9jW~u4${*-;O`2~zvp5KIQo+Oy5Pq< zHH(MV50lx>tqZ|%p&>lG;LY@p2H>Pu8sK(OmM&b&K-9wdWbT+c9Z;CY%nad}8bb_Z z?lod9(+RqbO~TnH@@bIy6S|>H2zSfArM!d2#F9Twh8k|uA+e=6^~zLiZmlOjFZ+Uh zvI53Moxz0P;k4nN1tv@9V`O>-Y6O*&>`hPUOKHkPl#ddL3rggCR~hjfeZ-sGkw&c4 zJ(!1zkx(P)!_&>2PUU9B!{C;6Fzsp@5$=CZ6F*$0zh$hj_CW*u(1~MCD8+;1*faVo zHG?4|i@=uiu&Cskkg%Ep)DzneRh8+i`)O{g+-nO{5;9@+p}i1RX9&Hn?)WsIgQ_jC z0KRxEEnc6(F=1}dp2S%oUD!j?pKhmv!QB4-SvQGWZHFpdQS@nwKJIwm#~k~7pLtTa zhRCICB-%X<#Bz=vWO5uQshB|$d_@=95_75FWf5$UjRfO1&SlO&iP1-MvDmE~f@j1+ zw9+Ml3WBimrwe^GnVXN70OI@E_(36<(t|2czv3WRUd(`%ZH3I`CR2R-`V6!Cd?t~3 z#qp+ZoS@!urI3=rg7PaHIOdf|PB0O8UW`7ojvn1#R?*h_i;OX z0=(1P>F~Q@B5SAs{m;+wCe>{rMk|)n=3|X$B*g8G_wIw;>s?`jNE@@LE}QIo)Xf+( zZjg9sC1$=!p*Ln8qXIJq=|$DgWNrH(ov!bNEolphwfa#qXWWCG{?itHTjIF8-DU2x zc*fJ&>_ys|qcLbxJwk^c>ms90PnFxEV#-Il#xVx`j3+`#D3`MiIRaloMd;Wf7bb1# zSt@+CknI#4rw6S9FzS);zb6qYU^g00^4=94Uy$EDw&BEJfPT@QA{iM123ys$+ z04C6jbf%_)&oIXY+!Dn&UW$N;7Z;OnUZS|SC!M$Idjfj!hTzr~M>cZw`kEh31`h$Qu&cbko!x~!km8<>{g4Q#w!CH@_tNX28?;~ zEo(7m;T3u=Q;>6Kgb>4k%@{IIfllEZNI_-?K>W;eqHy;#|IMsj^d@gEEDe)`kcu~a zUH^~tjAk_L+;2u2MxK)U>IpdQAD5BiGMTrkMX5^8Ia+bU38xfwlE7e&^KaBiwx(@j zCg$bP{>CVJT)G*u4k!}2@1t~ve=Box>n%olQaa3oVG>z#m%dhL2Z@K1EuQit;q|Xo zkXjoK-p2Y=$)O#{l}fNoD*%11DzdLB5Pa`VV?N89Liv2|c48n8-!{jQtA-1RW2FTV zc<2G<{kuUq?Hq=Mtl_Oq`pC~$w5QGrXCPW=CtQAUpWMp(1FZ{M;MntR@RMspEmcW? zh`&0pr|~rTlrxLg=4O$d$`8o3Yw56ya~Nsdsq1-jWVWjmI9&4RjR8|dcVa7@qNhts(|MRDp>FxVo2K^79EqVG5UkD~Jq$LfFM zcqJudWkghDWmF>NIiFk02t`7&l9o|cw9D6CDN$Brg;FFkpYyp%Xc3{UXh}P>q4hhz z|6G?pT-W0~=bZcgyx*@^RG=)xq*n8{^O{jmWhKsO?;`(c=1_;bisX2(H0_P?!A+Lu zK>2tSDfndyTFTK-w2XUKdFx8&U;PMezY5@AZ!I-lc>)}Y;=%TVAbl`>D<-y&Qli4XxqbP&o<_#U-Tm{7OQ*Qb5%? zofpx}u}OE=!BDCr)qLrO8HGvkCG#T4>IcGVxe55PX%|`W;}w+4go9t=eUMvuk3VZg z4@`EO2YbFNV!FgHD1VW})CRlIc_bfN_p=~WodJ@$o;dxP8GS3ILo~%A$Tp8qT-`Fj z`RusN8OL_tH0c!a_&mZsy`DnMoK}-<{p#59`5r0Rl1-f(XF*8j9@yksM)&D2hA6Te z*RJ6KZ}&8~^=B7dt2+nh7u?5~N3yg`qnun?%Ch=#ar~;U;<&4%oMf}(ypNYd&@)s5 z#%?r`nAG`%w{HurO|9eje}_?TekPXAyUQ-LN=0=^UH-LBU9fM>Bv0Q>gQ}c-D0*E6 zu^glM%dsD1_hBD;>hgCICnOK0_3E&l$HR}bks2@JGNt>+d5sn-=u=ljzj>MRK3TjW zDaR=3J)lEg#;t<;xCm+%j@K!0j@Q5KmzdX$a?rBsHF3y221`P@&wJzx;i;z6(hgO$ zyFUe|4e8(%8;4;VZapv#_3#u5!7xG_JP2x%TitDURysJJ$66?#TD zO`8K2Ad6B@HsbSR5$O473Y30V!#|vNG5pCUtoQcEu`5YC1cyTPGA0s4J$r*z` zPJ;0jv(Z)c6*rr5?wFP58BH&iyT<%T*z0RBR7zLVxzqmAize|@X!I)j4lRJ&GJElfPd&fe z09~h;V)}_&B!asO6=BLSCx!vTmOz|H-YU4nG>)HQ6PNIKTn9L9sE2nfIJ zrv+bpaNeOJlJ8VRUObq@4hqe}II&mM$4{Pg-HBCZwAT(Tf?RR*_cAB>GrQgOTCXeO2~kyd^73W$dIP77xZ6@DP2`6k281cGBb_ysZR4+ zP3MgNi^*&-Ac&gJ;p1x8?JA_jp=xH-Ch0nt6IiB=<#IP{*|myKwl+rl;2 z7jT!%(LyqQ_Ywbxi6)sAJQH!T4vzj1qVWx3nAfX9qBw?UM%rbn?HNugQr45f%0hZI z#R)s+KO}=zQ=ulghIRH@#iR-5gVN7=-1*xz>Nw2;{OdQPr;-v~;Kl36j$NT(o23a)=b7<64~t^QuX#`{AWVKZ z<$%`V>*QzRO;Tm?5hic}7Hho<@~LVW`|bDy=yAHt`+6w})_kobkHbwcr=|jI!*-BM z&ED{)IRm4=w$i5;bz$=a6SN##g||J%X-G*j85fmd(%fwE-@je7cttojQ{SOiz9vCQ zCg<3Et3ocFyFnvMis-pn>xo&l5-41rf%|`j)1_gPjlGUIf`CgA$fwH~*S`BkeuT?H z`Medj}_xpEnod(a6o@e)2WC zg?n$ZUHu=gtNAeRmI&wRsy2bK$djlx?H#q@>7c*EEm~}lLh-mSX4t?}* z#W3|#jwch`HOS*CX^7`(6XzcyfQ7fnho%B3cWUXVA~4Z?OA zP~xr!I=o8q`o~GQp4dj-UK7VqnJjY7M3R2TRjA-8L^n7Mv)Rh}wCnF#G}9F$PrT!Z z)2l@&x%d*Xj0d8#LW#Nv?T2x$54*PN4YTOnGcwTBL!|DCaiUaxlzO2H#x7iMNC3bz zi<_rKg2)aTbueshVJ^(-BFdg;pmawgINsj^7oH2CP!5lbtWbr~r!Z1hR1XW20XV-t}rEyi}sL0eqa^P0Dnw&xw{w;=DIXj5n?8ba6yIptuOd{E} z*crCf7K33!Jh(b?oL{Sz;Jr2!PH6U1{jLpoa$J#KPPt3lvpD|Tbu$!yj=1mB9OhgM zH@_7fN1F&45FV+6?~AvAJLiBj)mjV&sv_VN(MuHD*5V7_BN+eb4cnAz!Et8WX{Ngn z%=Wwn)uw6i+cJ>^XjYJ<^C|rQH1?r#PY0bvlQHW?27Gfr1>)ifB=*-__|w|UITvJb z-jz@=zurNP)`f#~wI8I~YoJT^U78fzPPPTyq+L?>)T!2lc3#du*+{0`1)H2D2Kws7u3aGN&!sD1Ckj7*A5eSr#+l z@>J(_ljd5A7_>LB;a{xx4uS{rx-){hY?= z#&Sip^~(e_X#-I(;2%9$z-+#YL`^r8Qt!v?TXiw!Oex1s$`OO)vPW$A#Ap;F|5zK& zQ9bZq3ekU+NGHvcg1!`%J#bhYtlGz!XGd<4f|D8K!(wmV@a=F^t8ZouFR#JZYldl$ zemC^5)-Z1CmxY6J;UMb0jrbmtfzh%lD4^|(@2{29<)>PR>Xn1&SrLK*lQoILdOJLu zQ(bp2q@UclbcxBdts*idYEYB?i0Ctc)TewgQ>R+NM9kiaxu>-OboYUgq#DCJCPbEb zRj|9HYS7B|B+NEH0T&|0;1=`~r|1_%Q)?M^M)a{}Ha4(ZBoO|7xlH#)yrsH6$2nKw z2C#VGLyfNLfT8b}QHLiL#d zn7MH+9sl9V&EHdD|Fkqzt9{MbW@-ginO?^9CDvxeO%~vB3{Z#~=BD&6Grg-khN%EIz)Xc6ZaxZw{`;D$IRoHeJFKEG)OcaCvsgB6rOuV1|N-@vX+Q;9;wb=^PWFy{8Ta$GHq# z*g|~yGME>s=0Nv-6M;wxJu*DI8Moz>lTI#A<9K~4zFn{mo?{68K0k!*T0R~Ab_tW&%$-U1d=%Qj#JXw*nkX~05 zhhXJ@u=J}IwC|V!X5MwMphgIUHwi=WHz{lliH2=4wpiRHY`pnd9xPPm&TaC8L1#}4 z*%2TMPaYLv<(943bTkGto_pcm^fP$l!am#|ae@w=y+~I~-HEsFMiZF{BSftu1Dnr3 zgSw2Xpz(_Zv!E8@dnp*6o)%}1YjNzB#|6}*G#y0`iWr|bUIb-FOUb_x6Jk1F9s(ZD z#U$?*a)oRgfRsG@&cr10ohKF)k`84qW04)llmB+8J>dYt-0 zuG#Fy8!avLFZTx)wh9o{%?b3qwmD`_Y~%+!i@^KePW0Ok7rYnK#l#rpFzqdA771H{YWd>rlmg5(>LHz-@v!LF7y5f=Ahg9U1=+MeB!OQAKBMAX#>5B{QZK+C zJylSNn}bo;I5v2r5OkEUhhfbt%#(lwYFHSCoqJNCx+)9WS{HKMhjQk|YeL>WE+Nz2 z){|{VIWB(dCd}>eg*!jBVN#j`Tpw77=d7e4_vJ4OrAePy3<54V&Djz4l98(oRhlNco8%`;AZ@SVeonrwfdl6C3v#@e@EZ7%l5%0l!AZa3iC%NB`N4zJxn@efx z@ym=%wz6@cjW7K8CJY{8X;9!5LcMn!0mC~RXsNOfjy%r6!cFHeSnUQHJeX3y%`O~6 zxc+H)=XN}!SWTODa#_7AepvT02BWmASh4OCIcZyDr(}Vb%Cz<|zFUf)R38<^L4z)g(qgUidxOep<5#usS|ANI~Qjr9AAKDK` z=vIjH&Vm%FYvf@yAsHNFwoId+xW5k~hPEoSF(Z*J{gg=O{;j5qj~>Le2V*JwH;Nf@ zOd;ZrqN$ljG~DI-l^a!O8RvR^f#t7V$)#Wwka=l<((;SRosQ@5XJIv5e76$yA^RzW|{bwrEw!X3XyBW_Jj68c%EvH@uSXY(vXQZ^3_!FxjSl{G$Iwn z*QsT#DteS$g|J=&*6U0m@AR5`1h>q<2mSBJ`>WxM$L>66&2h%tGuFbIiQ_~rPm;VG z?SMMnOOW2R6)L#C*P$a)z!*lrhtmc4$a^*ZwztEsjZ3gm!;Ie6oQD7X)FUtVN#Gg# z2jt_kWOVe|K{iHLaC}kD2`KJQ+!_J1OJf<;)yia~_d7X}avGX;$J5y&m!NrrIp`SX z!pF8-q(M~-Pixx4mR%Epc~Jt~3XU2L=8%3$!6+mj9RG1#JJ%jsRu)5)?q!l;Oj zUd#+Oih*%Z0}1*N4yG|I`EdCjY~GO%tC}TY_-PaDzOk3r-6)2)if0?^Rgb`vSJCh$ zNC+ygU7?W%%kj;k>!9*H3PRSV;?`I9VN#L?{1Q~bw>n|u^(BrKYP1s+-?A;X(-q$s$)$S#5MSdylHkXF= zC6!dOXgxf2(gB|@4MZ>f5uIyyo2XgM#wSC<$rRNSRANjB?nAiN-6~1xz#axjf{BE-b9eysQ zwW<<0S-FA)zdC|bsy3s?xy2Bt<3f+cq~T#hLgr6BkFFUbbmq!Zy8J*2x+ndmr>dS) zmF_aue2P2ecgLdVy{#a6cOuLam&fzmJL$pCOR-1I4sXro+;0IZalP9*nsmw&6}1&W z@B39+V*QOqH>#jD*wY!Wrr@Q+tu$$(1HJU&6|SpM#_C4|b$5!YaeKB&`OH9|@?mJu(T$+*M&0EQoEhr;SyNbH*j8)J=-=a)Y4>r92=h5#$f4LYvP~=t zPp94F%{bQYz;Kb|z+R*_|!oKFy$i(=GJ zAQWEk3PG>L9xVS&1RJYF_+WPn{6jLRz?6B=yQvmD|K3Lt!S(oiX$_mx=M=qhi?|{yG7gF@Ih(2;( zM=z9Da0@(NN^ac(vlCu;ezG1_R&6EG5&`hO{Rm9_F9tV1$|d>D5#Xm>&Ni2w0ukRS zH0{Y`Xn5a~ce+f|FEC^Ax)!J01<46>z7{B0O+Z9xk@ehiJV6s2gPf9}cX5 z5{|(dbj1;uJX#DVD>vXAu4nLVvm5PsEJR&OBtR{3DT?j&HQK(?1U~CbL1AQ2yF~~h z&IrM)wu|)p-B+Zv*^Jj~AAw5mwPA302mSUw4i#Pj^wp`*Nk1;J8ewU0g>!H1?ua2< zN}Zv$VF6qoeaX8|D&BN3+>0rzWo1d` zzl|hu)df`6MHTLk>%q^X$H2|R3%o5AVC@G3s1FEdeH~2U2)C0FzO|f*{3^rTesGL$ zV}6WCD++>j`Zj!LD#`Tx^T%V;N@>?G9(6X2WY?wcwBja@&e$BA&`~t6ZaS_XRx^JT;f>xv&zwA8VniH0QgQT@Q(0c2ZwCJKXh^V@5m{gLg}W zaJh955lo!PRNYUfPd1b?`9`jEhnf=XpB09ClB&t{vre>R+CSR1R}u=-G>AHUC2e;E z(fXPtQIUJWNOR2L->m_xt!yg2wap(4+wCB5!&$tys)ZyD6_EHx%4j|GnmoD6qxZL7 zBV!5&Xs>2E6=k-gKf2?okNdfV(^N&8KTCxS2;=6-xs}k!KynYHGxR;@W6f z(DQ{f8RXN&;n$dr%R|Yo0(UZ9d62z%YB4r)ObOuplwo#y5PNku%#n;|A8^j85It3T zY40PpWo#Y}+DwC$T%Z5Bi2y{)%Au@rB5|s-W-J?C6C1NR)U)0Qw;PCpxzZ!jQf7;$ zs>gBpXAKaW>Vb}ty^PDVFubFZNeqI!$m-4nFf=@c!lFu;eUW75u3*p~ z9wvh;x8MpcgErYv8}A-S;zNNI9vU9wC8}JcUC}4eXIcz8Ow>g|^N(baNh|f?t;1(^ zru4&#Ci;5CdE#Db&T)n;iG0pQIzMF*-aoC04?ZYDvqKcU_~;*7m^%ebPcv9M%M(0m zIdl^YSbf`+c8j%B9p5f;Ue*Bal$e0;1Alm}+etr8bcS3*1$MGYfRXOmjcjzQ zBh1tnCYL5DpyTswG_ux1k5!f!=WqzUMw6IdpZKH*2jJU+EXFF)6SwW24WpV$U~LeF zbCe`Fu6r2St`kXHxh~MI13$^xz*)p{LoB@JG7U~=oIrBT)Vd#6E#Wfb43E2=@#|7O z?#x7p&WaR7=CV9mMmxeA@At%HD1zlJEGF_xzEh_rJ$z9R0OF~OU=jZ$b$jMSmK=&= z%5B21M>>V$N{#c){^Oit>x1wqRR%ff9%>$}hy_RNsCM~rT)5^e$X?z9*&lz?En%r7 zAiE4New+rcmkrTmp+h8NK_n5{^nek%J(U);ECiLOS|E7T5ciAulR$$RbXuJ=+Ynq2 zF&j@q!lv(Jc=J@mldaIr<)TgWm2qE;7Ss#xr)Enpfp^V3u+LS3t;_zy4kbPOp>N3F zw1UeMHf2cS1ZOgn=(u($Y!|v)r^$OxWGdb<8J4~L^&8{q^=t0r zs!lK{z3_n0d|k*_zD)gMeb`b@IsDLCOmziLl7yI*Ot9!eEV;E8UGra&H{7h}b>k3b z=9$*IY@CSyn&kKv3RR5ErwC%b+Zm-26`(g4tr3VsYP0WVpHZ=54 z7d>=&kbamT3>?-Q=G522_nav(rD!pE*R=)J_BApq?B}ADb`_nzER6W+X+wH@G;LCf zq{)eCkP~v@BW!O#xIl`fjrA;BtA19a6E}R8rRf7?CiwJ!7MeZ+Rr2FoZgZlQ4TvB)w;?O^q+?0UM(yWP*(#7#Yce&cbYL{BH}Eu9JgRb(YW>9fP@6TyEdw z6#Wys113KHL#7{UB!9k_lap5`Lghd!yPIEwzG4B6o)9AGt^P2bbeFO>L;Nu*ZT#z`I!$Wzqrj1SFwD$OII;%mK3EsB_;}dS>?uOuP_}fBI~ALtf>~ z$ICaUo-a$*%~UfwT=9&Vr|gTdTPjGP#t*tRV?WunVmsy8#$eUpUGh1YPu!o#(tP=) zBy^etR#x}WJ8lQ?(Q!94-ZB^7I#v-I`_If2-)NW|xEqoh4&kz)n`Fx85y}hX7)hzK z@xo*&-ZRTd&|Z;1ZmBGyqC)!23nr0-i<`l4PcQk;H-P`u&IsCH>O%b9Q=~^<0ao3y zfR*A7@bcXY@-^u#$>iAKD}|F_=#~lX;r8mL^eX%Jf+A>l&VslwO>)gO3nWkPq@DlH zki3&~iKV9yh@4Y_SO+0ot+JOBnTx^H(&yynwgRr}XbAP*fPYqppe&%9 zbS&+JCOdz4aibPETLBo)h^0;eDO7)TDlDICi3Wq0KqA^0@4qf3o^YIRKC^&1cU}oi za>iMen?FcVc`mchArBJmBblj+f$&r*m^6=X0SndzFMU+QDQoA`@xw)MP3eAEAq5T&d%Qv7I?l=kI< z?L$4z8`%zP3zS$%BU7x=$fi|M<1|v~B6;Q-fe%u@kd=j_^!=|4#@ED;2>QvwmEVSJ z>;h+;qZ!U-^7l}WlL^ecXYuTKzzQ6V=^z$8c68XKgght~z!_0fa9f88H2k-nEPT9? zKXzFIPJEnC*4K)@=qk-vvyU@=NmcCwG<|_!<7We(6lKxKLM*iM7 zjPEk$VvXf@R?Vx5T(n+}0e4PFh6AZSdApKe9H^ABK1p`2`5dl|hwS-ASD zf=pNcOrn0gB1QWrK(cER$H$vM^LzP~CSOtT*OCqldh4UU>^VIKB(^g{Q;zgwxbtvmXv}b8TwtaopGQRmmTUt!22A{J(9Y4^e60UT3+8oZ?c!)|QWe|zS zSJBPsC^&rRVA|hQ!kLGI?0MN55X!v9gjNrejir-}-_V_Sxkr#lAG-r>9@!Ac@$=4Z zs0XEbV{+hc3R!Y%BIx~{PGn8Fot{w*`O(&fOUqx9V@{M@Z^=SSF0*`2$_V+*5p?~V zR=D#j8g0W%sEvXjBxf1Iq0ix*-?oVBp2Xu;-DVu!Ap~+h7Z7TLIlkRJvdYGlvHvRv zFVc_0E8{FWaWEH&$6{C*dJGaT1|zsF0+FNrJTsjx`cW($7gk!a{{Gg;D=b4JMJKHJ znSc*oPsTl0)X@D}KY75pDWv3;aUPeq_tI};{Qpj-!ZX|H*4KmNa%lqoEAD4qIVR`& zJwuptd<$BJA7EFnT92DQeZ#I%C-_jZ6ZRAx1tXF}*1CNpEO(~lenS#o2XIca!*{V% z=n!M0okc_ztBhVSy#UTW=jasaZaf?^-ME44@jFhj#njyg$mvP_v^SjFXBV22ttF3$meCaI zz>C4VC%YJrp)c6#BT97y8`)ULbG+5h82pi~2Ggz`fPsW+FVGsN_{|Ea%shr64RS`?CM)=|rNmhULgVEh_v~xU<#5z3TzxIqJU*=w6 z*0`@>7R}*0)MJ@&Qd%1qym7*>S=UJ|w_{3PEJ?joZhMbF-23Dlv`-46r7bRS=8yr3ZF8ns)Aiu|(}%bvT*Y|zcsvX~H>7XF z^Qc+X3Zk~Y0j^)pgOOFMaEmABQIxsH@r%+S?}q@q796IF3y;wk@nO)Qk%G>ZdDt9z zgjE?$$GCS7(CX%t`dPB~nAj9=S|70vt3O$DedS%mPHiIyaDD6C)7OnQ%B_H{KN4Vd z^Ee z2U!t%7(xfesrl4=$WqaTWN{txLRlZr7f^=19ZSPx1<}EzgH+IK5Z)#S=Q{o1d{!Oq zSlWl#2kyb*_Cugm(o7r_PC{p00SsT9L@X3m!GA8+%zM)|jEl^I;6{CTIqNVvw^0!G zw@-$j&pIe?yKZgqgHh_g_8loMlE8v}BIMVq6m;o`=dPpOgdcp7b(eO9@S#n(xm~q|hFJJG}W^8kT+^AX_(PLxq4dyqQOt^W6V+(7+86 zM4L$PyW@0))d8l%$_2#Q-Eiv7W5^!x!;e-Gc+p}Fo|*Xt=YJc;H3xjCBgf&I;l?qC z4=w_H#u2UhUvZ=(&159kfuxyBl0^i=8Yv zJ1`wSo>&6Qvs~bv>l{|zW(MSWf1^Gk{cLpHO0u-%EiHf22y)~ejMljTF?vXZxSqSL zmK4*Z|A{#=_Ls^siSQ@M08%*3c6iY=U8HmMG{K8G)xj_hsF!HgDakamOV-iZnrB9Zz6Xx~PH&UT6aC@BG>j)v`b=-d1k?<#FZ>C31 zir}=(f7wN0Dfn(R_kE6&r=C*su=YtCQ?~FNU71mbsu#?lFYpX2aQZ&UXy1>qE%o%b zk~dwf-3hf0S)eem3)~IQ^N#A4(uPw>gzT21PTSleBg_TFRcb*?uaUSa>Vq_w=^c>$ zOL>M|FN>tnH#d~I=g3pG=ln$!xcwcY>YKP3aXHM}qzXqKpCJ8PPmu3i?m(()D(S6> zBOCvYk(~PuWNmUCBX6cm_CE2WPKV3M)CGz3(~?U(ljcOY8~hQZKn5ZT#POZ$eWuTT zFGi|qW8IJphF$f+$X`FHYeg-FbIdaNf%Wj?z!4ZMt)Q<1tzmfYceavP;!Ddo>YZ>3 z3U6N|?@#T8ocd4fmf&9MTo6n?h+*USmbIBnJO>Y^_F|+B#z^M>f||&b0*8LczA-GXB2Rt z>>~T1=M1Qc#?v$(F?h7Fn&#QHgWaV!q-5$RtQI{7O?{I|ml6-?RuA03bwCpD`+}$D zK1dJ$L$)dCVx#&&I3*^EUD*%mM>{2smllPZru*rq;52-H%bLbN34?8MyK$QN2Aupv z7S|>UIFqOMb6Exi6zV<3wDp!II@0P>2%L6q2LnrCk8$ptpW!QFb3H}nXB%`~L zXpPLJZVP*efBQ;WxR(X>pc_=GxrEK%eib~O$Km{GXZVyg7ZY+)$)>p%dH1bYxU}~I ziZ8d|oSX|_nyR4jKDDzTmnXr0c|)A?xr}V*K6TuE#{;|m#!->LlUOETh@T8vutWYK zUgx^9gZiOlw00t#SUnMEzB>)MeoeG}sfKY-Y80_k=J-2Z0$|o>$92XknFg-AG2^@| zP7ghV^UI}-NBAt~{!^!%_K!No8R053j^BT@6mM+%MT5LIW1-CjB5vG@VW-TH|EG|< zH|_%qB_CLO$_8hPD?{u%%1%1I14EO7aoxxnI;g%2$2K(6?%#%Z=({YuFWAm5AkuJG z!5e0OErjkfT({9{Hg+3EV#$gL;9AGhS=~h#bIO^l5bYrK19fQL_Kbc?b7PwOHqzNO zspO+zDb^T8lP%uH4yXbGGFdTt)%TgYN&@}b%Aaep;A(qM|h8969#s)spg6O6T@ zpOK|UOTn$)3l%P|L(z`eM6K;HOY;_}Nfc7JxcUb;KuND@6Tn;5fkuJFaYDnT3up6j%YUaEz=k znoFauT>ypTaFFEkOj_%DNtI|8WZ7`%^;;Hj%wSi@Nme4`;%(&o(IoU;I*}d;)&y_I z4Y>8))Otq#JLMH7(^r3en4BkhL|xVc{_W?w!Cp6*v3Wm;{jC?oPxcf{O#$YW={L?< z)CI9(i&#Gdz>?angei#Pky^Le|-a2n_6*s+vZAm@sKpU>dO zyH8Q;;6+TgttR#LPw8rL0hF}JBxZdDbd>uPHI2++7yKX(%q5J1#cCN-t8$`hsDuhS zdSF@7PNw^3p!_F&(48(0i*mT{p1}-g_Dq7;Q%6ANIfM2tlEhL_6BeI-3saSAz|+M9 z$nj`+@sLu(N!uWQRRYb*DPk>bW{`aTYuc$Y0eb_v^XS$lw!vd3&F;TO_uLhLI|u%d zblJPq^XYN$mKq^Fw#(4Y#sD-0258$FcieOE1hM5KI z=KGUBuWnPxpe|64QKQCtqv((My+qqxgAKhkog8XYG#2~t7Q!dag3jWnP^D1>H%7Ez zio_BS4U2(m`wOY-fl?HC+KKsk30Qv6pZI*ah@K0yP$+CQw2m6$@;W)@Yc`+X@?#OG zoi3p1l~=$yx|}J__QAOL`*3>L8rmymAjSSOxTl_=)i)|pQ8x~(Pk(|J{3tr7_yT+X z{W1s}HpiPcOYt)A4OOr*K-mYE*gHqG@U62c_RHNN&PU#oAYUc6KjkcS+ttCp8nX|c zDR^LslqU(aIZ2m&Oy^ug+#X6>0IwXVr`kpjnYXtD$@TwkQ{9#WuSuiSuYIwv$n(QEG_Vwah-7$o@jgvBVoqJiL~{uKiCG{1O8iAu-$(K7FF$`W%sAS zITHzD-MoYM&MyR)JU0iE9jSEci`O)&@fg@XJp?|-xjiSJ(wz}!>756&aiF@7wiPr| zX~8ghFEgEl^FJ_u+U3xGMls1UnZ?aIZInOXi#r=jhr(lyFfZdg{dB*A7CQLC*hniC z?w4Tlml>goe>}$&tESUEXHe}NDLS-pC&bP1hA;fdnE!MlL?=t&Hs=vCThEm?{}&A# z9%Pak8m-i$#~7weT#Sw;W(@z0KR2fzr40?!p~1@)D|=HgEiH|-+LbdMAH&$>;fc_- zUIT>woF&;q=b*vt3^<0yl7eJKdeDInOoJ_1V_3vyybZvWMbUJuOq|POJ?BqP%K%J# zMXmlOlYzUnbkS=!`rJYSgoa!2QQ~?eWl1#rVkJ|)Iti2CU7-)3hG3ccCLET$&IVOb zva<0#5fjK~288|bn~5c!yMTTEVxX=gV3Tx;x}_etci({-TjgM{wGApoPD8zu^Qg4-61=+7lDf$QneeNUj7{xhtu&^<^-eWL zby)>Ha#@w@J$l+T_rtJ!Sy|plwjui)tnD!Hwu}Sp-yoI4N2!w&zg;>5GPGr zBE|63c5|qgmBxvylrY}RjJifi!Ph%#q~xI<);(4PtDabTrezf^>34@3j%6Wxe-1u! zD5gK+%%CS>9o*?(0`US#kfK%tFQTr%Q15TDZ{KP#_@xT6Lxm_>bDS8;{D*^mS80A= zJh@-+m(*}`xtvx9u^%lbMcYC_hs$Q2lN+JMB9y4V+QM}tr-N^3DSRtj2yGLs=oQlh zh(BQfcU@+p?wkK-tgaC3I}b0vjInir0$?Ma$oU?;aDNpy1dm-|E&r(CwXsK3Ei{j6 z-g(N_vJRkl@dMUWkDC zW_>W$*aV@wXM%Gkk8FEd4DKf~n4}tg(5l_X=Jz=gh4Za+<-YfHi``j>7K^8f%X8?e z@f!HGt`IfVo6%rrI}tyYh}AnS(Yx~%Y1`RC6~Ttg^>xD2W{%8H83!ucmrIL8E9joj zlR-~8f&N#Q4fX0j>2v;62-7_PXLV}oy30@Fyj!{C_|7b-JxIuc3zE#UOJO{Ikv_KE zxB$F$?v(YCA$2ESfV9|ESot;{LiX&SI~+Rj?Up)vs41GR=lHE=<6U(lwe3V|x)=TD zU4(o8ib9Olaj-sN4#}xI$Wi^fu;y6~ELS*BW_wJAXX|!S`)@~KHkU=QGTVs_c0n+{ z;~adbOCX~Y#^5YS8EYRCHNM!rnVkK-2zGg7kPE$e_yKm}&!+=4;X^w6_x46IcO{64ANs8*5N|T0X|DKo6yXXJ6mKWYwYcIFGuYI1M z&v9U*qCS=AjfL%xwb^Ui4M4RugBYpI##PVXlY-M3a9m<38yqYQ)r+!VZGjPynWY5Z zbve(bcs{dmqXE!et0Cu<9rzB56A9BM;xlp%4>xXscPe*5t8qE$*8B@ic}F0{S(d(g zy%3saDpIS*HsqeRB0Rd~1R0rC)YaS$9_34cX6!TwIlc=0w-1rLVh_lV8KqlndE}gt zGC5SFfIjBtu&#G5lIznU%wz&=)HkGm`rlhEi%|i^rBh(0*&(7m$lbe#6v%^HNuZ*v zk59r9@%M&sSd`}ilXFy2DP5JU7?g*VMuCv;69@m|BZ)z@FDhHL!|pYYAgRQgtb8(u z`N>2# zDJ$@kH8+Da%(hx%*38uC@xk~_9{H_xgvRD2qxg0ublvJsl+I59$MJDQrN9)wv3tlS zA18c#ITP&^&7rShH9VMah%IyeBf7^VxzC0SUHteIyQ{UGnCEozPrdp?Ht%~zg|{za zcdnBmk$)Y7%XqQAVyxtRMyH$vDwKlYYG-L!(17IER2fZmJH49nCr9 z?T#99^xO{edB_vS^EE*_E0TsemBRE}9BVkx1UE#gQoxgRQcXQJbN6tsS(W(1QwFY_ za)QI24xkxe3MbWyp!ZS(s84v!?rHMGfv49|te5+J%{KV5Rum0rJJ66I$g9}~M=n|6 zN8${j+a6J~Sqc#FV}t}|deJO(7fiM3BxVW7xa`?Tme0>73+70{>;tk)+tfq!Pkt3M zJKY7o`8=oRH#=dN2Lp~;hA?p=_pT5##_rQj4ICgY+wT@3MahBL4Y6YX!&G0#KfnWzC? zi_d_2w~QcqcLr5D@sesypG;?pRMF%KT|_~v7*y8{(bvHuR59=^eQ!SpHm=?Q-JGwm zL~A=Jm2vD;qd_vGem{KrPYoVF&45>pjnwAtejFN&BZXCC%w_AxZ0a-%u<`y)+U6_* z6REY>v2BF>J*!D?d0wIxQupApO$jJi=un>x%^)&l2j8>`tmXzu;lIAS+?(fQx=FT% zKVGGXoH=#C>ZL*>Xx=&ne?Altr?7LZM|K|BI&q8+o)h6U8hj@8V*7CN!;K_=c`Ed- zcu(HQ^zoan_`yQ18|;;4gs<28;)x@r^hRqo6*t!*F-KNXQPCO%-gfNVHiQ0|nh0l= zqe(+|8qIySpB#2cr?)<-({7L3RJ1OSPK!vvt)kMLpX4|(b|}TP;?kxSid*0xmrr|i zII<}`@Fw4N5@4;#cc%Vk3)R^biMmhQ;BojPnlpI=rfmKSTK*i*X;K;*@5+I10j{uj z77zaVPT-Awdk%HmuhGHCSh8ZY9xwgkob2M2m>=ScT~(^g$hO5WJHi|9|B@#kpQSK4 z!rsK-xR^lXT{%pday2c#2xo7;ZvbH$k=`-*(W{dgIg?Un%RSD zgdT)sHo)XtZV)O}Ptx}f&zDP2gsmUe!uA{6al%I~Kdx2^y~ERB_hQGJZ0Jc=&8;!Xxk1huvg7=DK5IR>$uaCbDGu3aAu8%M1nMP;OZ@Evd z%?yD?=k-+9!UC()52Epu9dP?YDLMO82UC=4AX}G5FaP8m$7ho0daXX%r4@i%qe5Y4 z$X&WeVlt}LWm!EcEJJ&*9O~vQA(?&X=4+uWA))_$yE%)B2?{J`)-@% ze>Pd)%9w65yQ#!x{b4hkoy{UPB^Nf>#0*th+gKd4F}-VVGnBK%W=hT>YsZhjtj(o_ zZ2ousZjJVXvE0@E@B9DX^_!Vln$G{fy8d&&OPB`XeUO)0PNrTSqdR|g&?$d{U~EiH zFw>TErTwdfL(9W3ec&jbYuN-1*KV*&0%S?xs{L5DCZ241eUus-2H;L7Ki+)L9Mm?S zMBf|jqTcJ*qTllqxVg9+MC8j@)6iS^Vxl}PU#Sh2T3KKf;*R~F<^SKmf2mi}?f;|e zpJ!}tW^DX_b^X=f{V{ZpDtS6rmzYIYGHcx_Ep58 znHqTfR5lGtI!QloZlH#$_3WQ>fbHUc*x>Rz+&oGH2Ef;@y0h{F(J-ezx&RcAs0K)y{$`bV(j%Z)xm6)!->O zdh!UBwOc~GZXSiE3*Mx%wT7f;nnC`DLh?dY3cNT!WbdJqf%`&t~RtQlz{oTPTs8MK-MyFfWv6LdJ?d^0^r4?Zpl3 zQk^wT2cOokd&h-gdHo{ht;R;w5v;}2Tap;lpqs4o=X$>VgaCHCaRiLz^B{|xuOGku zmHxOhg=%+rLM2}fr0ivAhgdxST&*I+DeQ;Nrw&|abRVYL-z5WU3h==xZH)RTjmN|| zoT|x54Bl}J+jfUwkk&UQX2gqGk-H1OcbU@EbXywx>kA3lk$|&2PY~ma1PrL{~fUA3`@S@?V+On#z_atT%B zqGl{RJ=K_sj2>cqoj8u*Z)3a^dy_dhY)$3lqv7gr6*>~6L$_I1vNyj-!T$Z@@Zc&V zx~XOZQ~Q1~xVBwq-JZ(fo!|m=RlH)A+8zYI4mDAbosPzDgrQqT9P&&Gh})h(RJ(G6 zb+>syZ)@1VyQMF9u4xN7d0p0&CuD*qOHyNV6hHukuSw@a!KrwiY4g!JO$${fVaEsGCV14 zgKDKK@L}Cmkl5NyV%jAz+8`T)g(L+BbdA7!fhey*I*RV>PlTh>I1k4_19gd>#+w=4AAe!Qr1xHTtLNwr#hGt93sOJeY@>=2CdIs)}Qt z_weoKzvB2XTVcZOG0fifhIvzw0Osqu=+f5})JvikpNMY7Q8RDA9T&moY6W~<@PqV! zeoXWt1K=PgLhv&YXb=z zdH6WJ5(NZkd&naKfjrSF7RP zm~8ON?t<%j=SV)6u^i#fdec^Zq2I;k!Fcy|aJl?Aq$V2RF^2(q<)j)4DvppT(JN?V z_91?{=?VNYI~qMgKa=zgqP+RNcD!v{>dC*NIbiwX5V+NThh~mbtUFW>j$#wgIiU>N zvlsBPa=eIV*BRP6xeuD}P3Gkvn#l#r4zQLfjm*I8lOTRjgl9NaAJROpLT+Umim1&K z{M48aaxYFp>G_8=QPYEWN>_-NaJv-wFXG{B|8;&|%O7%ey9m!WpL1Y;)e?jW%>~OV zJIDtMfUeW#Jo$bn!QbH|LHV0;Jf+G$$hkE@q_`eQ(!X=yKf@COt~_90h)Khi1y8}c z{t!JsCm7%T@CU^k^LQN}19@Vt^YE<)$7{O4b!}d+AQy$sz_Oa}*dKUIQ26gB%uURJ zeOIb6Q(!J=zqmml7*~O7v&?BW-GlVp1AM0~&%2p;vgz6Zah_I-2=C(moDBbMz*jrV z@a_KdcrQ2seKTd?#gmKRY;y$c^Sw|^RSDh-&BdQaB0P01QQp@r+)T2J%XI}Dz{zj2 z$i)HY=A;*(#C z>Y?xWZ)W@fW!N!T1dSQ;(5U{L?0W{_bXgZe?;G;gI&I@+k`thmeT(b+rogPW5N^&+ z>5N5YytB?0e83-*6ZYwxJF%GX}S-r-s=qu%KMqI7x7qRGMTqg_BBLL zdqO#BC2lob4B~PP;5)sV^NCCV^3)X?VvQl+!w)1K78c%OR-N@ z!#|@${H(u|YNnK8ob@}LgmS#B$IWEU{bTTT#tj%Se!>q3_aNi09KgEba3rNlRMzP= zJc~_7V2$&&4j;}|_B+@No&GkKU@PYul* z$;oQY`?Ql|RfxNTN5EpZDf^o0w?^Syu_qjt#1*__?j8TN4R?<)$7vG;P6mCVvals}b3Rs1O~99tsql$)E1??CG$@u!aq!u`QR#dQtAV8giE8X&9g} zYl`o+>e1%LEO@qDg>-g3U^-gTI7jeom}oNrl*VRIqj@vPH|MSJI&dNex=B*s>8YgM zb}|y7X{`2}-?UTh0Jncmr~OZU)5S&G$*YWIxZ=}Jw6!0iof=w1r=g#I3yvdx`?xt- zs{+X$J5HJ97SR0i3zQ=CBj;_^!~ykRG)c6BPHyRh?s`2O37AMluD-GIoo9q{ z&9Y?3KnwAA8m3O!iJ5K=_+4It4*94t55(K()Or5cw{RzVz5T#G-!c_q3!jqEm_sz? zkvYs{H$l#nY8vt6DGhwgW$;vA5a0KX^ecx3vrD@LLd*u}b77dFx|bk-G@21nK98)E z7<`#-hUIE<^o;O45~L`JugXGD!v7f=?+G}tp@`)$@;a`jqM9z_l=B4m(KEq1qn4r7LHyUu^Gr5o<#yKcAK|!HBh#3ab zcPi1aWOFWgSI(!O=4GLwuN;bq+(5g3c9>Q>O5f}AsqC}>d~ie`$FwC$?-m8PdG`|& zwq_gdIw^@g=Mzy$=nI`L91ZcsvT$>UEG^Hhq$$mZS*esf_-RuLDYjPlVQDmoMLB@C zvnO9!)ByG_kYOf8E~EF&O+o70U&cOJAN`VUgT&!V`q9xDgO5hxx6pXBN-pEPVMo~Y z4a@MTpDO!wnHXM~dX~;;3L~#Rh>{LYWpMRf2J0Ae1Rd2WUfCgo?_f2OfN=JZyBZm4 zm!M8kMQqp7xwyuCn3C{Rlz)8{<3)ck!-gtk`9(MKYW)j3*H;$*v?qYk$5zs`ERgJ3 zz@gCnI6QBR{$3e?#aw>( zn~N|kI`xKe@B2hdZpER)p?4%^lM{7+Ur2Nlg3&fi8!m?muwncxQV}@;?PZ?eEZzZ9 zP&N);W;BvhQvB>mpZG{h{)21_sY4z~1}&$iG85Xwp7RGlje8 z@6tG|o4JvWj&H!FcTeMyP;RHWs2sa1kI=1iHo_md61o~UkZ1b7*xWr1f1j7;mBq)x zm9Y|>oni!k5@T30&xU!y^`BIGJL&V?E*QskUo(v&5f?e2xy%wQ3D##NYmT9VKi3<1 zCWhY4Ux>j}M~KrXqDRjyql!1=S+g4)S5PIE>UCBizv?D_u`+@^P1`}j!Uwj~VhmH6 zhy|Z@@a6L|tNt=q%)V8JnOv?;MJgHIt+>Y5(1}E)#A+N3v_NZz?dW>=33m6n(dieH z(Y56o1}+!HHQEFCeDo&XSlq(o%l*fgFZzO4+$sHI^p(t$e8WgD;F!F%LhOz)S;7n5 z1q(Un{6?kOPn~Btv_n8I?p32oCE55WcPT~)TIt%(WAu8EHVy1Q$GUrN z0bid)e06dod1m4R9@51$*i8XixHIC^!B_a@kvlH7P{HSJQuy}Qacuve$1Q0Q^^ZHn zI>bDsWi8dD**OVA=9Eym7*)LeF%9=um!VMSWjJYf9^Wml1TD@7vz4Tyw(=9wHBXr1 z@0XA%K_W2U;VE_dRs(xf!^xyu2QlR12&&Aza>?hCgdj5X0UfH#B~A;X=yb;h_RF~Q z(8SBbXN4u`^iC8f#GNH47W&b3bvZOh{1`4$mBHb)`ysx537BpHd~IvQ9_WpSFOS2B zXu>RwdDLTNn2RNRS0J z(HxUOgBJZ&2jg}3ET1IQFsVZ-(5!kG&h1lz?j?43!Ip>SWh+Vifz_5zXRE;A&Kz`a zP3Fga>>*oD@UdK@j5~83hmwVHc-|rf+I8QNh;`*S$DV*)s~$+_UnQp<0*F%i6Q&q<;zX^7QB8S%oPy^g;~B3sJxcZ^nr4Q4NqTxQ`=Mw{UXf zLVWZpAAeP^z!N%0Vc^bEywMd&qQo)f!cKlLy+GnUuCSQ|+?=R1>(e>GIuuhWc z%`ijXnM;v9)kdp--={%8ny6pVRkmkA2DzisgAI!hVvLgvu6;wuH*PN{D(r>r1xaW; ztOj#hs?aiYoZz{3Haa@DpzNMhl3=$UdhB;X)NnYhzyFO~HCzI#zZ`%)6+ZZDMi_l3 zbC72DD&QT3Vq%|3Y18X4j)7D`Wi@?iM8ZP)Uq}SUkGz5)-A&Al^jP2h9?adAE@JX^ z1!i5)fR~Ss5}Tk3a^`mg=cm=iZ$A^PCbzaQZzXMDZ#X_Uw!BKq78$4{Bej-~m*ys$Z#byOWTOJ~CJ;vljlkYk-p*QO-@5UeI5 z#M0w24czsbc1d2~GBnNPQ*kmA8T0_MtL*5?o*Z!fdj#VQr=iD-FxGG|7Hw?KqVrjK zcslnI4leAaU%Ag&*Dp5`x=E7r@@NCUuY-GLC4h`sGtBn2!X@iBlHTHjV9%75Cp_h>P-iil)1GnC0MCk?76Jw$fD-$f6s=kkskSFl6v6FK=(o{lY4!d_Sf zSqqQi#5r&1JDUsavb{6t?*RapIO9PE?DY!l9NcW@~&-K~qODkZ_*8R(7pR^&Wp_(3@aKkUAQ8@^eyJ3Y$L z-(dl|S6ss+YY`mt+RSlmU*SaW>lnGb4V6#T;Ua@(I<)3IyVhzx3?&Vao_<#hecwn8 zJ~ly2|2bGVN1O~tIAKXwF`M%3IO@y%M?}qxAa<7wRg>r@i$_mm#HW>{amgJbh+M{W z4>I&rp^zZPahxE^`8;uJs%OS6*h)SAoMS4|wV^uT5s9$R#_|;f+ItST; zj^}Q=lv#@zWHwrjj*#J_2TA-x2lC{A2Na8ML*1XBnPC@BPuP`?$?@+n=5Q*$KHg6x zuJUNr8!?bK<#QDyBaCkEB8nResrj#VGCZsbVRJGu+UEx9Sy-X6PB+%RDZ)?jukp;| z?RfkS#dwPb>ffM9e#UvRy&2&Gv+m89CT4?W2Yt|I)E?FA+;C#(7yjVHXk1scAFt}g zk+roiQSNXS&fOV?t^b;sfX(}Hb=`6tdQgG%{#9(eV@_@!jKtEv7qGFQ0jC|{TfMp_ zU?fw1vsYy!C_md6ReSHzyrL{7yoT$x>=qYvg_)zsUlsU%vW`6HPr^mzxp<+20ckrS z0lVo4`fc*0k6)?b8ubD+OFC$^*(jV&A8DX64Iju~%_4Yxj3rm^F!0pK8>C(4u~su5 z5TjpJI9I`oDvMVUnc?4arRbHfH0ZXfFzvB9rfALd#BFarE#@*V5BzWFj6r1t{CP?JK z^>@&$5^puGO ze`%i;t~-}V%%09AQPS_}5fe)|y~i3%l8@5pjv27)rZ6h3SO8H%gJ3`7F?lG^gG8fE zuzI~Lq#0hKLH)*baCi&x2=IW|HUxgaVd__Zo1VY!!&iwdVogP+P#4k9P&!W>PX5cp zJ`ZCw;r_4q{uy-Of+ZCRxoG9ff$A45#tRfI3g^??8CA!ZDd-&-|c)%A@~f3<+QV(rB) zDAdMHuYXh3V@K)DnfJ(32_Dth%Mzy=f6V!@6eAPWVb;~H#CCio-==FKd{C>v_0N{F zM%xa+(*>r)`_WTKx3t9Skq&xl#TYxT+yh+n6|uRYnWlaFkE-O9P?K&&Xo(Hsa@>CS z$vX&F`Agz?Z7Jk`xi-cA)_(H_buGRlXpqunWFM zOsAt<*5moK)9}GPA5AR}W6*&_oPXH>cJEFgsMQZ&RS;Jjf2X)JhCLHDfw&YG(~#p1 z*sP+8I|Zh&@1iE|JnO`|=EuR8Gx`uI9EwHUGIHjo6&R_!5k?Z!sf%I*?d)_!@7*jJ z5bmZLTNP=D!(y0m+yX;o1{jGpPfQQ}O{P>SVgG@pbo5#Ry5E?9nJKEIY9`0(OzNRe zcATdT5nmaSk_2a8x`5XEQ*i6oW42?39-iiQ`*oilQHS($bbJ&6(;*nY7uS->rN*$O zGZk*?9$=v3E#vX_Jjsi{#-C_(p87nD=Qt*dp}6PA_n((}kHD8_uHJn6kfj)y_Czp_U zdr#n0`K#2t%^qgXKEPM8kcL6|a*RktQth+`r{^w2a+o1&+Z`Fl;@vQ+bOz!D)7cg4 zrn9B?lB8-s<+?TjWa67XR{BdfqdPK4ztl8i%%B*Zxg(6N{gj207BaBPej$#$@xyt_ zTVd);Yj#a?5L)%-61tFcrDUtaZ#D`nK5mB7o9p4rr&_R7?4fQKu3@k^=OS#|4EG8$ zV7-np%Gi$b9WSncuEbUJ-QNwoguDjWcyc$dHu@eTHa4HNn0=8u>q+oD*WYEk=a%4V z*H}z)N(AfDsd&C^J8ZZz0#awX;AylpFEFnLs{J02+-HF(YH%O_C8gu#h6kwT!lJaR z0M%yb<3)E#LG-Br)DSO3E0GvtDzb{X&rk~Z+{P=U9q zI+)yD1yH-Lu_?G>3z%+>1C<&*SZz|so21Y30v-&)Gl^&H0xLQ2=;QW;`(J{rxCr%C zE~FPLZ;(2deh~B~gLO$eq-|;9d{|Pvyxx3RdLbKL=TjmwN1f-pIG^V<=^qT3{Gj&n zE};3f6xw#U@!Gk(uH2X-++DVn9XM0T`GZw?%_m#nPv$kSHWA`w`>688!24eDd2@zm=qc_xB?aOdp}m?i&)^NP*j70$PS%k2wD@REa!bW$>} z>WvJq>ZT7b{l*O5ciQ7slJX0QU_m zu`G24qj!YQah09mu0%61A2MJx&W{eI_M?pwH(z*=K=ek$1y)o4!-vt)@ZwrM=~Y`m zC*^*mD>-ND?Ww!LM@%cZ`GajqGfnNJdK)izUNT1=8&iKu|nZK9t+)IAKMMrg>&6Y&Cv3C-i`%H*esK_#J zeXbC7OC3S7O%cZ}T7->}FHrYK9JVyJ(q+Xm*miLceU*f8VYN7P;9Cr{*Az6be2;%? z7&Hu>EXZ$s3NPZ*u#@q|VgrA0yxBljZpwyJUmba$?j8a0B+hekUX*w5S`6&XI1VTF z$`TPnY1na75r=DEk#xNmR%hA*v8|JWSCl4?4L<^=DvQvgI^+Xb)P{GF1co@7-SDCtQI z5{e!_q7@4}sIYhysy#bP9hP3i+ond?H6#Z6v!9au2+nOHc8+ND$dFSr8(9x7_YyMY zB(u?0gZwLcOe(%yZb}XQ3YW=4@Lep)8=hZH%Suw&0imDFT=Dzlt*I{@y)_#?xK)5_ z@*LbJ?o925cxcnnK$6eL;ltZoiRP1IEUQ<`s5`bWwj*0n__;sHp3gZ0j8&m|(l#Iq zwXi`yj>zS=k*60YK$7fu%APt%^n~I$FGDT1M(-d$uhh^@6K;@c#R*jOloTm(I|O&7 z3xT(7kiOlTNS!{vqS?oPG9zCr=w#tps515mvY&mU`bE0HydR*x_xs|BlvdRc~@pc|->iLh%Jd_1`-&nHQ z<}z(@<}#Nf+!^6uANyX4M}8Eqhc$;}=q8&Sjtf!2h%*xf!N;_5yV5~2ovFjt+!jnf zTn5`djiW;Ag#_Lyw=I`^-_4{(57N4#e|Xs?h&2#dMdvtGvN^usj|Va{1N^c|%7#>3C%X80Aw`Jx+clf9WCKnAA3yWVr;%<0GYZXgrw#kC;f zQ#)ub;W+-bvb=;xH&JwV6ID3aL+@H0qi<^3Ehpc!!@YMk$itr;_c(FXaz+!!Z1j16 zqn(dw!@?TIbmk7+Il&rbS0}P#J(cZug+QNTP z(cRT}GbWKZd8(5gsmq~w-3a}8Tn@e74_awwC)3p`)>v7;9f$f%;q=!PUhB4V@L|xf{YBwrk$-CXe?6D~>sw=|^$3iU8X=dfJ`>5ZXwfIJ4K17_U0KU=~ z_+R22xm9WS(7OiL4ei4jo`~nKKfxiLDAscCGVIvp28$kiWG_t0rZz(f@Z3y?eCWJG zWW%i3B$0{SXZQ}yy>1P%{hsWGe`jf1ofHYq;n;fPCBQN+nDm8Afn_)J!P2*yZd-DK z8jYPoBk3x-DasEO67w0UdnIhv--%p5?>71_|4b(AIRO4P+lcuRb(k2^126K@8I4G; z_g=G^I=cH)Eqxbup4SB4%jL0P`zaAqk`G|k=3cVwy@+7r?(Yz_ZYjLHsUes;^Q#s9 z7ex(^XyEv<2&4`5q_Txa<+pXS?sJdQcdpvdq~1&?vI%5F_7LpGR2=&8j6OOt7Xw1n zAWW^Do|0G(Gd^-GyF)r;5rlBa2a)3 zHH<6L)CFHe3y8y}Sa#*NWpKQ94@_R52j2^wA)wWkr5<+d>1+1X_I)12>)F92Pf5CE z-UJ9gXbbn2))I+7Ijr?&M>yc{0_+|OVZdl4vf94nP`)YczG}|c)K3F8;Q-B=5k%X@ z&Jssu37$!zHQd|o34Px(_~BC{@NK*h>wA=QTwmnp{@oFwX!fiR;!bjaS(M<|6 z^JJ;eD=l8-jca6i{W0nuSqt+9Yrrx~6$}?NvsKp~!@BK}_%%Ua@F-OXggG9&)JPhm zkZ;BNuDgxV*E~$l)Sia)Q~yYhjw5}$vYYeLp2nb7Z$V6i4Q5rV|d5>PHYo+Gi`qZ?0 z8gE^MD(^yqIQ)ysg6J*YxU*jylN4(pK;aVZ$u1P6O>`o=3YF3K?>}Pr@GH|NI!~ae z(1GdMlB7{rLvSo=0N=KLhL7JnVP@A>uyuocR3)oNajv}U z<2bK++7WuetOE2xqrf@hKbUsd2bZl*gnr%4aOUS%oZo((#8lWr+~rARLf9+#WiG;F zO8ye>dsS4o%pAT%%w==T%-KW66M5G~xlUOs2r<{9=Z4w+|_y0;m&$78_z0wYYyh9)?RE~NI-)AP+rCZ(FdmI%^0*HZh z0=d9!!p-~Ela3J$${tT(%3}uU>Mfth=~D;LXw5A2vdgBvH5(uzMufL-cRvwZCk3aq zc9HR2WsFRq7;n?x2gLldnxN(KWt`SA#>UmWA*0S$n2#K@GEyU z1*xzmGn4C3_(0;-3ozw2AHJ!bAa8=_P@_viwAA_)`Tj1JYSzzy#3$M~E@PF|ewQ`S z8o3awN{eU%x1VgkriL>wsu0$EG76Uo=vNU}y87y3bUHc#yqk!CA~zdgbZ>B^Jw3nh7Zi*3m|Zy8dPke$X7 z;5*3{Hx-%DvMV(Neu#tP164eewiu4|E8;FgPx5Uu4+2Cue{o(Ot(0=a8-ai6ddWt5 zH{uqpuu7*Q)w*H~|yF49VyZS=TvA0^f95dC@vX#IH!OV2MP`%5O#nY})c zFEWE19UR9CbS($XF(LRNu)wn48Dzpc9zKbbM-^9=V*zn<=};d!&8ZT;H?6?YDibJ; z+y$>Eu#jwc3?}s@g2k1Suy#`$;e}YAp z4CFZ)(ZvgM*_Ac{So>LqH_hn_-1&V0w{Q8zCY`Z@ahv^c!H-H}_}^5lF#g7`n*NEL z;heFD9@hbr*Gk%-7eK^PABJ=gs7^D(tm0)5f7X$zKe&Ya>=Z`sB7vo)mb{Yk3=obi zW>!XL!-u=Nq;9(zFN1S9t=uU@beRJ%8k7xgH`hb_{4&y>w+%9a^2kVH5w`sUl$_Q@ z4%8K~msVc|!mojMLFrJ!c{;t0Ws}lHf#8(+k1T(gOQx1t!i3%2g_cG(U{$XY+KDAqQlLjcEqPc@AM$( zDiG)WTf}i=f3=VWd+vc$za!gl`4gBXNCSUt3I-I+#it(U_-QBR!&R=7w|Mp%vbM37 zE%+!yc6S|sJfA#xAtk~4sV4<_@&WYjr((__x02SZY9s@n$H2%bi&z(W5GTb6@UZ+9 zEY;$?NgYX0u<g0Lyw|(K=zASz=-vEvqCPKo}OY}L%YkI_W3AXg8(f=$a)6do^R(H)) zi0GBQQ1^X2#yP~I^@37Nez*n;#}6|nwiLn5h%4YFEy~;eNdztzq~X@T!BpnVL;mgZ z+l=B2caF#Yh932IqEn{&VDE+u98U3v^M6Iqv2X?|wVPty;Su7gm5PZ?vKXVekaH`k zV~SS})mk_Ur{z-U*H}g8HqXY-G!-0l>)^}fPGb1Hmh#G%qj=9H)@u4c+Avyzb4Ew&Tuo=#L}{!bNKd8GhJb-%d6x14%3~2@MY#v zBJ-#kKmG|o<@vI7Au|=H9zDzXImO}5MRz8@BLoAwLossb7ro`CgUvzt7i6yZ@`1$vY2%G zCbe032TD|SU|LZERt9p;=#?#S+hQxE7i?rt*m7MA1qXZ-F+itG;6=zp7x&))wMO@F^SwQ>Fo8+5&_LRLzipq)J*sbIrpknxt`S(W(W zraS8)Z#Bn9x~MGJnNWaBL?2<;%oc7Ijl}Dq9Paa}ffldhc;ME1x_I41a!$Aqg6GV{ zfP2MwaKU4&o16|Bsp0r&Q4Lce(}4kdyuizHhTuQp3cTr*Ll>9!l9pGeiTn5Qy!1;` z1RpZh1WOJ)#-3jcwuBWyVeU-&Ain1MRi~NG@GS!rr(s zC2K=)`HBEIH@Sjs6e`9>`7fx55pep$UmOnB!fAt{c$VBo@Auhc_`h+2KWlq2YCh-O zR98c}^?Bsl`6kl$EEsR8#e?Q-8Sv|$hP6J?U^7t?gMW7hAiF=(?w(%(Ry{@KPdEwOe-eeR=>Z9E64OltR z8ZQrv3I=ZJk%0$IVEa~?H`vlb{&@If^P2-$>^BK}vy!0y*BvMj6mc`0GR&PCMBR4~ zlH5~(#I1_fC#vD04i}i>{RVGKah-vamc0JIpSd%WEKXSJgzjgh1dNCTwkxHe`p$In z(!hj%J;z~qtiyoGU4Wj>dN@((GScO{(c(xp=P!07PW2gN-hQqR+4GaWE|X&4ZVX1( zeY0@?**FkL`m)Wtc90z7CZZQwishNs`1314+7-?!V=VND7SNZ%`%$@4nMbtyakKCT z)K#*;>*?JzA|iu^wds*1uM)t0))&Tb{9LQ=;woT1?gEpjI298;PoM?2PrBGUg!E4e zypdDE;q$?;b>~SMy5SPp_7Lc%h|AbEa|xEcSc2X{UZ_PosExNXgd3aV3~oLhd-@)g zB?0(Br3e|0FB;jpliO>?!=BqlRFerJNBs&pj%pD8a2t=~j`v~goFsf&kVFIXfFoU|(Nx=!lQby$3 zAJ%Mt6}syjWO)TM(6ZzTb1VBS-L!oX<}xKvzDI&Kym3HvotyMosSn!p+2hY&+T1%* z7Sp)E7gI(u`BzIPa?U4B7-?IBf6sZr?>bf3W+#n)>$*7xIQO}XI7CnUeguaDxfx?| zCrZy3;rUhF=JsM~aG`TLoP2wZ+_8L1T1!r#A@@JJ%3Mvbane0F7SHWHxN}hJjfYg- zTnq0-*TOVi7hJM$5*?m`=zf!Lgf&g5ptfWkxD|IS|9!@&~bgyFW6kS5W%YfT%zD zNcJ0?ZcMv`nlBPy<+Asb<2+2Yu+6e3(l9l)-K0#&~DeHt34T zgO%x*xgO0*L9J~)EsWVplC6^Y&Ya7F-_wBp(1%ZaD@ZPvS27NA#}a`R^f9NoS*i!* zRf@tmb3SydyaKiEcoaN~p{~2GQw@g8JL~-+U-Lxi=&9S(!?B(|SrG6<+kOgDz%cim*1>wjSVRfJa{Bo7{j zJIQ!2H5}i*oA!OLrN_m8LwHF%?{V@FCe>Qtu`RP47r3aq6(YscX>8{uvgx@WxZL-Hdw#bd z!$z2@7p1ZG>jv21s(c!G*_6v{a2WczA8?@VIy|t_g?|qSTyQlcIZ9d(WT(R1^D4!Z z*l$d<;2X7RX@ul@PdH?gLZ)0ug@4=4dGl`T@YY<)WA}|Fvxk!-n7@}tXrdT{Qwpck zh(jl6$cIYmZy8IS>bGJ|O$ZJ!anvE~9z>6?Aj%RR_%dP@L{%!_*r#pqEc6Tgwyc~@ zDBXrDxf#NsehH+lw!y4it`DDM4Z>&IScxZb{O+`5w%z9}ie8?|3f)b>xt|u&p>gTl zje8#MD)ND2RXU{Bs+3~|=|WV75JjUQ;(Yr8t(=&P_VbV7&)aHn%}^S3l0|S-cP0Kx zxkUF~S%)=F4dnRpIB@iK0>iD9R4|FlF*#hKDjkdI1ZHKt&8`f+@)&lw`0?PuRlm`esq z=Hfa969|x&p*rIXfM@uLT>I@!e+Z00T|=2DdgtJTcL%}M;wp82JB?X1P)WWzBw@5DYqHp=?!~6m8)8t=Tq>5JM$0*m@7`}$*?A@- zv?ArorC0C9lf!fpxCZEBrjt1QafkumJx0Xt-#d07FB6yc1i?c61X5kK8BFJU(ytlc zs7hxxi1ZucWXVTFHc8DaPIPJwTF!{FR z;ih`HGuH+5EiY5;^a(gOznge{C-`;uc2F_o_#Y#E#4~#qjz$aUcJ7+tN;m( zE8)r)X{4HmNYW)s#-ziA)-9JKZm*}KP|z9FkBHAyGv}kK9EtYsl)~uOHr}VoL*Kv;ESn2>HudRsxqDES{#saIn8<^7lA}IDi z1&s%SvEWf1v)W`F)p*VAM7NpYx?=-W^>ZvPoP7W{&C9`s)Ro=!i>34T_L3K~+rh%N zf_d9uhe}gVz{n16mvP4wcU}p`(l^Jb+qg1#zJqg+j609-*EJB)rV=6;eNL($+#{)L zGf6g2jn@1>6rFcGR_`0fjqF`Al1M2dLPef)U&l%)l}MNvVA_?wsD|X6MD)Z)`frXAv|1&Q|CAn*W`{N! znfj7W2%f-g4Hm%iKbxu12_Yuf7?6;vQ@HVKEXF--z=;E!=;*nYe9o1>a~%|d$=hg{ z_jn}<{=eJ%OrHRMx{%WLzuXyZ4HTGtBM$l+M9kd;?$41R>ub}2@O{bD_Az)d)(<*! zu7TP#3GkUPlgztq3`V7*M5zeqXStJnKCXuD&7X;<^&)uw(H`<_VmWpMO9&;}#^VOr zD(YVtfI*Wk^Uu^0Zn9=EebkVFPZfJOkJEpNwp9bVwZ~#&ehOWrWP-CyE5UWrSK=`{ zn7R5|5u<;lLHWt;RKR5sSQpOt0AR9wB6+UbNrsd5fGhJK`Lc5g-5{Q+ncmO59w=iz_nx7P&QYSx=Yq%cckn~U!${st2FD*3g>g!DWH6%> z=UtPf-=%wq2a2Pc<^*2u5zE|qT~KFIeY-Zawhc#jeZy^Mb@5gCJvyEi)UCW4kL$ha zIX31!ZAns~ZtGV=Y+NB|N{uFCW`5z|&O0LGa)w+v=Kz6OA@KfrG8vHVB1ifw$lTy` z@G&i+A2cPYdE92Y*6bZEd7Fi&_atNb%^qs%Re%wX|3B-V4=HD(@Q9QRoxNs|>MmWx z6=l?s3(wMchRS3<-*y~~K!KqkC#`khV!cBXz?|IR?nUYr-#E)W6KU&C0>M;>mQ)|J7x5-I>C7VeTCPwm(pN1 z0*yr?@SAoae$^%r{_qeQ@jU11%|&!zj3c>W9D{kjX|TYw97la!h2Hs+Bu^xB~Af@t|ib}vI@4iZG>qXr{cX=W?0;Fg#K2WfV*oG_@Le_I+UvgMv;Dkfg&;C z@x7h6@)6%1T`UiyYewOu_2=ogA7PxfHt(d8f6Ox~%vnR@4Un9wL&5(N217!~|uQ-z2jQQsI_OE9}ra4C?Eu;i;oB zdv^(k-1&*Zm2b_|rXK0^F-Y4%6V1CaQ*973jL!kT-J@s-s$ zVRk4-S2t{cY;P}c_;Q42pY?;x+JD66#zgj;!#i5koJ)V!jOE?%o-p8YgZq8QjFeuT z0E&va(3^V$I-a_s!{sOVdbW~KbBq|9))oavnik>K_<9oX@+}$jDHKE8e$t&A#JSgZ zd~tJ8B4lpvBB_rakR>{;w6BPTbGvOJS65Uxa$8Q=rJ#r-_jtDca~GCck7f5>seq$R zE8&IGTJV{67mr(Az*#}3@XO=JWYZ26c$uMs3vHf(*DG7L$M_MSty_T`bu4g+?nC&n zfbXEZI{^(d*TF80Uh?|hURs!4N!)*#2oqzagf%O|afatlqGo%?x@X#3;&`A4RQ%;x zA2Bgl3>UE?_&yfqpCf9@|)vbM4_+*0!Hh?S3C;R?|J5kQ9ew%_W`7m#^BgX;&}1QZNc1J zFEpAp0T*8$;T|N5qQTc*u)H)&5b)w84VVzZO_X$l((LQ>@T|l1dRrkpOrXGam2)~W z2-&MHF#$FXC!(70Q@o4w^CuUW3 z@C@@|m^u3ZnY>*EZC%fRneUtNo}W`}GG+UnpmT#d zOW89ALEIM@KoKKQ_3`!P8EU53?6N`l-fV^SO`O$IG;nf3Fem(=I~o#{;;3Ab~1; z^+%JYaC)=267{+wP`W6UsD)Nwnw>W8HyNQ*{#5hMx;^v|jYCPhFjP<$;3~-@Sa!b% z_l(m;`vE&BujyyLS9KGMO+N(WQH#K&CDPhl+7zr?yOD7s~C2Z*CcA7Q0^XX>b8*KN`c@d;TR2)>~=8 z%|LJ{y#*gP8ju~sUCalUe=yWU;G}pi%}ny9(igtdr6C45IhdGK>!W zu0(>2VGAvLL0j1wM!Qa=)<$7ilBK~W9c(An(|yUM(TCA>Ghqvkj$vnvuc<3Yh=Lv$ zS?JUVXU|r&k)VZ0uD?yfTSsf?u&Ob8eckf%B;Fwt)1FMeO!g!SZ|&p;vqw_|GEj z79BnOZ5NNH75V$f!^JSqrw6Xqw(vQ!C&=91%&l{kVEeYbf#N_H1-ST`3>w9yVB(KzGSp!Tb;DOc z5WNlpZM&%2p=^9#H2{GtM_^2#9K5#*M9&o(xOMb)s^Qy%A`#-maQQ_T6?hqqH`$}} zatG)r{|IPjf`%3yWI>^T-FtB+jyzPLu?d!N&KL!LfwQ2&eF51uK)Dvbb{HMd z3`O26;Fxh23H|UHMPP(o}`M z#YQM0R{_-8`hr?(hH3mFwGZA!nzsgPx7# zmFVjl6Z?f|f2afvYJSvlIv3lb^si zX)CVdjR&^1v$P}Q9x>Y2hP_D}$cr`;%>VBow=&s}aqbl|3ndn|$3aC_Fd6SWoi@715vy6p4q+dWJR*wNIiyA^cP9PWK7Bc7-M;F{~}HBMgaBX*?G+B@m{0eg~!cOVHS11~+-J#nzmq)NyJe z8K^|k{`oYlQaVfWZ(HM2zH7QBf!_^olPA~f9)R(iA~=!S2YSEx&WZJ25WjwrStOfD zwkMCq-zT2Jk9~;{^1Ta!yTm~wq!fzV#=yT{S7^$e{an1%9d6<86pSv2Lp;(36FrtN ze?J)G*GaeO#f$Qg*SZvY;u)dOs%|Q_<1L77)nwN{O9#t+F7QUo7F@69(E4S`u=PnZ z>55h+`$8W=``EM+3kZn%g^Kb{f%(&qm0nb;4IHa+=N;+ZFQFq%Yy#6jo?3T z0%p99hPU?W!sI!Y?+`1qFXH1qo$7|+43csj{crU{)X7VZl;(1?FfUR`A)F2s)JN@#i6Im zbQpXzjdt9BNWMN91siIfkefG5;Dn7kjOZ6Yno$R^@AAk*UuR6~yh2@blfX;hf(9?Q zLd&%bxaHn}=3+(Mb}eOe4iKl{*9DfDJOgrGE<~JtO^lut09&#fYlrmV$&KqY_3e1! z_=)xyqrvy27KniRpHD=Q&o|FhdQA5SHCX?Dzd`+@7#xu90td%x^7UmSQO)D;4!3VX zK7#1UhV4=5t}zn{?beT6XVk1bQX{UGf9uoPnL zBbfn>BK%49j(Mp{bIw|J_-Wvlm!k)dzp-oAH%8r5l0Nk^9ssuZWQL z0;=(64ZQo-M1#G{sIjap*r$Hrgm#KlLrKV3k9kUVxCMd3{N1o)ZX*pVokd=_9;P!z zGce$|9c)?ki*sfD>2UKAh_buSssB0&Yky6}-|bHL?0E`Nk$OaZMmxdMhH*q|l?iU2 z8$(8a-G=Vn(X@VS71u8xk9V($fZ`_y)bxKyPFo#CkI|9Xw!V|fEHJ=FUo?o;_RVNt z7f5%_tS03jCZg})Pipb&1bjZ!Lo!;%@)_?g-n6q%pyqXv=51R-(&8gfDNGV?O#04+ z8?VQi5~pyQOB{V*mBXBOH$nfkisZERCU|j^&w3U<8r5fhqjUbs*u?C@11pab2NP9#bwwaI z`F12dY$F4suJuu?!Q({cyE>6BM}bU*D;~F-g41?tmr(UERAF znUHo)q$Y0z#l4->dA!Jrp(~aJiI2kmj0as#JasOt@;SEC@ydUw3j(c7t_`$Q_u9jKi z#IL;5u;&-&C^}5L@h+WhAmDvZI_RUUj2k#Joct=EXlpBBqdbTA^KWq9hh6B?CljIN z(mdMMwu!E;n}P3Fhrz1zQh2T*kesA$5d2~%y?e8vZimr&Zc=|D!Z|U#{$nQGJMMrX zb4)RP`E$m~tCJ)t$zgufPW+aHr2FtJj5{+ERN`cCz1?~`J6{=_^6rzg7#|e;Fod$2 zd}`C*M;1I>fGdB+;dL1n>9jm7+|x!L84_-Rax*#6qJ*sx(|CT-XQpApSU9?825f&t zV4IgIPS|Tt)*9$z+;?AociPD4I;+6aenYNu#|dv$ zq>;Pk;?tYSXfwwZuX<0%1yiGm+_!W1RPF+izZeEN&;D?8 zcl$!U=49?9P62E8UF0D@D@u)TV0IsWPvxJK)jd4sF1WS90za;3q1Qq(>CdWt)bE=Q zYFr*6$4|(yEfb4K!<(s?zvv8bOFTdzQU@Po9%I?lHF&a`W4^YnfUMv0tmMmA#I8)A zW@`@9*FK6u{f+lQ!A6P{7#858))@M8k^-&lk%J8WZ_(X;5;0>G;K5P@d@xZ1IMGAQ zafqOM064R0mub-IZFkwXOuNMy$-76yc6LXOW}>fsuLqBS#Me(iTiNV*J0 z^;Reo7lxnakLUg^(&AmXmTW&x+-=o^F z?J=!-*NUM(mI>WM&cm|%&*8wq0@NR)%WkN84U&US{AZ1YcwsRVs?CD%^Er?a>Mayj zN()0HztZtV`$50v8SLY;%7-US6}sh{2@S?R2EW+jP#5u%Z2VkI@|@}+p?^2{7^RZ4 zA1^UikKY41jR9P=(ir#NUxfv{d$d3O8~^M#rERY_lFP>{;c@>tJ}VQB0h#lKcNfP9 z3*Jexy565))Aj_=Tyg;YqxFTmy-tu#UG-lEy^YCf#dMPu^RZbuLzWW^GpAOe3xjq zC3CBG4(ydWLp4q%!IcTSL8~AXJ)Mei)~gdRoK^y9JUchvQ5Bruu7XX6XA;vJQ-ukK z<=C~ZXNl5`JJx%KoZ;(qUG^zXgV!!LsB=0T?026K3^ad(JbM*3%dZ&sJUoll=PyD` z$8qu|H4Be8T!1RM%edlG928DU0%d+i_fjbfgj$ddON>h1Z&uaP=x#TzR&VtUoIcx}_>`m&t~))k(0Wa130W z@sn%Uv0?%ghVadwgCMVM&a+3Iu<)8ao0X6c@^TSmaCbIfeG}OBsj(JWYv>!x2HkKOHMPJ#59jFoT}XA7KO;ZVOv~*S;8TxNm_00k$5cPiKkj-^Hf1`_b}Yt$m^3b- zaTGSLOy;@OMKHwY%6|B#gQxy6>V0SjB%ff>*jG-t#mI+?&q~1WvunwcvF2EIXg2SI zeg-)vFQER^Vp93U3Ju$CfYbXTaO%28Yr|HuN7Vm8zrqA~=pRAjYKNhSe|FXgLP&7PHrn(PI;&M-}=lmfw6zam?PYg(&t>F|}TES-B8b1H) zg~|b`cz@SZk`ZDDXZjz~J?fb-`(G}!Jt(5Tk5Ra-VUA)iWwB51HnUds5c%4^0aD5~ z;s5gVq8r8G zhsr6^eKZpX@8sd!PX(CuvygL6$ftW7PmuS9yI{v zF8%!tGJ5wEdS|eQ$&;Hx-Z1j)>0nuy)IAAj>p4Jh+yE!aXT8(!hhpHkr{qyHpjbsU zu3PNL=cw;uYhN6?r{ASIUZU*BFP-3WwH~5p+=l95aaQ!Yg>be02|R1?4bBzhW3Kr! z$XO-Hekg7rxn<2z@o*RdZpyL_F|LrjSXOv)y(PPDN*gQ>ZHGN_k&vFh5Y|P>uo~Cz zVeayKm=-Yw$IZ22Z34z&a7+l!wHwXeRhVySRK{%LJM-pTos_T8!OaWFLP_9hG59241E?O* zW1rQ%0GD}E?7+$hbm-x;@HIEdHQ5|&a2%wIK8|CTuT6saCzlJlYR|*pw%JhX!WVL1 z1>kA%(;yf%kzIF_e^0Kkp>LLKfDJ0ndG8uH;Y`rxxV6@%5+KU+v0$d zOHSeejTAJQs=$f}4#A#ly;O1$@;ko=5GydPtCA^!Q~Vy|^vSzq;o@NUvLqAi!W-xm z>1K#CInGWGSp@0NmoWYj9>WKPfpT6IW`#)YL5 zv!AQrli?BKA9RY2R~8k{{T<8}8_r}+!_JV0^}XEqq)4#+9zmClK7&haLP^PrQh2Yn z7;`uNB+>T#{P1r#z4amlCojoD+mdR!HaL~<8jphvS7+8sY#eK*&Js7}GQOWH2Q!ne zk-!O)=<}tfI3=SJMQ=_*8OxbmsCyDjA~|53We-~>Kc{Z0qv z4HEOOkc(NbX!Ddt+}MzdH)C_?#=pgkg<39}lnvkn*G;%8`!@+1bszsblm|2OGT_-~ z7P%Y;9Ll)~A9|0`C%y5t9a__2l0yt6mz^ThW6WUUCLKulcmd9gQf3V&TY$(8z$?U0b}3_YhZnH_32_om zZBKuMh`_vsfD^*y3FH2l*c(0}d)LQ~gh$6|lW0N&fXh<~r+ec)naG0o%= zS6QtMXBVEL-~1ZVaU0KV)strOImz&m?!_~;l#vvx{?Mb?%& zSJw!rcdvnm{CRw(DTY2gp@_1+41ANd;rVkjP`IKDo36xDr%^TZPQ)@Ov}^{=zjYwC zqK&xrO4J?yGe~aLoCQ(7Uq2*k4%PeAVfJA~obf{wSARE$hNtJqIX`cBSQLP(Gw0*8 ziYxT!(OIPNmn1IPF&;#dRB`7cM=DK6S(n~BjZ;?5XRf8(r6F4VaD03+XnEwr+6%kM zr>s!SE>;CHsSl1^;=34Yx59vRCoEX;0Jbc22eIy*AbNQjm1WD|f-*mEx4A>!eJdd8 zuK}ue{e(EvLQtudV4W`e!LRbaP*OwCAxw*h*3x>YUN6*1oQ1|Zu zQR_>kqUs%VhS*ZvVfhwIKTZ;kyIhMi%-Zna>ysFtU5-WGYp`UQ26+24gX8OZk}he3 z{VQ~_eMdF=Z|40UI#ZxpbUsKJxS?m+Gp>G38Iirl;+-ph=&x@Pa4F+5T)z>HK~8(I z`dkk9IyzxUI-e7*VBm9d0xj6L4>p|J1tnGwNpW=m)9`0HUi^81uKFbdt2*+a;nfg) z(T*m?$z?EAm*-GyO+?8&5p0^PL{D%juySr3EXeOf)0z78hH)H3ihUz9c$c4H!h33c zCXHHMD1=NyImT(u1=5stoV!)w9Mm=l+&ww@%ZOw+1(4)-9+=GlIeU1uW z;>c>dQhL2!k7hk7r>)D6P;tk@V0iR3eWZRA*`1X{%gz@kmd1dt?|J(Cvoz=zhjWpA zHn{qr2!1-g99Hwbz(Hit{I3O`-t>sisz=e2%Prxj{7+(M1x zoz+8DozG`vWsXvFfg}C4;2wGTIn$1r|I zosGmd_c%-wtcMjfBgFFS^}0Ad%jqALN;WPyNxiaSh;a4>=*~C;fqDtVo%i_OAD#du zl3L`B@+w%=Zv`4(ZosYbqsSRtCWU{eW1V6rvwYMn%(DCl-%KMw=4~LE%xy>8*BMOh z`~-{+Ho}@6?j&}FB%Al~By@K<(SfmBAZSl7SnWT-?dqz84Ik3+vb7|;X6YT~WyEC+ zu~vbVVvXRoEQqbCNkO5MJsmUA1JyQMr84q$Fn75usuMcDeT>Mj*Ato;97>G8M%3Sa7yS$epjmV_r(wx+Hw|uy?3;J zT?(eNU!RFGc96#S383syk%M_+w=CY!A}#Ar3MYPbX`#bKz#4JUi6d z4iiJ3ljm>c=-N*K!Np69RiX9m%#!m*|7L|ItSmcfs(j3eYdS z4)>`SkQ zX{JW7-}Ss8ZBPb$c|O<_y>E1pu^WK@8Nq=(e_T@opw_+~dvEdcSJ^1KytWnZtC=#D zb4oY|PyP)3IR)DOS@Et7am57kHn>~#0-}u%@Lf1>ye2NB zTbHMi&qaITh?*6rC#T2vgE7KGPq!_dz3HQC`^#Q_RUaYPF?%LCGweevhotK)aCClQ<}+>!3(tdd=h^j$b&{VE4-8UkqVOc zQ*XfyiW8R5sm1=N166e%S^r>Pg)$reaWoh5mV@ud%DMASGPq=vIaGBP)PCHx0k4ev zM2;OugRgc{!r-~r$cKdrT!3vB-szOU-9ysCMSjv~FiVSV%)Sb@uL#lp*99nv)FO>4 z49fVuAtmLB_A7oR6|2%HlOiHKH9+8AE+c&9d;Of#s##VEd}#~m$-;E-=JS( z2ADSK@b8M-L80pnah^f=_qSBEX>G%0TGz>%_8%zeSB4pj#4-A<7AOcD=$^3k;5I%A zk|(5s=hsybsXU3B?#=tsU5}xIaSoKtPO3Y&>JBxDRKx(606h3E99jU0y!Z%NHu)NH zo7F_GPkTWhu04d+*=NbU#<6%}eGWC8UQAn$uIBTgRe1L0Px^gaIHYa3P!}pI1q&6O z(R%Z1a&oH!WG6sw`@m$vaOEBTN7%V+q4{v`TBs1w^NZ8KLDmB%iy5=l3-7*<} zmQ~WP`UOP(r!V!;8)WX@Qls6^`MdusUreH>>GgwwFrg_D*=3i=)X{UX#7La)){4-J zeGjRu_$D&?PbJ}=?FFW-6-@YpVoatYdnwkBth90A5{J@p9nTS0Q&%LMqd6O&5(r7T zw>Zn#QfN;f&%V5U6mBief*+RKVRVTWcmFzzcLlHTOZ!x`J8p@#s9V>CU6 zt9Ngpu21+r`pOEND<=!hJE9;@$`iNh1;7?QCo`e!6jZn)JvVZnN+iA@Q-ej>IImV% zKV$?q!W}uIoIEOK{g{g0SA&HIG;o~EQViKT6P0f+rg05HU~|=!%?@g!CM#uxe%-Qg zU&2plwI~M{e|iXB;Zd+;(5#tBo~!(mY_rIQ|o;=k4aI-_oUa* zlNJeQ!|}d-D1EquTD-_)eip~W`7RCC?cObzU!Y1BJDJhqR}I{=cLm(Q)6Xcq;}Y@w zv58%wpvhWRe1|Pv*;L)k6oV)5``;B7q`TJz;(k(YjmI0}Vk~5SE!U%y4eyg`<8x4@ zyPV`^N#I@Ob7a)L(dfOuI|N3U-(E6xo{8DDvZIESInU>D3!bTav3aH^o2MW-@}+4 z(!x}peYNezMs7_Kf!ksCFs|?lbdKKzK6i%b3FRAb|Du85TaFA3{Ba2FmW85*=ya3` z+zVsHMzgiM+epNg-=G&H&kjh5ux0cl=u8a9=_9e2tsjMp_V}RAo5zC5tD0%Sj#&D+ zpdL2Q#WvoLj* z1XKC7ipZI3;g}W5$eeV?H0c~12uUFqS6-wwGeVh==o(Hxc@svC;WKI%nqZBg61;YI z<~dSsOz6{4)HKM(!xzHnpC3DMv#$(T>+FH>T{3LWn$ZxXytVFL&Ue~f%FnN@KH-ml zhP2t<5>{sjiA~8ZJX#cic99Zn`K*U9RdpPdayo>)Y{+xNYOO_`mh&xB4peBz8z=$_qnn_tRaslwc%i3eFZa6NYuV;n?bCn5t<@ zMmE0}yr!aTL)voens}B(#VC=h%0o2DbhvhQj2*DMj-p`oI{ejrtZv|SHFxivk9Bm8 z4mr4Tmay@mHn74@&>l`9GHN^*ez5|$oQ)vcHHGj=BM%?^Dxw`r=G8sbs)5sI_JLzz zG%PvQ43{%Sgzp-k(P&vcxGmF)cDeO9Gbj;MPZ!{W^M#PIzA*yt%(H=Y@}GHbsW|+8dI4>2+cRq1d32e|V#1So^i$p< zT+6>(7B?#}iymar7e2i>^FTZbstjP;Nk97dM;*<0yGF1yO~`@|MVoz>!pIwWb+A>tVl+M<8x@qTD}uhT|kmwQqIL- z4*qz0huVLiiYq_ACtennL|@~)fcs&DbDy*1o&0V*rsRz-mu(>5A{15kkAZ2=q)=(W zcBX3RB<{8eM-ev-&^pyg<{AH`VcupKR@_rpos~kWOQ$lQ=072tJBzt^*F=(=+e!-d zXz^}!K2sVo7jDhscXJ+Fp-+2+rZ(w8_skjmo#`lTsr^JRjK9LTNdG0xVG8h^yF~7f zS<9GPToTl1IKlk7aI$7#C-1NyqSE3&Xz1B>T#A1J8TxIDa#F<%&#FO#mAmk*(QK?3 zlBTSy89g)ElIHk&w@OOvnO%EUQD z8&$^2qgLZ_&X>QxjB8nfMRI)Z%u58@=N#eP6vi-L?JyREn4s_dW^T0Z8ydy$|D3)I zacfIA!n?>^(iM`(^hQTP<^vZ<+WeAkJ|G68Ho4L~#R&ST!wBc?8nISx-AS*#3TJK= z2V;J`C7OmWAsNN?e9!4MasLb`nIVlEe@au~#D(Dh%AL;Q*|aTz0jO}Xjzle&q?sy}%izA1Z;22kpn1PGCLOy- zi;Qc?s|D$p);>aSKrBP2o5Sip4^;dsig}IWaYphS%u5u7hjL@7>%vjEFVq^oI({IQ zz4OuF^jaeQce0=&OP@Jy?udVD(rJs|PMG#inV$#9L%aSJ>SaEcJ8L-_{WnHp;A?%n z?YaR6&(EWc7k|)csr*c9U=7QB=@2U>R#YNe%(^B$+6hoGO{ zeZXL(@f2?B(oQ;TG#!rIEG1uk;^?554xZs1xc!CE7Xa~=Y zl;CHy_6ek(_X009{*Rt~R!U7yt-)K@`PmllBfoq%kW88FfnzI75Z2A5p`~J2q@+My zO&l1*aiwVVNt%(qYz#q$Y4~;eR-*sx0~xc!j|(}y5&w;g!OK>JEN%vo@2f;W-d{>QCU+XDVFt z6KVK4gLkBTS4H_PnsEE$0I43k6m27|KwH8ScN$Jbw=b@ABV9mjpNGTA<5Bc{u`it) z7>OxH@0dx)@_3G&kdqk+AQu1JVBgDJDmh1u=sl9cl_#s|&Z0CBO(y7KDPa6>e`dOO zS>dv?tLXKm?Tlb+F%_4~!yv`w_$fq}YS*!-w(utXX|aGx{kuYbyVzr>?>8dTH;-C% z4bUrti*d&T8$uNlxqZ75u;Q5`J^E@buIl(qNa#&!P@_V=DO5n|r%6yeP|c80F;q+T z3W?nO4vMz#heI*m$ZTIp#=4KQ?$OVJ%YiJ2|J7yB&lKl#{>!20LNGa1F_zBNs)K=J zR?P{HS^nCQRJxdQvmaLg& zxe!(#P=O*@7NXqu)32L6Kq6}v=nl)GNxcG&+u=y&?wQEmd*co{T9TOd)UxhYnmSQ@ z8Ur)7M?sOOAIJ}u)@UvE!q!PXv|aWT#QaSF^-Ozc8aNCx-Uo3S|6S{QR5HKk-k}%x zeMEQYUYgjf3LkSSseH~FD9{tYv)UE(o}UX}djE`dQY-PTg@kZ<&KD53jfM*s^5Au9 zAa(?8MJ1&Pb&9dcbP}oKyTDFhHhvB~CFVquN2tyITY=TmfG(^VuJB4FVn^a2Zh8iM zcl<}fEoSkoy4kR$nPA7*P|`1w3G2Vg3%@4?ql&>bjGE=lihhrUjvXanUQ~lG*F_Vt z6OLSMOEf=seNP|Tbl1I~GK(zztjvlYwxP8F@#ML5CWFEDIP`>{1KHfhz-T3&pP0t8 z7WTom;5Tqc_a(P;#~>W;>|xd`SK!*zjaZ|n3%2Axm@lz}y`y`S9%^_(t@~1N@}quw zU914MKW%~eVwZ5Y_c|c{iPTg)7e+tqf=f&;_*`3q1|54L)RPFkW%TfVjUSz|?*ctN z_W@UK846Rz&1b`k`ssl3)!9}Dx1;2=a@-KS2HvMc&~2*}(e^0IJ^Ggpx1R=}|DMlu z^4tBG6A}QrYyXm+L)#$f%YA6`yhk29;$1n64QR?}vel=uh}8FFuu0gC%bQkX$K7zI zA=-^3y={k=GpECa8f9UN9mhC?jK$5R`7(U$Btx*Hn_EwqYVQemuI*xJ)gKJz!gE z7VNxrnH=rRgA1E^#?YKx`s>|ZIBs)<|C<(rWuvCxwh=|PK3t5(y_OKlY}wA4emY27 zW_pob zDi{a9m$%XbqkE`G!FDp=Aszbccah#v0mN`@F4uTjNM9V@g$6Q-G}JMhQxvHuwSFI& z`dybu&Amln`TY;}El{NVH&1)K)WITSHrRNb6hs!Lk}G%Jxjh4cApTz>*mORG?eVW^ z1+QWloIjrR9u>{rca{)tR(wXU{*#7HbN-)m*$O@vBEXZ0$CVu!Xf^bY1W&(D7MPoZ zZc{FJ-W_7<=ba)?D@W*_E^9Op@1Qw}m&j8ZjWWM(;?aUpC=yyjZOkIEHQ*hYve%8Q z{8foFQ;qP}!zXmU_Z8&qo}yPbhclN1WAa;$-qmQN>-@#w#!wwO#k(y8x7(q}c|N?E z5Wm~ns|l`j2KZdBMHzGzJtCY z1J+DDmP|0=&nEu{I9BV-vtk~BW_~UhuC;;W^j=5=1K2zuK*zW+Zm__EDj(YhH?AH6 zQTuB!^+j==^Ys~^?fIb2HYgTeRV{{h!4`D6AQU`au42gVNd8^sFs9aelA3xB*R1Wv zV=lLd?vxy?T(p^4uRfce7k8p5gDX)f{RpI|lz~I00ljFEf@MDvnOi2CLGfcOv~)W` zdPE%5sw=ZiMQ35gxeTVX(HWnHDPlLz#c1dEn|tJSC@^WbWTC2{TE_-ZlaML=JHq#8 zVX!rL0q*iDr*C=QCnJ6q{g=dX6XzFzW0|M0=v^&7?Nerrwte7^jERQ-l#hWUCn{XM zA&TFrU*mfxxnzUsEx6$x0jj$$Ve)}^D2%&B%8PiPz`Pvv<+}@4`ojcE%|p@3Q-Fny z0{GAV1etM30oC^W<@^EyK%o8rQbToxUzN1+RHZAE9(k8gXC1;;iokH*Rk*yM8m=&e z?LRX>*NX_jG(em!;Xl9d+#3R4*Fdr-&#o)Uf%?M^?7Y|BsPS1JhO2wvm2e5iExHOX zqr>R`NPF{Ws@|~w-&hnOnIm(_P>8Va>qt?AR73+6DUnJViOeE0ltjoBQ8Y+~v+s*2 zDMJ#KCQ9?Cfo4ke+n;Bx??2D8o@f2O-{-8gmu0cezW3RCpMBrg^?twJ3vXW_2NivB zBv_bT+&2oF52S#_>;yP{c`FDibkMx~#boH`RS;R0LJnVTgAskulTTgao5*V@!@P?DG-oD@>A-1V zkDs7#5*=XRi7UKfO4-BD%D{U#97Z*dlKuK$$cN9Ij#D#*D92r7*S#C0W)>`QN)p6Q zF##)!z4EB?y`3*VljGK`sH5&XD#*Ecqu_iyhzMU9B>HbAf|jm6-SBx8;n|$Tm-n8s zIm&~mGp2!OO7n43r!4+5OQmL~S7L45A9j0h4B;#PW+uutLVD#rnB+4L_k$68_3J6x z^==3%yFKAfPA6%7B!@+Q@94z}Gio1`2kpOw@JNsXMlG!d$>E2vIaCEKDnG!s;AoOF zumS{M+Y){GC<|dtQF_!#1Xr&gkEj1+;ns1N*+u>yn7_;mo9=EPyH~c*hHVj0X1tdz zDtStE-Skl8@_xKgw;ubimSVuGYT6d3L_)gO!%5#XJo4!glYeC!>LlfYh?6i+_U&v^ zz}|tX_9Egq;E8ijEhZT%luZBp5uUoJaCK+_)agpb`#sVPJ)bLaj#N3jyCMkg`6j}d zZd2^CzDue{n&5fiS$hAD72ex95w@nU!0m=M)ccMp?tR-t8aG+Of``_u&C?ZF*3`td z``;#tS5`m^O5+7i-*R^#9ruj8&v^sWnVolLqD%=v+lB|kD|0HSKX<~(m#*WV>05Au z5)TI_aD1&Fu_V~wG0l9J49(j^u|z%wiVTZMk--pK)zD8W3#~x%QUjX&swN6soKUjs zD`QZsgl*!p;Z5-nxSr$m_~%<_B8LR|v{Mm3&{)=YG?I#>zhJHu1;foz6<&i}4O)ut z#C`1sP1r# zM7}==t#|aGJ@pvT3seSmDK}I~-%osg`huy87oNF{oG$eQGJdOwk^efNa=+;s&U>p` z<%wgV?Wp@e9Ze>edE>fR>O;O19uwd+_Et##|>^v&Oyj~6xQCeb*Y zBVd7g3R_@@a}u-o$Yk=Xoa1Uvj36T|N8!Q3DEKnviB;LVSrDkJ09hXrF(ZjvFLCuL zUVRBB>g2#q^AD)Mx&`Y)`1o<>G`wlih?{LIQR4naVzy}>2l5|e@fP1bsl&>_CaR#YlIAa|V@~Z_k868m*m<|cNP?^`-FQ9^R$P{&!Hhm6 zp5S;(a_+3bMIlK3bBgY!%{1txI4t*4K$~5wur*N$7~5BHr}#Vsu8XIm%}+Va)pDHg ztA=gTcImT|DF%-FO@&9c;?sdzdOBN@K6p44RYU7w(=k6xTRMo9x)Z?~i?B@U z7A;xCd2Q<5aGuXy{#=QvJi*>&sGXC87D_GDtzrRAR&l|+OLNdt|3YA{guyG2)Hx2qRpcoR)>yg%?J!Ic7$GUqk6K5EoW@Gwi zv!!Dm_-xT*2#vV}bNSP$+_o_?NxK{I*d#dc{XAJzJeQgEri{{6C(y~aiyq=fl8fPL z7$Q z@QC9tl9q9b=9cu4%*a00}ZRQc|yBLOhMi1kO51Oz@{t>)XdJXG( z8sRT1$@_fOmZzr|!e97J0<#wFCi@HSfkP%2Rq<{qt&-@5X-AqFsq;M$baxZZFcGI` zq9?%m>|j_QTY&F(h=SMiA?9zf70zEgjW;ZLfzGgt!$*PTv_aqyeQst8IvF=emr@Rm zTXd41(c&@Nb0=n!7F8c))7 z;vg=2J+KobF*-JJZJuCa zwh!?>I|7RP7rEJVzbI=Bx znlJQBGK<0o4H_gZmT-E=9GJ^_*Sju@!Tf!SWcm6BU|?_qI-UK|HToxOZ?KLRac&yV zYg7!*ibX-)xFYWFD`0C?H=0S+QXQQ={NhSK`c24?whq-m@t_({@2xCP*M9}CP(~W& znF^vy0Ed<`SLXbs=g7m5r0DYRHJdC9M1LozDD62FqqHfRubb^^JT5w;t=lKdR?wR=gFM-@nUcR~bQd z?h{lVSH_?Grx;FZmOysB8+_Cj!lmZ>AbyWH`glFFeBj(_mGIJ*MEvnX+43p4u}B!} zzh&ZH6$`j@`Va;RJ;#g(9J^p`EMZ>FfGp`c=)R?$?27><|+yJkWs=Ub(Z1L zy$Lva!-Bn*)lEHxzp)2>wJ`6<1*qjbdn!EwG}V@?^$nC^>5m`C@BL2e#3DelZio)f z3xvX&6`+wY0Rs(n_}ku3flc-?aKUae{GCTgzuX^!e)g>6?@ow2oVN_9%d4c=}CB}TMQB$ufc1RaC-ce15M9qK)<(h zxo6l9cCwQ{4SCJObd|&O>>7EPu=6|J_pF!7&UeEgMis5(?C`b11ho3d2YYTU=ym-C z^sJ2scGey0ImH1ay=vk8YG0J~l|j)N)!5#dKwb8^;1eM(?=74QdGG6j8zyqFEBG^b zX(>WTo*G#7W<%qsHK&d9LMNl|^sdQ#_IhVO7L>nb5AINcH4`2{$;I0+KlKh-_;)JaJNoewD3Tc;Pa@kJJt$ z!MZBkef0n`ulEpPu?z5XZa=L3*#s%O8p)ROPoOIrPnTV|Nrd+%lFa?$RL`=AKg+Wd zx0xKnZ0R73FqC1(3Zn3HMK>;X;d1n5Y~{43UzwE0$>ipZ7)IsC7mgwF8EjILxV6~4 z`o7^S5E@oNUR*Kf7#~aNhq;T``0NGW{?$#(Wq%ICldP#wx?GSLzvI?C zsvNsDei`<@$YeJxujN=K)8UrySLWz~Vj`q9Ois_K$DqS~Xs2@){!ZajjjaywvY-$6 zWz8^PehNLFufloVnYdQ45eFr^NZ9woAn4OXUK;ALdTj^bc~21()y(4UpHK#?CYs=z zuu6DmQB9`)lm%g_XiHJfCn!~9PC64x$gp+>(XeQu4S$X4t2g3k=C~fMv@G$`!6bUl z^**!boF#enU@P1(kf=Rx<-@*OV2LZcq>)}ZM`X7rWB2b_yrtI)p?S_%GMv;2ElYhs zuKX7h`0NjB^6ehct<;1aF|VjW`Cc|=n=$-z(GLH9mBQ7T9(W*?k9v!fn7Io($dNQ} zT)ycw6Zv(J3dHZl-M<@{KEDb^xyS}9-CmQ##tC>?N*>Z0gsEDBJgRd!vpKP%4N>mi zbj1>3lw2RngeU5vc>XOSl-opa|M~?gR|+80NEudhhCu!|jxX(Z4z!LP1|`KyV5P%= zWv@H<&-cL6fh;mlcLPn!^dSZ+D(saGT@Y!A!|*hFCeKKOXjhzPlA0wU+V2jd zD>gtxul^-t6RojgNgP@K+6j*4Uc|z^v808o&CXfNKuk*<+*L>g2|tFNs(TDg3^@** zUpN&$P|IbAeL```8ti^SV6v$KZ^-XAD7Qutlk1xB`Qs?F_SZ~Q66nBaUI@nJCS&p> z6_~!Qlnl>50U7fafb!!g_;kyZ_<1Me*Kh4;b`q%lUsX1L8^zo_ECJ=&)R zcq3wnrWjAeL8m5~@O24Hvpa@X%c2oIhD7 zLT!9Q)#xse>b2kks2W%+lFC$!(*U85R=gcI@6$GkmimcTT}iZ(0Pk}O$8|OT1Jg^K zV9S@YkoAJAxf)3~^f&&()?=wuRcer$-)n&Gshpm}a1w9Hw0~epj}T9NM-++%j3e3O ztr~7NQcwU-l;$;x9H*@DNes+amQ->Dt%IYLlnPc zsDq~cJX%;)ifPm5Hl(SBV~hE3HlaNaj;3%~P`1%9Y1>g~zIBZB-p;A_eIwS8srU|m zL}%z;R10!kih$8`V_e zX)PWiMi+D8)8gZFMMoz6eNhlU?^S}bZym6!bvn$rB+qFnQ_09YWnNh46)Ldh1f9}( zks2r~(S%dh(DLRG*CW;hhqP>_E!>wRuTVwbAJ?ce69iLdHp0&GsZj3M3i>*nxW_h{26pRGZCvMi3rDYUknPnWLBq8S=o2D8>= zQa13@GR)^BZd3$_`NxJGa#W(sqAV2EOu}c!i>Y7pO!(;{1FL_>!EJ7hV;epL)kep| z^d0Bu(6yp@p)?bJ`UT*X{W$*V_qA5z2z>Th_jr-6udM$a$F5G97HMt_|8D=&I1K;uI4n%f zOpQ$z&e!|@KMu2@NNWcYVjZ0tVm(7I(7I!IkM(G3sCCx%bnCL$d#wepMOybRjI<73 z6K&lr9%=3IXq)w>#^67|8cw(+xwLwxnuoz`=5^Y zznp&yv)N{I&HtC@Khm1p^MAYjdp?>z7kpRe#`f>_KaEfIznl-V+2$79b)od%pAYUW z|Ks()y8bN8=a^Y?=l%cT`ujio|L=bOJFdzV6O`1sfB1L%zdL?QQJ@zG*k`TtAl};QpS;E|_jRo+=e}=v&Ma$u zSXp6hG3A~0OnpCV6cuW8*G;wNYt~x}%R5@9NJ?A3Q#p>`b|1E`>Je_3l3~+`X&KgS zZ_=y}m@jX%Nhz?V2TZL$?}+)2>(5c;XI3P4Z2xZm)A9Y6>(6qwiMiST?)uA2vBXR_ zZ&cjsinms15HtRGEQ;5``R=xG{!AA7MC);^+$UC(Z=Z+Ub!8;G;v~M-oJW^^*-uYr zg`ixqC|FIh!c&z7^o#9MDn4O4EEaf6n)Bk|(dTN~7k7x=s$xw?=3Sy)BeUpuwFLgI z&J64r5+rI%XVT+UD@li}IS3p+2ufm2*v&fYb)pUPNH44ac`7*1bF}a|Mddr&OS-YdSOt*j@39}=T<-^qA z&keR5Y_YNL1%2oL4_}R)4kpS!cHv2*hh#l@OCRuVvnSta zfy1k2+NfLy2kYXn>B<3sZZlY>W`mdP4nlKBGT|pAWB;i}+BKX+mrO6>bc^9M?1lig zeU|~vPjASrS{amIr~qPDHHhLpuD){DglM!2jq!b#u_@|7D`Riv0_SYvaAAfEd6$?+L{0WkEv-Fx=H>!y zvN+3Lu76KEwltvK?G6mp&Y%@eNaIsqFz-%s1)0)Cv}2((R=e%Qq#G_I%XuR52J<); z_(5#`(2kSdilL`(3QF~)VVuYXY~7%MfltYFdW#Air!Xu3 z1g^Uofbtq2;CWp#NoaP$Zq0P6;J1=I>70R2dp6@rHjF+#9f{`GV&Qg}7(AG#j(+CP zsr-9Ws6LYf5056`$eF=UtE`Qw)xONA%m%m_=mzgyo{(OJ$?Thv?<6yA4GH~m z6GERRTzT?so;TepC+zcg#U#TWOWl4f59@i*DDuO<*onZj*wqi@(uV_bRA}-8MR!8Ngl}pMV{vNhnyY z$NW075MGt-B+uGPFfCRBDy-u0#^#Ge_WJ;*>*m(Pb#^#3x1GL{u0g+UcN}`1|4cmj8ewo zO|I@4Qn(ycROC^!cruK{+@V5iWWXzTCI0zgLZ0-`pz1}VOqNX&wk=(b;nk(IJ^c~6 zzefkdoC?XGVjt2!=z)fp_rbWk1*BHe2PR5X!k(rgxEitu;L1eYwsZkb@{)#yoo1kz zIE8<1w2waco=8kRW-->uB~UUxobT0tiW&qiCW}gVFp(Dl`^y8M=1w2`iDN%J3Z4j0 zKAS>Y&?1uhrqs&Sz#RhGUJ%hKNzC;RqCDfiK*)Ey4!@4>B^5nW(6*{IO6tAF{Ve9(@* znzI_}JIm-8>j4UlmjQP!2T?!HFWpj0B0CZxKXd|U3aDea=}#Jb)g2~mJxwK<)$nzy zJ>?rSAmgA5^KJ@Z-QayPMOB>~c&ka^r7h0fVok!QKA@}nB`^Z+QJlX73!a$a;rgv; zv8)vG&q_g_z(M-)V>Yyn-6#5u|?3fCK3QEB* z)3q3Pd;w}1XyC(n736g8H6m)4O9MQD$d1QX$hZqr!1$IFyqGx?FIFnSi(}HnW|cnv zIWa=?g-ggldp|^Mb0*SFhavjf8=_ni*yoa`82zL`uykAnU14_M zI=qeF*}5Mp@5+IwzZh>?g%QtPEEliG$Ka0*86+cF9u-TTQ)4Ah9Ew{)P>==wbQwm} zWiPFDaw9{VBdPwZ9Dc4s0tSB+gTvy1IO~%UE>?KW2tAC)Y*VhD^;ZTD#m3+Vj&W)j zh*aP$(rkgiZUIFW4+>RfMEJfMh#H}jyp$q7bZHB*w@5v@d3E1nFjD<==G_e06Ei^(B+ZKi{k{RUA+!y8<8^eGrcb2<`_WU5`e ziQZ{uVb**jcx%p(e7OP`E-bW)8|MHM!dY5*?I1j!sezF@S7S+F1JyimmYLB#2R4ul zI95DLhn&u`yQlr7K4tc}FIpD2RJ>vg0tO+qF980j`#?rgt6=lfba20D44$EiYo+1Hikz$NanTp8Edd5bE4A6&bv)LW{&0+NYINbg~ z7#2=mi5pB`leoNzklnGAACUH(d7J)=6w1rOB4ua%uC;_FL`+L z2Xk_F2sJvTkC*4|hFu26IGf{jI%JFB3r@@He&RYc>Gvo4?eZ9Kw3d8!5x}aST5P_@ zah&$y13NBD7yHLcV)>4ST17Ph=$V{}4pE2cLH-`ly!(z-xY$VTPP`%O76{_j<1zKA z?YY?79EvOVY-d|u22sy7MRYjPfjYgB!8uCLt!kPh@q^6^q8#y^1nxM9PX{$nY*r03 z>(fWN@*7ZDx{Z2>wkH2St>=uKJNp=mo|dSe{^u;Ka+5>U=7)Se1r&X5Mft4=tK5Y zTXZ>pl2ti2m4yGcqC>GAjLkJZJxCofp>>1Pu)0SU zwpm(WoopA~x#l1ZeWgRGwkYMT(?jRSwy3o$5==Myk*(ur(!{dq@PcD!1gty7jP7|z z!tytAK}Iz=pkr6>9mVA^otuevycpD*vWa=K>;kPSnv1#P*V4Z?pR)%pYJ%c~Rd{FK zL2!>!#t1VJV(HRM3S0?pekevPiv`GZe``4Wp_T{*{;>)%8ldR`Yf(p12s&1lk^^bC zshYhaXx%Y5uOttLZS3(>_&I*vw*=Hsvc<1I^O+X25WJ^dkD5>C~omfTa2^TC<${_IYA?0qjf6)wBBm&;zH_&Rr#zVy1np6c60U;SyMNt<31g^W<@6O@A= zPQPHMtT~P4o2TI8!WKN+Uy57^DDB3=F4JYvSTL>TwM;z z`-qi;=trV|T%YCxgO`q~^VDSA9r$HwPRYraxSce#wZno87BjK=kQ?h-|lZhCu(Fta*F4ZeE$(EXn$ zz^E=IRu^osy>}ay&2S+h{41nIvWvR^5GK{j`m)Mx5PNLHH8SA4 z88=?9K`C^=!YmiO@<$u5ZR1m!lJ}&0vp5l0Vo567YUq|tfoSl%ocQQka4eo!{GQTI zdc2ch2%z zhx9rs7q!+ER z>N)V+r}wpoX#;NjSIlF01LqeRf-au?}C__y_YJ)IB z5#+KQjGh#s*2;I(;Zq4s$o@&o#0v3^TN!<#KFk;x=waQ#Sp21Nm@3?hB+E~&VqbHf z?pzOFEG|eU-+q0e`3r4u-GL4GEbB9~b-W{8zKUgn-dR9r@?z|`5JoEI?;}Fh@o2SK z6tmhc;P+o`m^rS5&R@*nhspr#jz}caJbZ9DOhSpTYq00k9XciW3Hd3UPGTfZQL2}L z?CvqLeXRm3m;8&~Nbsgb2Na;sbPKzd28hNNkoz`k)4 zV9&T1a#a5Yc^TwI1~(j{{$8`eqPK{#m!F8qA`3V@L@6ncI*<3Wlkj4PK3x7G$<1LD z@SBY;swT{UkcNMVIz36WUYp?IMVrvAubbZzk%@e*w^So+EyxyJqrx6sk4#A#n)=0I z{?`MX?==e(pU1h`xva{afi#;R4eN~Nk&0P6sD$z* zXt-{SD|WeKTA~}WPjo=hp39Hrd=e{XB+z*eLdo%%YxV7OQ<;?$^Krh>GsaLt4o(?& zkeaR87#8-9zT2-#dWKIk-(-}5R>@*VQ4B_ut6}BlApEH5hm*Hi;0v7?s%mkJ3b?kB zpyg5Y^4|~Sg@+)17dIiEf?IJ_t~``viKBDF4KABo6z9hp;BAhza`O5SeEp%4-i@0? z5+&!O+pQd?-Xsw}>1`peM}5fywO~fqy%4pnmgCVQu3UcTD!kyf3r90-X@u2nax*^` zqy?Q}znlQx7`bPaXZ?hZ@Pqhc>ZTmGR|a(sOo3fNBG|+2=R5DUm6FFC7*~D=6+?|_ zPcEPG%d0WLb}oF)3n$-GwnD9FEXM4O0So1Y@c}1$|uOJ{3X( zR-pI6JG8RE24K+6Eg!h|*-}+@}Zodd#c^#*=XT#BXNE;!0gZsIHA-NSKZgA8@+eq%$G9sPS8?#v?-Gi0$`3K_|Da!j;Pi z=2m2*p#DZyk{?9mijQy%uE`vu@f5l~w8H^18(S|l(3KqT(K=gz3HYvo@$ZYs97PS> zNl!4QOVViSk`<67ZjYZ<{3Wdix%zM8Ijk9UA-^3Y;Y`8;=GGrQwBEA-*2QQ;*=2Pg zRd*;3dXlE*c_hCzzJA+aDoNcPgmSzJ+LiN$TF&6=ec!**^9Qz*BXv)yx_L2*?^uU> zSL{Zs)O41dI7R**KScuSUeL=cWKfXnvrc!hX0N+hLaE?7y7|2VxjNZ}nQt-~q^kqT ziG)1RoRdZ-)@Wl-K`Xttw3fJiUyq|R4p95~iOlBJXE2uA*UP90&_}p&jJr?Xo*QMZ zmyg4j!2&S*%ycN>^0_BIc}cDPZ;_HWB~)QnJW2g3LhDE*-i~(1>0h@I_?5y)9=}ah z3h$Wcs=Aac8qfV z;0qe46nG5F&$N^FuEQYJzlDab$|vnyE!r<)DFkU$(9&jC959{=3+|@TNmh1@|AlN~ z_)?1MN?a%JxNL|C&xeWjG6}L?h(Z6;10?7lNhk{Xlw?pH*hOUn>v#Khw}opEkMT84(_hjV-8EkvHCTeA>+LrZVEj?&MFGS$D_kcf3H63`e#v* zF+1*iAq1uxYao9_1h4qqA|Ag5@UndszCWOf-F_8xsGKSi{OziGZk2 z0xoZxh5?nwaEtj>Y=}39%5jN=f4GJCbMsKk56Sf6(jppI$1x9B7rc8ckJCcFWUI<$ zQQbWi>Wo5YUtkn_ccThc#J(iHw>D$%;=62)@pW=N^&?fT|3szJO^IN22|IZpA9?99 zWYe~l#I}X<2g8$L#9ayBI|ft5uj=5<>BfIO*$=59($J=<1cT9Bu7eUckGLZR+v=v^ zgJ@%Fv-2Q$FTD(t#>A2dDCxaR0|ye>^=lrGHYNhRbCc-Z-_z0c z!dH^oJPV4j7+yZv3MWmYso(i@II9{5_l)Z3ot##3a~zi~9V<-oR)~|Ce>txccbviG zCo@lw<7v(rrnWi*)bN8W4(5KKGp^3U`F`^;Kkyg*rs@b!WrZPJF$WH0CQ|b{Gq8PX z4*b|IV4HO5x_O6Ss$M&M+0a099xB7~KWjl`i7=c$p$iMIohC`Od@@Hv40AtmnW+7@ ztU`1*quQhhYTx3;b~R;Tz`l)W!S%ot+zv1c9(9tNx7R@Uha_S)?;feT8N~iJum|t@ zALL=t5~yDxz#PdrOnTc2`1jt_(Kp%)z}6{>2$n2>jD3yJ;xP;E1m2>LLxs6akXBOl zrvm;|suDmM<{j-2}-`FI2P zAM_=10)6nlXbf6ee|o&Q7*D)0f+afh>7I?}$eX(-i20Os8uD!s%>9wTX>u~@Q`vD; zxNj>2%1%Yy(F}+i*#N04y>O|pI4!H44jPs#$#*}_hqSRCM4vt+7Y{XpT8$T+wAf27 z$!0Po0#~`rL3tR}xdQ5&^Wk7?GFhQj4_b4^h>J!Y_}n}LVFF8uSk8D3e?tND}OIR3b(k zv#!8%h)#KVocvkS%B;)3NR{>VNZ99Zq;<9|>{#7tmAovIc6Elq`xnVr`sN6II9?DX z?AKtH$tUK<%NX=~aFPTSpJ5kk)zkY^m7wy&J0dg|04Ma4=ujFE1En+cUbz@{^Kw9J z?-3fYS`iofiQ)Q>T8z&cdn}Z0qG@T4tdoln?fBzH_p{Sr!AKDMit|C88Lg&^SyyIfdmsdc|0Ssr`mpJ~B3E-+K$Esf;QpL2Mp&zbI@Y`(&7R`Cq2>|hf5oL@o0>39q(#@0$^>l07773~7GVJ6J%pNml@ zLjyAYXuELPu>~v7U5-(Bm^>Z@m9WA43x*SL4Mm%-T+l*J# zu9FQH7Qr!nu0~fl591>Dla{#!L$lAEu2nP6psh9VISD&q(q#P zQ{XR`QQ$D{3Jm@^0aNc}k)fj*U|RBvdWb)zS-pE`aP1*T>EZmhU2z~#TuTBc8^BKw z1$t(49kHdBxOJ5ePHwlLFS-Y<9L+MRj+8MztdQVckamI#ZyX@nV>!W+wXmzloO_Q6 zJcVj0C~|BCGXXUk;~x*gD^8QVf`xd@zm%ESBMxD^o5`A#4%Sjp4A#~hB+oU1u~wst z>=JEa#<$xLndXJKtZ6E&EENLZk|qwv;Yh!ht1L!+n&j6d5#^z0WvSj8Uot`9RJ-5<&zxZ$nN6@z^^93?s7Wuu>Okv3O@S zZLuLte6Ry@I7WCyd=hw_vf@0r2t|>lu<+yyW@+v{BG=hZRXpV3$ABvA(mYDf&VNVu zChB4D&JA$avWz&djsrKJy^N91WDLlE3}=n)sp0e%#u`(g@lY;gglfXs1FPYA&SpmS z_-cB?`6f8j2*S8nV>onV83<-^I=;EmV0PVvs=s{ADv@KTJzWNTW<LL{%e|j+w?|#xsDX&|?&ZPNVUu!_;B;Dn6ZMNRKVq%&|Z6@q_&bA~kLbzfk-R z@$_|KyvKhg5AAIb_nswlH=c&a>V+8K8%y48eak%!X5#PFmzlT^nwYX?KSsQ)0Qsb3 z_^c|$+MfLmYueA!sT(GseeXGZbc;`}eBDP(FEZ>#!Cuy1s1FT@30zi+M`M}ec)0Wx zDLdzlW0sZF@&0*mb+>_|Z-T(l@&Z_fErB)L23fn6uStC16S8bbi9Rq;g%c(#VD436 zyni;6s?Scwp9!bXFO-L2Qrn2lwQvkOyAx+R<)iIxD}3%N%SPonP_=@kjJwT3GvYuf2}x~-kzU6@FXAN`;nXP5q)*9Axa`Ai)z)xn&ZzAz{*4NF>*G5p+j{1EDi zzAB>lyvrMJWEG?CsvaQ6g+Mjm(n?6%7c&ChAoCytN9VVbrqNd7UVNWPs2AkbNAO{I z;0t-&)(i_Zl~~1>is-Y>lx+VRMRUqm!L#ibtgiE(W58V{JhN{CiP~EVqH+G9bT5sB zw@5>0)n4cm_r@OED|FeCuS|2sQs%g;Dg6ENf!w*=$)wn}kQZS0iN4bgN2f6y!kfGuUGb%sH zgHQ)bCUH3qPcx2y>$PQgd#ye5b2ayU+4+K;-#QM}IL-V0_uinSYYD*}Q|LV386b3Z z2MBw|kfr4pK>l$7ck5|kL`Vx{J=6!~o8GWESR7VgNyPnnuIOMW%BE(?q5j_<{M+*d z0w!*P?eS`4W7kKpPPq(y3z}JS(t_ju&BU!+89ehf3LYr+(oJH%c&cqXq%`gVKamY2 z#o!jn?wE^q{W&o2w=HVac9YQ?k$}GB;J~(O2`nXpytKHXQuBRkiX;p#ET`a9u^&`(N6_An0uZ-Ns zUR<1%&M2y%CVNV|si6piQyyI;j!tdh_lMIVxEO)1R1=z8G@(X>08ie#2TnzvW&erv zB;msaG)l9C{j_r@9GJ)Hhb(`h@}^YC>QshJpJ$-HPaTsrTbKAgOXTKmSIO(Mzv=i# z#^}1wp8VV*LL*JV5}11sw1%9ChhPfTUAi7h?{agO(g*bZfD_7EWKp98&MSB$jOv*K3RG^vPQDva zJ063j%~y%P>J1qCI80{ER)@z;lr2#hU>3O_?< z3k)$oeLe8{wkR6pIs*glti#9NEp&N%1>MGFr|v5rhk46IsM7j_7+W$87q@fX+^pU3 z?HhypMTbcJV;f@R=mi3I?9o0z27eSb(HPMzCN0YtM=vR(hHkf;aILBtUYae3lJF)Fn^_Dpzs2CpuEP+u&m10q3}q@z zmQoLWQ;fZ%N?b3?LF4S*oQHaz)tiMwL{2&c(za@XP2?zjryWU~)jY78`~F<9*Nsv8 zwiW&$ORD5JPqcX-T`e~aWgdT`yS60bS%)$*?S>mpuPb17xn01X$=fhl+n6f1cM|gq z2Y6~XY}H*JZFOE{CJHcj$=ahOOysK5FeWLBkSbD)46bm|nnULb+@ zURdB~30aa}br*lmy#yDcuM_D-+2|sE26EnSgx(PuG<3KK5=l|0pLUr(n3Mr|W%}^< zr8OM+VrDgxKSJ&;>*F%_4uPL~J$>r$2!2%tbic(Fn3kxD2S=?SL%{^1++9dntp^iq zltp|loFxzTNPwr?C{3?l4m!!2FjiVdemdI2({o9vVxB;xN;aVOthw~)8AJL{?+Y>% zFNHbvi?HvWGCbIP09Hl`qONutO-!0fTla2;n@8rrGPfQ!`%pXt{IH?Y_db%48QpYK zfD>-WD5pwc{nT~U1SUprH_2aZg)d}_Nx9e_@O!!zy1O2;z5c0?H0=i?Y1#-OYG>if zrL|xb;b_%OR|0R|3A7XpV-_CkV17)VOP8khFo9k(p=N0~#0`k>G*5+)Z>|SPSN|<` z&Y5g9NHZq9#foUTcNIACPtl2rS@6C=6`t7~fJ-_+L$}*f!!;tHYN~+0b+g%(9nYBX z4e}Tv9s_SC?1h|FQqX_Qpw6q+2Nu1OAmhgh*^OhOaQWOL^5)4+)__|#?fmM+@mL~2 z@LMT#dM@I!(XNtN+BYEMRV)OjE2CSFHeM?F$}ysM5^eK^czsNRj;maOhu&XfuWVU> zF|&24QSk&)Fy@YftE1t2O(3inU4*|lUZUscROrj!4U_q?Q1M!ch&-79_6@}#!t;bL zT&DKp-dO%Uw>X?O)r2^NigW#fRdjlCEv-=BN>vt$pq%S5IH=pN2G{2aZ%;zu7imzR8v}OR8pvQ#0w!{-?GIw}@yDWyHCgY_E>J|4> zwGE}LX8&<4jQ7DHjtd(3sgInkE@j7(B%ynGIRr;f0u2>0(k7tEWr574J94+dyZvRb z@39u_s5(twFZ2VKndbE-jnkkldOwWpc|-PPEu%ZvN#VYjVz%``9~Dtkz=>B4u<|VD zVV-sk2F|}HjD9MtTO~uH{@D&sTBd_!Y6P=?NC3Qoi@@RXI8g2@!62cxWa-y4?4zfO z{C$#wAUCm&e7Sg^IEP>0e;yUYU)sM(!~aLodBxi8A7P%1@2 zgQ!$iJ4I&pDtknPqLA%5_w~@WB}ysn(o$dT-S7PV_SboNp7Y%Ib$veX_Ya2r-slYH z_I+k=)w!6TJ2(us&es^%stEde?@3_9a%tt4&0zYzgUIYv;@)G1kQo#S?=*g}V|xrGLU;psY;Rxm@Zhxwol}-hNnu12j?zo ztTjWOH5%xDG@bUyHJb}QTnY=Pf2Z-2{6T&}6e&su)u5qix}&~Td(s1UBFzckb)|tPuOOOdD~U6?z1pKBf{`-a z-JYTR-O#-;(Wc_@)S|7`cG^A3tusmV%M5eh|6mUG)2sa9o#c%(;(Si1us; zkoTUCiC>bzq4g23`d%h&I93K50@`5cgf!`?%LnDd#~{k@ED2P*LH;b!q`y~vAwU0f zgQdaloZD?aX-#keGml!xjXw&TeGX6q6)}3!^*V3;ns`_gil8dYrvYXsNbG`Ca{BNw zjHwudj+52oUUw9gEWAw1r;0%LB0GrxtqzK!Gue)NpE$P>pKN*mj1DnsaAb!(BsIy< znge6h=$os#nC@$4=#?H>v9pVM?Xw^Sm)28*M?uuLdoeDAar$B==f+KR!9D-oW0v36 zC5!({C%tX^;LWu-@IO=yYerJ(4drI23r_Xh3#q3R-<1?uO{>JU1*?X_kXFm00 zIrmOIQJ+CT+LL)1vWD#ZUP~P!wZJqt8tgd2u4A|j*xi@`a_9C^pEXMGlqU)4W)2{+ zG7=rdWudZSh(^Txp+ODiARKs|>HAW}EWA+wTXZ}@Kl=)7awulXzX*}fZFw-xWf14Z zzNe*vLKfS;w!m0xDzoJ5JkYn82TMwZ%p*^9kPoQ@t}sIQD(?-|)$+kMty(-~eGs~r z1Y&yJZp!2pL*#u&kolmCYmGd)p6LR{F)0Qn%cZt_TcHh)lb_J{4PGs6KFP#IC!YAe zC}6jLdTAz5Di7NiO@>X$7Id1_7dA0l2`(w}$iK+}l<_ElnISVVXZSj^x^#%}Y*(Y+ zG!qP4>IeHWT`}swF5GoX7xkNGV}Y{{ahI&3l78ZNv+OqBSa1ZyuB)PC)Km--JZ>&} z#-Ha=Q-X?8H%b1k9XR^p3QbD*%oOruP_jP@x1_#9>Fo;q4I~#oJ?o^MTLk!DViQn) zh+|aF59VfUfh3_QmUw%J!tdl>^7wN+>b&S+KW(!hT_JPG%||h0=Zv@HLP8a8DjCH| z(y#F4-wBw#&6*9K`52FE^F!B5%dqTWIQcnn3bw>Np$Zl!nI~JHF%QRAP_Kp$Emolk z;I*uu97~SCp4ZJZmUHyJC@{kKss?yNRLQtP0qylX4Ot5cdF!9+<2AiG^yuQ#V7$AC zr?6WL+#F?L{#G+g8{f;ES+ft1RBtDbBI1E&iNVEzM0);hDLm2cC)?(#pko8~zgrZI z7pB+HuD6^=e#nGw_I}?ig>Xi5?rL5ic=S zy32D3+`l##Qufu5`ZXz3Z=EIkiZ_coEpx+~bT6FR7)0mqUx`v*6bS-2`99Ab4eJz#h7p#5pTFsONbBNVdET%`2yJj#?X> zk#&Zy9k!;DQ(f_f-WFV%dm2KwFGStN-o&}{i@9Q(BfDPa8RK)wi~Vue9}3FXU?h8z zq$)okfm~mq+s6P;S)HNcEh0Eoe>Mp_VMS%KbKN;)Mi?zS$ z$4T~}I95pOd228vZX4}soJ$hwQ>gG{Bhbo}f@3lVFnYx)RR5ZUeB0w-bZ8&Dkt4e6P=@_5uvk2a0Tp+l??<}Xvj%_}rO;LAyp9r%&AVVg39TZ|A`7>C~7|B;61 z_jG=t1C#0G0GFn5^Up{7uwGai-+0f2BL7SfetL>(CZ>@0UaQPabnS7^4OQ^7d`R5Z zPJr;v5_64lWAnR7>*1nq5*n@EMvFwXh@xpHZI%u|2NDSxOMj56*Uczt*-Dli-Ug{j zMwqWzPb-zLvBQB$wB5-B3R`O+_)!{&rs|SS!%ocF5;yN>QKb{|XB-4tm>>81*hE(uj{WhB+;erq=i*cF>G>*pP?t}6&P#~Hl{F;okSQ}R zriw>iS)yBgA?kCvz1Nx|kT|>>_%}I6L4h5rzE;5rQgXOs_7n2Gt(}>{Yo?X2E8%fc zIh?PK*}H7aW||LF@~D`3h4OL5!0AhA|KI#yP9LU zSrEnJUnf|2r1-#dj;Zuu|1~IjE^FaEy#^|~4KOt$kF_jZf}im!T_76E<>J>-HP0|Q z;Yc_fcyy8ZrjC}csU`$5g=CwTD*QeU}ElPk~ z{*h~b^oI)+oth8Ufv>4F_s*XA>H)DiQI8(IHMnGsE8YoFqM>n9Vf;oAthm5+=%+=% zvsgdJ^V2S!4H_2E4pGl6;B$O!=Gau*p{*PDDAu8Pf`~!E`6F zf06?*O&OVQl9;aWj$BNZ#Hi>`tWR(_on{tdu2uYzEz7o~E{VOIYyCCnXuN`SK?Rmy z7UkIF2K0lf#(@ zfaA_xdxY=Bo0wzajfKQ+zdOKOsA6gY)sHerTOq-b|&qTIn%PKe%+D9f{umImH zsW4(0NwRO7ns1!qhldWt;iXt{@OpTXIZ~+(&kUXMc7p;e_Ss19MLNUZE9dZ%qByyJ z{|CMLD~0H&oFE?qCvfh(yV%t`50Ac2#*}Y*;4N;7O*f-h>wCj=SZ*f?j=N3|2_L|v zv;Q%J%Z)HtVja4uN@9<3J;#SziWkHbsZi2k=KK2|8r1C$C%Fz{X7(2nlwb>nN`Yif zY73McTL6cCClQ}1@8RLoVThIbMxVc+bavc4uynE|c5=Plm! zbLQA}-)YL0lbDs}hcn!Fk*Fa~cH6&kj22A`G1-D<6(H@=8MB&c@Vl&Gfy({|A z>s&c$b~{btLx<>j<5`41sSRI@O5vmSFtTc6Es@AL&h8iI80f7AAZ^vd82{W31!IZe z&`>}EFYTrRd+$)MXA|H-(Q_L2!U2}6#ju8f7pUr7Yw(J)BWKisFi+RO>>VMH6xYsN z*}oo)*F7h_>JBhF&K3uvi^-zqOjRQ4rF zozHckxZk(;i$y5Qn*c+C(@?-77Qc%}Ld(eygv*2wt6yC9>GDG2x%)?pi=h>Lm7Ykq zE2_i9igey~aVgy1J3!V!481Pl3=zM#Lq*G3=D5f<{P&wBL+eCv&65dO_vbeq$!Vvq zts9{`)fCjN&k>Dj9NR>qf@7Uf0x3Z-a%2nXdovyLR!QJHei_6{3gMDZ#?+)v7S%7A zz=pCu`gh#~nB^Y|1$n>8uC{d8w4#EQdaxY!KaoJcd-7~@QWovc*-nmL3V`Z~Pw3QL zlS%P?VW>a-)x7iG1dL!5@R>% zO0+uM0IKYqA@C1(zR8~ft7`KY*Plu#v#W-jUY$j|_Z=laTIVraOauT|e`LWs0kqRt%`Q$+ppyE! za7eeEStw$_@h^X|(p!#Fy?+6C$U1^}sl>CIB_ec>pgOkg)8+QKZV}Q{BKF7DDsY`_1OA*d zRo|@%@5)M=A77IJ=WUB1;NN=aRlP!EChUQ3o+`XYKN_b$i+cX_M62)IZ)?3J9Jn$C zPm6HbWzMDTE-@G9i|L^}w+mc5u#{uAAg=PWPzU`)&>M& ztL8CAzI88*Np7Z1nL3c?@q{q>AIR~L*)(Y9D6`X315^Lxf$6yfE{9`5U1HC$LDgOm z^U;v5ojgcF#+RanrX}dUT}5<4=0f-PxwyVyfV%%oC#^5mk;Z{^>a=JnNs}*Nlt#X? zvEF4=qrHVn{(V3Sml(mQd<>iZGYba88=$AI6xvQX!sb?v$Cbo&=!Cf4ll~Eyu5gy> zOp5}M8GmTlY+t;3`V_l=WjTr7A_BK=+$1$))0y4+-n91OHTIR3CD?E~omnp)(Te^I zcpt6<&BN-LWzEg|Zf!&HD{fH!oO`}dVMb2zF{`s{H#}(&fDw^WZr+hfN)Iw*nu9)A zPH~1h2_slRUJ}q@=-^DwAvLCgC8xg7Z+QmPuH6X+eieen+#PIgd^p6gYT(?w86uwC zBbK)gg23N$_J>6Y)0esePgV$k%chmkP#TTL-{w=_ejnP?a+UO!Y{z6hZ-!qeMk`Mq z$Ez2c=_8pvsHw3Nv+s9OeGf}|k^CS-e>T%)?_ba_2i}o=4}C!?QVy=~O(Rp+FD1n< z#n3H90Z)7kBck4AI48In&yR%Sukt@ktIiOYE9@jg&RJOLzY-5i+hLEsFt+r6YPxgJ zj*6-+B2WM9qNC2?pgTPT{>jARL2h63t49;39(qk~=T;DL&XIL!&v`0;+?+gVFGK5+ zqx9BtBe1lb$n5zsi5_z|!B@jCsH2kxh&&~9;SVQNl!(O_VdvReuXvoz^+mgsr*pZ{ zJbHObHwk>}h&9rZAQ85k92gy7(<)TJJ^KQ^81Ib2UQ?jqel;z86vuoPzeq2nY#@Wi zQ?c5{mD~`TPb;@on6C@$q;tw1Fwz3LD8B0<**0WKt&iKonX?)omiC67)_ef7l-9w@ zyRslwtPHW0vq=0)8~lEK6ZX4lpupUtjNR!sbkiYEs#dxKV}Ee$`3FHb-m({F+@DK( z>RfQA)E!p%o)*!SFu*G>^AX-kpxZe|X5x%hI3)6%3?zObCi{lzrX4vziX};a>j_3q z9Kh$qF}lps0aI2>;6S4`+Q?p_AopzMj-tdiz?~?)d=3m5TWh!AP(s2Df z7^pH0#lFOlITp4MsOg3m4&UZ{(r=kxOgvLoJqIp5Gr;ZSGx2b=M&mG3JfyUgIlf2} zm;X`6tJ&KiC-N1!pXmc~*^!K2#U19}uWangkET5rTX1|^F+FfIJI6Lgl%r7KGwk}SbLaR?(wrT2y)+w};=np4s3#kL(cQq?w)Z zwDs>d+E-pnv*&oC)b3TF_thM>Ep@_A3(}anwnsZsIiTU?UE5 z9L%3?ws>Kh3pWdq1Q!xaKYllXp=Yt=Mz9llDRX_O4xIF9|(8Pga7J%NHup)UkBevS4laUx8pqc)~<&O znXxd#Ka8}F3R2%`Jh*u688v-Yf|cJ+LB*pK^6Fw4?XM`HKNKvX+jc5mjycUdbeaos z-0aw1`wMjECV|`MWn{IC2mFgJAf4|XkkDnJr0+uuKDtqcMsY@ve&ib6on22hPNLwF zphu=V31Q$+60;;Y9sj$1i)sdbAbUo(65k<1;&QkYZVxsvpG&*hmhL{X@uM23JMUsX zzP$|}d!y*zsyTRYu!0VbOOxF~cI=w7J|N5G=o8H}@Qg(PY@1dNS>I$WPy8eOJ$#P-lAF4s|ipbWo1+i1S3 zg&BKIKzREdB3n$L|LuIJHF{5fu6<0V z=scy_`=3$HYKm`?)Y0Zv3r}BFgWffm3BLlX=*TKP$ZaiWR3vlBY5YK5&eevF3Fir4 z=Q+85Dx0=hbNQ;_$sp_>%8uPTgBgwI@hz9#bej=E)a;hQ-^Tfv5-pB5#3fwm4?I={;t&5$rkDnC-`hsI*fbOu1X^&}rx^Ik%@CKLP=ig54Z!0W zL2}DGVl=UZJls2tnpX0uK)V+EQ0@syFUX^sLkjRuIhnldh-TK^6oKP+6d+oCBh=5y zWMbJItgabiN9DsvquWzPv}`u4+MWn&K6b#~kyOZvJqaUU1wm0Pp32QBf?r$b5ZZT= zeB-SK@!Um>ftVWeU#}bto9~4~#_r(L^?-`KQiVyQ+nBk*ZN##4mHm z%xcbIs_%7pA(;%$l3mP-SXa2b(Fp&!1mRQJTIfhVN@n`xLz!V4Wafl}c?TuE{m&+Yd;4-y+iYZRWJieaAOu;kx)R=w8>;{1H6TJJK}P;32EY;3~YH-rez?4Plnh)bEyz z!Z}@Y*58@SL@b3K-;=Z;9f77NL zbzTy)Y&($3xj;&l%1M5_D^@UqAf5S)+~@An(y2*iPqXCEG_s4GRegu1>TRTZ#MG(u zy9)Y4(2vAreIrM^&XLXDl`TPAl4xhR5k0~rgIACP?&D_KyJXW~-@jxK{rQvVFB*bF z2GO9N)K1b>^5FM>NhDJwiUhhILaS;QjNaHz8I=k;?XNY2D&L|fW-Y>rGKF~0IT`KR&4QEmoha5j|=etH+I`utsC8eEBAFu$V{Y*{JY;1)%;aoLEvJ|j?Q5`$UGPzcYpGkxz`Rc ze61=Pu;CcY-SvgF(Aq?1O+ZpG+XQA-og_DewaJYY@7YPG=WyQ>&dgy!= z&R$eCyhB?}s zVb0SGVl&o27t}<l8kl62!mR92+Uf5?kKs)id?wEZ z`G^qzuhDFmA2)m4rVkYmh{OFz4&H7c;@spnsGPwd@3S;Uc0Ta;c;HgE5S~`jUush~ zKoxGBWzXztBcHFHp{>)Ki14j5G^$+;esVi1-rhJGEdq$m}&n3@nPZBeZ z`LSI6HY3T-rj0$D(PKygZl;L9te+y#6BmIo>cY4pCJaUE_#k89h+&J%Y06Dei`a#q zK;;J?j1oGT{i@Dz`qBq;nZw3-;6Eksx7Y%=13F31)lQJjz6Lt$(rC*bdEAq~4bwww zfbJ8(zCWfkEM1%_+RkNotX`8h+eIy6Je|mV&EuG*ArC*pg`kcXk8%Cgq&FrA=KNcU z($C(($?b|*ws-+GSdh-~9BN?e&6~9RSznTcMR=h&s6xgHG^#n{K<8J zL0)~MKcotE(~v`HuvzZ}*>{7_q-#yU(~Voe@O?BKTHQ()U+sdPt1j@hyq7kwSU?h0 zs^H9;a?ti*DY&l0oA-}npmZV#8FCEw)h<}KXENAI4KVVL^S~-IoU~+ej*IGrWbe5w zNE>kicc%;#V9OwF8s`D@Ea6z&r=e!Iy2V@3?VwqE0_+o}(usQ$c)0;Xc)u!uzG@ET zZL(~D32vrv*-XIVLGU?zb=8(E*kJ~R0mtcG^>d_aO%|DY(Hm1NtuW_%6l%t3z*X+K zlyfE#VgF>*EuBVFl)cy;`mafEXBst{cAdt97X7rpkQ|IXPRp-X!JVt>v>+^uZcLsI z)gC1f9Y-Nkhex-lRFci6BIvB}gw{JvLwTyHeEo175vc70%hzh=GK<@2wfG`T z>2pTcDN}Glzb6SWX~eXSsTK#+6fMquYa->bgD{`>fy7&=;AT2)@@x=J$pi0RF|?m^hF-g3h40HR(5ih)ao-gUuuYY~8SRZI zpE(FV)x-4Vt_VCaE1T%MwUg_r2SFo^^GF@70GT~^$@O)bG9DH`0gAt00o@ zgpuS8Wa_I&bhpJY$Og92t|UL^T52*mwLJ_%N@l>Hx)LH#UPkV{YDPvP26hg2P`hq5 z&TklOUhWMrA2k)@z%_?bMMu^hJ?-34`=`)cJnUohD*1j8FyVkG#O zRFsvIs)v5C)AtjvecTU1Vyqyk#D_8GGL3Dk+R3>wds-%04sF7>*`h9e;wKpnH4E$L zP;?(}(l>hukxpXtIIiG`{!aK((GN*ZXQmzh01Du#Y@qdZ=@pAJ3TaKeGElTP+MuBm0Ekt_g zpk&*^HIOXYgNnLe$dMlV?<()={kddyZv)x7K!vPb zSj95S7XssNjZ0!X$PZ=?J-7Hb)k!TNRv%>PJ{=$jiyEnhz;YPeB|t6)Yv9>FO>7Kf zsGRcy@cNel!i8Z(toI&V5@{g$8git6C;&95v82|EMQ;9b{j<~uJLJYOrZBR^MC^(&!paGwY_*Ayg%#akfDxR8{b zDS!llF=ocLJnn9ElU}%X0sj741mT+Y^oFAr*scnKeWK=Ae9!_yrz|EmFQ!An8y1B7 ze$n4wo0vB}`HW#kBh2CQtUvO`IRB^s*?aE=>9tT}M>LEed!UOdofx3cl;?fa1acT@U=2Wo3_70T)cQ>8o z!0mn3l+iyg7Nh1%4a^ZgL{@)~Bh4N8bbn7M`FHXbwVgId13Aa-H2xs1vy^}tTn}Nx zUq@W{p9)FXFbk9CD3FNh(HPsGP4Mp+X*ijQ7Q(jZ_Hl%$R_Eb|y)Ec_O$2{U*iJL< zSDS~N4<;`50I5sN(DzIy+3&axTr0CdCfflLC)TEe8i$2Xd~i#P3D01}lzmmM zOuWM~@y8`?D15yVDq?zRb$%upUuX$#WSHom_rSLBGI3o5N&3I{n3WJsFR1N zu1F|#yH#pllbu7HR{S9azGujf`7EotkY&y1Ns@FuX?p8nAL7OdMgjY#Z#PTcK`QRh|<5zb7&;fgaPa-9gIs3ASQ z_crNj`b0S<4B69q9G!Wav2;o#w!HVCK3{Ir`J6jRDma=Pw({V-g6ddnYsTJNdx&)R z&mbXc$6*J5KR9mR3op3c+F(u+#B$w$$`o19^>c=j8&M$sTo!x<7vn15EpWk6nspsF zf)?)iCr7S?V{R%io*IGkGW=8tJ#`q24R?(czu%q zvAd>96)m>1i3*9hxh|CMxVQ;}-e|JccNDOBiV2jIel#=NJV4(6Y$HVIE-zw599cd* zK(J>m%~I~8`|fv}&sh7IDqm@$<4rB>fe(}5puawj-CBfkeX-=+3JaVy>O|gsILbKu z@j^|5U2rr)5Y+1pX&7ro!=vXw>p>-Yw;>sO|E$Fv6 zMAh@3k@XR0s7I;*9)79?K3OX8?(A3E|7M&X&=JSCk?Hv9H;>j9$-y2EY3xZD=QYI@ z!^aX;lF^k#t~MW`1J^2Gt+zc5sqZGb9;J+w^D=B!SB3jM$HDU0A~X3)amebN2d!^A z;LD~ct{2fyrfjVxrk^IlnvP0RRu)E#gS5bD%`ax3y9QlRex8}`7mSnbTX7yYJIvLj zFtum`_D{S4e4E!Gqg+p5JrWCBL%1|=JvXm2!|)6L(dID)?i@3p{l4!Td+X#FVIE&2 zSM0J$`&>(yQs@t@ryI!gNBh}%s=XwC_GdUUAs4O&pP)CoY|%I7Fv_&$!);HFFQMNB zi4(Si{ggK_Y?KTm3**UCYtDn|tBb;ljc|ZhLS0%J+Vc1!_dno1)3+Cbq0=&a-55jL z))gR#sA0gF1=wRQ>=ayp|4p~e_srpvD6>FHO`|Z#^30&k6YOb zBCX)H{1%mz-U@;X#Hhy31vs}_0@BkPA&pH1ll$4M#q|#KkO{$2uPylMgAl4Kv=QBW zS5RiIbKe^)5-t-5{R3rWU+^m6gzJC@#2}61Z{Cx+3?`MAVLh#aTWP`IBHy~ za-KZywWN6yxXxwyW0KUh6T{gEsI2|~rzb{%YVsG>x4x8D(GpJ=C?$d4rAKg$p9g=Q z2=VcI>&8N0K2($q9YTrY!%&z7nct`UE#~J&pr3P^E!A^P-;Z-ERoK4_jd6 z@MGfJ&u6Y|4Fxf&60+!868fDc#L31Ah8%)T@6;62n-AAu=gd)t_g^!|A2-KOx8}1` za~(kH+Ic7w(}lLu6c{x%rC#2{yiZAs$#FpmH1dr=>u!Wmi+pG)41&oLTi8&|z2w6d zJ=o%HirbfMMdu%9(WBW6U2Yd~T^;Fjt?Lq z1K)3n!@FmKJPFhD%;b3!VaEPlBs4~g+c7(1$TCU(lbzflf080MajHZq+0~HpEP?8L z2tdoX;XH>s87ONajxpQH==lRSsPs;fU!ze<4b?8;xk-n4AJ)XupPR#RUhX>_bnK%u zMJ4#BrcT5g=d;n{Zw-C%Z8=^o7{a6z8Q7THi;Zg6@aPsfz5w}xB?}qcnr(}V$0ngo zS31o|@&HREZ8-L@njX9_N5)JalLZg2(=Gk^@bUahqTbkp7u$vSKN3}N=-_62^!zb> zt^AVazSqUl)86+5-K!+$o`>k@O;9m{n zpH8ZnA(4#X^_?#>XFlM{W^0kzPPgboH|>pZ3#y zuRR$3q?^XvtS9<8dm%)ea~l-5(S(M-Y7)uV^!|08PFkdds`qut0+o~adgwBVnpJ@IzCASX za}<96CxAz;@rkK|G)jx~Q`7jbMAJM3)#OdEs6+{c-UqW!c6(uGT|IfG=1gWAgi}gR z!Qk2btY!K>SoR?SF7KL0-(CJq>ZBIYHJe5G0x*d`NBEYxjLlmb{xJoW504R@-{C0# zSRI{f-q6Q`@i;m406oc_3)UuIMA?bsI9L~ss((_@{N*F`h<{8uYA%*LSK!*+n)s>T z1fS-OW1PPxNbaykk=w`6C3-isHdteXY7wnV7G;JNJ;>!l-)YCESQNZbj&-S7l#SdD zxcfa*==Gaw?{I@+&v>#~WB^2Sr@^(})v#;MZIUrF2cAr6qdyHS;Z^(!&@R+rl63zv zvRv=<@%>VIL+2`u-Ju4x+qixE4n7G9X6a_fI(nwDjff5D<3D{nY-bK*>(!a``}1Q^ zuIvFTKVBtwW`w}ofj+wQzcB7DxE4PtY@~8_&tU#=6MI7966TrniJHGZaX(hcaS5EU zYx8}od2$vT&8vX+iL>xYcL)A_6i3bq{-B>6U9rrrhb&)HjB{nv=!R3)xTQV;Q(ycc zRiEUs`Hd8<&y2z*@%eaOIhyV%vq#HK=Sj+w%QR`_S$uiBhB-4Fffus+v2?Bxiu85k z$=QN1Po|zF=3mH*mC<19lS((dGJ!$C95~UTN!~X3frvThZZ?d<(?_zX;@~yZl3R#6 z*74}>D8t{;?uw`V6u{X%oRQ~pH_bNMIO+K*9M;XDk4|Z!jE;c0SlUqcEXNL*#E zH)&&9=xrwB+Acht@|T3&_(+bvT!Tvb5>!Ykgsi*}NW`{Fvl&NY$l{_QD(#d5HQe)` ze(ntJm+YX<2MIWsvh8O10zzjgvvE)Amx9Jm6bX^6%ErL z6Hyl}NEVj{>jkE4k%l9_3EfVYn7b3ZeX~$$;eJdxm4oqDuaIx868LZ|n;tZrfUsE- zIC&qEkVvzMI~UO3MJ4o2qAl5>G7+`U-D7*+oTqyOD#<~~c=SF}LHyNK@fvqle0+L4 z9XzrXD{5U(xla*FUn=2|$M&2nq>?c0v(atuV$hZB;%V-mK!4qd$2-5IIab;X2>!Yo za|IHq-QE(k^1n=6Cq`hqb0=Al^pu?YW{L%KZ19c}#|XkAyfSYpZ*h(s&Xw5G^78xp z7TtkxlIX#)@BDs~IdAjH7o!EB*Ebc#IcC+Pv;;D(ERMQ-X`te&7PvP|1ta)1=*km9 ztB3-|NL>T9>a0oWzz=fu-FfrzY0J>}TNr-aTtP&`H_(gME)!wCIhqA=GxdYGG#3Ha&katN?=BzF{&nXT*8Fmm1#a%V{j^~xwFTE7)>*`OE- zil4xANlA#z4Z+*pS!81SJQUBpK~tj6@LckiL;X~FxVJn6f8kqlSaC63p`-%M8SdoP zTm?K*-btf0lyPEOBU!j%AGiBh1gRWrE$U+%@wzPu&A#3c_-QJdyG)>GcHbu93*L1AFaD1@PIrVYhknx_xuvvl?^f(F zE2T!wGZ<#k0X*GVKu%8IiieFwz*0sBEEhS`|MPT%&P}9CSOJb>D@;d6#bHCtMLK!) z6tG`A7ysULhFS|HlG;&2Dpj8mmm}45bdwh6tY3ikQHwBd@(_I~9ggp(?&aZH za&j+Q3l&NvXvn2!cko>UP#9>^O7?Y`0AWrB`K+%W^OEIk_Jw&VlJPs z*03Mb%}1!lcq2Z2(1pjid-@dZrTD(2gFRhjga1X#@TcX^;X_*u)`idKpVX7%4`(gG z4G$x!`k^)|E5DcCTqg@h-n79D)hK!-ryO#Plj*eQUrEx59A>AuCFf?mjfdZB@zefl z@W%{m*xYIX8u9Ku{#7`}tSz}g#riK`4j91k7u%>)W*Um!n+aQ16{33dPjtVq3?{#A zWCevLVQQx+Ue(M)w|D#Sw()sr`00Z`bsykyh0DaYtb&{$u>p&)L-67ph2;-6kut3BE5HKvPW&wZ6dM z_1ej#>C$U#7Z&FCh**;+#Y@1iunj)>DVj?pIHO|w6i_rYf#J48V6s(|LtnR1>46+} z;NBJXzvhd?sx}ImZZ5{3SEJz4#t^gSl()EURtq^*_=tVxI7oLc^k;0QM1p8e4tzRT zM{hpLp@C|rVbzRzAT+Vwd_Bhnc>0Blmmm4g1V8`H&Ql0Mn^ht-aKQ@{P_D+}Wu3^p zYr)6et;{(^3s5z;pJoTNGtqx74RU#P%8yWAL$a6F#7W4n+%&;m1~ z2Gm!~#Nd+|gx|z5MLQk&Zc?1Lc`yq5oX%kYo5J-dPGInjb2#$h1+y|xnHry34I-nG zFsXYz8H^hu7bgfJGaL*}3k6~4j&)F+BL^12(X?e>1Tf>NpdKOzr{t~aYTgydOTP)v zN1EV#Z#d6p!D6^OnhK*eh2(~yB;-1HaqJ0u`g^$x=^6DP{IUfwsV<&-vzbD!cRDMp zI7Cf<*aAPO8VQGY#A#fRkPpV)E`=_`PU0JP8&=L4zvX?_EeXJ=eg&stx4D z&6!l6+u3R|`R2W!$8clZOuj|qRKD@UbMz6%>U*;=1~+77l4abxPL_ijO%=`{N^5Lz zb4xd_mP>&LPnN)`%iCeY%sE^K@H?#R+(n8w09|fCB_uu?A-SRIFugt!HF*Wp@^uQy zej15AyJh&|PTufh{d1goPK;ly970oNIk!~GQB1tlLTnDZGy5j3|8Jd218cJfSiI7+33 zRpCF*<&l_|58B@c*^#N8iSF{8^M;F4j zUw{sI=49JVq>@WNQS;<%jjXue6u~nJ+=9dvKH3naQ^Fb$7d5gZfr2vOE!=z3B!NIi=FeftvzP$MXvJM`w z>hC@CDP5M-wZk4q?%u+RQ?B&z=|Y+xaSQi!TGOf+J{i9+1$(Pkp;y`n)oYywi;t~C zvSEq&rko~h{p~{{HR73sD|i1#+M7q!^#Ad{N2O9EMM{P!6`>MM`~9j+Ns|gkM5RbX zLNX*8G;5ycc_t-|`~6C$q(Vp{QY1r$$R|VL?(e_9weDT(-h0+Mf7EKN)86~+{eHh* zujljmUVmRLgiiSxqKW z70x?Qfz!%*QO@cws=d94BO_-)-8}`I=t;OV^){%#O@do)mx$Q<9&X-sf!;~kL%tXH zbL^`yh~anzx+6wVvELeZj;A1FE5H<-^o7vHlsyr32m|({(~GJqbZF%(Ix;&Q4I})p z`}7QfWDg^Bo&Q4@ah?t9vRL40 z*0SFQTIfFAY<%hc05$!)Y3ZMDSYjqmf?CDEdW!;j8SjR3vp3O@zB*u~dx?Qi6t%L5 zY-qIaqde!ySbFsl5zUW71M3o2H%Shf-SpUJ9Y2Xi^GuvruaE8e5^(MGN$kIFPq!ML zU@Xc-$WVSRQ60%6`bwT?W*Dv4ne7RhQm62i@eT5LkqhpS7sd^11Ovc zaErrYn3`h*&(#>%u_hVLl&2CYp(o62qtu4NK?Cf3wh$$Dm(c3;{q(Jw54<|-4Z4;q zp!$uoCx$!+Jr56Y8ZK~hN#8NgKv!uRJu7Ej>r9gdTB0$ zpz#-JZCpX8PtL$F@|(^+txxZmf1uygb#Nc258o#c2Qk&%(%{f+PFH4isZ zA#VT%sX}0!aS(bA8$y)-C`~KAP8QH|*6HLh`dKc()iohl>~jN8o;`yDnom$mWgn5v z?V#nR&bY?uB1nAmBt8bx+?*vC{3eIM_`hc`_&bP^>kGt7r{z)7EEE2@tb`xGt4Toh z9b8j6gu4@U$?)?Q^7Q-)=EbNxeW)9Z6AZ@nGxhz@c6285(R>*8ZQ?XJJS9>gU`sA0 zUZAa$^s)P(2E8f%5U%dofj;C5rK8BYk8dDKcX@QmCkuTa>n>7|A43iGmcd^mj#rTW zox~exV88t>_Ndhh)H0YrjGh0`k>a}z4IiQ#lw#)4!XN#h!>zBymtK)~de>1Uw+lx) zDrx$bYW%^?oI?^gAMdMjGBaJA(NnBvNf6bq;PUiSPo5?9esOg5>nF_Zf4ZccH_;&A z-6KFe0N=m;N3W_;n&Fl~+)1x8GTA3hL9j;;Ho4xSpT;6#x<(g# z(9b6V`cIjJeKSd4rwxdWSJRj`EI!{_48zL{V5hwU3AucLnY5c=^)e%Rgb{#`dSB`O zTRqscw}Cz7oC}A-UbBWO9!%D%{qXWr5InLhV`j?up{xYwsa-mWUilQ#Fq5poHFp<+ z^3%JZxu^yF26`Etj#>Eh6U)`hTfoPzn3Qaq4KE6IqS<{x(6BIt=#h9@V?0iReCLuC za)q$irWYoTah~vk!{Bbcuz@!*2E0f9(amb{xc{65`W#H7A}XqQOlAq~2);ymADWX@ z&lq?(?1!sm-SDyIO|*DBh3Zbxgd2LB!L2YIXL7x>ZL7Rs?wtf$_4pcGK75m|U)@gE zKRrY?eH-Ms)Ctsfqa^VZ6hqT_A$X&!fHd|_!G|QBy7~X5fe$CaK@nffDZ4@6*6Bg* z3{Go%IRbOr=iqdi`H&%g3~p~erN85;0}f3VB8m*a?Du(ab!{3%b)F`?_w`KKwtQyb z`Z4lic{zDD7K65thM48#OSY{EfybqATuX@d6UN2}MhwgadW_5tY_vS+FZ$dc^AJIC~1{)4<;j(#3 zh`)FcVHLIE;k)T@cZxFHy-v|2IG?5#M`4y#Hgh84G0pEZB+~}-7;T|Aa(;F@+&i#} z+zCsfr*R%Rs~~_Ie~RM8P8BF$)2)9^P!MOFafTS5o22#kByNAa3Y#o8;H&akc<-Gi z_63LFf%_lH*fK3JlL`m14X%_OwkEOHkcvoJqm|P?I-`36d)737+WLB6q?|0N{uBxp zF`Bqhn4#s0B_!k0Qu;*Qoe19JxH;~#A?p~&Y?Hc7`S&7Ou_OTVQ|s`9`7*B7oxtu> zm`NNiHNxSKI&89eCUx-sk2W<=N3o?3NOtrweClb7BlF^bDxU!LXcr)wicol?kTqs2 z=-8+?WHEPYuRH~X&ExSC4ONpPP&nN|PfwfEOEu5H+gfMv%hog0_l`2QuP#OA zpBb7)UZx6>XQAP)DCq7E2misdT$Vs7k)FB{9tLw6%CAMKmWU917kCVfsiAPVMjCjH zM_`en5%h0-Poh2d-ikrHkYmdB{#(FUk3^_2_`}NfJ4%gmr7q)6qqV zsQ=|Gp6>P}wU3YDD%n9M?rks#ya^&H?-TI-rz$#h(HZ6p$l?^UsrY<<7$#sEn{l9m z9&>3SJ2id5^V<)aD;NoX&)#HPlCLnts0v<`Z-EJ)jcMqVYC0ek&M|7!^$kkTFzXDK zlGgGPW^+mi)_h-q+5@3vw}Axys3}FAWj^HD$Shnl{RGxOU60nQ6*1&ZGX$*@gnUE7 z`B1iEQsQ1{4w(nBodmZ9a2eEzb5Q5)02{N(k=luGXC?Cj>2&5ZZT3*X_p6<$iU^nCm9^;p2&SXx9a!L-0TGw$ij5zY% zdMl}qHzs}=!m#@bR|~K8BYQuYV$fazgG;?toR;?(c+7eWk&8c&vo}TPA)hw5b@2*& zFgqG-wDjQ3%Qj}fIt{+7nRCA%qHhm&Ghx$Ggeq;6eJm$eA3JETOC1)v&4jA(0t5iki{i$ei-Y5b*gEy>mkm*i9^vTJnI% zPBRA^i!2BrM{xaQTN+iJ2#V@WWbEp5FuZ;UlD5Q=uusBxZC)iUyH)}lDweVv{3Pjz zaRErQnFSfs4au&ie{AUzUnc1nQ?8j&5} zXTn@@SFl{W8RzZ(O*gxVkbM>liP)>j`0fW~TN1D8xB9Hd1#`F>t3m-2?o{I%gSYhW zpTi(;CWimrd`iY*|p78cj3A?2^hgw54q%E(}YwQw+&=;Bj;`0&^ zTzUc4SEbZ$QC|VyR&$w{;+?cs_!8ah{|vS57o*a*RzMR;*sXSi+&g!W?cZ0^@Ym@F z)e4!&ynMRd!vNMGP7 zIGZ^{V}dgws$Q3MzX*7IX&xjNCxC$S8jx7J7&4#&7>yh@)pI{8C|#okQByH8MGZyd zx>0jwPQBWgt-g^+E7ZzQhB7Zha_f#F3Ak<#R--nsyJ#w1y5&5?tDk^pe?~|`trfLd zSVQ(Ei9--qBilVs=d^;#kabxeq~)`T%#b+!87GP#W;Bw@gPAz<_bP1r#BpL5ws2Xa z4`9!Nr_5DujWH8m1es<-pfK??yY{0F*-^Hfz4dJ$ED!aEKMN1T#%lom^?N|YD;kOf z1egdVMF?B8l^9o?M%8Qy;tAPgjp8BVEpAh*?qf)M7qk-+a(z!x^_FXxx2$0aV02P?Fw1M7#0LH zkrxin=*y0Mc+|iF_uZI}2I4>I^qV|zZ-7WhCZ5Sc#`jEGAcr*Tdnd1EgTVU((z;hrZl-3E%sNFgE$(m^pc>!K;{Rxc1nO z))mZ0(@Yz(5+q%w+hhX$En;GLZDYjhoL_<5aI=_T&?HY8|!|Z;)U5Z}r}> z?HG=~p4Xy4rv`4EA%)|={g^QBdAxS%WQe?d6r5lB(6z7n8;pchK;?4-O26m9?!sJr zO5^A%C0WqE@9yBQu<8$a)Yl+B~dc!Bq<+L;mLKGhJeq>4fo?G z!quz&4EmZ;f5%PiSraApMRO0$Q@o=$BGnFE;YqBajW1oZ@jkxRIfxqvR^zWbP8h#C zh_sw^LX#OEIj-<|xH3@)-I{Mu{Ur=edz*}s>$j1-FhK*qPj|rGKY`xs^`W;6av*O? zBN%kov&Ey3kBfP@DMq3O`UA3=dyUe#xr{#$w7Z~ zD_Pwu$9YNvp<*M)9O~KxVx1+NkM}+O_wPB03RXdfi4ib(Y8>Qxxa@BSna1g|=dor? ziK-`abG_z5GP8usQIPpSf5#O<)P_)8cPartO?XaziTy!W>uGp%_BM8zP6Zj=ej1a; zTgVdT0$#d#0Skx2(DrC7UNG2-T}#vu+_+k5{1AP!NSJgkEamd155t%EVkWx!E&Wv# zNw13->Myvkn7-O*KrggBAqS=9$%;!oRC=l|(kr$Y^j!wG{tdhIIuGW7Q{`3<5Sk+-q8#isWh3GKa0fn&)wAK zR2d$M(tu8RV`3X1ib+lbB;ME!!e}9olYS)jk|?S>6_Yi6w_)$D9*D7&rKiM7*_N~* zw5#`JVMqe)D>xQ${XN_>>np9gyn<$*-hyh+7U8RF#n|ht#YCVfwG3N=Ilg`jf9FgC zSNq5CV4*Wu{Mm)xw?EfU#$@;+aUDOKNFd)*0_jT~D*r$dKJ60*6`c=QT^EY!$1~X< z?+LiN?L$wl{~PVToodCRxV`2{5PZO!iS6|5EJfp_PBLsL^;Wj1;>;krhi#2L6M% zPI1(zsb+6apfKIM0+#g80M9E8V0}W7ir0p+FA~;a%NIrV*0cbWZqp@8f-1ovNCBIr z$|0j&nR1Y1V4L33-=ZstolrDA`l${6+$A{WlpW zOtNUkL%ENsK$Q^u8Om&^b(Vy&R)(f?`RNsJtUz|0QH8I^paR9Ivz^ zk-z1!Lwt9`ziV4D?BX91WZB%X_>mvo)@BGBN{^CbVo%x0A}^Sv%SFg)wc+AT>GbQT zE<)Nk4=?W#e3$ejf=7EUMwtJlTL=Wgs{6$o+k$153tdV zTcAO632Z+%$$(7Q%=MlV*b=Yr4IW$`QNDW~>dx<@ebGkraOQisk#qohd``oP2dd=D zqF6ADN~5bDnBe(sv$4i?13rt|j0wLA>9W;C&nv#5VE*mBF6sVp*Mh=^b zmA8Ue{$<#x_aDqpje!NsW|E$CoYt(o$=qGlfMZW*H!fQ^f~VUR=(Vs)T-Sey8m~!& zl5j1!+}aJM8l9jaRtdgw(_z7~Sbe1qmN>C3tlq|I_8akHCha**>Oxn;tp!S?`@|Xe zqIQKG>2!rOuft?PRvLNbGzGusn6lHImV+HPi16Vs-k&!tmfzbYL- z=83*mydD&sc7lcaB_#K+8v5P5O4Xl75PPXmG`Pd*{Rd*mz;7u?y)l9Qt-8<7Srf!g zt(%X%UA)GyiPrGkQZw9abyG57Eg%fR;^;o?piA0UWq1C?tY@9HOOpDn=4FCSdp>5(Q zH`#;Kj>uzFTO?kqzRFsfC(y_G04=LRnR3%lG(;q&%wKNz)&4$-rk9St?W2P zy$QZ6mu*~sVRj?sd}Yby;@DRIjz&*+!i-g6Y|vO7Oq^gzc0MzwcQ%KEm5&#wFHFP> zUw^Y2?~l<{q8WIyyBArfKv+2K43l~51Lim`V8bI8kQj|9G9+CI<$c{$#quf+wXT8P z*>}(?tddS<{eYbkNG3O+qz(X~cb>A#&SnDo|!oUESE*z|QKI*i|=ZwR>Uge z!P2!bbxfFKd^(1Kud8YN#qIbmM*<%GJ$x6tI2N8|4swasg|z`+Z17gpI2)$Z*8KH;bzu4>DRECtAFQjHpE3% z^YlBdPNGU}8r(ARC3(#iWa)Q5xFc##3+}bk{^nfvLF6@}@_iww8v-<#pTYNI+PGiw zCUff?$D?mB!dI&$Kr*Y6HuETHKfn?)VJ1dabLaj=DC)0uf}1`{^z>uS->L}sVe5JN zd6yIvHF6mb8uEHl5|IsSv@7tG$izm`Mf2d)4Qo2Xd_G#w{7NIqw8r&eHCTF^=`~}Hi~b)OQWoMkW9m$LhzYSbpHD=5 zjN!|xLA=dza;8ptM84!%W5lNkWT?g(l6s%Xf0Xq7&of?SJKZB@;(!ip6<)z~?71Ki-M^>l;zY z))33L%5h`)VbVVD3hbJ@i8d*8AXz&DMgy#I#h<5aX_zd=|JEVuCDm-@t9W9;Y4PsA zI!8)F4Pf!(KQ!N=8t$!~3TblHbi?^E>ijJS#!7YkqjYzH5dcd^|HB zYXybi<19fkWkUjLNpSn3hnwlyZ-1$nc{!?-)zVb=SNPp;2b!)Af=`z(k`eipsQobu z=UMQueZN&hLYn|Q-*6J2$sJ>^S;t|sj456)nZ-K)wV@(ecFgsDXCk^Tlq#<{!FW#; z=5liTs6mnj*o_E+`IaGO{-Iw)G$4chv4!JM-grlAH=n{%$U>JdVK~!o6|6}5MRi9e zHySA(A*-HfLH?9Va&Af&oHv_*+dSXnw?_grag{Aj;+V`dPJN|K9)aj$cb#XSv4zujA)F^8fMmzyI&z7BM*m?yvs${(t)a z=KP=6M^j^^&T?Jj)pGy$*C)u(pETEpfd`$39-f_aO^E`GetJN8+y3aQ4Y{$49Wt2~!K=>B_>C67} z!m_}njPH7XqSa!Lq9P@bU49mQdvY;+OotlDyK!C0M5>V;Lq0DO#?P}OAUPI*|6n@w zXl(@EoG^B@#S7+b4#$VBA?Q;2f|waL(LT2@xHplY;`UW2VjhVG1!>S#Urpp6i=(h# zB{it91*ep3?EM~&t|=Sfp6e0Z>mP}I=VpM{=s`G2vrusQLhO62L+%Z)K((pQX_vM!Gz%5NEo1(k-ZUMHP%xa~a8~NMMzw zV2Fq^XlYHt#3osv~(yGx)h}u;k}8dnwEoYUyRVBZG^PBdqC{#bnH0W zN`0>^LEeYY`l5mHINB(Qv-?ZXdr%4mpPvIWm#wHU0AM7=<)H8RMjO|1b>Ff8xOYtq zs~n=CL+vT$tqW!w-^{?P8Kn>>P=ZEt%9%2wU8GRe1o*1W4PH-5iG0K=*yNcAw&&bY zwz2@5{&|rh^CxucsX*itW#Y+kIEE$*kh97`sMza=Cf}!kh66YRG|DQavKKv&U#!Zg#alB>>S9>HZKQSgx9nt(;F&!So$*oaIB@-|Xb( zxKp9*q$u%7Rz<;RS@<#-g$g4Q#3KQ~H{k=L9QKVWl(~`XIvHr?6;I0EN-|9oo>7T_ z7|=NIm{#}%pteFOrd@eR%&y3Qx)f9vhZ`|NOQWlo+Vn_$aYN!iZ35?Hg5~Apf zYKz}7UB4GW&xJ&^?Q%tNJ6pKK3&*D4wJcvPjf^_%2geURl-H1sqW0X}eR>4S+)HI! zF0TT$dL3GGPMIpO`SdU9qT#6=Q0*5*w!##8K5c-Wd(pJY|P~MVHI@;`Es91uI-WVV)+)SUT zxKEW^JBiA_B3MRbP^L>0&4z;@ZLpR!9#6zN>Ej@5nMb(k3(9L9hrc#~=>Ikk`8Nq` zcDevvpSh!WE2kAZxDOp)c#*WZ0nm1FCC25=#L;QK*xdh$m~0Eh+iWHpJ)DS}?50A+ zqWh%hCxh9wk}%7&5PmK?hKc*dh<4T)Z2EPbWj5!4^jGdX6Fvhq_=muBz8^MUTL=!X zIfkgqLa^;C2D=hV3@;j{Cr}O6&+vyP_6p0_T1yVxivklvFVq-QNB;2vrpG!E{xY*r zbaXxN_XROh?+eh(ek*KEFXHrkMPL+eUAH}IqLk{*W@E}PG{UPzd z2JX7D^g@3=(u@dT=}Y>#lFQY~F+!H_gyDTwwC2DrFcJxXrkyPFU8M+n1_&1J7^B+S z(X{KQBaX~J2Uc4WpvLtN8GG}G&ONmWTE{b?Icbz8Zj2;lKJAoo;`;h`r(@fM+r&h4 zE_fNJg7}3yRM?`0+K-;Z>tks+_Ei)Y@Df1yPy#hGHJ~2LzmUD)&pC<7&qR_2i_kZ!8Qa)g4|B3E+pb1yJ@bi@KegO~=ML?{u;UWfdmE*jO4d$}Js0FD97NsLaio=27qonki@ey6>~W=dF4J=XM059Qm|X@Yu6aQf*~ z4Mx8&rP&H+xZJI7!ryXIKgu)(j)og~or*cz5Ec7*fzcmXS=0c|~wq%Zt7 zEqfTp^1j+|_iGt(Run|9s#Vx+bsl8Og^AJm1j>&-$7;LIpslrFD|8$xm_i7*D+~=JF|S;F zLD4S{y<(QoZm0icq^`uo@B0bw?PjYqrYXPnP93(D+|(XMR;?Va#s*!b@ z%Ir;|(PHT&sGt~{L(TBsyfY~M+z!0n_>j6CmT>xFJ`{4?ugvHeROWKdqeUE`v2zEP z>vNcn@9Js@ri8IC;YgcT3*+<>h-k~m=l2KG=3$%rJK;QnE zWbx{B7+kIn!e>%QqYw{$!|fP_(?X;y?u)YZI#Cgmn~rM!~ysQ+X#Qb7Ix6d5TxHFz>tz3=c^r|L#;`)&vQ5UCUa|D zRxFkc$C9Qo9#mz8qrk*y@a^0O;Q@O%#!4)4ncq%`PdFYiI1e3(#U#K&`G4n#j^~Hq zu)sZ9?luVp_fNpSSvz3KhBV;2YBNo>>eTJmbCPz>5}c-RpF8sxNp@b39bT)kQ8xsw z60TE|SIXFP?;2V2#|koManI%hsnlzNE^*qCh$HK~L3yx+c!X3C%eR>zxMwHaoRbMP zi%!tZK3T9#LI9PWB5BvEjbIib0An!`#MeNPm|hHp=F~V&Yj703&q{%I?=1SrN)X(N z{h7W_C*m7#j)k{O!7kY#ji0eHur1^IRP z_~?ZM)cjsed*ZpZQOFu}-}*u0@?}^ybsEVvi^oLAyNpc5U)q-}jLwm}fPYn7f0WDW z={oYBcDGN4!c4?eH4>Xon5WCJ zZ1)Cz-^OojSF9lO`-(4AoZ1fo8jHX#yp+DO&%lsBPT<7~P$R8roSw9bX`VO(%3GJf zlOBJ}^$voOyP8n*@i02Z$kQ~fND}rf7Mf%fL9|#0WYlYz(zH?>Ui^!+y;u#TCKuhR z>KQk#*ToC2Bwgu+pkO5nJqkm(D-*%**JV5ljbp}ps*^N z^2Hty?`>7ITRIyGzkMNAvkLJg$4C9~I{;=D_ybRvWxVwF5rtk(|EsbUo9;G{Xf_^n zPjJ1LihU^Ba2gcfOhDOL9uTL;d3$+#QPMSzbXgUV>)iLOiMJCKMrT2q$W3Z~A`q@W zO+nwAYZCH^^G}5#A7D|<2wghN(6xyl}mMWxEdivhVbWv>RXNn zV2h3%h(>IKFUx~4bFLxqsV~^9h=aI#3n;u5Pi7B<;<9vWu$#-(VFA~eQQ7UZqcs#N zlon!5-wF5`G#7YPgQV0T8TdYN4FPW!qkZ}^(AgUTWw*tc=4Iogh4VlKM3vxdlQdNL zGl}S?&W243tZ;vR0We)_AUb+F^51==UUR0B@`?6b-I<17y-Ogv1}BDZL%M>_Y6pN&>~uF&!Y%&_tz>Ql z=XpUDOmy2vhZ+-!agPb6)`y|Cj3<$_h$P~5?Nr8QAJxqk29LcyAjytXvn6AsXkGyD zYOUDb6m4AnIufofOh*}pGEL!~Y}ZbX>AHLi4e!+i(N0_FduvX0zpg`tTRa@rizeY+ z#n^U-QfGTPjQ;X~Cfn`+k?Y}Lvo{WE=zp{?HXi2|#$fi3>qPh7N_wA3D(;n#{ z<>FeBB3jZ z%W(ZRA7p3f!_}_|XqXoZ>H)D})!j;mE=v-5^#`>1o)ETtm@sU*a||hB&X@ijsAugqQlA z7`bkT{Z&!m__LS{8eJ!j^Max78UY!%jmS~E(QVE_PG9hmM8AAMd$l)U{=6Wx26j)}G5gpmlGr@JEX(Dx>$q(B^;roh^Tr0fwsYF; zg${V{TOzmzg+ZC09vx3gf{+R8&?CtS2ZaU*KkI~k#k(U|Swld%Gl-h__Subw5aYTri$^;RTnr`QhJlr{P7q>pmfg4ZG!=+STG`i77_z5dXo0cf@Hy6`0Lj;$}pM<6$bNry6 z4Ql7QiLBTG%&thMs#1< z;Pv?^_T)&Sg3n*-ruvcH)a3wec895VJjVgya?RojTu{ ztDA*E+!dP^PsU%Dfko6XFYjtv^p(g5!wjqr>of zLNtU(NT7`HIk5dA1ZBA)s9k%PNIx^hq4ql@Tl^*E*E{3fE74GPCAOit;u(q7*bSmd zT#xCOBrMw+f-M)MkROypwBtMJ+;19C^Td}Huhhln>s+5`h61UhlhC*ID(#tagC;Ji zW4hb(z_GH4HoNu^3A06brhYTnhgl)BYk(Lv2eAr@mhBG2l%o2+T-F`Tk&Rdb$dQeFh05Jw(eS zlW6#`CrYk70X0TabmKLyFH*woElO8_Z$J=h{8#~pwy4k^H_i)gG#B~tA*7Dkf@70E z(a5}GAbsx`GG4byPr?*ziBduNoI%1boPhT4tRQH*HbgDShA#8H%&0EsGgJOWqwNAg zqdyxA{w~7F8Zn@|b2W-y+677f!XYTZ3Lp6{0X2oGbd1}RJ03d6@g$ewknM6bKGr~f z+nxhK>*HWDDgudrFH!H_V)9v_2)cysG8)nC^bF_Y5Z%MADcVnHPZJ-#o>!5w%gQ)n zb{bs|tKru3rD$?375m&4k=D@jAkNL&PF&W-C}++qvfYYfW(A_jr*q)8NR%#%6M|@G z2QVAXL`lmZB)d$5!@($%^pIpU>-a%O)1&F-(LB)hvBNf%G3tAY&nP>!WhdcJJ}%{j)i!) zfVE#Z9Tg^v;k)?^7M869$0rhGRCOM?Bo~BhY!#tw8=rJpgwf#>OQ0;}c|*3!DE0ch zm~=UvVrLCyp_lGMdOPnts!bN*vR3ATPHZ}QCA*U|`X_OeDIhj4Vqmzom-621U~4!Q zQnAA-&V%oW;(A3?*&-5UP6@$KND2(g&x8Z2SzvX$5X{Oq(^2sNkS!GCGW+w;PWKtT zvE?w9tsboxzc`;9^~(au!OL`Hd@FpOHx0XlMQN&eA!r*UkiyYZC@<;-%a%+6-^wPY zOIeU9D?L)v*d7V|^lFA3Rm3r;7^2poN@P^_kbkXyU_ZM6-OngM_F_3=yzn@9#E4&L5`2tK86aW(hohAI+`T z&gf(p1btV&QC}ll!q30W`ajJCk2M7(C`1s3Yc$chR~_#c=RjSq92DN{qII8LQU6*3 z$7SaK{y&;y(z*9=|`lF(^daWT?qW6G0-)m5Yt?*QClBZ*rc`%n#YqM`j6aQM+mV4GdhF_!Boyxqh&d2_u#GeZcD zj7POpU=zPv6MoFC`m$+0^tNL?46IKJ0GD6VFm`0Zijo2Q$qFXM-AV5lHHAUbLHjur;up*aVx&pVGp0&m!mztiD5 zcMa4wgrP)0IOO~IW7$R@jC!92YJp48`!lBnxnGP|x&30JWISs3*kXJ?SMyC!M76R) z!hf2_7ViB?hd(4>_a6g%@;M8Pp68IvkW4O5ZYg$&gfq?dTexdls(&Q02#xmjvnDl` zC>W>+HQydk-@iu8y=Z;hd#Dgj%-@Oozi_<_kr(=f7Y*@dKrW0L4bexgwpgK4g0p%G zp=oLt)z!%aXU8?@{h$yB4;%;I94$tio15D}Ed1Oca!)RoYy>jD-?}50s$S z}$RJjySG?ZGjlswHlSXBSHS_ zKgyq8OC%-klAc;=e?I2T22izZIEt>n z6p`mS*5G381NVl-QTZ#kHt9HG_!m*)dN&b=OOTG(Y{8CwjvR;YAss0*gR%$3T<=H{ zWwH!l?coquqhX1oTg$1kVlb#aa0SU7(?HuOhwHs+Ls_gW)LbvZpthx0apM~GZLeVY znriyt?l7CumMMqP zGB*jWfb(?7RFN+A`HayvPZIf07Zqz|FnOmA=ilE1#*TAvxYM7EIa%PW>ycBbXJD2CjBesLq7I3cp}5aWO?_-OZ5xD;>&$R2ZAh$x!9(3uV_w^zvmwVdRGt zltq@-2YF$|gIZ zY=2t)$PR7nI8#A+)m$&<#6B2W#ix7w@?m&W0i^M`p3sG$2JO6~H2Y*Kk)L7&pQU6l zC?W%DHr110`4ZGo499_od3Zq~3x=KD!9^;Uc4zsZjO`Kpy(xE*tOF0=^JOhkQ zUL-9XN88=Y8;#T(n6%k12>;1r*68>}61hzSP9+6!{3H>Qh^t72bOr5Pl!9%CJy17p zE1pe_#Jn$#&?L16J#5dDp*cU;Cb2I}Q@}I~?|n_&R{tdfqQ%%%9L(_FH8Za9k|6qE zHGFs+k8MSUWbBI$^yxjN!+S=_{tsawGtx@k_uGSW)_KrKO@bTId=xL52TdH4IC0M` z(lOwS-*kiVz_>rA{z=BPm&YK;Jr|7PSh9R#B)YooL8C}>lqj~uWK9>G?pX?%r5330 zrklE@1hGnoITl6v2`H91iY|X{5+hM1s)&Ukvn3C+48q{&R#{B!?`9qAlHlHG5;#@I zfXSpqAkO(NRF{+h-*W-F{7Rwxo>dKrpZC%1>?9C>;|f)7Ytf4Hx^_G`3(?OHVWXV_ zR!vYPQ`hFbeDs>gsEZ&U9_4!mh zb`G((OGG#2`Oqi$i#RUUBFiQm!?tJt{x8zrJ09!zjsG@_jL3=-Qb=aD_jz1d4YNJ8 zl+aR|8iZ`3M6yQ;8IfeZ&x0r`N}A$>L@C+}rE%t9Ur#Z?+D7iIt9%aH{juUq2OXZ6Q55_ zCCk&t=+fQ7@IJel-MZS27O{7jn`f7Sh_WmMovmZ$ONBBo-YMds)g<_|P63Ndx6)-1 znfP8w22_oT==ykWmu6{1A70D?wtNTJ4hq427jDM%D$Zj5)_x}3VH-EIa{xX~TO#?? z6jUD{=DZUN!D{bJ&cViU*IxAzu|hQ}l_v>WVbSQdJ`HaAx&jwH;4p9{tf^`sm;Zc8 z7eCO%jd2pNwxf$&xM+aKBAuYz%@Ak(nhaXER{>)kj{nrT9m#YxD*q;nZSCGiujFyh z3(QMfNC>MKE55cv2QSd%}A=#0Yf{QQZ(1krI9CvnU4af~*EboLzTZ%RhfP%*N4N+`DaKPJ!X6!D$L0=P6Z0~TAkK>0yK&a=@^Do4Yx zRe2@sui6FKhxgOAPeE`;Bmu29ZlHV%RGFgK0lN66IaE$Ig|!tk$<)8;xFydGio6nN z9Ctnps&i+bd)m{7c{%VT+8NRhgks{m3eT`jKTG^|m=#b>CKp*S7@9Sbd-RmUsKj z!n*frW>#y8V;7E3j zHLsiEqg*$9UYrN6yvOv_UvYfW#Sb^X))1R_jr4C!Db;D~rLrSs^l*AI6%)|`-*yAA z=$40}*^L%9HSU1lL&&tc4dz!JZP-bcoY%5?E!uU)qsX@b66R$Oa@W;r^qIxrpZKwM z^kOrS3|Y*^-p{8y*5)t+BfcP^t<3sP62|RQn~Ana8co1;Tz)8v)VW2VweLmjtom*i%X`Lp5Up<3MT-azkHhcOxnGr{r4GdNXV2SU>oXi!TXO;b&S zdlP%`yj46S%kzNN!^re?CQ

H%RDRMNpVx%DAd;B4xH!sJpZnH(noNJZnq=O>H1a z=>p7gUJT9ZsTi0ig!0MC7;`Bf^^+4&BgGoO@m`bApA$rp&koKCuER9OALoh~;)X?^ znRdqk>a;G9u6mY$M-=aqw2qJT%N!+ez2nFb&N-6qELf|y$QXLoFQN^fbYRNIHu!0< z7IwV7!svu3!GE`=qRZeJNRtYn7V?^~>C0>K%H0pvi1X2FcX`B5jPpB&V@<`m5d6FU z1KSpGlT>e!fngjS}VLnDMK=76fQGF2qg zI3J7$mVT1rxUo(!bxn0GM{h%^{_Cuc#T~{Qe3%c-!BoBXBX>91hk7l8DEj6XJE#3C zePI6p=I8E#&PkE@j&Cg(2G1e(7gcD~GzT13xXwD%G?5+!Cw8j;2;2_ag?@&6vDW4i z7J7^l!P&!P`(QDtJkm_BO`ZY=8n`}j)jV{|`bq3<<;c?d1Nd1tn`m86ptF4E)>cit zU~XT}r1eCdJyqBOy%%i~kh_Wh z!p~y#lp+{DUJjDKu5$h^J8=J%4+q2z$%FlIILYrEKC@qnZfSyabTj8`n|TjD&kV&+ zOfC6)_$3L|Pi0vv2}W{~DD0Xym#se0L)ic>7cOWH<41%cdLRNT&IDNmJ1OIt1xH}l zb`xBe?oJftuX0)O0Ptft4zulL*v)sB?K)Kej?+whU1@01gu1MbNiN9~;%H zFs^hyQB6)_nv~N)$z=v?`KyZN&Pq@j`GW}hXtCB_w@9(RIILVK1-f6vApLF#QAiPm z4QCdiw6GCA_V&fj^NAQ!a*nE4Mb?yjbpns7AYhu4@jG|68*rDRFFLutxbqjHe_GD6 zx$z;CW((u`Fy%Ut^A(`B{1Zgwro;Mc&(SNe2WKpoL#giTAn+p)>Ti1yjdc~Uc78qt z@De~|ZUWxT2tqxnQ|M!_M4r6d0gE@DK~=4K7}_Gq3;x0VFY&8hy@M=$uPsoi{Sa6Ik>U-FeG6dxZDr7_*c+N2IPZDXNwJ4;T4L{1XiML zidtQg_G5VeCkoVGTftmEC$jI8I`2Kr;Y6K@Pq@)5%YWe zA+Pi@JTR{#gSAOGtG68e@5vJv+X$S#a}pkzW`=5AotTm%S;xz3!cQ_HAa-vC*d#g- zbuV|&4CX=N!e`3S1)x0bBDJIZ^bs@C4@$+X&iETQPWf*G%sBdv>bp#?JM?cO z8Jm#`ZNs2fAL^dXzd6lp`to0(K2bQx^9Qb|ud*TJ%bOJRxiJnRV# z!Reb`GL8AGVejy{+B#tdA8ubyL^H0^-h53`KU9ZdTMWSHa4~IG$|HL%meJ&LJ7jc~ zSb-u%kYA{PSds_Zxqk0xZ7CDU?Kr&t&EO!68l+{x66)Wrk2j@lFuhlYZ2#9mD=&m_ zT!~E>dcp#;r(45LCXD0!jFIM%nIJm8ikY+h2#%Vq!6~Ydv}M6u{GqT9a%Krr@1|+^ zLbs5<+%Jc34?kvXj#$!Tdi!d(E?1&LRSY=Hiepv6)$xgpHRyLTcz;?X>WgoL(enxP zhWH@$-T0XPaqFak?kVJzpASkmmZ8$}cua6}$01K87*QXht;R7pzSWtrSJnZ;!_!ge zXd1@s?P5l~pAg5~GWzK2Al3S$guPtm_d)6#68=t=PUZGf8UJPC2gl1Kf1rcxDK^K0 zA#GGUJdq~#ttK~B#L&Dh18jBm=$ji?$Z*6u{Je1rbu>MNKV-IGkC7h7DKy3f zin~bQNl|=ls*j7D{phB#QX(<20*G5Zz2#>}0)N(`&`fUc$Z0Ch3*Kb{PyAp!rfh=M zxQ31mG&6Iv)F9TIWu}|wV}18rNE48wVRv_7pnEZKf4YvuE!`ZRN*^1MA4>b#=@b(!s*rS7?lP8asK$1-yFeDE{hQfJ+k2 zP_y~lFmq!*Gb1LAb>SRl#XY}i@BLeh;9eQ}epfcTElLU^_iEu5ZvVCHuK+4IPJ*k; z&EV4fd!(kIm|4wr6Y~|mu>bK>>SkgAH*(9szE6Z>U)?lcjw*1}#{L=`bE zgQu~SZ0OjAA4<(&=;b1|N!AgKA7;?dTOxE1cg{Adb;Lb$4^i~pjltf+C?vd>;Yp{G z{;M`P>&|pIbHW-VCRyNHy9h$wM58VDy&w^@1#f@WMCT!KvUi;tT$RuQ`8O3*cJUb^ z^iY!dx#9%rIpmM`Y8IeNJWB%%mB>?76}ntt2hMOX$0-fvMCNBCd09|Ud+<;izTPW9 zZfqMOW?I~=-&qiJmQTj`_hB?pDid~1=gzgbmi=d~$eb0(V~!OX(gO;M@It5@W-D%o zhYzf{nes*4w0kPqRC*fCq~_ujlVLVRMUG?+YhmjlW0*4`#N|ULq1`|qUB~T1Qt~8V zHd|Ahej=5nej3D~#)5kuNfG$E$z4s(hqap%rLOfxz zq$d25xlbJbt{~@K7Q@tMdJuP11h;A=G9i-^us~=N%)AkXE0i{&fzb$-Yj`i5e0y z!<}^ZMKdx!Qw)Qp2j~N1c|6h1V;#JQ=*wNsP{-wU5z8*gHdRhxDyw>F~YBEg0OUX9;$B1McbdI$nWVxHAh|W>84HO zXiE(V6EDNSK>?0c5JXhpCZYRzD^j(#hFsWv38}oO#r9Tvbieh9{Pg!g&zTYQzn~v% zmd_YbxaQ4n$v8*Clf7^r$2aLw;D_*nccepn8GcZRK*OpaEHzi9*Q|ueZ<{Kn;Gs22 zAJ9dMh;lRwc)?!!{fmk2TE}WP4AaX8cj7(i=^*n|5rO)Vkc*FMQ!cN?(iyKP-%18j zv`eVftZVe<)vcKR!U8HaGV!!?GI|Z?V3O)Pdf=4@ny;A;m%hFugPe25Y{n`Q7O)aM zJ7S2|~Pf^NGD21NthX5b=kYRlKB`aSxd%vpa~z z-7LItED6VsN|E_O@g!hM0XDRI;g4Ne)NP=OI&wQHlgGo9nPZH0h0Yewmjr^J|KIAd z?^9u0-W0knKoQHhnMvwHJs6cwWfI3eS!~-LgaxDVD0}4*x(plB?Se9x_Wd|X`@RWA z=T1X0OKz7a_?}rk2_U}rA?v3+K&J0_Pvst@V&_jQokSWt`2m@Vf5g#GmolZD)cwR3 zy5#vPQuK8-St*>1({KqMEZ6}Wv;_OB(`Zp+2<3mejefsq0z22J!iut)v^m-t^7MDmAO&4 z;5(PAZ`DNW;!IpKDg@fEe=;|j8nUo;4jj3(nhu`ah9aL&;7DExk+`5tr?+3HcMZL% zlC%lkuulY6oX)4OqmnU2bSfHn6k|CT5({vWgA*KMveNn{cDJ6#XSb};XLl)%@2w;6 zOrBDa_hs~z^kq^!F$0^@Jn0>UPS&_injX*=Cz8*D=s_Jh5yXzcj+;b4k4hLhp!UwvByNh^wysPb*nT=P3)w%v{F$w*X4fqw#^-gt2f~e;J)^&R^H!ola-%bA}~BRV1lr4=&ioF=e99;4y7~=twzF z!hkQ{ml9+z=>^?!Nv=b9X7son_N@6UvqK~=hYRXy?DT|hL&LM+b) zZ6?%SkC>Lur>~5Ju*PeFg-)PQoyrCNy5Q^o@Ra0cki3=wKH^y*J{k)mB`Ivri%Rfb zvW={|?t=5#9@MXz3M&s+Gqqb;y0vQwX6}wak*#~_w;8!;P%exm$xGnS{lgg0Er^jS z1mBJ&;>d1sx=bV-neJJ5_a!Czk=tvQ%V?p6@qQ3?Gz6WqK18HMfVvufZ^>T>c#AZw&^g#8k+;P)sszeW#AI2idIeyU^y~S&U6tO2*u|`H)Q? z;T^OgQ|?T{TO(m;GB!qg_AArman3oDaf#J^#4B-5qdMH_T|#djio`eT#Zcg09vwXPln&e5pwsP#wd?B@>B@aGpgN-x zPPjX=J1e-olm;L9^{)<@Ggt8P50*ZP+k+)437Gm_3Qwl)!Zlh1GJ z$*xH^aIJA8eY^4u7WKuWL*q(%+=!2KC!7bv4@ESt?=2JPItwx__Cw^uQ+Pb>A(r~x z#%I2!OwZTA+UIRopk#6b{B?VTpT-_=cY!I`ZnYj*lXtMMHHZG4FU;-hRJhqeJ(M0k z#_D<~gWM5A)@S}2a(He$v&_{75;P-$|BNL3+_N1LWHhmC$wmywH1Zu{xqI&d1rz{-^w59C_b>M4Y9Mq-UyUL&U2lnIqX%4T_X#b-(HiSrFUyOWooI~c57%TRf1Xd-Xu@)3VEleM%K9Hpu5vj z8lcMU)($6=TbHuQA=zuxfy<{$YbtPDk_^22mt)X)K4pT8gNcR8Oy;3M8TFbq#BBX+ z0g4tCFm);)_LhgxH@PBkAkrWI2J9fS-AP)aq{$=qv5QC42bb&B+#8;X8%rSMUqOdDTRqWt#BW?PJz@dORG#rAYZCL z&9Q+LY6wHx13^fc*8n%U+{Rp4C2GFAg2w+)hk@fusmatdR#ul|Tbg^)(WBbvetQ-? zNK>LQ-M{GWsMnF*!0#i2%ChdF&&m-OP6TRVqh~aX8(g7{p`#R%LeV%_+Tu1uV!FW|3|4zV z7EB(bvrbDuFfWx%EcS#yL=eLSZApaAXM(mFs2bP+rGM2(^BFg+c$`iSEIkHmC#gbR zX&C0*-a~(DbkRqb+Mr8Zf@dvp9)7OANj1CA0QgxmrB3Fs=*b0G(Pa%rs@X)TFcNlm zd?#xCF|1j+5HETg$E;i8!n`%9rWR7+jAPb4ST%Nmysg|y4;y?TF)LR<)27={b=if^ zW8-MSf;f`1VH9i^Jz#!(%%1+@u-gG){?R1*2E8j?vFpGs(%cMM@JN-top& zUN@=orZ3E~U@P47DW1IGd_QmAms69xXgIRi7&LGFV1sT+bH1BsSeSH>oR7awq_Bn& zTOkhR6ZTxc+8Z^`yd#&M9-*hI=RnpKQ@Zru2zhN(3~M)B!DDLK7*d*!ojdr@PUAV* z%(nukp7MvD-8|UB%_}#{yr4CD3rOLy9Q?&)RYt!pz_&lIP@}#KRA6^P$LAub$*N}) z=H$`{F5~Dt-we(x$TNW#<)I+|2KjT-7+YWsR*0&@xhJ~tHw(!p?jBV&%*Sy78Zj{O zB4pP#LDio!8h`r}EAAM|d5ewVrpk89mdQUz{ICT6N>k>wjmh#Zum1v5b3&j_ayNCG z``FKQBW}U) z>QEdppL~gym8wF^{5#Cg^=i=283IM8i(q=&XO1gW20Hw=i3rE7h$m(k{Wk+HNdnA! zH5oSki=+FW$zx@p3@%AeMQ@FAOg{4vyBF>tr>7r)YXQA<#;>JVkyM2Gi;s|+aVctJ zBu^9`pC$3PkFizPvgoq8o5B4=K0Vnr2|Wyhsbr2M?zw%GR;%#n(6i_8U!gS5DdiNL z+Mx`4zSpw-azprgtQJ;|c0#}R3ebI<360lZLa1XgNGoq(OP-#F`=aZMLDygAX_Th2NVMtr zMX!1pp^6j1ANGMLXOdZy^HCOBeb0eK{x34=y)yEa1=FmKIDDh;4b#O=u_-^>Yf}r9 zv0#=ieEFyV)A+x`-{mr}L1QmwoSYyofyz|&fENfZ;p6QbVc^&O>DZ;k;(OpaE0t5> z?!aT_(9~pdHdc`LPrC`io;-w{4X3F~t_k~k<#BrABgX+2yn;uT`cqlHYaBW?7fJ{3 zz&xcl^nYIKmGNmHthO92Q@Jd!(`>wEm#rZMIq-h~~rK4{w;MrGd~;WXMbKXTi15 z6t~j?&=}8!p}OO6T(F#tjCjD^+2vsD!yRIFs2Hx?62iuN-E@PvGV#jw!wx+){MJ!U zZT6c&UPKl=S#b`g@f{=npTnW;P%)LO(E*h(0gzlMfkzfkkn~hHTrx|EE?N7SF=)zo z1LIUR;5)^=4FQupoj8qfJBRno-@!;ke&V0Y;{HJ-W} zgOfMnM@w5Xm3K9VCE%CRu5e<~cSH3f;qxin|w1%0MJlX#irGKbF}z+jGH zW3!(h0u=Ai@B#%mPucG(Xx4;xa*yS0k2@9|l>J@XzpJ}Sv&NmA%fEn!TPas#X9m!ZCC4R~1` zMg4qHQ2$j64)rqNNGrjishyeIuZJnO8pzdG-PH2lWa!(*Ws%2&%@uq!$lb~X)WydV zg|97#_S?#+<`ZXmY42=QJ#mv(hze0P3m@{WNEGgWy8(qd3&_?gPZ~1%f|xJ84W~i` z;O*#alB?~3vosnp>dzM_6_zAlf9t_aRRP|C#a1+ClETo8_grS*tWGcBrM%mzTnOv!Co?Q_lO~XHOi$7ofCM863&l2ZdKMz~h)X zDlX3Bx`+uiSzQu{*0x~InMbKjzW!&dun0`H8LXA|oKH%%GFgvaU>Q7}8J5@c)QFalEypLzKPCd7*Zeba* z?zzl(i99cT!4Hs#Zi3;07cerIW?`+`K>x^9fpX3yT$>O_7{;9UWnmc%#K%EvL<1bL zT#de;3$WvJHPmknf!KU$Zry+Tj@_b zzuJB^Lzro{l*=-OQnxdH?AHA~@M+Z{IN+oP-99nUXsLiA^a&}JyGFe{)nP)vAHwF{ zfoTUHLi0gY_%IYrXByritV1}2_Ra&=zZ6tU;p=CnHUa)mM#|F)bcx*Op; z%{(eUy%;8MNCM3Tee96pITGOD4PU}yk#**SNDWDt#Xo~wJv|TH57$tEQdOLz@r>|- zrosE!7c3^n&m{*ZF5u!ZbzJ*L9zMPP03AB>h)3jAkODERsZGViK}{$wZX>T<&%iA& zOU8fhdeX4=znZv5ZLs1(9hAm&lW(0I1GMBW{HV>OA1Wn^y>rI^b13eaWB*z%_n9%SZF(%Mebec zp#n1ppjv7GHosX!gZQeUz$+bi8*13!F5O%=asdSA@Uu#ZH^8gG8D)Z3!sEH^aNYY7 z=tgIQ+~2D-G3`0Fb@r3h<=QaiR1Un0-NURLzD4?vKY^oNQgF1D2ir9M(vK2vVQgs_ z6b`s!j%6b_OB53`w>NC<=mfbUeUXG(U&4W|Oeo)QnOwANsXhKc9UApaEgfg>rti+C zl3Ve&$k_!vjvebx)vYd5(#KDtpZ`Y|ZPy?xqddvq;_KXA>=RqEZ5Je~?8T^Gz3A3^ z52H76?7>&h87p9kgNigrT;ESuZhuo7eo7YHz4&1M*m<(oyo#CnE&yj%yr#YeoRjG7 zFkLjRjw^)jFh>8bA~g;nZL?-Em4|I{t&p8%^C=0^@i+{%a_4aG!+p}?X%5|%`-sH; zHrA|vC&s)tAfG-JQpsG-_g1|M&+QMTKmS@YzYp8v^`F!56s*J4w~3bT2KM5fGyxQ> zR6)C3ZDixynN7d@Nqxy#e0781^N4FCE2@jAI|kv*ljX#(Lxk&AaCdJB26nG(p%F1T z)M}L}%m}r>&Q;lrPTe#Z*EoxZFC`K0l6>Z?kS9GEH5m(%bEvRzHO6y3h2**7+?j!M z$lrKtnctU&o2}1aR`)e#KbRA>d)oN9?=YVHvbpxstp--+%p@`?w27E_Plde2>&Sti z37RXLM$WHZ!{8fJToG;r%iEWelf?%xy5j=9?)j6tYyVgKVv_)BSp?H-UFLZ5+X3h_ zkb^pNZian2nHmp1qfQ*F_xl%VA{v!dGyTM4a(q~l>tjja*n=r}LUtpU)9IjdAL)=& z;|}6%3W3TjmXUd<%qNiLoo;d4`CwsOreSM#a-0>Rf z`1v%==eD?=oe^aIyGUx*X~dnYH!{+LHFVj3+sI7utDKit3D!<4#Pf^JVd#Vh3A~t# zA4h|U?N;tA7$3~#fwIZ*TpMEXGz>HIZjeJ3(fEiFwKRTkn{>X|N=~*&liAVIs5aJ2 zo!wPw<)=XWZ8shI#!KjlWj-8FU?YwgnBbHxE#&%eWUaxSzjWjCW-|Y_JjR~d$D~Qe z;}sWMRC;!nM?HXdg+r#(h=p>35;Od}(;F?X&cGAR8{y30e{@36 z6`kWs$O~QzeLXRc{@t!XBPC~H6u%a1S>=lr=l9`;7$ef|qe9xoI2Pb;PqZ&Oj=$vh zB^Db_7?qZ!A~TB{0QRV+bG(G!bqXkq3i1xBH=g_KR+z}#9NO(x%~ z$F}SwtXL&SvjR8byr&81dY1E)ubRR1uhE7dzx1j6l!eUA6&1|Eg#x($_zj|T@gC86 z$3w?|E7={rl5jF-1==}}(|d87@Ew;^ZIE>aYZG_uDXFF-vkf4{e>Hpf8q!LsQy}eI zPiz)j;D+lD=?3E<;&jOxZH#J3#hxJ0%{UEl?Q`f0&L`X8d6=$D;d*!7Ewrk~guM1T zi%pylcvFiRbod(J7U^Y_{S;06+IN|MnEoF-?_>~tDP&9Thd9vjDqXlBSI9m)_>+hn z+e|N6Zo^ZJtt933KG5}Gneo`$>;}zURB_fc)E!xYoy%lsLB9=A9!{p7@Qm0i-=wFX z@#8HU3E09td+y8EFwLtc$d@lCiR-)oaxcsS3T4t^<_R@el2Sp(I2LX2gFGs}bQV5x z`ap~>j)S7+DVVAG1zw0~g0|iwde1un`8IPLpVeGO8jnNPyw7kzeLcu}zJeveH^5zI z1H5)xhSoD1vFuSeEqpSU$IcYwyi9Sx|Dp`!`p?3bJ#We0vg>H+d>N0OF@mhi4?rb9 zlPr8=3Clh$Ck8_RhaY_-mM>?L;p}$ivcpAMSD4Oqq_nB;JQ!96rpG31np42 zMTKX5rXe*!bhkkw@O)pA?54F4>dd(Yif%&Ltf`>u-9p{A*Acf*3P{yPNRZ-QGTUVm zTcvQF>W6uW9BY&B5wC9X>TT% z0{_G9afaSA*5Y0`BC7~SI~!rlYZ9*``VrM>D8lLUEJ)0MaS9|ELH!SeU zXXd=)`HA4Yjk!ua8AKOlCNGTW}D2L;-ro)#+ZU=Od%f5XV zpnbw;z~W;U+_(8h7i?M$7xP_Ut?MIVFx!p_S?e$ksb`7&!59({x(>cPY-S$m$)Na= zBs_gnhjXLsB2m)y^khRm+bngS$eimXKB2N~^AZ7`nbbb`_Ea5?K^xuEVb64yR6~Zq zHQMfSmR4>(&AA~m$OWw(Q1C<_Ht4LP4q;O0=KGXQCzD`;>6v#SSAE*H~tV4eml^2i=t+W4j@0rWxba_mCGpU zvWv_wkek)Ruyh&^j{Y@cUNm*!&5fsV*@i{%yJ0so(vb%uyK|ZTb5BSN!`Ir)=%oo#qb)(%BiE$4awe(dh`ZFI|O9lZTkpE?Z-!u*zbba!1E zPTq-hk$5J(aG(r&zYLN?KZI*nP3(Ydr#iSD?f{>4=c4QLFT}_Z!Bh4)tXNS-rX*c} zHtqNHLyQT+pe){rJBAi-^&h9Aa`_3)rT5y0g`oSj#=D;hA}of}J7s8+ZOv ziF-uY3(6q5e1ybv%!eK6=Cnpx05?2zL7x+^i9+mA>J`jjWxXlLv}e*syQbsdUrliT zUPs^Qaty2W=c&PWEi9aTktXiAhWq{qz^Rxv5D}Jx`H#9S^Eh{d-kb{fp1BUUkG-v( zPWQlu>UdPB8HKL?0eE}*4Y|bQgBb1a)FV@Yu80hP<|YZMT;qqc3m5SwHJ3wG)fre! zgTbw+gv3t~f; ztZn);AA()nU{22f_cv&z>wcF|_OKP+oo`BAvBUCnq%{`YR0F9M)uhKw1njN|^7dLa z!MG?`6{tqcbsjdlHVi9S7@LxXRup{rXrL0Cx! zqr3SjV^=c^!CIR6%eigt?DdCTX14HDEg9}rj#Fu&SG0_TLu8U5k6bJw-_|<9oyB92 zp?V9pZ&SnVrgI@uL^LRzM+p@V+8#K5* z-7C9#5RZ6H7W3Ujd?t?ht1{VL92?CzVSwWXXhC}GHY(&FP4a%6gxmh15L#ElWS`nb zgH6k!^yO?Q>CUnk?c*3~66;Vd?FiQVxQIDVZqvA+it3Y97tna_XUjD%lv;4#=LQ)Z zOJMC}sOXg?wtkvu_WS~!BRv_@UGLFOdjkZr4IX@Z0!wT)sQ894#->#tS4bSAu^#=f zyYnGD=0gZg3x?>yM5bKs3My@U&anq)bN@%85YkZsUcFu5@n8r@buMH&l)wZ1cpOooS=(12pu znU%j? zycW6v>NAJPxTGq2W|`yb>*rzkT@iirmJfx+{A#Q=%>z@jqpVy`6ewRA1((e`VDqb5 z_P@Gx@?h#FqW3%z_WvD(sJ;|xI6O+C{6u+*A0EOZrIV`=G%nH&zG-~1DS^!_KHo%j;u9g$m1ZlZ% z1TOmajU3h)to`$0HFirU(<>j;!03<~ElXaDULP-@>_#=-#2pHaCsQHH!-HNP-b)P9 zkApKaXwl%VPqQ|r(+b66^6H8zPM+xsfnFbppj`r)C$)rK6d_A>4nARXei)H(*Ms=s z^E(>hCC2q61hLFW9@GQ`@H96YEjUYH%k>FzIy9ZUjZ)_Q;`o6}jJM+Ngf5!4N1mLj zxsAS&OXwQmHE7s$4i{yt#=v}jXyjW0`#v5gRv*{l!I<93sHQ@yvqAMlA;bz^VRIN&+_+th#Och3#^DUGcx%RZ>Ybowj$-ggvz-i0 zzfCN;+_v|lqx44rx5u3(17~xlKwt+yx@6uWmqZO=<(51~)z%NsSCj+)h5gV`ql@1K zIHy+sCDlQmjMRo@VTCjzwaieyG0>t`Yxzyk%X?#F(id;BFdL1!!bpB zxMd{->(kSS!5;})ps9k->raDYr7&;ZZ&6q^z8NKM3V^6+DET>80>UQ`Lc`y4Fll`k zog1RZv%5K+w~}KoY|g(xUQ}>=htyd7FD(((&Nb6O0abXgA_`0&KeJTbcMvDMX2bb= zk#M)`9_Sx*Ci7ONp#2wJcwQ;N6X7^K61mb$UC=zty^{{}0!xVW)*@E=jx~MRZOapE z_yxU>7UNcZS6Vy~&gE*t$()xp0JFD|$*z(3s^kXrGv-{_VjFC;sl@L14Dbw4hIf)t zV4d9!(H(E;Qn3$YhG8UxYE@7#dwxv0YlBNneK4g~6k;ciL+sn-5U-hvVV~cSrFH9J zae6JK#n0%eWF7SHiy-6Hhj9CmapD_VN3-_Y!4VCvFW9;V9rV_rN%MCm<3kgOTIa)p z_kv)Y7mE6QK2Vj%xsIO4K{}LzW3(w4%U!^pQ~VfoDw^CFX(9PHWbtq48?r7{0~x&n zdOY5P%iO83#|!w;t6PQ^&8@_(D<9J8KQj0}IG0X4+{cJ$S;1AMGo-6q3V!j|5D5_t zu0MB-K5q1-ISN;>Qmck`D$B47=4_w_`Z8ct_=!}$Dr2qPWx-@6Kw8j4%YaE7-`M3i zuHZhepXyT}=}<3O9b}445+8}&&UnW0f+)1Nm%#gWY3Ta+g+?aVfRYWzB~iJJx17Gv zt-Gee_2U$t75;!LH!eY!jx_|k#ln`S(X_B55B1HrF#2Z}L&hyZ-m9E{P`$1UoT?ky z&O}jOrSE1?Dc*n%FE--KrFMAo9OuZB7X~jSv7}9nJsjf@l;uQx=nLl7}_Y2Z8 zrc>$0r4-bLxSW+M>k&In{aVY2?aKxDYNN!J54zr`|Y!;{I##kpKw!i3a)HNuHjNzB_4MxUPjP5N{`!rbrJ<`eA8`3JP`Fqx`WLqA4_!?67MfOS@jd=?!u` zO<`f$QrgPRiFQ+Rb}I?C{>&VE=TFPj9+4_>FZ#JQ38GeUIflV;vM?(g>~lkzH+`!u zrh6CC8^!*lgx1lwX6e|oypO&dmM5;$gy@Zig*emg6Ac|bMH8f(=vX7iqIN2Q_G@=Y zO3@vXRv$|w51V7~d%c>^i#_pq*KYXUmGO{N^+LgrUh3PP57*mmvHtl{XgDFw zo4lQZalH`g9lZ#mt2)5JyNf98O^5qa)OoRDe7xy%@<1UV7CP#?KvoLi!g~rbBGc-= z=>NnDsW39_^fDM%-3!sHknCITLf!QEdE@^VMd#s9_4mhdGeR;WE0mIzq`~LBFNKUW zHAzZF-!v#~4YJG3h$ynlERp*;Zz)?*ks@hPNn6^+@ALZ)?&IG3IiGXR`}KN0hr>z7 zl@It@VlB2_oQ$LV3h+5m013OU(uD37`1`R2W?g+oG6q68p1&RBy)cGV)>0fpcYr2k zYcR_>#x}2M2^?JXn6yu*#E12dsrD>gxFahGzGpAOm3!A=>}M#lqYsFXsVVqYH&KO2 zDyTSA2om+5nMpFEbcNO+!21xYyh{><@9PpPMO8r2#d0wZC0 zcGvkAlsJWAWtlhb@oOfJ!c5_`ju<_*-3)GVUIKQR9Ph~qXS&*A8=O6Q4@50r5hWuX zVm-l{#HyySO{LW&^F{e0aDagvX+QWXeX7`*$~hk&$(uoqsfL&W)c+o@Bb>beQylFoF*+Fs05ObmKL2dB6xtTO?C$Rin1J1JAR$* zxVnmSE=;r`D@0A`Kw>0V-*W`so@G3X?OmX(r$*LY1lW=Hiul$!fnJ^n9zEj-UiXp8 zINCt;QZ7#sx&~*+`r?C#J}Mabkwp0F!tEVekP%fz3NJn3{=YN8CQb-cPn+^0n;pST zb}p@W^bK7eB`~wpzVWvdSb+V+a5CkQ8K~F}kOwuz)TDd?oSJJ*&dUOklpmtJQ_b|T zlP3n>TMXX1UF65pYFg?$!ZvcAm!H9Tr0-!cTPGpFTVFB@f2qr2`MXsZZ?v5xOb@|8 z!*PZuBo98|kgesctqPKYEmO5&DE2jJ2Q50V^AJxScqrs9IP@jGaM$d9<{V@}E?yZT;>h%^_Dw=}M z3DePaZCh1R+YmDv8wr{>Y{13i6jq$z^A{JYK)l3aSY8wj-$Tu?v*RVa*dM}Y_y?f0 zp%LEe)WXv-UHW|89yH99**M;@Co3xteX*wOcqFdH_4)(#Qa{N9f(nfir*aXA_EQ^V_=?`OVo18Eo)#{MK1 zQdxJ7NbLzCaj6?&LtYA88`tEy+a$r3;3J^%Zk%{n94D1la@A_r=AnmxBOKYBi%rM0 zcrk_HL|O6|IkZy&i;kAlpl}VI)y_HaxXcIEbNd<_2YHwqrwL}ijrrpbg?SZaXTX2@ zZBo9e5X<=8^j&TalM~tmDQy#R`gj$c*qVbOc7yyqXSXl`i;m-Z&fB+QivYP?ZVEk_ zlYsX$1uict0uNCM-g(1us`GR@?hydHVg10}Zd5he59b z=)1F3jGE$Al3FQjc`+)xlSsHIA^krc~kfvLe->~j1|*c1)&`$7n=El4Cw zB1Gs#-hQ?^DIfH=_|Vm^K2TI3S^fRdFBGwsgOcE6+;znj%@oy0vST<^dVi2zle3)O z>&>GHRtNC2i#3!V7GmSdzLPygkz9AQf$cnc3$<@(LBp3EI(7L+6z80+7Yrw&W@;)4 zys{Wtqy8}Ug!9R-t0q}xVkjkSfde_BFi}w!?U!7j-s18w$Lb!<&b&v||80im{(dwN zd4rei1>v}E32H}NW)D5%vK4c3aSO)^z1o)tYH@ebuJaA1-4%g1!Q1irT?t%M5)Nk` zq>{J3+v(P;wwPn@#unbGK>GlW3DsbW@;n8QcsZS9=eS^V&1*Vv)eg00)KNJXbqE!o zLe{SCB`IqxS>Lr9NUIZRde>!Eqiq}cv~P^GL|TK-)zhS^Pmt8uCeW8BljtW;c~BlO zXM;z0_-kevI$Mm=^<$#^bGqHsah4tZG}J_#jAYUKToFDsdrAv8dvo2Hw>QOZ8$dwt z5~wZKfqy#Np~|q0o^IEnqMh%_67q%03Z!D(D>-7d^Ez%(&7)=#lTo1iEKYU5N(F9y zrRy(0!hbuOQ9~?-?u!n?Be$iC3&i~0C+ z2HbjLj$1$IQJ)AadZL=k%jnqSz8)V)sS5-(z(|9V`<_}&95cV`JhRD0O$d<-VTqfcH_eRXo zwbmXbWAt#t(zO^eqmPabXJJ|CK1{qTi4F#dRB)~j8g6(_yEfh;yceAqJF$b_3H(lO zOv=V*$9Bej zNuh0$J?Phe7cJj()9%%FXz8$ki1aIerIY2BzTF&S~H; zqDlAUXObVrYiPaGN7^F$nPbWaGpkg}XkdQ}Eq=0}{m;jq%$HjM9;VK4a$qvE|4tmM zSfGnHx&FU!j1_j7G59Q!^L)flgg55P;l7nTH4AX2-Pb1Im$-ZM(d$Qap4bmkJy?bY z;u$#HVNN#Y%^;t=1E|)LW5^c2pwp&YL(Nt>;xK&y^X6_EmT0bpBPtJ}cB~lkZs|h9 z*eh!6zX>-_5UKWFFcp~PJK*hHd2;G!A8j%E0WWeneu{Mj+AQ8fUH%zh-_d3`-FXdq zjvIq>jydhw9SisOHZT)77JqbX0Mw5FZkauuXOv>W%exr~f-$pUL(2y6Pfmpf0mPts zKlJ7$VfphaSgrLJG^<^(<0lL5Y7X!?l)#7RKy;qNgI=c?6wc-xZEuQU^MnK@W_lT6 zX#*VAY)7v!il;eGYvE@>+^v8xGi4jN9pt+0E~Y%4s}H#>hanR?Ybn)Qr4C)bVmNy? z4oH5TWmcE~yh=FqQxcgBYb{)>8 zpB-hf(prx+Tv4R2jy__YhHnz`RuR$~E<(FV5XcX@KSTY5M&M2pD|YHc&h?h#1v740Q}-RW$eED{+I;yv371yjjT~*H$NFTd zS1g~)u8-e>uI?&4C8KN5c*+ePU$upIZm%G0N-Ru`xkgi;J|X36)G(B-fbCx>sEX_( z6SPz@Gw>n?$g09Zt2%PaIFR!uBr)y>qfwhD9_=dY{%IEg#lVlH|%>K`;p?5iDH}gRG%mmV#`H4}E(nWqm z5&o;vqYIRhnO(jK*r(l0KMmXC*~ej|cM;(9>boSe_Yt#5;UBBM#}jAv96=vZj#Hs+ zK+~-fX++mN$Z%3)+&+%LnTKbIcI_9O-M@fZ*#kCNiSQJgzd}t!4JrJf!7;MbiPmIp z<}xb;_g_w@{@?83KDWP~|9h7j3)5N#yhGn5i2= zqAWYf^r$v$Cg0uKw+fmjzk-kKoYbSRM$;R&mT-)Mmn`{sJ`VgJoyJQuvY|G-lu9?(z zTMJD-&oN8xn6g^Iq1d)e9FOdbKt-ntD&qElsSe1+ug5Ns2GObLp0$D+SKgsJRZm@8250$1PI4hFDn);uzeQYPLYu{%&$+JvZ0heH9!Z zE`^TfH=HlQk+*wJEBIdbV`j>mLQ8TaoN{R+!__lkZpwe~_^U84&sdMA)6xPB{^_8* zFdfDVcEaSjOW@W=NAjzCB`oqwg$3?yoNFx$G>X$nmcU}*J}Q^jxd9GAwp6ao3)0*X z95ti@Jj~>B`U%H`VRm&8>bWF>52WJ< zGjGoQX8`9o7Kwo3a^8c991AUcC)D35hlevqVX>Y%vp<%_Wle#ozs~}13Y+5B23Kb2 zc{W59Oo0%=L8|w#9*vGqAcb(A+{~DOM^bXh674nks^c2%?~|rKeBLo$DaD}KI2i;l zhk?ZL>EQd@2{JV;pnI+_J31HW-OZ~Zu}r3V`mzUz>r>JHyDa#Z>VQ!!H{bf#Me4Gx z;dzKY%=j~vDg5vc!h`0~YZ)6*^?(FOTg~BVbncW=aF4kiv;_RM z*VE0S3N-O*F8ndx4oBMgq$gnp&m+{BcS!CA_N;6H@#r?rS$&s=h4+yU!8Y*r$O+u< z97FeNX~C)At-y~uP3GR-jSsVAQ0m<`GCN$y{LYidOieJKZYnp%{HEjde(w$H{vm>9 zb=R{KE$2g7j{YKTi^E{=V{M-2 zoe!KR>@JCzX$!ss4!4s4qClLYVH0P?=-_{ArUc+Hr^OK^P!^RI3sqo)tUK*SS_ z+T?@|`etZr76w!NCxUN-I}SE%#nqQhN#3ie&?=G#iN!6Wx@NiERVnN zIDFZ&jee=l0o9^p{JavGcqwP3)8b)YusAQAL8v&M!K98Pg2B=c@L#7dUg2{-+4cP% z)fC^&b$r#Sw#X^YTM)^(EmflS>8|LHhsnAlcd7qPG15G51?2x;4h>VewQoobT@;P5 zGGaMw=k9Udbj~HKKXF`Q=@e*tdw}R{oPd?%GvUW`hI-t|#M<1I@KOH{>Cftdl~x|4 z{Lw6?*X=A?Rt!*y)3G>JXexfN=h6C(5V|h(Ha(WAfZu;!Bp~I-TA%PBYUdgW7q+C* z9}eN=N`0g~Ks2iac*UBR=`4i=SonCD{jy>Sm>a4AYf?`fwYQoZd7R_i1&-vEpE&;c zm%&(!n{ip;SmA;w$3SYyugx z>_9U60Az7&r<9Yw$ir2cBw&*o&Riyk`#gWqh1r{+^)k0s-sPM=)zXl-MH*9^t`Z+v zMVg&(5k)#vX^D9>bs1|X_x;MukGe&0S^AUEzttZ$q-cT1-9l8o5dgjyc7Ww=W7_wr z0ANU;^>18_z9|fjrG?PHr`j5(mpC#-_4E>@X2b=4vF>~CH2%s`Hk{O(j@CD?UG{fz7Me?W9 zm)scoNLTr2v$Ad}Ae%6W{E@bY?-qYxMwEMLd1As)cnyc)$0)v?x*1Vl&M zKtyK}&&gPbH-r7o?o3#RZo8h4_zhQZ^^aouNo^$?yjhfYAn+1d>FEe3;~&tOBa-;q zzzD-;-)0|Pd_o5wZXy*2<-yB8o#yO{A~#Yhp!7u$h#t|UbI%7Nvz+UcoR`7{OOL?I z#tQg#b|xgI+JM5CAh~f@9m~Gn=R7A%h}+fY*fP}1cqelG8T6t1#udQ9;SQbm<1}hN z;kY-0Vvr{(gOY&~uF2K}!8KLXzBdt5mTGeANH$c>mVxI{wvc}6Gt58m5{CpYW0CkA@K%yU zO{FNJ9MTMv55_`9b_D1)0*P3%85B4CVlHhW1S+4(qLd$0OPhvUM zp0gckdJEjK`i!x!n~-fTW{fy~c>j1X==T2ut4aY_A1J^xdY253&gfC`!EH2BN(2A> zjD$$*GA<{48AK&Cv2*VZ3{f&8N(=Vkj<7Oxlpdn{j84G9Q|Dk=+(8odZ8dnk`NjNj zD+IFtEzxQbLE(X~v@y{YU)t{>t;Lq~%l2MIi}N{{bjPqRVlm|4;~D&MF3)o6o*JGh zoC`h^XF+%3rK);|@31!J2ITaKq21Le{GFpj^7iM$^Xsc<4;}koAkQ*ZnYE;37Vd zT?TvXd#IOn1idb)!EjMk6xTluauv&==!Y(d=FDWvELCXCx&k7nmCl}9E{rLiHROBr z3iKW#VBxhE3TE7b>bG5FdDw3F#rd_K&5uO8Cw3)wo^v)WqT03Bba{G*E&&+Z>$#G_~o1N%({Z{4@Ka!qVHGRZ;=}h^^{Oc;w7#5dH9zCC>nDoX=#-!2ETWf_4rkumh3 zX&jytaltx=F`6Z(27gxkr3bB=$n$Y?Y`8c?#wN^XGRFdOKbHxb=n_K4>y+_)n?$vl zRvNI~N5QcyjBRic!meRaoMpcohts6-R?$atv{RTqeiVgF*h!RLei$qI^uTcZ0$4?H zop0p>P;PhV%pHLKo+gy{qfYVWcugNFu4)Qy(>Rfp|kS}s1Wyn zpXGnqeai84!gv_gi5ua&w}xQxObZ1z&ZL)kuAB$i3TKa>VJ|J+23D$;bUD}g9MR7v ztYQc57MH1BQ`QTwx#xfTC1sSFTuRI`HpA42Oi-F|2HLjP6HUefg%y7h!@N&$?rkJH zLqwl^b%?`k@djLIT}m>1CS%C#BQ$KHB(xeSF$?n3n6i69AbE2tlUJ01%E|*E^!_%H z;<7K!`Oj!?$sx1}`NkH1si4DcFUV(6AH1rQ2G>rfVXj#tE{gmEx`AV?g=#kakrRrJ z4q7x*lAEK%8Nr}|0Pm4|8Y8?;n_FWzk7ITXbMn$woHR9$W;&FU;dW;{cI^W-iTg%{ zMx9_Ym(ljhxNiRZgFGy*p9HCKgH$zb8yVa~&8Ky0S5HtzPKF!5C& z)My5ipZ=!$j(lQtH-n~sawd+`kAmK6Q&@1`1Dn_6%{IftXjnLC*F{%7Bg zzNVo>s7`?)_UOXF&|FttGOxmDTSR9_W(Q3W^;3Mj=ikkLTuMYps?L8 zQhM(PN&YU6;lEyyJ)R6-NzsMYiQmG;wrb8-who&&{iCz;oM679F>^MdfKG3nR9zGM z0hi9XZT{#^w3%r70=j4Mu(`2REj{-wh(w3f(le%2^vVrH_m#8IdE_-ax~Bq<{9DR7 zh7{m&X)W_4T%YZ%jR$f&5q@O-M{|vl+8Is3nX|L$ql$W(f8L)ETQQv4D^wk7or6~w zCDOE}66$-N<058>gNu4H%n*EiQ!cIp9v)W1tv^)osryH=M_!HCjtbF*=6lg0a|aXX znMDjE-PqV!KbQq?+nJx^wIn-C0lt^?kgchL>A;%arsJJNvvO*})krlpZ5 z59Cm-FOrP(OoS`Om-v^%MOcxr^_W#YfSVSEvi>i1z^1B%YA3R&8@>$2C-&03S7*S0 z%Ma!)(HNy;D$}%TZw;!{sNj$3oHpbxYlJ(u9zIPyjQIOsl~03SJ?k;W_)FyZE}a$E;* z$uReBu)GM`d<$5UpiQ?X4nt!|KByS!(}dJDWF+e_$?nT1oBw8TUXC@Oc(0y(u8V_L z+|2#5O$I4ej|b()`#@#b65RBQp#JVX>SH9&@s<)GiR+it2^OR8*evchwS&bo7T}~0 zSGb%U5(|%YI8|i?mTSESHODAYb3_z4t`_X@%7U{O&qB>LS@OtJo{Cn~K=;y8Fj}a@ z_>5hIhh>)ZU56g?dEaWt+aC+n<5$SihSM-MYz2u6reJ;aDx8@7ff#p*V>;oOHZS&4 zsjOC7-(tke5RoFc4dtQvNG*u;E+aiZ4}i-J1(46W3RliV66<=~UlftZ`8>B_|Ae);ZhhNGTVS>pyx?&)i3PhX2aoYmu{W=-i z{yc?wKRKSG{4)5@@Fa{C`q6xj$7`EqME08eBzvvqQ@6MRd}TcwEX(eb&f3)^;&l%R zcIhN_g#++y;|i*J-x?m>T)^{s_5#9=Z9tXZituAnAY@gT6T|+)ur*(nQFVPm;+j=> zre#_1is@i#h0cTQ{e$rRRVxWN(@YM;@mZOZCb%lAmXZNWa7ehv?z%GJDLlj&qihcY?j+X4sJ)%40ySNK%iNh<6IK)x&-zi^B?jb{S9 zpr3t={;me{+Mfr!xIg3%yOxe;sA(vN_0W+KOc}iAxv6lBvECK2e2)2DwQZX4JN09At)w^Rys@qb(I?sQt=Q^ z3rvJTjtOPB!v|en#6f@hKh}2n2)Qy3)zH8a&;Aa-wE<4xa_KL*H9t$TL}wqux0ra~;P_k1Qd_ zAD)65ZXaI1^cq#zza8fMo(b2!c#(MI1KXiVCbnN7tKU9=fqgP?VmuL3o$WzCOdacr z;;HKjF*s7&1jf5{ux#U0+`iuk6w~*Tiw<5iZ>J7fXlz11?DWI+WksN(YKlS|Cg2+J zX3A(*VwR0H*=V>FwjH>DUd1NNzpl-=a#tXIuJRvj3Hb)DP3oXl@5!F_7@`w3Q<=}M z68My(aaM>wB8t9ixbC+IP8x}4MFfA6d4@+=TfeP%>6-<*CrPvKeQH53;~2(Eveeq` z29=t*3ty|`6QMI0;wT6=mrtlGU8{5y*9n4cbgTDl!3c0YxpH|s!U zQ!$=yKTSI>x6su|cj4!TAbQw)ChDJl0=G@W!B0CCtTrd%3z=5j$Jj4gU^GTtwXMk! z){;sQONiXl4k!9JCb_LNX#e9_Mme?g{>LxGUuG(_{VhQS(`w-7MM3L-&tUTVS`_{( zjfLDERWE;tFry_TXz6L(YCVysJ$ok=;FtjITQ8dL+2%$RR)*81DM65EVoFb`uEpPS zndIQe4(Rg@g|2!rc=&8GK72VuOZ?Kvol7gw%l;S|m@D&SHr2z~ECtGi0CB^fC&bO| z3jMYG6B~PTfXG(-2f;!1ICoVx5jr|XPOeX;cbodLm!8I&d-|kLdL$V)Uh56T}A%GLHvKK~Hff_~nbh&8lDwJO2!<(+|PC zs%ONgqZ2g>#!>LkI;`T5mVu#uXm5we_cnyO%InNJAxZcwn$G;Ky^T|<8>rRJ>A3h; z0wZdZ0!}&!xH!dx^qHlS&5t$Uy<8YSn(@TbDO|2+#bcDXa1DjqDOf-0hHKA~>6XIj z*g7u{%~Gq$@lgg$kL`n)vulagUk~8FHsysiB*J~QP<*n|A5ZT2Oy+EV&M2Ebq8lq7 z6Wt_9tg$bm#|ysk4?LKI*C$A!mYNya?QtHmF0F&i{&c!t>?+$_RL?Zr-wSsa8sUP& zgn0N`pn2{O^OWi~{8%kr?HHZLWwutpZYfbnw$3E(RyV1j#sS>jcn8w+MS1z>>S3;* zEOR;JB1AYxz+}Ns)N=a)2-%UqmRzl*TFx$9rk&7-i_F2JDIKQ0O~isN*%CVjls^%Rj}fy9rEX%M~8>mn0o9dZE{1h zK3EE7i=D=zKi=e{RRzQ?-VH(auju*NTj@ssB=fQSF!*ycA5s@K^Ct>*(&a08q)Pi8 z^(~x&-%>a?w5SVxel!pKZyJ-x9zTe0-vHklRe62w7ol$bDZ02M1Dl5i7>C1ou*l^q zGw)X^{M>t;^Q0@`HMc?my01um7z~sm< z^M6pwv13qlyC44BI~i(^h0(iPri1dKy|^wnm#9C#&qOWZ zxLj)vKyASa(CeE4E}^ZAM|up6coYu3Njy3o<6&K>C0y##L@k9jbJnbwFYD4s4u28F zpHfSSkHj?yjW2*U`zlx%9!(Ej%R%Q{n`*}@4Kh){7zx*>yD+r{o;iIW2PdbKZLz&X zM`1pWJD67o+dn359h*3(L9f~21=~SgN{l`0_t<>?sZ1FDa26}?$ySHW(LoRSVp8xY z5Bnqw;LKPkmA2ahng3NoTlHU#7rvnSl7tL-W)@212G^ptohDCtS{Tf{z_Di29U!2g zh6LLE#?;CjlCf$K8NI_OkzNnIFW!)7Za?y=rUK%nrjx7`jq1G-(~-~Td}U73?1LT! zlKU(Iu1)wr29-s5%H0igKtZ*-!ec*C&p(A1y@Jtd|38wp=@vb(QW*>@qL`wG#Uvs-lj7TF?790Z;C@mZ z%GpVw@g^*dn*a*j_Zr=@ z8*F{{QH|&pa_CSyIdh70)+qe}O$!esiW1eHb8Vscff!1<{KaL?(!3fU8+dkYG33m< z2=fXhd9wqnutRu|ypul#N($$}J%`(CkJxZdhH#iA&Ie0%ImooTNtw7DI5a&5JU8Xg zs5vo^d2^J${Ii#y@2myq>5-%=MGakJg)rCpG(G*#7(eGlgVU2L5G{WNOLm5n-!EG* zS3S8#n_32fBfOlGC+#toffJc-pW$;jKu;LxnalYgSfCN{>RSny-I z>4qRqzPlMeao@k^cTt%0;}6HzEQjB5XQ3_f9?RPsK$YhNa~z%|RwiN}`F5D$Es*~U z^Fy~_(7$3F4_uGR$6eXQCO$C8xpXRp#L1miJ@m7^S@mxfCEl!qXQ8#&o&B~nkTM)+ zQoS*l=x8ZmP;m&ke&ss*@2vqY50?N!&ceH-H}pU5&cE;{%j~GHA&ysa;a0!~@O-iq zZ*{wYMzSICdB~zj*&Fiux<9xaQH7KIr&QixA7kFG0=6%+XmVgVvAUmtKi9<3)7sB5 zP3r`gFJ)!CQo;7?yR z*c))JoZA!7Z-pB+XJlZ#%VeJO&>Q%2a1#`ab{bwMl4mdx%Eo#l!l&_sQ|lZ+LRm8;EP+@>q3| z@XCKRo^t7+&lA+q&TVktOcD0hY=pnPlDux; zF<9Fjjni~k(z-egw3o=jV?l2WueD;1wjHF`%w7@G?_V(9U~%=ri{oJOirf1}AIJL4 ze7daj8{@`hz6L#?lfe9wTpvmsQbs&T=-_)Qd;KiLc-f)4AyTDL&aI)@OPMMS&>B@E z#g;osW!_8_jZsCt%Smj_i+uV?;xm0`J%zV+N-wEbIf=zNnjjtd5du1l$e)rSHpF5J zn$+B-3ua!Y6?>zx;&UVYTGoL2A)jce!e*ScQVC5px=F)^d*q?UdC1?X4VL=%v9|XQ z$4K&m;oxRaZUtrcW=2 z`0LYYrtLml+A>a8%!^|)3?9MTTPJucCP{%0xI$94-64nU zt;lO>J)Ghu4g2n_q7mO!!E4THFe{DW2Z}6#9-kD_dZP!F9t-kn&h94LIz7P5&KaI= zazJ+86ZW*@GIZIymwVT=keja)@LOYCwY5}oHwXjR;Q*l!($$MUDJytK_Ue2FR+YstV}Qzv}6 zJ{cRTg7DL%`5?Q#8@$e2aUCC>>f1AF;mWs2s0n^X0xClB)s-Zy+p>Ti>9d0M>Zv&8 z#~98LaN^xx^%c%FrJ=suCcOS)kmP+?3+KB!hmmCz-$pwkzw z;1zaT!695GnGRm*g1i~rFkesl0F*i8!1`5p>6VaG8s}C)wY+sfB)pVp?hxP=s88pu z>)%Pu)BEYG%tzF?mz!OcZ9vynYplP|-BaIQ2!iXLlT5D9H}dzGdBNlrF!JsvEl6!8 zt`Sk-YoS2@t@}a$oaPgkB_pILxCg)T)}j5lD@K{iKz#3deCM|gLh^o*wLhZh`gPW@ z)6@#iZG2DH(N|>e3K{NBA(RB@JYx$wz3|N+K|Gh!Mcc+VArWIbt;Wlj^`YRE7G^H;g1I$A)N0F4 zycZx}oxie>oX~M+%GZQ(p0QjkFcSdBT{SSo^-At0dosHWYOv(}9wO7biA~~i*^B=3 zK#4XUQ8n!#cQ|h!Z`TF7`d}8`ZjUA2tv0A!5sd>;w#3Hf0eLr}j?PxGpa&ae8Tpz3 z%-bbI;<@wMmOF-Y!Ru*o`>`RO9UUfz|Ih5wHi3Y0%DMDj&_`2@V29mH`sT3!-SFcc zY0_N;bp_%y{IV4ztQJE~CF`@lWeQ2rN_(uSaDudNiEwy&F_kmXBq3Ks87L{o9Ooer zl()huO=Wnewt(CXNA^+qTF`RZ$?YNTp!D__{83s<%09L*%@$^CQ%^4u`8Jg(_lrP- zWCP3Jr-?)48VVh>L~r+Q`f7q;_5S%+i9~r4cID(UwbLYEc$`mfzY4*c!}?(BF+l2A z9%QXK%uFs;1!G4=-oGI`Xq7XEC|QZ>UK7rX*OiR664R?iiyd+GWO*Dv)pl0d%II4c%tY^X{ICoT%yv=ri?)`7b$DCp+YpIFrR7}zB9k-{LHXkRQ_rje# z5x64qg7sVL1bgE*GyVawn4dcto-c@HOTM>|IH7G^FgBPutzW=aDW)C_0!Y{0_>Kgr)mi%87MWE?#f zh=+R)!z9NteE(@PzO5?e|GKY1wRF!@t=`vk*YjqwabYtwY&5|zH!-@liE~XKssNjY zdbrvBm85T%h9tcxw(RB}II**V46bgYZbLh{XKgnL$~;1!v}wRv$4xXkG6tnrTA@i; z6xrT*7v--OFvZYFjGrmd-i-^fu;3e{R98dhxIFwi-~w&mhS4G5DSe+O3#m^1WUJFu zMrGOzI_=F~)+@pW_!FJ^N@tGY+nIx8I9wU;ADBx#2TfpuM=(TmC}1?pVt%YA{IhAG zi+@Z;LAhnHtJVdWv+?wVs~J&DngA=~!Z1ktGRu1u%Q(D=XSf3?DV_X=9GT+I4!bF% zU1Unt^;4~k)bm*|&%}$BemzPnKiZI*u76eg-IZ7a(Y>%behVCnn~1pC7dXQyPa*sO z6KJ*^{)$+G#~M8S@hHE{`&A_+A{d@bP5X1RK)3FAw+A1Eyv6XB^Q&$aSk0} zMt|Fb?@tCL&-^CQGG1VkXo*3$bn$Is3f#%pK}pdkbY{zJ@H>1NoYNFBXU;u3)Nvf> zg#y9^1mn}^^7vSAK0Wfm9g7c%qZK#Xcp1D17jmxg(pfJ^40rEsReq9G#{XhszH8tN z{bz9U;v0ChCLOGWhslgseL8F51%6ijZD>)jgnvWcpgDCun5%4uul@$GLt6*CXB2{< zt{&A^X(nx2Pod|9F7XZd3ieW8$VG_~Fiy^=HmVsA5vD;?Zdrk;wjNBJdJHaFHbU%y zsnGNCB@EUI;hpfOOsdj0_$$Rw&qJe3xd4~>Fsp$b6%xGXt@VtPSOfK2=?S)mlqR+h z5taERpx&K*5*NKXw&JoJ%vj;qmGIhJr{G@D4KnW5Il+l=eT82ztu2dpsYAPu{n@uoGG z3+tEyBDtT*%ZCF*^ynlAf4m9}no^OKJB0!A$jt^bIL0$~C(t6ot9twz5-#O~7HdJ* zxg;}0dkthJG~oBf{mjZqtu(n$66fe_!?rU8c=o;wnP%Jr@{_nc^sI}J`&)uN8oQYM z*sKFX6$5ZFZ@wo&9%|?(cL3kGTT|~7X>i%qiKdT5z=@t< z;@s3u`NeP9m6I$;<*X{^_4*2UYi5eHL6^4C3B1ccOJSf+n7sD6P8x^5GBNEhXm8VA zU_8~KxO4@GKMjOUt&hkqn;Q6&zn^@b`3&Z8th7xfyJ^67L1Zcu7{A4Su=e?DNdD0Y z8{@oSRZuRw??4$-zHAeGanUr>TeXPPxx9y>c5$9lR}ga|K@$%3%i&9%B(o)C1v#E5 zhZ(77(dW}dUPpc!82TQD)T{;&Du{*M+8Oj_hXyRexu7v1O#a)KNPL<5aJ4*_*qxGr z+R`w18TziOz~&GLxZI*8*9A$VK`t_ux=Pb zj_^Zd7HnEmKo&_RK(WC-=<6@y{N7a{Quvw-%!tLH4MlYL$4k2Wm<9G4hT(SK z=jLa6Cei@CFKl*IJpA4<4F4G&gElu4D*UGtGteH@bk;IeHbG>%mLI&3zDbuJ?WO#^ zv#_5jLN$}M7*&&qD>ezi$JiT0x_cWuPQGMj@!>BkDRmlKf-ljH-TTc0OOo(}ULm=(1fbrzLAcAdC51=6qD!Z7R=gtFG&xTP^0y~cAPVRk+F zGhrOW?dIXiIh!!oFc%!bp61dUJ9kbVi-+^}Xl5@_qc9|;4%dI4l zp4z1PS3fK2vy-Uk&xSSAIG@VKEfCPw4^e&1a7y_B9g2=-Oc$J|Wk+*}5uFbrukE2c zS{WzwICB}ek3`5=nHUw$#60dUAzEZEXn%Z9N}GN&waOD{XNn^}f6z~7SeN0vjIUJi zU=(o-Uxn8WRngE756zR6I_M-kgBv!6VX*2MOuhMuYFcufi*X(B>DrFLhSJz!^Mjsi=^$MNV8wGYf z)1dg!8IsBMiKN$6^Jh5s6J4Je(rxaEJ5^b{Xp+I~BF%7N<5`#~Gzrc)EdpirA&$*w z%j)uS(NU1|-ml%$;XTeut#dfh;u$GY!FK+~-%3S%8Pt&V!RlB{*Mcgnq>+v$wD2!rzB7)Loy; zk(esLk^Aw?ueSs;T|;Qx%LE$g{he+ItiUew3}VFfAV}qTT>4EJe!bZQ5xzlWkFp(9 zTE6B(^l#|W=k=0;#sum zzDtG|K82O7TVY7Hn_iO*Aa*O%xS9G^+@+@` z2}J3wGN#_z3tQwQVC=UJOddN0IHV5`X9rTz$J@zpk2wB>V3PP>HeKR1#Q6UUr_KNN zqm#=K_RPym=-6e-k7(3!}qU1K2e!mx=a>q2`NLad&uny!sIY z)zJg+5NqJq(_6$~&1-U3;R5^b%3~7vr;Gk>oeQ681bJ_+EyRl-zcYeMtx3^(Z&3Ny zN*4IM$Lk42)Zy84@V&DfPJH4z!@n27FBLB$bYB53H<_Sz{w~_+v6pk`HA329Q4r8r zjWgz&K*&Tf!jy!W_hpsRDw|3wWnP0%qdpPud1v@4_otJ8ajDRMM3Fb;`DOU9|2kRy zCYvoeERMlzqhbA)bEN*GGbl+X7k?-4$Pcnk2fu0DXY`Jv3cU#hU)9HDkfIqBW2 zLE4saPNWy_=vk%hjNcv^Dz$7rFW)BsVoUBo(GDrJ7=K1=lG0$xa$#(^tPQ(o$g#%4 zT0G77+0b5h5$sL=BX1V3!8O+x+wSl`;@&(O ztMC0AH-(7EP{~*nMaE3`zV>}s)N|h7-+$j{eLw5@JfHPj&sl4)#d0s_y3RiLK4)LoYZ%$7NPi8Iq=D`8$Z4PV z;>w&(^2t&R?OwNF_TZf`YkLj3wP+k>9}|=5<#XZ00m=$~UBtC7Zwp!vc(6fgdj%@# zGUQo}BiZFH4@YMjv9fq`_#jMx2|vv+_TwvYM3A#!T>dlGu%?_q;;qf zcnYuETAdfZ9D&joO~9&QA7sa!CPDjK;f#C*Dd)AeTlbE_6MMJ9lSTU>qGL5%OH!dA zS`%{(PYQm!-{RNxI8yrP5BZxnnEs5DhaV@OlEz1kkStRI52f~iuTv3m9IFP#M;3zZ z>Ekf;Xew-3JR3rLQXx~mgeaejh5Q(Oc5hJ&E*70(8RJzUyyGUMw@qdbEbhUB;}H;~ z)8)w#5L)CZzgng?ehc9d4q9=o)psEDyy*5I+l}K<-{sr?*Sc&Ua zE5r6bOW<2ZDc*}&3QuH@!qQJC;Pyc)zPAzt$J}yBaAu_V;>*u$|*vbRGNDf z-aNHJ`*()CmxMNC$%tUf5O=Y5`e{}Un$T08$P~JC$(&uv&?>Y*SL1bX-@gbC_h+-} zeYQNu`6C;oUCFk$UzX}3ngCHzN8;*Mf3MMHOVVzziZVnv>I^H9h%uO>iV0-aHXNh=@-bqrXd`a+g zHUFMyRLJZ4V#Mye~}pJyKUQvVE-diTIlZEIM~ zh(TL;P2oW7)Hp*@-zmaSuXudztbw04s3N-T<}rwinO4I@Y%yq$tYlhWAVk|s8Z^6U2~UdvX&$MK6x8`*VN5nn8L$9`97LZ7EOPO}*T1(vdS ze{~pHI@b%eFJ57NG0V{~+!V!J0^7WAGRiO+VvAc{Y- z*t6I^RyTYUERXjWbUK8gXJj2)lUm2Z&c};254e!hYvUX2lKPXoOO4--zq#vN5SohCKB;&RW76#67o61bh4ZAmL;tewLNQfW}NL?LUAC z^OJ~vq#yfzWdzEvutOybhUH!sMc;xgg zva8(=1DC%PAG3@kw_VN2{$GQ^`ggM6d2^W9f07&-dB_#X%S>Vr;7(poG9XJN)N!5; z1t*1txO;3Qw5>Hj&qotr@M~zIAa{I6|U=xZcSO>F(v|}Hf4ziIogw9uAkWL1%Cwf-jm?t&Je+-s&j&jya8Bd z=7xIyjp+InaERtP$L@O*&|pt0<}_c$+re?D!*oERSqM#MH1LmV6!9tPW6HCJu=x`b ziNTO8ETa{IL&bYAYfvHa>b` zTZjzPDq6~h@I6wpDGC*~%HvU6a~K(F4Fmn|u<2RNj)Ch|q59Cz#P_#0WZDP9*kz-^ zS347(M_RMs+bq~Ux`D~eLCy(p z6HRorONXjedmt`46HI)Uum>U2m{fx-99XcQ)lJvLA3T@FzlzsIGNrJ7?PzAQTT=Xr z_kFQY%!TVxU2F!A4c7eWj+$wo1Z!-A1)nO7#LdkS7_dYUMr|^H)0)SyL1_RXFQPC> z)(+1P+mA9Tyk51(b_ht817U>}t2l|dbctGIlfB97Ew z1vB;cxq;EnK zQ~%53`T6hCgq3q(7Kbc$!Emyg)e81+IZx)j^y9U2cn!I}t;{%A9p6=1kWn+2~xb4RLcfVyv^ zQ2MMDl=7VPgI4P>C_I&U&wq?(CeO!vm9}`f;QWmV56<1bMRwj6YV3l0wj!;b5KZQ&Xwkpl2-{v25Ckp|OtX@JMANEXzvpG^BZ z2ds7VAvt`nST!z_WttseN5)IBDf54d$H*=u&(E3(qCSts6!}J?I`#)?(^Y`6MosKp zTpSDSRDh$8+ysA=&XLrHt?13yZbK^*1acK8V6bC4F_bA}4LlEQy1pUW*to&8tVH%c z)d?0?7l@t6F_t@eKBmv$>tHFT$(7<5`-OHfD4Vj6`GlMXrIKyD#?LEp=Y@3au;=>& zJ_cx3v0hLo+K2s5p71_TCx~%9uSY+H*Zyi$1L5gL!Mj77*oaS81P2A{@J--O@%5fk zp2N_Lk22Np;hr@Da~|t9GHASDuSl7cbl+wL--f`m`JPZJSB7)7%kXn&sh}?>jA?ug zN8^19n2*p4mN>>i+lbpF=jI+19v#jyb00WX$si7G6CqchCvG#6<_5ld!UT)2!Mq_8 z#1D>&@qyw5l9n8T`aLB$uHG2OFRdewLu=WjW6#+KiEMO@cEN+&bx|;NCVo*Fi|#L* zSoXy=EOC_^nQZNc6*0G2;^R^b*gPLYOV&d4sWvk9@;Hp=aT&LImk~$*D6xaQ33%&O zlftqw`26#0rn1YI4RF54wog7!X0G@p$l`f#&y}ykTa^kJZ2gSwN)LzQrX}FLY6u(f zaiq9l{|O>8ok|?ilh~M?erCI<7(#vy#p_=rvGb)K|7^VsuAdj;pGGNIb10LQjG9Tj zG?GD$Cwm1xAA;Er`$)9qQaor8!OV9$!1S{#@z%Uf<~GR$ob_VSKQt1b&pyJY=QzVN zE}LQBHs&g>Ws9vhgM>^}P4Of*T%tRg44mXZii$RY#ofd3`0IOOx#=|k-w)rj<}|u> zB$8hF!AN&{;7`Rqz`u(jE&m3Lot!R+j;>|bT1%Lm)g5pNZ-%R*m*Jj|U7%1E4qj@C z*c-PS6kjV~(Xc=!><@?C`az^%X)RNgJOI_(J`#^p^C2o{C=8IQBD#^+SX{|5qEavj zHv|;o!^aQclIV@#SD!ze>XfDnc7=f6+r#X9LLi*1wnyDz#-v$c8SGpW4P_hOvVEc{ z;OgGb{O9ZAkhn%BX-b*#pLm{!)(eUQ+5~+!Bgtb$Il6w*0BSJl9IOj;VcNSS;HdXF zR49pnsmqAquKa42GSdKiBf}tl$^(+W}iekK|v!T9)@DI*V$Fimx9tR47> zRqpL#DX5E`POFKh&uF}FqeT;oE`r2Le<sgRLk&e8J0MT|DM&7=?AnpwI1ig&|VRFU?QgweHlRC%ynJX4xjJ7odw)8lB zmi#~ltZQQj1C?M`djib6rH+rsZ-LG49y1ns4OUIv3B5K0#hP~(!Kd#hnR@ROGI+^V zSXGdLFSAaI1I`|Y;dVSnd*%;8=$v8HUyJ85B_*>}?#37#n@>D7()^E2EBIb5fveXhVw0o?tMLnF zsTw0;@(CUAT09;+3!4Pn^j4xxa{;eYaDgq%TZMxSKQfc!<4Nd)*>EPwP&@%0VO!}t zSgXI9*B-70qv6U#fBhHn!3R--#()*@r96x!-+xPvtv?Aj%Y@LrDFc$yJ6OVFH;nH- z%k#yxiFx57*r4vtJdZiDM>Y{S(_uK+Y(^M-b_Tn*A_z7$O=>Lh5xt5o%!2@ub!W*HCuAEcJJl_VKlrJ){UAbta&~_SbL?j zcJ@>wp^-$PP}HK|Yc68|-Fy`PjDMBi|91b`THDzzd`(L56_$Z0sSk|p#O(0 zhBq>a;}D zbJLWmkB1cX&C#G{TXkq+P%ybRT3Ya7qB^~1SP$OwHDNWgp~7{lG-9bTU9?D+=Dj{8 z7*H-vMYGIl$9PvTH>(i8*EXknHN;Rq1t8$uVA{XDf>`W737;f~Q*XQvw|{AZ#&T;; zcrOb~0uyn`!DX;-^eEcK_gYuy=tISOSunjF%BsG9C$Wa+Vn64}IG`zs%*gH*$cEKn zQG*=)vr`Wi>wF>iT(me9UWPE>ttwaZ;xQiEmWRL0Ejj(*S7>dt4;wDqaF)h1s0)AH z4c-i-+2Mh(ty+urYmbJ$&{HtVq!gNhieW*{7*1iUJC}I35fdyOxGD9MIW_re+}t>f z8y0WJJy4Y3&Ko+?6))uI>@r7MYpVgTH?+gH4I^P^l>t@RBt<3C;vrLM5w$-071YAd zz_Zo^kdb&0q-^KXkiS0ko0$s@(ilj`JoBJ_oHjMxuTM9tHNtg|xzy?24G7=7mU4kZ zXu%&t+S49F(C#KN%$dnd&Dbs^Lt*Fu40IFzgN-uT3g7KtT0cGI|^yVQMx+MA)WR(u3_NS~NMnRIEKW0qtTANUpl^Kw7DT0>9 zJ>_+s8sW^_pKvB^93`10;CFijWxDHWPR>kvc8NdjJQPnuzs{l$@6V^xg_G&|smtiY zH&L|mg$wn?`x&W+^pWfzk6 zwH4;O$hdzOP`j0{&heO}}-eflr1#b&#>Aw~A%xY->}9&tfq3>s#;=l#APakK3BSHCW{LkD&P_^4!?m-!OPr7rZ#P400Am zK#KGbECUzuj@cu~xOdCY$$vA8Dj5hzlFY%TJQdPY1>&pAy`gaERy6bQ#AP-C;D7K8 zMqQP_wX>Yr21i8@+1(~SZ?1uh&K)34I&@6=G7x>}1r^Yxm4&Ua^?3}83W|p5j*&RH zI}B}~Dq+7K$P#8 z5uRN6CJWBneGum_?!y9uOs+gm2H%V4;Qp0LoJxc`9$9|{!(DB-+e>x1os-H~%fdmN zVC_S(u;Vn38L8p-jt9xPp7VmdzeiA3YdQKhCt;`N39@JO4|F%{!gaMv(T?x?d#wG9 zbKGmN(W@GV_{(wz)+fZExdrwal!5!nU*LbZpBXR9f-m1D;?1-s@*={Le3x>!6+N8JeMv8o5> zIR(UZX)Q31HukBU*YPbo#p9@kgL&efsQb`8=O)`^Z7%Q; z4FpLlPYXRg;YXVe>{@IGCRulgoJSDM%)JL0doMv;k`Ss_nGm0S0wRA^8hvZJ7QLE05HYwtPRP6f%?vOoXuXPZ)-`-C=KyYH;+7mx5(sdqKT{7hxN9 zo*D0Hz<51rP~EG};^(f$C4YRdeDMg7IB*qP1s8C-(@VB~{s>5)8ZNe2R*F~lGyHS( zIo=ISK*ddZ&>0es&h32|7vjL_v&Dqcyh4a9NoVk z!&j>(V}ZOb9QerLBsX3&-PwfnmC?ZMf8WfwlVD@)j z%SKB;x7CcG+vl25x%9ixe{Le(z33~fcHIC{H5H^MO$A=ZRzqWo79G>J5ayO{fy85` z?7<^rDD<7nvOVKq!GuKgdQ}ETGZIJ#n+=C$Re2AL4^Sht2D@>KP+#4f>kXUA?S6h5 zwSR`=-KmwhZEZ5vvTob2Q* zteLU}-Zgci#Nl&n*Nbv-vG_BJTH8@iPXhH`aOnMhG=8~XNnVBiB-ekM!3KqQu<*MD zIbYHOGk)6P=*ukZ-pML%38(i9F4(vOG{{|%E8|fGTe+A zJ=kH;g5`gu*s$f<=;)xubzTqP%%=o#M`8jwLnFd1zqfipvP1Wb&$S*32TbKmbJGT=@#1~?0wINq{a~M~fA;+(8RdA(#HXI14 zA_21|qq~*?+U&UqD+B5ry9?6bvG;cn9REQH_T=p2gC3Uda-b5mq zsRp7jC%9^GfZa?R&uTi1F)1>N_czUjmvfF0{hmlr9rP01W-Gy@U$$WNM2=o|oeP>P z8ypK9Qwa?nMZ>78rx)O&_JJ$#a13mguC^c*SrsXq|fzq!-W8|UHclyR_5p%uop z>%-+9a~P7O4#l}~$niXa581hbVRxKiNz@t8F;9joDjURydWX=;4-Wx-87!G`8-^Z` zqKhke4p-0&a1%~~glR7Hxd8_@`ik`Ct=m9%#>3Z%Joh}f0~Vfr3n9fK*nHp@1f-|J z`^wGGqqhJ)RK&xRn9Z=$T7}ky60o`#1je32X_VUmQe^fGj&-|%W9~)b@%cTtT@ug^ z-2y0bRHqW^3N-2L9S}~Epze8&RO#v#@V}x!r3X%;4|`BQ9B9tNLZF}WanMyEc@uksu)yO`KRq9PUc7{XSF6$Xpcc+b=CwoS32A`R0UG?r zkN!xRO)rHd(3WLUbbI9-dTL1!b+xgk!zGu{Zi`KHdx{-BbR~gKc#%NumZnpz37|hy z)T!2>G--tUIJ6O`%6@(p0yphpYWYtftc6zJQ> zb~HI+F_mswMbpa6>FdjH;Qau7YBXjO&ry!YD<*Q7I^#PYUOSFkW9^D_QasTnxfWOH zyhi_7rYJq}J<;!70aJIUkVkt(=;9;~PQ4{KOzJph9`0oe_}uPNz2l4yk~qsm^!t%u13#KGo;FnWuSE5 zn5%ml$4$xe%BxVkn!g*D_s8O9%ag{o0Tlarwg&XSd*VK4ei#y>Y|J>z9+$A5q z-7!frnr&`ZfE(X0p|5%g>Bt`emTNcTUmn+4^;eFr@l}9RLA(zu-v{~1`!t_u-Hn@q zJ>bC6V0^oj-!nF^p_wu|REm^>R_QQ0QT-BxUl>oD9%)jApwGPOiaV`eI*)FgGn^ig zdJKaSOlXby7*Nk1Lt{OysjJ5xP`#Bxa&lj=U~5VEwK5W;BEI66ogH}Do9{*U9KV7ax`sKjKDAF=Dvj?;rL3!^Zh=_-C$umJ8o zo>wDj=a1V)F2il_vN6ii2kUH}FtWCSrE}MV?Bk6PbnhFnQsFUf%I5T7 zVim6uJO@1P7?PjKqv-RlA=K-w7VYxb0IE4-A+`7=ybo7`SZ@!ST{W9-H~s)8rbyCn zws)bS=L@g5aT;vuf?>nL6c~8<5Db^#U{lKvcxYU~Yvz{&+*YQ$PhKPq=1nkjQYd-Z zatdC)x(|)=f5eyM1aR;}19{gr0~AdVUahGEulqx&#`G?@TT~2Nl%?p{#W?~mCPze# zk6_l0B9L?HfZQz?;Pvq~*xki@L%Oz*q_vuG8#wZE1n zIPZqjl`*J2(A|FDoPAh$ToK5b;n=pi6yF@b0H+EY;ZSp{cn*)F-Li<+gzW7{8;#A_ z_4+x^_Yh#uBg$dD12^5_eSSSqq+kLWxInWlohg=IKzi4KX;nTiXp zRHKQ#Ayuj4d5;F$;P2c?^qIL6RqwK)ZZE=Vxz24Ee$o^oZdl+bmomKc`GH{MuoN`6 z<>U2M=H?_>!)ML6yyoU79Nz5q+xPBJRf2{I6pF?ABTs+L}_dK_I(-Vl3qMMVIFtyh#6<)>&@+#-@xs4 zn8Qu*{*I>Gba|bMCb5;j2i(^k1wU^@vz~@|c+lKNEKwehGb)zih*1uB?cGawvsng4 zT>3@a_AAo<(qS-5ubXLi?t|RHm)YU^9|F5tCsh` z6DdMXC*G5-#E$n}Ri$?xl)=V`dk}RY9_s4iAVl{Cd{ot;k-3*Z?|nRY1`nop^M=!} z7wou%{D*<~vhoxq0w| zc+*izwzTZU9{Tp-IjZsCIQ{f8kM0j%LD$dpq-PJs(I=X^d<|KiZdf~mJ{-DVeaqsy!Ub>j-A&*)Xj3>Ox_td z(H9GUZyo@fH+igottXvEnqfh4E66I&q*KTmn&!|4h9MrbnJlMkMS4_e-jSNcgp0h_&S_>ng4Ik~QN{WPRKp2tFSt40k=i*i7&~h(>~_(o^IIaQ|Izid*E@v1 zkyuZae+SZn>xa;KP84>Z7eejY2vm}t2R~mS|UczlHTbScXb;P&pP-};F}l99(DGuwj{rQc$GfA@oF{Qz=s z{TlI-l3elh;wpTYY6hIZ61?);urr=Rlk&eT!r&U3CB&1DzdUh`S0^%Hznk`AZK4-nN9ht@ZjFMEw#UGP_ha^>X*^d%g4~pMfST<)@m9z@ zoOk-D;L~X#%r}vRkXOy{c4jd2+0TO>wX0A&_8{>*p+UbKxdvOdjiW2%%HUh#R4hBZ z9Sz2(qYP<-aM+A*n%{_ZhN)wx;~uzs69X zc{G&F6-_z+E+7M<+~jFy!%H|3zZ_g_M#8P1PXsrmIam;5F4*wXh)Nelv0#->7Ok3u zR)cmkKW`)Mk777G^v+lO1HU3mtw0jG7`W6)kojsbvnk7BN0#%NZ!H?&BNYZurm>of zmnG?`2rV>?F2;i(6DQJ^Ud*Y<%p2RhSnAFo0BqAoBUVnKc9^@4`& zTL_*V0V^KnlPzA);MpxlI_Jv@i1;-KZoILlA9ReMPTmHT`8^~zSDC+d=Kwa%rCmjB zP*P<>cL$3h@c0SAtW%d^XSoi|x>pNpLO+rNefVgz?op~3=@YivRbU$ppk_m}BrqZ*ip`7Mn8_s-4 zIM=e$mrJd`g`?C$IsXD{ZrKtyF6!Gt&hO6`a?{Tc-o1|?ZR6KL?tptR)czQGKX)y8 zT`wk|Oq1cs`AaO?dI(fbI!)FMoB&eZWq4WI9R%9SP&auXzW%Wa#{_o3q~=D53QvL1 zYC`ue*an*yra^PZIIz9+4J0?bgbO~yF=IsnhA)s2Z~uYNJy#JkJFCe{bN*eP*O4{I z)W(X3au6+a#~~k{WA8Clv2>w7UUhUulM$*g?DkUgl;PqP zC3x{yj@TBQGJjBU&z9(`h(YFv6rw6gfWw%iKIwP4I9hN1BXu^)E@L}QchQ+zwf8ZNtkL%$nHRt3b17s*z#G~aUa?bQNMNKA*)`PtYt zbvf7!IYI`l@53d7?qb}}r+lri5dGw5U{0(ecc@5`OS&+W+oz+%Rnxy%mF!tjC5FR`N*9_Dl?4Tq3bhW{Ngch(W>4F(6 zzltS%{K3z>nP{v$568v9;t}*}QM&mo~CJSD9V%-w*b>E~G6mP4IW}NA_q-6$@N23(m{@65PCU5(~c0!>SP$ zAh5I}y8B`UCw@s|-R{#ky@<`5XM3*O18u#B{! zTs3zF54Q6-a*-C7G4C248QFoq7OHXcM-1f-*qPu9pM@lL+d}wmTSBfLZ6Z~kI%K2H zOmclo3;W%F8p-rbwD8{qM-JS=)`ZO%zV8Dhwb+u`ofEPC?{t)=yK#=uSmtTIT(Gfh zBOD8NgSXn*&{UNO9kr?C=8wi2HG^=NcwikY_qK&+uItD+`Fufy+#~p1Py*L4jKT)h zLNfWm9+qu11-4lR!-+wU$&9_)SXZ(V3a59&p0)judHMqEDqR5vIZ4p`LYi*w44+LOE)&d;JWCasrs+I9)7_oc(hb+6$G?+t9M&g)DKjDl!> zFTAZl4itGU+E0_}K|*;i^ydwwPquA@em@x)|8pR{??b7AjRd`ST!Ma`)eR{LN>Dk# z62`5OqTgem)?|82gP}vO6Q?O_U~S$gIw^4`RevZ)Gj5sC`#0n%vv~`1R_f5M+WXKx zJf5E2xB$4m4i zsMR)IBt6?wG(YX8C_BGeH0RY*;p|fnM0S&=J3XFtL1boZ=5!%=tthmuRrJri&2H4I z+s)_x&-nN9x3;#J@So+Mzx$JL*JCC+FCHv%f4@Rxo?0&|ap`ax_M}{>8|W!in|xK& zt|btSe{@K=$?m;K`sNE^ti*iL>l;@^o`)tl&EL0GKxPVSc8u)4DS`qUDX%qJ14>MHlWI7E1V8iqd+Y|5yGdYu^9;zsuj= z(%$Yr!yo=D?C1Z<-~O4uv4xYU{@{>#vXUK#(GxJ5({?Vd?2dab>GqyOn<-3Y(r*CpPmn0U2czhDxRvY4^ z>=GlAo|YpVKl+-`H6unOS@&M3X_+cobMmK?v_y$;MtO$tN$Omu%r0dS^UiY8*_j}+ zI=WZ*X-(08eSbIiwm;v^&%!_B-bC5@Frs2FPE$koTChq-l2};HGy}V}OBqPBowP3JvQ|IJLZ{YlevCQqpFN{r)f;;u8So@{2 zrvJz(lF_9A$vfNOxQPaJ`6&U7m+!(UzIHzUyDHi5HHfPBSAfo4EA-CdJ$2JX@RRR< zdBqO{^*cfAYSvTuuzfqIYo3Icg$>|5OBo8aFA#;`EL=0TQE=<@35*(?0B01#&((7| zXxkzW1D&lP+wLOSlqrHqD+cq}m^f@doxv{U2SWYk=PdG&8yu@Hf!-sD_~qUaFl^v! zJAQj$Y)le3tgVBBh4&yhD2NQ7KNyajTnO_Xw7|jR^WgcaX1Ksv(z&Ji5aCEc-CP-s zr&pka^efc)>w>KACfU9v0{^b(d04?8Fk4fdvsO1Ixrd`Me|HA<`A0C?@e}L6e`C5& zFX8Byl3d$FYwR-1BOP-ip*6S%a-IHiu2|{*1tX7cW@m$+)cjbq8xp%?h(2Fi==L5XxU0bLv(M@wQGLV|{1TW_>0SKx zG6V}Z-Nyk_hI0ol^s}Eg53wb6e*~kP^f@}kf?as=2uH*=qo8OUcXoIK3oU$t*^4G{ zqcux#4eueLYf(Y;j#{HxoDPxLB};Z34`;4CYRe=B`hUM%w3v8=KC!AX{oFn(ppqFVal8 z+PisRK9skV@i~O^W8|@PM>&i<5ygt)YGJ_ZWAO7&u-K+MSscH930zZN3mI`|c&(Ky zB<8^}a^rTsc!A7pa9XuoTyfzTTq`{fh6{bjDCNV-RF4uDtvWe7j24lD9`J%zcS3FQ1{wTlK|kX1by zZa5K|ro@1@$x!h@qtAkGA0HAg7!M#>%3fb+XU6_!;u%No2#yXeXIia2P~-KCsPg&` zKJtgaDz!NHTL;9$eqD0WRYqV)G^fnk0(_ z8~huKytd4?RnsA^Wdp0(nBr(WEEtzgNEh3FyUpTL7J#TX zg69u}g5`?>!M2PzIAmxHBNu*VcTKmz$B;zm9H|EK#Vs&!7)QKDXyCzjPax+suTS)2 zAm*OyAeUDb@w&Ig@Hl)2*b6_LZ$5P$Wv)tac^fV{Ou74o%rY}#393Qh-g*_)T4f;e zVJ&Q^nTMOqFR;~fn!rBwI2`m%Az!Dak*O;cAxE~66z}Y3VVl&+C-(!mVUY^V-F5{1 z_DN#qN(S07d{&&1)Stt(ODoH1(%xrq1Osex)NZ@U`pv;GFn?Wf5731ivoN#VqMsxf!(&UIE4GnRGRWui-x0T%iid3^3lcR? zfOMZF_1I~|HODmL>-NuhX6`nYyrh$T4IMyjEQZiuo9yY%7;~Bv-OJXxNMhLiDP)m! zGqazJ(6Q|Rj9euEgOsVD_9_pC*nB0H9s8ieW+44r8HvX|oZ+) z;{fLiP@oVBldrVF&TM_`5XsQO5;>^<&eyAoWofnH6x!Uh90eWG%!ps>RbyORVBk$Rzb7qH*siXnhjH7xg-Fx2Ou< z*l~ikgmE~({3QA6*C|+H#y~lr0=KP>Ts?7s{JpITMT)wRP;eHtK4m~LuEeUS0-|Wx z1N-KDhfR*rkU9Spt|;#&DtV(ZYwrxU(WMAZ@mQc#+iaMjElr!-jp^&vR|S{f{DkL{ zlWCUFpPhJl0#@z)4q03UY2UOQ^7BX2c!_;@aX_78n*I$uw}oNn>GkNBF`O8EbHw76 zUN~vI5TAyZpuxBY=+mXZoqO~b*Qm{9`_n`4{M?T?sVEXVr!?RyKV|N8PzVc{Dg&Xz zXJGl)M%=Q@mn_h>VQKFlLyKz$UNCu#ALrGgQMeA*?LV9Qla$PbcuH~e;|FphKWlTh zB|W&DSV?hmUn_3wNCK_l-2&AMzr_P)j3L`|&WL}u=nDLIHIvHUb)cwi%=Y%Lgzx%y zU^`KzudJ-7%2sLm#s4|f>{Fq)ea+Bn%ud1Vu3E>2j4-G(s)C@uN67p)gD`5SEL`Jj z&MER=P;GbyiaAVmcyeVj^87YK3E>u}z)ybGy#8Qka&2Tsxb7e?QSVG}QEb4E__xHRbH!XZ-uA^^zu`(S=9d`?k&TrirQ~)IwceZ z0i~oA0YQ-1^In96B8pNfh%L4#Dp)ApEnOn5Qj)@&_eN2~#sF-wQ86*Fz_XtJ$MfM_ z?>Wzhm+M+z*=ujuYu6Ja74pxW5o3B4+BS zxFv^#*GfSH6$cwwi*>o@c}tD{-rmza&@$x)xDKkq`fwh&*gxRSt5U{xo*cxQ znebv2*5LE4f_QSNBviI8q02AJG2s?5&^tDsN!N3P=;xuZQTZ7BRN;Dx(w@*tsW#~M zIs_|o;;bJXU5k@X{eiW6qiNHj7;@pwHO|i@!`N%jrZ=a>03+~}s@1<|f9#5cA(<28 zQt@~CGb0@W?0GowG88||5(H;U7Tv;slPO}Mcx?J)I8!wTy$dcu{;C)#m%GjTa&;4& z<=^1#MjfzyArI^9&G67E9n^Ze5FVsGrOO=znf*%rB+puw&zswU=lXLw{&57ZFL+C% zt8dZgvDb0*)GvC=@e_=hP_pLi6m*KSr)6m>&^BBGpZyGAnb{?x_qigxf#Xy#7yQ-fix4r zdCRX3>chV++DyT_rRbjiifEK`dBQW&u=GL#?y87~?w0qgQo~hPJvf8ud*wm-D$yiP z`8C-6I>52A3_xT3Sz5BE1eE6<0v+#u)Qro-om_88$J_|?d8f*ol9vwOnL>U$ks%>!}%vSOWE*!md)hfi~dSy{^oiq zo4;XtUI~}$x`zpsUVJmsPc%O$;>Ji{R1&+)X`!5+woMogbhog_OH8TrrkU_hwGYih zu47t&2><$KReng{CH#CKALBcW`I8mvao_N7R5TyNw;;|RZ#0FUaa0p;@37&EG}dCW zXgnROxPeE0Y2fiM-{>rRZGNRw9_EZ0^Y`88#GY5rQU78ZUVS}*|28>=Hc!*UvM(7Z z{G*S!UY-QhS%HS)WSm{!M1H8T;Odpio3*@$+<7w|2IPvt597%E#>p_?`<8foeut}? zU=NxOw^^Nit-|1F4zSGTS zs#x(oh0J~&jt8r?so|Gyth*mgBqp&=mv@wo#4d_*mK;x~5rch74!n~q zrr@>JN6}?0k?NdXO)|`1gWJ)m_&k>TezWJu^NYL9T)8|wc`LTwvz{WpV@e_MTQKR&w}sx z0lr=`huOhrpep78Y{<%o(WXDJ?heXay;xx*upz~bUlsurUy%M>fwB9 zD|MF;Cl&jw=xF_E6nw2p=+_(AaeO@gK#&p0+^?m2L$ZA32|wsOfqiJSL5vxGAVJ4| zjX|Ag5hYG?xYnx<>OGFZNAY-a&~+wQ#tK2^v@hgE?_~J%@R7CW`A**Ju2LdfE5Jl% zbI!fpbhF>)VOMlzMuLM_dK40U3tPBkE9;oZu>=J zeLOKoClj(NW?oonNs!Bcs$Jc%-=F22dn_~huQh2v*I^X@V1b?ZUEq}A2IzRlD z5P#L|JGAMaBmdw`HSF0r0kG)_?ACkAyXg3X$h=5}jZO7X(iTHvIwCnw1=n4>`41d7 z7H8(F$TG)1?E=SBLUf1ZI@lE*10ExlIIlSurib*Cho$W#xRxS+!A{cF`V3uWE76Su zR=iicE#N>+95LGKgrTvqVEgYIoT;>C0$+EN4~ZM0!F3HIB^`>Co6QbHIYTrTOuan2 z6Bco25YNgl!047Z*uOZGt^GjZ;kR?(xq`>^y^FxhN_Vhm(OmwbUE}yp3OanBo>M5% zQ-fx|#rS))qCh5Bk$+_L5y$pg&tH9M3;xbjFueZ$8;E|pLvAKY!11nEY~rgBJS>dumAbun>C8mF ze4rfvO6+p#v3UYIzBFtvUzp8P+g?gNhQm=vwT}L^REGoRxn!ui4)(MR(W<+mbix@) zuvtDI?%O$`ghm-{{Irfp?EgyFD6fUZ=2IA7ULL9Nj)7_>4kQLSUfM`6Ox)`SQ$vLC z#*OQ=;ZF~Is#HL0nKCxknbJx|Cq4)D+4HPTnu;+g>L`dc7=wl0 zFLK#D0S;=|;hth;hH_qF9Z2N$mS&)-ZavSn`5LK0_`0%`?jHIsn0*9xcpf<}o z;fKE@Sj>OU{;>K7csn27R9&J`&bPtTQ-t9qDloeppMaTeIbY| zr)cpnObbMt1E*M-n{ToDp(y|PUT5OX`Q@%%$c62p*N7B90+JeMSV{WYSTFh>1yk>F zTx{`9uy$EbK9$PgW{zWD@;V=8j1|C;(L)ekK9{6bhJnW`KCjzij82fL1c^6CF!jzo z(l+q{ao%Tzk|MqIio-fQ^S}ZR_iEtxx35T(*aM~6%^J;~M^qmZONABDp~6M*)+p;7fu*k4x+rqcvL zsYZaQx$_xTEuG2uM5GZOk;mledq|Yh1n8XN3qCgkVRQN^X#O$?&AAQa$a;}@nzW3us?)Vop@g zWy)AOmX#F|RL{EZ_VQ$LE$H*&PQjHLS5j(+|X3T%g5O z3OlZ5pw`V-R^p03;m=Gfvd_c{R*Rc~jGjFkXwe3(m74J3;t2F@+)Dq9?SZ&Q2Wj~E zDX{iO3t5?W8kIiS!D72T*umv}?PQ0@jPj|F`}{368CL{iuD(=j+iXI@PLsEeJ3!mL z5B>-W!_BS7;BkEk?R+c=??p~o?QL_0&2OI3sR2Q_svwC<3KUpJcR3J+1CMB`)F(Ke zvWhL-auh1tm6$mO+n}mvJDgCJWafPy0L_L7=7Dk%6JHX;oV2cIj8>dvzUyCL#x=$= zGj9(=)+QAu=*t%7>cMzMd%*@KCL@%~l`Uj${^rhy?^rWBmsT@lN}HKyDr2xYMVq-J zq|O+-pM(kDtieJ>fmsaaAae)8;r^STc*`CBL~nxL;7<02Gna8)n+)@pZ3fM)A~4VN z4FskhqN69OaOdYz%KMdq2DWNsv;P>rIZ=d<^3zzOcgPyNIE{g;|1n09Vm2}7k1@A{ zuQ4-n2AEkJN*MoN)r{?CJ|hHq%*?}Am|Iu!nX0f>CQbejqqnh-N%HStWWI(mNjfP^ zo1Z6BT363}+grlC%`arU-v=;RTS^(@CwrNuUE3JBk#MHdAcEn~S;h2!xDVbs*WrTu zXUN(u&9D)xnMc>^A+_C)2`uF?i$?CFr4PmEG&%mypSt}1Y4-fi_~rZ+AD&{=++uVT zk>v}ItmikbH{&l{?#y?*(1-71XYki9m*US8Q{#Vl8NnCnp3VOgzJw84^Ax6(g)p#c z2V;>C$_y=ZWfnak%mnMlAXBo4QImGThXxn1R!snW9WJtcllZv#N)*)Yy$!x?9M^-j zL+OGTrem@&BgyG6|8z{5jOUI_XWJui^weS+CXT`^i>qLAqzMAd9)fc}H(Q;QV$w>k z!FP+v%5DmHFsGSbuGwbBv{hHN#_oNv?QFjdZb6rkvEmClJR~=ps-N^CL<;ea8&fq9}kYxA%!50NxbmPWQ{O0_b ztm!|6Zx(FlSI(J_Taya#f#x$jB3)0u4jN+anIs%g(SW~cr%?XP3-bPy3zP(ZCx=&@ zv(B>M`o>ikz=|bjprHRG?3%ouHSrCF82g_fRs9!4HJza6&0jdA)DP~y{&;6*B`--J z9kaZSp{!vF_*~n-t)Ul){BawU*QjL^rQ4zC@?!9}mxYhh#Te^5tH6AsAE`W|+IC^R z2U-6qisp~&p0}Yp6`of{$3nd&VGTisr}^d z?W5SS0~lAaHr8S;w;pJ{1>=}wczHmDmv<+Sr#SHuPIxGb@!J-YPr(*wT-*R_FPwx0 z^d&LcW`NE^{p^kAy-@k;1!Oe#!SKHOpm6>gM88bMdU4M4t?r1mjVF-JDL~&Gjmqv4(h58KAJmFdaXYW8-E# z#Yvg_QPg=G>g)3HnQc9?v2SUcXc~rInZqoed}K)FVlHZfcd zX1^X2T^I+U&$ukOV>?KXegpZl;!KUD4r8Rc0*}VtB89(SfZ?^haF2fs9Cw*9D^CbB zb$xowq&=QY#0D*9AYYxaN~wY^ndZ#MdL3qycPH#m&xc`~i=cnh8y;KOLQnB88o0{< z3Wdz@{O=%`Tl1C{W|^>ST4&?@z)4`MA4QXD2I%wFaNhBP5?IAdgHN{#=<~Hg*4yKn zpm9bte4ccMx8bloj5~am=o^*7JUtD_2zJKMuG75fTu1Qga34rKVu;;di^#|60rK5$)4+*Az^$5mXz99RwfUT#rAjUat&Q;!624&d!FOn+Y=81gvla*3^hHcymP`l)4MyOjyaV`PyF5dr#$&6%EA-Sq33aXw z*k$yQOgHhPT6tUWK$ZkPd$o~@TyrB&=6@y;SK{&1W&?2hX#l)~`q&Y(hB@~tp7C>! zW~y%RxaZyyX8yN@%(+raW&)=xL@W$u)E>)Xtfv^?F~<+z7Pz8{H^--(CyiUz3Sw=4 z9=RoN0I%92nCBh`m~Zd%nOm0TjJ~!%lOJWntp2wSMykKU9=+{M}p)NGmdTg05pX%dG7zz`7X&b(Zc^Bj+89M(N7-uzN!v=esX)2PpZVO zsoL86`zW6CtLM(3XQ8sjH4J-BaacMPqb2}24yx7m6yEYguNN}B~FJ$2DkLU2s+K*lK z&H*!*DMGXQ4AB3bM9$%N>}`07YD0C{B&dnMdb6B!;Os;S{|I!=XZ;y4eXAnFfPGbv-z#ar4jOSSs6p z1(sC~!tz^3L1|SXHdv2g?HVyC;rKa~Z4;39+zH41`^jqTPXgj&it5j`n2fFe;KM9i zMkenGv};;19;bwu?;BS#b9cotCl3TLn|}#1>E4r>P?ZXB`FtPl`-}j0-UQi4e!}z% zf(#K~#ys{&gTX@+nBLDW%!aWjkX8Ezt=yUAcKZ)-@Z~f}-NKzybL&~K+A(&=pc2oc z@F5&C=z`Qf5%~7Fr(NKU5)Myuv>l&rDXhhgKH;~TgTfd1dG5; zH%qSPb2a1gc^;$hsLy#@eHhKL66V>KbY_0=TBf7jhSBz##5C3~VVDzpn9I9=L;Hy! z=7uydyOeIh^~@;dVz(L-eO8x=_#MuCd$)`63od5Xb)9BZQ{=C>Y{=U<5 z`A?oagYP>wGg`OiG48pku<7hvM!fSccna~Dt3u|Cd_XFUlRJ)q{C)W8U^Gtu(M24r zo)FF9gMf|iXp)N}=q`$dyQ?*smV0{4>$j5_ySXmR+E=!W_K+&`EPFgNUuF~d@8tBf zBhBRFMlGhlNR44{og~8@#*F6WNsP4BZ-}$H1E&5m%&#|v%qz(##%x-UJg0K@z;a*Py@}qo@BAw}{`2~#_EYHp+v{7I&zb#y_xjvh{Qvdmzw%F- zn_HOtm;UdRGIP6^M?cvZD7o4hUgO)4Wvw;*HswZ|?Yu5( zYvhq-({3+i`$T-6ZP3z4yA#U8HubBk>{PGE+O{1q`=9Us%r_wmL%F}gf3E-2|J(oW zf1hJM$JG44^v^Cn+J|4p30O~f{T=ff=cDJD)wukO0`<=sZC~|11dEP*qB_M(ajB{V zL_{0m9C2-IEObJv%s15b<18ZfL=hf!*3f5dpV-Clm4xn#qXVm4iR1HHsMD;aGgJI% zA6W=ekqIzs$sJm?%nE~_PXnE1Zy0sUCF+;GU}MHnl<-}T8uJ6ln$=&)^hHKQ;G!sx zaazO*%ZHM0tH!~Gd-vF7gHm)Tdl^jDHewfXe!sKbkElzOHJ$nE38^p(#V^IvAZfcd z*3OHeJ2Xz?^G+E^oGF0)-e2&?6LqY~m!yK6F5z48n2vnZI&(y&7#9@oAUnrQ@!rh} zbX5Lny{NgCNcU}Fn~rDV=aM3<+%%D6N*_T5hXAw~|C0Wj(?OI;8Ij4|NX|R8S-YS0 zp>9{NP&J=eOs-svO>G+N$WkufC6adqI)<4y1JHiL4Se{vf$dCJ zrGedPn9`w2Ib#9dT-9EO=+w`Bo>^2g@+3)~>Br9Q%f>vld^%&|4mkZ$9WGZ(!tU3Fa4B^iJ$(Bv z{dq`<$8<&lIi`5BVNc_4=9SbIGqSx5n?353$$SDzyJt|QEuTR=T>wzsW z3?f(;dIZI@hOCzyO-9Ak7j)L;8CGc$+*!9s7S)n}%RBYGmHg^*BNFQ)2!CBJUDeBV zl5XrHqob|#Qe6tRoz2IydYtBlMdZdZLomPeoGd-{h`l4Z1~&Z|;{9#@MTgwpv6@_G za<#5KHfhL{I|;~YZxNx1U*gE=(Mnvu>LeN^2*8eiX*fUkHCF9jPQJEmrKOo?xxV-{ zxR&n2k8W$=+`AC^^Bu>4EM!@}#W*;4Et#ga$>OsqD{&q(NNo zaqFmn4YM{=r@$hT)#VO3BjF@Yvxu&=ID}OLAKB`@n{@G2KkU8*w9EGhO5R%uet(wX zD_%MKH-OvM)tn}EOG>PN9@zqRqZuUds~k++nAjfB9S#Fx`Ka`IDK>_u;IT9DxTPS1 z_q*&dW!Gk6d8IOro6a#ZN29<`Tm>ez+OZYGXNiJ9A1!*a9!sBIZx8G_fKi?**17>6 zBvwTP1#YBL!PGyrM9>QL2cFQ=Q+?RB3~!ts(Z=o1A5jIjW;QCb6KBky4xb)WwLcDu zAboW==>m-vY@i9B9DhHTK7G5vx<$r;JnPP8>l~!uj*%B?;9(SzP{H3v7qO?thv253 zAS`ec#{d-vbU(+Pk>5Lqq5IF^%$^x|&ORSYTC`|+aiaC1)>_uc>koVE&PuQyuA--W z44}fqfaD*O!HbJ_V(o$_bli`BES=|wV$ZB;-2P|io=)jPXML$Yfoar;%;1XIv$d^*|KmQ559gb zW1B4(!plc4*u?plTl{+=XQ2#{2{b~V);Kb9dm5@FZNP`UNwnem5-e-&q_3~Z(>X0K z+9&?xG0hrI%%JfeWE^zdA zBW3-npe92I`?hA%{H##a+!07Oes$o^p678ay+mA)*@(+G&E#GDo`>^eOi*QCBEIcu zhA9V;#4Ft(Q%6O>p>8s-;;bG>4C^ zy3cRKW1ile7orypmet|H+djxwsK@T#XYjXPI=<8A&Q0#ulGPhFAv5PCO??*2y3P5? z)6o+~W!cG8;cyt+8E%APhmMnTw+)$xJ5IyM^b7RTp>34DFCl+wYB23cH#7v;!uShv z7!z;`ye%g{z{njQ|EL})2`5t%Ex>#gUA!>51wTr+V6cu7^ZrCA_-m}8Yb>fERr3!K z`cRIgeUgl^cohh7{TVx@d)fJa+-cADP|#P3BkFbS6tl|#d-_i z1M^*barbaO`cG0O8NtWUKwkuBf1X25S6*SW!z9pbb`-t9M$tRWGVB`jgV~EpxsIg$ zDC^b&k2faJx`$86&9@D3L;E+>{0sxtr$cbNMV@(c_6C&?`UD=&#xs|GY$HO6s~FSf z-ONe9F4(-Z1!f3-2A?rWCTwdiD0~=zCF(3hWSKBC^zTDJ=o_f`QVD+#IFbFo%V2Ay zJWi`0CSrfWA@R&fUQnkRbY@wDPsIeh_)&vwY)+yJbq(2rZo%9+n+?{*yhVo!u4}NM z6Ki)QLeOz>W-L7m;`D3a!|x>|qay^Wc$u)PV;fwSKLNjWCGf)XGIW|2j@gn5xY6V^ z=18jW4_uxIx?7B}h<60jZ4ctQkTKo|#+VL{FQIL71c`~EBpw&Cfuz$xz9Gogb-XIf#m&lFrK9zd~Dhj(W;(ia!R(3?!fTOk#+BrpR7X13u< z&OcpNewe7~Yv9bqHt6u!f?kp_!0(qec!Il=aPlC>M?7VQfjt6XT_lBbR5{j@pDRAz zevU`oS&l!e5ASOD(N;W&%w1Qex7bDCyh4-HpW2d?=tkVdB zj>el*=XwbZy3tH8J1?Lc&!nTg!zejkp~m)G3$gEX{D@`ZemL60wUy{-@{CT!!_-8c<&T+%1jdt(<}G4meD%910|Gv{%BOiw!bhCKIuYp0z#iR9?BI&@s;k9YUE z^7wJdJZHCZDnB9$gPy5m+Z{p7^In2tN3N0Do#^&2Zvd1z5Jq z3B831Xok>A(*0m9&)~KpPv^ZpeU*EeqzvEXJz6h`vA+B9aEu{p2WvuS=K&nCFT@iY_6MoXIZB2;z96oT2}VA0 zz@3UFV8nSIn?!YCjo1QgR#Snklj2Fl?~A;BU-rO5kL7UJ)RaB^LW+!8#go<9`sma4 zfsCk$;FxRx%}+Oh!JaS-kqE)1t$TT@&6>n_Sunds$pk*{uS#PJ}3n(+DCb2*8$8d``EC{!n~3s8M5u?J@(1&izF$B zM{AX9h>t)bnIgHN{a(~2xV%o9tbM|1Gu-pOCDQ?nw(Db%^h$Jh+YUSKHuD_Zed(qV zPJa@ZNMFbAqs@0)h@#d-A~$S{elyk)_16h_Z|)n~f4&kwUu4*|=MCU+cQQK8uVB@- z6j8UiA$ZTC8ugRPSm!nCP_!=)r$3Pf%_HID#mf~a%IUHaH4k~^<0s<6S2{i>T_iGP#`^6KY<_AG@pMp zMU>xo;UA8LUB~ZM=nVhw7DJ7dNbJKwx*H?1dzbWh-Z$#=I+=Tp% zGw4G}K}Jn{D-8=#22*YZ_n+F$Qx0B9^uHe?7rthLM7krX^b=+L%jc5&yBxscS|=Q9 z-$6fK$;1Sw5A3l&KDcSC9R`Lap;BHJdR=U2cQ~EH`aZXYVXimz`wCfH7m2*@Q;p%% z29`}&X@=J=cag}ja`f?>L{{xL#do?K*KPPcUB>kuN1Jl|f6DnZ;tFAf(_O01=@G|m zZh%T%H(1Wt3(B72*s*p6D29p>ofS4PrN#;B&P|0Ua#tWjqzr=hXb?+Hb8=?eNv^A{ z5y)wA5NLWpUZ^Ho`ABe$E)*)0>qpSU9wjF5Ay$5Gdj1iM_ zW<-VG!n-*|&}R7-tQDdmg5&z#J{!AksFJ%*g`3W2Ly-1-?gMgliqw5^ce>A{GXq+L;Vs&EmOP)XQ!kh2mzn|~&VH{so zK$pKgZ!$kj!kGW|=?wnWB`J6*Sr!}k5Yh9+HKQG?4jZXUmg zc;w7Lh1AcMwjOc#OO?~o;#)XRp$ZE2FXY&>qu2$?{D%o=(Q=sp#2%f3r;7bK-c~mz z)U?pP?+4Jics$K}BS3;-NQ+WZrKK$if=;1hpt$L8@E<>Xit)|gFHDpqdF|13!MmmIVl7fBTh<1`9 zuKd1&&GqN@Om|Yqf`hp_7Y>Xuz=ZDkY^b)*Z9ZvF=G@)DZN8FJx0~gwP z((%8yVky%~N==I4?5&O9;L3votB%sx8{bIyl3e;@@hNtwE)<{keP=J;n}dTwr>I56 zQLNQF-_G9AMbpz|*m`*(In*Hwc3bXJ=b6vwmCr11E;pNN%8kdy^9RxFk*2jlwm2ML zO^Lb#r^h~VfCkf7G}m&9Rejejw!5^A+-elTLy4i}V6!0@>IzVIl@u(LzRY{K_au8n zAdSR3C*#E5q96(WWL&E&JLN$)JK}i>OnBb_l%B%v702Pn&U9FGHvo7yj>Ax2CTxU6 z_?L2(Mtg^&KzKiP?O2aLE*7BMCNus8jWO&DyoA3RlCipf5OwxiV}yGl$~OCRhl_q!| zgK-9ZMOtJ<`MT4ep>NeSN>|sB*&JVStq+%(pXp~4U7l~prwwNf@#T2j;)P(u$3B{-0{fFwUDr&UKHxW4Ukzzldo zgybSnoa6x;q-DXWb_%>$U!;?=*7?i#44?~Zdlx(}zqTAx57RKAvGd|CjHRu#aS>s#nQ znRzH`kb!2pK3Hn=jd;4Nl0z?M!_t?NnCg21%+Ati@O--!t&0Zeqz5F9VoUEWbRftu?aFS$+WyynDu@uo|BfsU)w2_nEf0gM6+R8kq(qU%LLw; z0%~mblf3ayreEy|T-TR_w1*9ZqpH!@va0Z>d?Csl-T}AEa>47j1$uqY#(5VuLFu3l z7}RAGa}`5Kn#eJ!rIzyV2U~Lf<>mYgDP{gh=mP#<SI2$c5$vkuC z!TPNT_D(5y;dMQ(lDmsvO%>22sTdFM<#NQ9%TcoH54)hc4u$?s!?z#P>FbqcD1VLt z^-Fx7lCu*IIZr~KV*(4`^zoU)b#`);1|HSCi3habxBD)*g)yR4`2Bc1dM)JP&0n6_ z6=KEIzEog#ja&x<+v!YRf*w;@CBevhyD^DRLZuGR7knVbHli9kjYuLewjLETNL{$1efSelDXun%giu*qjQDl+wWi zH8^Q!E*}4@grTdO@TAftEVi!#Jq2^RsVxHkRT-n9a5zsXMjG5L`_V^K7Iivr5&2pP zI%w00vZem`jOzn(4lZC_`}rs9=kB8w3?oNCCGJ#gyZMmE||Ni2EC7N!@DB~(K4_ZXJ4O)M%|7)lb2@@RiaVJ zb0%IGmw;A>DyYQN(@&^kaTdEcbj8=}DM!Fn85nSqj)MdU=@ zdD!G71t|(L@OoKn`)*T3m=-I>YOxn-RE!y1E(qlX@9U#6XVlSu_dl4rB#nIW{KS5G zBf|*oV%YWdc93T8g+a%Jd9^bHP%uY>?4H?5PdG-wVPyiV`E%*PZDnBBDoUa(*J0w# zgXrI)0wL3^ad^XfWK8p6lZP(nv69DTpNm+z!4Hd?ZsNhKVR&xhApWu##2v2{`OS?J z`OfcrvF%+WyMAXFnd)>8WG`ys>l-W~8{%Rq1z1@RSx>si-lu5bQMltM(w-Y>xn`6tMTUfMuD z3OAD}Uu@}hnFPFXp$bY8s^M>}7uR3437mPUpw=r3@(YY$>|#0$-Af1e#I4Zy-X1K5 zCEDgLDq#(>^TFt671v=s$S!pf1?yv9$))w0*4#)&mK#3i89FAT7B2;F?mULmJF1{x zZXd+;tDxuBz3`f^Ozk6|(6Es%NSQkUR2Oa|?(hHM+>T;&&z#TC7Ink|qsJIp`3i$C zXVW_^AF)FF5caIy1o#i#@i}z^}syHT9JxBDwMFROB6BLl{QYhfrVCI$f1#Tp0ln1 zsg72MFNun{yi6UVMmZ0&(>S^_?+l$Bt%%QRM_8+EvS_fR61_sYc;lqQ@Wj9?%&;gS zN}ACepE?&4cCLd@!{cD&X)#VunZ`3|$cK;LMu?(FK0&T0tz!8xSlzA%I`>Mz*WHyK zkfyw%`}?qSTp_w*5v{0vj!ax6hCd2H>Gc()_sj-TqUcKwEvzDSn_RiQa|%lB zIz*11-;IBYkCH=EZOiLlXZT!VGTaQ|=L_%092jI?h*b{A?O- z9oj`F#YU4rscP1@a2jeXOC{2v4f$aPgs+o}mZz_v#`j(flsnG5i_eHbRR zZovioQ`Fbn0ExR5YFDnnCD$y8bm$cHxu6bzFHC~iY(9L{iG`&_PN-kE1+5JesMj-d zFj=vYUU_weZU6R?eW5fPS3MCyFQ0Wht)6^*eC`QbS&TJ&@jfIhCqOg+ajjljM>87&R@jgt(ED zWa!g+h$IJD_Yrq2Nm>d%hu4!MwsOdS>;*wC(NuA5WW=j=yy%ow)U5dm$#Z8gy{Wx@s+bz}DxXK!4Cv$a zyG0nHCWax=nGkz^oON62Z#vFTix=kgkp8D%FF5KIms=JB>!C`rRbPzrXRZb5HMeY?$->tw&e`m)?W>cPj#U@+6umI6=wP$&V;^F_uJ1))52XLmAwQ$E;h^VnxGnStf+{NEJg3pfbN7;F zpusaaT197z_R^ZSPuVZ)GkFzST6o^W9Ub15NaymA8jra>r|L7Bv*S9MeOee? z7QCVzi(c?7>XfO+$6`*mO=tg^Nr8vp30!x{2+uA0h4){_V6a#-wkez@4yHFqCYI8P zom!mk;SG7pt8k9jT=+FE43u9g!_HNPxU4u26&4co4Hl>4e`!9f9N8H8`{7}4>=%W#GKPhNUk4V9_<$kPbB#cl}p!OVj$w02cB+@B=?zw(qJt|SO5 z%TIuY?0m?4C<4;ApYYzSQ6pC`*n{v>F1Hl9hYs}Df>o$Ixt*B;*$+2>>*c%j>d`u2 z#z~Qn+vlN3z#-m`3JsOy?|5 zOKTamou7`^MFPQiw<%;BtU{mTN?@{9pS9m-L`Bq0AY|!g(rPpnj>lgmWiaYbL zt2&WtPc_7u&C%_XZbnj>g>OiZ)Jk-Gkc*t9=a{SPR^7g z!C4g`*&75q@{8d7vm(l|qsZs%EO@{B5^1`;hVq$NaHeI5>|ZL0SJ#<>rsr3pnpi;g zYWqUmvPj;egum7w(g=_^yBrA0Quy{v}7KbB`<2}c68Nx4TS@`>c zfaS#~lB||Ymv=|fhxa4k;Z1FlnX((&TUBV^-5VszI2ls&GO3flHJrVg1wYm%!fOA$ z5W4Rk`%{wZ>XIDC?F-CF`wUC+f-eg_e_zvg3$Ix>edpoYffV>KHJQfe|DwZ_uCh}N zBiJTW7knzci3+^!L^jc%TI{qUuP+B+X{;Nm9lS;Z3w7bK+$K89Bm$>uEkeVLP{P}l zj4c)uAo0X+P>SMMGkKrMliBB?DR~%VcOPX3Iw!-G0Tbvm-j7;`83;FhOAqbb1})Y8 z=yXFBHNRL8-*^5vxJ(ycN*_k6sp+VQ?yPXj0MWashzp$@XmF@9m6Nl?`mN3=?A_1$ zmFLpWlcKR?ObRzmQ^8*S9P}9P&@SNRi5*WHvD)7bCo6MkqkZ%6yNWQ#xI4jvyUyfn z@jlGz7Dx9#wGh-$jz=Cmqqf`bkui;0Ue>-vAnKJutQF#6R4|fWys(uny`h9=NB3cL z8(!Q~xAmqTX&C1*1lH7WS<{6 zEb4)8f~86E!@pF0q!IT(9TswIqRG)IXklHCf&#g`2giz0a>E{6u)3GYVYwkrs3 z%mKk2l~ArI18Ip;B-tSh{5Xv_?OPY!7g|MR#>-$`!E}%{K0)iEpOYWO zoX*gw%v}8a4&F#9!3TN?{<57AW_}DTC(LA?x_^a~duH&puA$BL`B&0ec7hhZyH2a+ zIc{6hC~+E!qYIvCV@~Ze-h!|KOyBbe-_@qzVpfqawfrFJhVW7FeGPtWy@2-{`tk8q z8SpBTXODi_MBiQA3#GFjla*QeV5heSJO`>^^IjqFovjHr%`te#))(JARO7vhcf(){ zC3K0uKr7nSFek?akNHKQ_U3lHzKF#O*Y9JYVn0rfzr;N|Qjv@$km2Xj{QdKVaa-?h zs*x{)23CDE#B3v2wW&Z!g)N3>uf)7hYS=D*mY2J?1@fx-bf(o6*p`$HDy%iMhkW8@ zM?vWQlmX_VPwD+SP57FXkN4hwB)!vDpwd@c=x9C8<%WXrxq}0SIEGW7(QM36jm7={ z4A4h50KbUOLXmq@amh3#EcD)h;^@XKnjz7#{Ot+&G$j;-}+k1^fFUqc-^ ze^$(LC$O7h$?@$b5ueLq|BIvZj_2xq|9D7NQlStbl3n`9I`{RC6s3|GDNULxN<+!W zj_fU=l8jPD#b18=j5-T%Rk^l@t1nTy5T{v<0^ z5}))8;pBbFbVXJGU97A|sr44r*mnvW(-Y8E^Eir*MpyrJ{mqPSMp*d#E)=8=k=Ae# zQnjoe*4>&*Jd?+1?6#}q%$*lpzpE{^9^~QGx;1d}_Ci<})JAxY$xQiLLMO7?h`1gP zSe5N2?~IqD(Q!R^TKki*suLuFj#rO4ohKEeYeBn79&F8@5}2nzN)(f!{*nsEGS{V- zW1QeY-(Mz4JsFB3?~oz2+hp#y)AVCVI^$*0K&F2ALxp8#62F9F?DW`=G}Z7lH#cg+ zam(4DQZWs@%_N}hstP4d4`6@DClEZ;%*^8UA3-L&=;Ov!^s1p1ecZGfph*+?o1*Z) z!6C*oc|Y#Yy8^Gv!fE#PXsWSE6eiE*<7VMNE?Y8_5f5r&zFXaf;%0Lg_tc`+;|8Q< z;6B~wv<3b}*fP~>1?1`r55S|sD6-)c>^N4%NI!W>c0Ex7!GU(Be3d83ZoW(EFNMGp z0Rj{L9IN4H5X+z9RL#2<&mM9Xz@UTnRO!r>Dl_xLU|ea#EO^bJL(3BC9-mF>)@wsT z?G84t&6j-N$~`-oh2+JuVe%k!FMasNokYxBN>koFBh7aOF=7Xoe+%7*J9-y_&+ba% znwLa<+xeMJIT>8oB@L+GOaos;(y0gg>2rS0h*a)OO@StXwWRJXjCqbKb+{8(a_U z7k=KpQ*(GqqSJVP43E)QE)lS%H396!Cc}fVN@zKg2<9iBkZ=5_Nl*P22yD!ty_d|W zvz$B>XBog2w<~0sa4DU>p@o`<31Ql!Y4o-r3uczGZ2idqs9QM`POR^s7YeuxSy(CU zFvuZOB$e4tZjU?TUm;}t{Yb(NCqbV47T{7HRCm%XXup&N5kJP*v287|FLI3B%v6F; z1N%9RFBTLp6hYz9JtlkH0+}UW$3X4QYi{3qiv~wXa(j$9&_7LxxC?({do}{$?NbE- z??v!&8`o7+V*-2UJt5PNiSWj+<-n1!HRSo&aqwwxX0nP2_yrj-qXNr;NqkB^zno9* zsb~?I(FoeY=>h6C*<{n{bn>mWgMHSL2AcBibZG(~o{W7-Mkh^S;)RcaR)HhzzqJ>- zeRHUX>`vmp)Dbfd%fJ)U6}bM+6g-e9K~^+fBQ4^aV9%yZ*v+v{7W~SjK@Gcz?52Bt(Hs@7gLR^pY4u)?H`LQeO|>Yv)Sn|Yt#6o@kIU(XplQ71$SQIy z@uKlct4>Jwzd*_)nnC#BCDPU+%;?26!)JqNsCzmDw`()tW?~6gZZBcn9U0izVMo{2 z214VV0d|&?1I(4a#-=4Vv5k{ol3>ke^keNocrm(=R!_|Z&3Gx0+M%0?J-6vk zK0cf(FqKp~FQp0<7s#*u$r$fmL{sv2!M{!av9o=ZQ2DGCc^7pS7VWh~^Xg6D9yMTM zYw(X{h8DBae}9CA3OmTFKS0LUUxMDk7CJEVBDpP82wJCvak)n>xHSvH%}t7Mpuh!^ zW^SuKF769!>lBdhZ$BNBvV@gM=ZSQ^k%k{^24gaaq{WJbQ0h!N|w)fTU}{26NA1=!iU#6a9C`F7G0e~KV++e zjeRrdgsJhClDiP6I*ljV_7{4(@5B83GMM&T6TY!um~71yRHuLG{?n7e`i4AS3!6jR z7l&8ZNtT)T?GXj>>uab~{#3S0GzPbQ(nGPD^K|)xAheM;MWJB>eERt~8q;k=@xpRa z^)MJu?3#{0Wv^3V6=f>#|CkI2oukoAZneasW#BrLOz(eONn`db0?V~yY>%G}BN#9n zYD%qW^M>7I;q@F)-I)LfUNq4c-$#gm|3PB@%@jiZa$LpBc5o#s9d_@I1+9a5R2QY8 z>sdBFcwy&8rCGh{im+qa0qD=)2l^5+&e+>7woPdH4G4OU?3bC`wf@du!;Ft4M8rW9Aj4s*>Iocmd`3F~^ zPBL`-SUQ|&JN!Hl_q)K2Cf;r}LwTFUPDN>iS`nZl4ExWo)T zFhqxdv()#C8Qru`nD@SW4)54&4H$pW3?E|O!7-buyaCq%R`-kn(9#J|8GcPWK50P8 z>o{DR8^OLD(8lC_q7Zd<7O*d8QD`kQX&cL8Z5+PSqq^#F#d00?Y1!k$GC4>V?xlvK zr{L7sMy%!elSVTo{N=`==89(6Tyzk2%nTtqoj-}<(lgAI(Ssa^L>asJ)N$KXQSinF z)-}Wg%Cxni`OZQZ4fdixEM6P;zAS~jJG()@T^_swo1scQka<7rHiT(@2eG(h82;t} zfv*$cUqL9DZT^h8ICu+grEt646MsyqzsU1O^jwJ4_)Hj|=LGLAI>S2GRp@o~1{_|S zM)?OU(X(F-hG$%6+)dVkk!3g=_w^4GpVvdH)Q#XweGe14?g+`Y)5g9ZX=pxc6=}^q zOGQPvoo_@ks+p8b^$imN1r>p zm1`zX4Wz7~DcRN%fgu~Ud0#*Dz~YtdurgnV7xJPKJmGNHeaeE zZyD2z*L#@a^^!3EN-|aSUQZkKfv zH?bQ+muAs}$q``uqMz8R%d!D&eVFwth`F}22xsoN!lsX= zY7z>8H?WXyu-ZU$ibk!>!7Hsk$&86 zgymX$iT|AG^w{(dRP*o@JQiRLz9tM=!<|hJj~8Hw%mSz=Fd`n;tm%iQJUCLqLy0sk zy4)uaK63k-_9lJa+PW2R{f{uuz?Wm=9ZiAR+r6m(dka=NCS%yK6ZEP6Q+yz83tn}Zg)T)~aU$S1e$6jKy+(DS zj9Zw-gU4~A+7Q(g6xh#eL&46bn3>R-jwi2Fku9Iy;OU~v?6=%zPB&jd?$oZJPD}q_ z?w}Gm61No<#g*~DIpf@(&kde?^g)gb$3mDlgX$j61KWYwD%M78n{?kv}=IUMqkywKT&;-y??>D#;L+uDk)Z_lC5 zrFkSWY60$$?!m*QBa}J&g=yK_OU(^VgVMXe>eE}5h|+%}bScO6$|#70*iuPsH|D&d z4jnW{pX+n=9>wo@->_TQ7eBv$O`}hwVQq;oe)Lm@jce=3ov}H*liev$W+X)iv@5`> zFEOm^2wz<1XL%EyYv9;DtaqPI>c;!58R zVmxU9{x?sKP7BV!5oa5S^|=CizL|7J`5{>RcoS91*~mDY^#TzmbK+5K2=Tkm;u(dh zHG=Dx)l8dPikcC&H9w9D)d-OJ_?eF4=Z$ahM{NoGT9iq(_Dj&IkLIzxnsW3g*P}Ua zY73p8#N*Cn7dq762`T2COvu))RCk*a%uo~39 z)Pv6}1D@Y^Kk|?Y(~ali$?}A+ELSf}-KDE(R$nya2+RSw&+hC;9T}4GVix|r5=RzY z;(Ad_qG3i_JyGaln76JPB>d5F(qz0EEE0rhG__~WZ`^9^_G>H1^`03fZMOm3WattMcjSU17-dOL)Q`!Ts0z!M~;PKf>AU*xmOf+bts_a&jmO# z>Q3gISHr(q3cx?}Bv`nxRBh$u>Xd+^CILZGpxdBQ9a`2wwu?!DkisJ9*zN&lPLIfN z(>CCHEeGrKV!(ZuA=P|xonAj@g)!T*uxM`xzSoPwU$RBSfk?w<5{_0G+_Ms^1M3#@ zgGQAH{rf!~L%JEf>#jjpe3ycBO;Jc|Qh?9tO0bd_ihCBvGF_u@=!qAX$<&C`RAiGI zmIR)`UYUF*>9Ho=eV~@jvEV1+f3A{OT9--Qrz+~<|C30+&SEQnOQOzQZ91B3iT5In z=zQ+1^f?kq`^-yVWA{O3ouemJ5SYeufe<1yVg?)}mnSKA1FTJ-LXis(T-Qd^;(0C9 zOF9A~SA3vv_T|F(6tpr z_Ghj1zI-YC-V{zGJ+0W{sv+Q|KM!5k zTAH+Oyh?HuIQ`N!3rK+p9J+Re3?8{dM(bCSM=J!$ww24F$Z!>AY7CGm`_GVxCFk*} z(Ia|tn+m*M@`cEB{h%3tkFkOm?eMxT=O+o+1M9a$G2Z-7nUyWB*hMqp!U`Xl_q3a7 z5z8U?ss`!?uYzrlB+uc`eRh+qBOM>hfO9r4Na^WV2u*pz>`XdN?a$>v(lLM3AFd;I zUfEnH#W}h*ON)N&55?k)Dfq+89Oh1mV5w>8=Y|DrwDJ3fiSNwWHs!1;D&CdA;jm;V)TeeV>>?wqRrG(?7GYX`Ygzd z#xUYo11BINVJi{1riS}8s^~jwKU9`HfRf+!(Ml*6yzSj#;fiFF`MN={iBF4}bk7hZ z>s~?Eu4iDAE6j8A-UKBx4nxvzV^G>Q3?~J-`T0c}IdC!w&iuVXsHhhnJMou9I!Fn|mG{xAxNe7Y1qT z-NX1rV1U)PR)N1E8n{*?oaUE40;jXd#Prc5UJJy-lkcw~xLTdJG3W+dPp+pQE{4(c zU4vxK*|{WHX*oVN%EHNK|Imn8=&2vFy z+VxYw|93sS+dc{F+nedO`lS%`*#JhqE5N|JTIh2sg^>B3pd%*2yJW%7dwu026pwK% z4;67>`Dgf{NFbAA<3!G~fb^L=AbQGtX1|jjRW3}T z#|LUmB2+WU#6xeBmZNP{=(st!sXW2b>N0%3Z4!RGGfWS(cH+D+@tSroDO~dR2JRi7 ziD&(%W8JkH!sJZDLv>c9MX{IJ;&O>-DTffle|?}LEd_N3sjT$HK~k~*F616N55n2! ziGNKG)Gqi5YR-L-(zX|ba_wjk-z|LLBaBz6C!Sali&L&%!&^n+NDifvnB>9q;jm*Xtr;qAIuTfV>aZjrIs(x zlOO3(81puZd3|;dMjy05=bHk+n;b##*g6!b&82z9dI(83iOuJgD980tt8OkMeunOJ zZ>%lMZnJ{ZOM{8e@0qao{TcGKLY6m0uoA>i@ZkKh?{IW+I@pic!|HxjIC{Pq%DBIY z$MPLOB9(Xx3t33-;NB>2ZJu7rY+n4xYv_wr;r(|=o98dJi0Ax4nrEG2#Ve(!c(z)) zyiZ>a@>Dc$vpyhCB-cc4+{F-j~;Eqp+Z<4fvl|+Vr zHTsDC)N`{>uya?KFL^Ho-l!!h5PxAGj2+m%;pPc2LgZTV#;4XJ`Ayp%NaqF3= zyZ30lIOpNFiGYh6PZO_|2~@Op8<@mN;I1`GiQrQsz!80(pTlf88MzNC4BwK@)~USY z?RhXFy&SgBO@xO>g?K`n)wXz!(XpKl*SM{cSkb3R$hm18}CwVvZ8x#&qn`( zdiwmrG-#Y}661T$Z*tBGCNH{Ee=?C2g8HA(@k%kd2o=S1dqCom0xEv033iDoi>+&`;dqFF#0dDEZ^V}1);NF>W$kYA^#)?Nx z(uNk}xBtwE+h2F^lAevW(rO^^aV5mx;xbwjlkvPg!GKf+*qXB$Z|pXuaVhm|hD;{O zE|WlyNrfc0!yK)n^Fi;d0o=LFk5jEuNOs{X(y^d}HXU!JEuBw@TDk?b|K&;=|I45Y z-+6INp=hF!rh)TcxDnxt{2J0CrtzlpCd{`9eMpU^w z`RkBbz*Ebk!O0(qnZXru?8G}Jz_Xj4<7PxvzGC3F)gXuU&eA-kCv?82BK0$=qB^^b z$m-Bh2u<6JZ?dm5#Vh!DJ3qCNFmnY|Yxae8XC7h5G!e|br$=UUcW}v%uc_+b4d@&@ zL6g^P! zCz*=UIT!a}?nD&&YMWwH@9=fj}42v7OJ8nExoW>hWKL8^f(WUb7A zSb>WK4+!#NRzGFx{?mrF=CNEZJeFj&Hxf~e0LIY%B>J!3jggxMNODpMn1xxwf@!Ak z=UJ9rut=RG4IR(r!I**(@J(tP6{`fIQ zVZI{~PibHxC2teuoK&=_lA#-JxM6;h1kU8nAZhWl^!NBN(y+oBv2iWVFygmMGBn~y2+aEAl9H$hkW^>33qzDsj2H^+>pHq777Yfdv%-vwfb_1 zcHT>(xcpmWsyKG>X;5#K<)B)S%`EFKA>pajbii>PV>P6T-v^JtLuD0s{__ANUTUS+ ze_w?0{;xDiMGi_f_mRkHT<^@{B$JGU66^@_FbT4ZM~%P~HjCRi%w9mySpN#%QTRjc zT;5aPs4(n4uEWS>SyHLJkLXU$gE3@jM~TmFd|8xF?iwG(tDezd!`;X3ltf{n!US#X zx`z9j-Ox2;K0cO|MFrLy^(t2o%Q;0*l->xhy^>(vGd)X8vzdm;4x+(p0}9e-K|07e-p^| zI+LdT!K8KQAiO(PXL28tsf-81W3Z;Q&3D2XZX*ncW44KJel&A~9#A&y7RS;C`eGl==5MYOg>ptV;ZDa_#f zPr;^?*VIWPKj{)N**J7g>ZSg9XK2b}N9;K+hWc3?Pa)tC6gH(%o2kVlZKV_`o^hPk z%|2^#+V>u68YSV_=mH#8+DU9?l%l|@qxkV$9PVr=K}E-#V9uuqK94HMn3XR?Ij2Cx zl)H>jaXa*PUxXE>C3pd!Z?Xza=h1ta6f~NdV#?LU7&1SC3FEZOc!_MX-{B{D(qCoL z6R3>KH>6`?aXYQP!QzLssr3FbH)?&~hq0Xhn5y5Hz@3KTHSZ6#&<9!PaF@U`{F)iS zz2BKMU6sYheYhDCAhk|BAH9{gLkwP^erw~6 z9bCp|@&ZV^`kri8SwU>yDRQ56D|S?(mV`~xLF1XXNWk(#M4l_O-e#kRya68)`8kJN z(YCAZIIIpY8`j`5vnAlYdO1;<{)7ytUnGVXlu7hf!ThJ>n&kOi64oTyS zdHMwlcxOHCk{F-6@cXegujTe5)Y7_%dUgTyQA!MkE%CuVb_RL(>JAD|@bE+XTbzBa z3!hysq=ymYmL>MhVkvb4*36=gf&9P;d#gy z`==s^T$=lcsY7UTb3p2yNUCgE8iCPp=QW{QeTR z&3wGDSV#Pw{+vpX8PJ(^0BoGCNV;Pg5iR3*8fWa#=4}}G?zlj|dar;Rk7t3Us3*w! zWPl6bS6IL|9o`uZ5z&8(dAeqr&|umQPBx#xDBv7w(9amTehqH?uFi4B_M`WWy>zY5 zFlPF$M5o9cx-+Ambe8-j<$FX>JhPgd*W!NH!<`WN-&*SZdj-56{0f@~l0izcj`jS( zkMdQA;Mq$7u;y|Rr+57zv&K5;!8_5g&;APB8+c5X-RNNt=WL^C-~W-|AR)A#E@$lE zaR?X3TA=SeWpKJJPO4OQ(e_|2FE((UZu!uJB_4O^^291KLv=4@m0VG7);etY7C`3g zwM70!d??K4LDz5aK>3S`WbYF@!mdhzlD-r=qI8+4O-~^u8(+`_No6wQ&~uZLGt2N% zTsj%h4MUHxVx0H2jcSgIag5jioG+e&HFFkLT@sFElhRFbgKjsCzNb&E>h*wYIKT%w zfq3SN3vL^BqjX6Kwudgnk~KqQ=x#0R_jVCj|9wRg2f4nlN3)tNo$1v)YnVRe}V935BW$%<9c z@0(>|gX|bvncTrzxVRDZ;q!3v=VBuNQ3U+2oQ39fo5HqO#fFy z`mxVM$z);U9EIV3= zW3&uYB_h$zP#!+iMq>EVXqN3?jq7iJL+aL&L2PL`hl^iH$f1#F9 z?-=6`pNQyNC#*iAi#`3(C|1SIZAWLov|@2sXJHN-q$=3mE#HY<(;J%nKn*tvJz`&5 z$l-x04%oNNjbxoUgQI`k0O##O$Kt85d+KsjOWc9)Y~PcyoG{>DIt}~=uQC^kAA@fi z3n^8nX$Z&0ssA7Wf3EouwM#*W9&^cPcoHk?xC;4GIfm=*ZfaFI!e~va$8}Y5s6XQv ziqDV63F8`cuB~F<@4SG^U*5$XJBF#4?ihW(mfJsi9>I*3^K`|B$*|HY0+*6E)l@1=DQ!pJWTeKnnWj?GwX2t9u zcmZQg%DktUH{fSuD7@h``&OkS#>V#!*%opaPJf#QEwU|Cr!fo8j4h*0J^i$uyeEf) zBIrW?B0BTnC5S(|nH;zAgoN`#AohC^eR=o`adH)4(GcO-5)asZ{u(558Jk0L+=g_` zYdGvt!dNZTMWxT#xFPioh8ghHob>9z_RY!ozKEs8yDCVSQ5u|fjRil)A!e`NVi<0j z1fq`f!QCekwbrPRjNl85^~Eian{B|o8?VTjX`hKO*R8N3|36StJxC=U$;08m28fup z7)x?xv1@fU?CP(h2PWo#L}@8qt@(|94VYYg4pXT|{9O`WpvJ~d4}}4lJLGcjcG%sO zR$cx0G=;dc6fH#{Otz2f=9`57)Vo+)vBzXa%>*O-aRY|PPQvxAzo|y)CcM!!4SvKJ zgP}$l`|;^MqJF{!g72J%_5K0yUU3BaRH~VtS+2N2Q5!6yj+56OvCO1_OW@bY2ZHSe z3GL|i83`uFKTxB+H}IDw96Q?-3v8!0Z|1I2op^aghZIv-k3 zmw1ZMF3J-3Eqe5tpA#u9v|$DpU&c!_-_d~SZ%F0K<-}*B2U)r!5{!#XKxsEi=0zOA z>0DNO@cI_qQFECrFbk$>KMrHTT#kud$d6`QR-@?209^TUE9yjVLD19(RS_|ezL-a+ zjJeU5OaSQHgrH0EYLh(!*6fC(apbY11TIdjqUW}9o{{OIICJe(#XY(3dnmm&bi|In<@Z6H}DaP{S_>^Dj$^KUN!?N4*5OV?oa*C2Vg$QMuU z25_wSHBHp-##}NzVK-G&lED)%e2D8uHB$5^h24Kw9XG0~;f!ySSmPXX{HFSVt7Spl@`tDqP5MY zFj@EyrRTTd_<=Ach+m5-y?G0&u7<&p{LQ4yTbx&TG97Mnxoe*&VV-+{Hr!88g2{dL zj8$tXP5#SiJ%`%pl!wdkAXLzG;t_aO%Mj`=z9ZNETB2Z0EzPQO;5_`*2MgiEWL4bXAWQrtbgQr#lHi}|m_7JXH(<3exl zJl~i=GLqDZ?F*LNPLcs3e|s*6qYk}p)9~x+c_4khkF0*u%Q$BEK!CJ8n9f&$W1G@& zck>4Xf4F7DEfc-d62AN;jeTvyQbM2q<0-a(WogvewCQa z+hd2>iya`2e;R%8dpEXOM>3|@yIJLKLkKss!H@1IustUQt!&J2gU)%B5!zkd&E>xt zEe|*nCx@4~yWad2=joR?AN-XOfkl;JRQTada!YNDR!I$zSLqagv^wL$1skE8V+B-k z3;><^igfQZY1|s-jl*ss_+-^F{3Fwb&J97>%AG5p3k2!zk^5}?-*7zi^ek>(Tf*&S zJwbWfBFuHW!!8iWLzyOB=sV|0C!Q+cmR-3pbm@P583w|wxvu907Thc^LlXZ*!Xthm zQ14$s`xOhxRyczPI_AQ(rL*Ack&db#b3{n*gF_^$EA0Py0EIrr=yFD$O}LprV!czL z_8G@Xk$ef-Ud`cg-5$20W1b z7)(sF%80Ia36(mi0>6dU(ud2Jag6n&_;=l0d{EUvpT-APwd1dvRI!y-kk|&$4)a752Uf( z#U0jNi~~{KWO(DSAAWdiLe4gS$m>aj_mgIm!#nfni(#(2Flv+-g-78V(IDb;^ArtA zw8Kh^pY){CVR+bf7To36qwYB?7&O;L(SQ&ToN*hJncHl1nj!Auzlr&m?!x6)y^Q~- zZ_KPu=g{qOC2DAU5IFO#THMr;`DtZl@@uX?n$?!$6P^LK{?Wtx27DlD3>a^Ks1_N4 z6~2#{cfnF*WjAhP3`|3y>U$}#D zX*|WTAEYoMCIFLY4eEL~;IsFpDCky&Up@EYQ&%TkH!~Pro*Uu~{yC^nCWXgJEa=PM z{y6WKFy7e}!)d(!v}bh+yKZ(PdZiVbln#Yp*i<{vx>W`0-W*foW+c=VUMKA@W>di^ zQ|Mk*OoZxVAyN1$6LaV(3D)w#pUzc~|m1Z8eFK?%PN1x)$$q(sn-8v@mem3^;{!s((b>R1qp~JKN zX%1Nrw6}yd{tKWw{$I(~uPWqL2B9C4+^AP3=fUkUg+LK?^y3wh!X!RkjYBCMOnwIM zxL(JPTW8|-gmcWPumsqy{*WeFN*n(BZVbnjY{0`Ih6p9t5(U|2$Vxi^4*Q%y;o%`@ zzo?Ere6H9pIu(3_9upsaU7TdL3g<6L#xv3U+#Dy5hb>m4v0X6ga_><`?LE5OtO+kF zm9zGPi*W7y5WM?O2;OZtO74B$gI*R~=BPInvXovk2ZAK9rNIi0a%ZGnf%@=T6aF?@|H;eGvS`X?=i#LPZUJi_w{pKu!7vswm>P~fIlBbE;XY0jHg=EMOd60mX# z4n+9U(xfyx??o(5o?J@$+Bw$B)dYGrw!o2lb&PQ~OV^6PzdD;ekoK$DSJG z$TWMR)*S)^pUuEpvJ&1F{v)nuSHWs<0Umpn_UHuQ)&LMi% z4VljOKXKvhnKgV3M{u;CuSUqQ4@FQya`@;XgwCnWLTkSY;tGo^Ek_TjAG&oC?z>49aP zShOMtwaf0)Z9AGNU9%m!4<3TiRvlatVg%RUuYeKL`LwZ=2cgq0!R|H&LI;M)zS*X* z_wPN(iwuH)TdEj0ro1L0?=EwnUgiy=xmWR5Yg@McH__aXps3o(c1>HdT7d zuvJCBa@bo@LG+820#(u1Cn4J((Q>^`P=C6ZzTx)vixS?!x>^@_;I)#Zf+Wwiw+V(N zolwK|JpCGO4UPO<-fh`Q7~t4!)1OYlw1~TGUePSr?(vbNs#cQd4|f@xj}ml&%_uPo z8YT75eUP~x#jIKKj@XXqpq=S1W;&N)-8LMI(j1%rZdn$-k?_VGEsl$Sz=bN`n}s7X z=V(^?KCD?G2sLZ?Xbk^*VwVsA4=TN=_Hiq4zuZrL#Pe{UNi5g#y$pR%O2gVIi||f- zDSqim#XrZ_kth$Ki;br-+S;?Rv}+nY^)3RI#1ERZ*=fQq&C}Q+V+F~>C$PLmpBT#pVuwdF z{%g<18%qwrB9j-Sq4OyDVF~n==vi_n65&zDBIt3*WoE{NlE)SMD|B`RS)R+vVk?5 zabRj14Sbx=$`TnAyB|wUcBr&9wvhAj>59M}`!A&7L;_tm8~`&WrNElbwXjj57TD_-pvuaa%aw;gxr8yeKB%Be zHUR2rK4iUxR%2hsGOi!sDO=ssLj&xy$m3<9STUqSmvYg}Rj&XJGQCs*D6?+lAJxdD zRPB=)PJ$KKcB>F=-zK1GTtD+sHy1O92WeDOCSzy&kjnK*Vct7k`dr2g=RICQ-zkOT zdb#rI_;OojWAsw2dRj_K4sJrJ@3X*mVu;4S*@9F1SD=#cMY8cjBBfl;X}ZM)ngRao z@$#GW=h=RY>aIldiFJq@CD8xGH+s0kllY#wPyf}0uxgcu+1kqsaPVn4b#g7joN;%Y zRdNc&g>E7rUl7SzGLKsCSHsORS=e~5fi{$Upw_GX@NE4PbdA4PB+9bu0xUR4#=S53pg)L zx;ou8*`Lh5z|s{rv}v3`Dtx!jhK+ooAhui?%+LE0)wmY&wCD#3=~0LGv$|<*TR$1< zeojZ;TQQ~wW@C29Y}j&IA9|cqiLP`wo)D4Ya)}K%xi=eijth`@^&EPp<1+5PV*m?7 zq+p=L5PRR*(c_;@z~lTHD6lt#MHlR#?wSzvao(Z@i2=B=DIAB-?ZrvAl~8GE6zad3 z1fO^ZKEgVNe46KKN1mC+NtB|D2`p0fZF}l^n5tS>I*f% zcsdh0ytk6t@A<^hU@5*CY{bk1C73+Spax$)jr_Xr2|i~uQt(2XbGm3MWJ7js zPaqP~JMq|(0=&E+6@&cv@z?kaniU<5i{{=WliP&2eQYL9a`;AcI3LW0fJv9S7P3^BB0hZc!3QGrwWXBVMbFr|%yJ!4H?y zFz?Gx)+%71$s2(;B;3w@n3;cjQ<9o$-p?KDq`Pq&WT*FN)6NvI747 zn(*V{T~^#HhAf>C1*HbIRDRYZxXsOaUgrvEimf#r{NY6x`a4l2^{Yn17;YrF?=`nK z6+@ogO|;K{&6;pJrBQkU{62IB-W3FKor8bK_7^jtsmqS*wH3iEKQT-QjKm3>pG@v} zExmLwlSJopnE)F_ynE(#^@+w(YVm#=vj1%bV^RupH)%kH;38uFY6Dn&c}Wj`&|}NZ zB;nA|d#JBn0NEVFVo|UU+#78J%MDX_BaK>c$h;YhbRWPayNC2Ysf}1UT^C<|81jVTf7J>CWJ1G}n%hKfa+v#_c6*;9h~uPKv)Q_|ciu!{>k zib-+Ls_<(z%UuA!Jbq1rr$&&4xhKiri}&czq+@jWr7OGDJ{HS2mr}7uzu>9TG+xd1 z0jSdu<&Bz3@Vd{>=Y7dPzyrpfmrJJeCJnrWo|Pgz$;<=@P;=(>Rx0x*9#p~hT2-Fk zJSm>0$y6TigD!R2Udp^~x1$M}?abYWisXXx8kBxpPcrUYz;wCuXu8RV+^kU}(}Q>5 zW@l-9v8|X+-#Eao^IZj`b|&aV1)EsR{K^RG$AL(B3VA%UmebnD8RrAG7$7UdJMng; z+E=-riVNHD?&Z$rJ^!_bSL?i)>O+UXte23pZR?FQ~UbPfxi zy+WB6>eNDApW_?}*X+2Ej9Vvq(D>D9BthCZvHm$#KbJt~-6_IPWlmVTmCHFK@4%zM zv#4XrW{x%X2WFlUo6*W(&9ASeD4bRIcotOTcwNs zdt^a+p)37&s2Y8f4%IrIINe86Ei$UD-tksu>(%*?4!OJ za=fK}{Jg=Xio7q*y1Wy^b9e`{t3afGGB5SWFj!mcfzg%QvFFQFNNrQXP5koJ6Za|g zPPM?7g0wgwHr zGudF6*Wm{FFI0G<*F<@agDud8o-lUq6?xMe1%l#5%oO!KfJwq6^Y?6``#}SkSzk%{ zqcLjRYfLLIpTU+V0yPy~|6xO?YE7m=5=!R{V$`23{5GOcb4PGmP0(`jnru;7YP01P zx%^fNbMpNe!Y77LwXW0q|Hs*xg;Vv0ZJdyKDoIf^C_~5`>wR8DG%1xrX+TPv=iyK0 zS!5_r z7qTD{}sX%u^4jHjmLvcPZo_%WmooBfv~ z&Ke>IE-Nst3^{Zaq_JL6ZOm*>XESQASN|Gsk58TVz$VY-0P3nNeYprfaLUmCR{bSf z zSI;(jqI4Hs@?DvZJZMHem$=d`+7oEXKNb4!&?vZ?eTV0I_`p{M9q2gG&i0XBa?wv2 z_xxA{k1LXieeYK`;rkw3$!E;R%SU3?;77K$XMj8#Jci*(HF&tElgk*grRUA>z<7t1 zH2h&8eW&kBA6=e9pIMxso8KLv8|HaZA3vTKtq@f`qMz?aT`vn;q~*Bxo8z(EeTLt8*3^g@bMIDVwmrTMTd4^y~LC1)VOvwhG)y3eejdi z`$&S+;%{Vgj~7`i?E^&uWpuKe%yuQ^V8VBv7529t`7A2G_oye^i#7J>fB*sVl$- z=_+Km_e8VknyL;4W1c%`%gUhYt+NtjU_CD_v?v2 zdP+ue!R!pvV?ObV1y^>SW-SZvuqfV_JWHY!do20REQ!@z!O41Dd@4yW$*qHpD3r&` z&HhBr*#-OcZdB*-`HGs9Z`_g3lDN@m70fC&zB0L?vHF&?9Nayy4KrF=xF5Q^aQ}2i zoH{CvFxQ1pc0Ng97`+?4${k6}sZ{KFzm%AoU*IljxC?4M3%O4|;{=hBx{&*33S=#6 zWoj?&aoNlcfyz%!bXu!~D|L+EYV#*9A?zntXl;x)A`X)IGpD2K8AbT7+W{RVobc@= zfN2~2$fWC!N$P~BTz%nZcCf;SOFr|J%}kw#S3fv$>L;UcNN!jVFtnA_oYcVIc88em z*zsuc$%GY0wc%A8ag530xLdhvNfJNr1imu>?Qm1HZ!*TnHJzl#T%P|Z?ySj2acMOJcB(UBRh@Gv@Y$v63A&%s;~!g7X}3Qp|34w9}p6(@zIiwWD0Z zA~BeFVL5x*;Q-4uF2mB`c;eW&i1WSon~Bvu5lGkE6qx8&lGdAi7j4dCQV=^@P#2Ji zt#fs7%#Z>z(z;9Th3b-x&Zk&0QDMo|y4ZAB4n0yXu_VcSaidaGk_9+zzC?aJvc<423y6F!V9KXfpzI4uMEe^U2!p_;`Vu$C zzzmL#1HP}dlemPa;Jbiu%+AojkB;l1O4pfm8c&4UdNre*W%`YO2*4wPtrY^u|+KDWD{~6{n!3V838scT0 zGPJpLQt*uTaVVt!V~b*y+0>6A=r?$U?K3oH3NbRcsHTySi^rHZ&sX_07>@M%=4u&> z2($ID{h`ElJ#Qhej zXsWXe*L;s9J{j%;kDG^Zp4|;5KS2V28G5lrD}D$*d);6&e3n|9udYG42kWgzMXA9A z*F5YGE@Ha}j^da9)S3G+JN&J-9LlC-;`R7&rWPB{ciYvnsaY~KQ`&p9b(mXh^x4KolBaqoilGpW+(Tja4gXeYmPob>kC4% zb59?hb^F8KOQ(Sm84ITM#jrThlk`vHvqMssh=iJ%Kqqpoz#%6B>3=>Lrc=P$2fuRO zzY_6!T^->>4WW2r2>CH^l~m2TV!fls0Xucn&^Ifdym6Gn`ea`wlDLoe2oMD@YM-x3u(OqHFU8j87#dPv0Z1l-p;4)2+sCt3R&(KYiv^Z(q1a%DVq)gH-tNsJOVVQ!Yu=y$#xd$-IaQf-s0m%doa z%C_mCrK=Cy^DKx-xC@z|x)CGSOW4=?0_^ZtMuT}DSg7W0Y^o1J-Iz@LRv<3i5VjN* zHdbL48G-M9DRUxo(#R62=~(sHlFwMIg#NuIm^Lz$)t-Jz{`++wSJYOqU8%O%Dj0)% zo{5vy3i&9nb&M^kj$_t00`Xyr757!v1myy3(K<&7?^Iuci#!kD<@a=Gt@8liS2A?! zZoXTQ_hUDN9pwtH_>!Sqgzd(ZFs#iB+ED|Z~kH&O4=Ea3<$`Gn(xxoY^{-yGj(hzVu3 z7GsiQ2#c_-MJCCQuZz#Ig48?A`>qYU9%li0{Znb9pc|eI2qDDfAH--Zham9@R< zOyr#eWS{!Z5+C*oV)um$WCBgG&F&OiN0eaSm;|g|7>1dRJcl|{5ubPEV}^wtTcOm? zdUw1Oq#c=wpC7Ekq>OxKcIKzx6ekZ$YI!{_qK7FhNUIi~nSkrmkbCF4~DrL#pz$|$@Hw| zLfjv62G6}g{2&ZRnd(H0sCj|$w&R4+(i4OWjVkf+0tNihb&I{aAtAIrumeZjD@WBS zA90<6m@sNnATBt54mW6QgOah8Y}FwhEVwioau@A|H7~A`k+1kn&k1$r7_I~NBj%vl z+I-wPa2LDX(pX~o51eW&AaM!4f;ihie&1Qm1|BXZ{cEbZhPYg^Z|@dza0lOA)gyyD zR`dCFuFu-9H5SLl?PVFQJJ99CA2eX4=+eFkhce!>Cv~!HY={!*#bglQq)52AH~>b4 z#e?5u#JCdDQ;XP@!@Iybs)=;k-iHX@ zzifGJi0^EZq@{rjsy+h!^ZXOJGV&nb<#b8lRJsJSM<}t)*HXCE?|F1|yh z@)xXm94z>rJDyhgThNzVWrRQXpU3);3e?%qf#!Ergj-t^@PpGJa-SdKz?dW)voHm# zHE%ML<3)lx=@LYq4H403%kAB;1oKwOVsS?>PL)0Ykw4er=6!CUBN{=jsXJodW*cl; zIudeb8R4i!9mIO+1-5KnBPwkl=Dw;r;LF431mBWEaL>hjK~JYD?q9oKpf$7tkH1wx zQ~4=)Flq)S+Sd?qr)_93!Hv~jDd)Zqufiu!IM~r|3MM;&E&3xMWd)x|en~!zP0nL! zdlX>jX+4<6vm5?xbA-WD6jV(INwf4$;y1RNv&zWC7ZMeCvRWAj=ou(8NQc^xji5d> z4j-&ygzBWT13t6ilJ!-=Z+Z&0e{zS1l3vy;qr)KE>jSa8dz8HS?nWkLS%B5%2gG2f zB$oU>fX$V>=ix2jtkq|5c(ot?xVWpjQuP9h+N^@LUXz*l6LFmUI-H3Pb(5$C+i;}i z2X?kzoNPC7V*c%$(K78D^OYD4dHx$=FxwzEJAL|bLp?z69*|kUu&OXelx@MV46938ZdP*vB`yGS_zDE!h_ioZHnTCT` zC!(-C4Xe_l@#ZcKyde<|Gy3%L;H^NMwr3*yX>Nw&t>xLa(n=y)`G|z{#8`K*^_;2x zXi(8g#-)Z)7%3}@qsmJ-&ykMgyj3&t-4Vxf)>6SFeH&;}9>*p$*`bEgSiG~+5ay(8 z#J4PHoOXUDL7bOPiZ}y_z6=QPv z{V3ArPEp4>7aPwVA_uPiBO&tJQE&4CBGOsHROZI9PW2D$OID^}uycS&I(%j?0?ncS z$QO1={~|LN4doVZEF+4i_L7ShE4bMU%GrWv!{oJ-F@(Mw4~?c5Np0>a*vjjHKcjU> z;rdW!zB7^R>zq@i%=0E+JsKuG#Usd!(A_9j#&@#j9U_ksTZm>=7P;YjmSipW#1*?M z1nWALs(w8lBDoRna8qGC%;H(!IR!^xm1zZ$%yft0DIxH7*L+B8X=FCap=fho47Dfq zFhTcPD0>qCE4)6jr-CfD@<;(5Usi&ayE1X!2{-op-339h=Q8rote4aKdJX;ii%{`! zGfs*2#l+hOxQf}v_}KXj%4J*Onp7p^*J#!?s}<1n+Z{p5!;#ztgFbRr(}_DKC16%H zF>LyrVoZq`hwUz+Fr>E?U+#K^flJP##=n>7Hrg5EAp#FNzQFRt54iMjJ}!TH7HzKZ z47|`p+}CrTI0v_q-p>?q$2NBTnI*GH*Ta>E1#tb)8}O-n3@`rt1d%#rDn4fpD1`zY z5y@+=&etL8;#UZ-vVy*kMj&pdNNuJ1$ZR!9l#dxpMMkwiP11YvUe28?eB4HIcBrA< zrc3CXc^DthuEScfAm*hz5ic2h!qd-cVe5q@aL*-#MK=dSqK^(PzmS6Swg}t<8VW<3=;I#JvC+H||0 z3tdyHN5g;cx_R*^>Yk?y${*6%P){?4Hbn9B*eJGqu>p?yGm2y#Y(uBt`FOMQCYSKO z7R^-duz(X6**cylWc8{O%N+QQ$fa2V6+3Udb)q!wQxmU}HwuKx(vW}i$_`TU=R!U$L) zn2NG@Rx*jVbD2UwFe#qpf~9r+96Kz6RSQSp`}S&ZkL_Zvy{}M7PKnLm){9@KMKWEx zQ8><5A4gu-#oebL;_8{7n6k-pOf^`G7yVX18%cn#b520C?>=I>y#UJ3X|t^tQi-Df zD%kwI940Imr;XdQ$!)(9@Q{$9o<+-<;(In?QdR`ad^hO(kgjN@f44sEAM{dEgp&Q^P70j%RZo(30d9vd5V)P3* z$agsYAv^Zy!0D3{AXC{Ftmsr|l|Kr%om`o^w<$c=*MRB5kL1?gL#%=Csy?Ci2+DIU z$V0vZ`DkfA{2Vu<`XQfrJLR|&JI8jSab5s6Y^z6ZQ34yXk-=rtr{QBU387zS6Fw{f zEX&!Cf&VVyf8XZ|EZ!KR(vvfI_r(<^sZ)+?>T5u>`Wkd59wPFS=F%^Yr{Km^3vN=U zEESoQ4t?$pjOB^Y-(4E??Uax3`M4pCjF+KB8DHUFf;W}?H zmp%*JM31{lQ>zaabW#VQ(oq(4`S%7e;(Y@nVkIGLe;9N|D`D~1X=pi+LzcZSMV)Pt zSoSIjzZN`U1;%$c1(S6+w`vYbSIoh4A9FA^AsxM4WwBH%4ihJ-QS(f`|8MpPI&sb( zdi|6tJ+N^$&3|b|A6}hICOHW{s(-u5^Z4y4s)+2WF9q?(dHftGt&ODmk!0)*;uKRQV z&+IbcpPOOm-`0VrEL36IA|dvqm|Jh(^@kiBa~@Ss%VI;}uc{!)o7}3J1p?@hozC8*av^8?Q(oflz{kkxGEt@;hUO?21BROli5xh>Y z3N>Dw$9)|S5DMFI&HQFm8Z77811;=~732M+y%_!K6gvcVc&gBWc?MMC`ITu%Z=?{F z@=&(zUmpIe&nIuTb#UtBG3j4qiV-VbaMD@waN>M6Yqs{m3Cna?{@Z*sXo_WrpDEz< zt6nH-R>Cg2O9-zu@qMS`8qhq&gJs6H;nV(~Y)gzQ8uPsS1Ix=X+Q?df#rC+h0?9D~@|TT+b{`Xx(^kidAKRhktQf(saRyu;&#Uv+kiiB~Ni3eS7#6

~{MrNLR|Mjy#uu7cNPn2k-H(>@f1tn`_mkB-JbFh_uDW%_5j@axEtTBri9Vcnyl+0gp)X>#89cdwB=D9kPflnBd3O4JR^*IeGALAcDA` zzD%yKw+5CQ#KLXl;eBQhj!B4utVfN|@%=B{*t?8m7JI^@qHgQ9QHIc&+YDpgYy%DZ zrI6MkWDks`*v^_I@VZTvn0|f1$nOZE;}?!!c4pzVc?NhqRDdSSba961Cw8T^0FB>t zB5wfVJ<~$ezMH}#_&sH_#y41N*kL!?G76_Ac39PS!|$o z4I6D*#_u@_$g8I=aDwkP%J8|!&aM7JHa(4j+m|HZHvb!*wsk!2c`O5(Po1lC%H{CF zT6LUN6o|Q(qpZlvXjV2l4CCa-;T2sw7)~2OMlZOX@j`X)|twA=qmmH19 zF5D30@p{$#N2;u9M-|$i4q`4fhPa^U3)3B_;W?u#nZU;aa}<9tN$pXX@+1I~78!s? zFW&{WPmgtnP2zsHnZWlwZlvaJ8krd*#ZLbFOm=5UqSt64^X>42&yrVJ!yY{@Gb@%2 zb~mt`yHa>Y=^*i#YDAhEUb67+8`bJbNdDyRV`&v~xYxuDCI?#KwmBOyM`k7Iow5}d zUQHznJ>Cks_VM}Dd&(Gkc`KXMKLbi#=VEh4F>{=xK$4~HhMZHN-IY2 zH1#^>@>w49ugRD<`x!glCW^Pm&B5OOLu@V2O=%uAA3vrIv%Sj4G4<|3(Efdmw42vs z+J9%TDEbH6P%6ReIWGi`V(F-FCJ&7hX5cF~DcI2HgPBRH81Y?4Fh%V%G4zoF-566S zJ|@rmJd3fi)(GW)ZNd{SU4nvhCFBSH%$gVMjt09O@$dH#a*t=eYfqWU&$afvAO0H) zHWw3|lWJ!9-oMCl8V5=f4>8x->o9l8B2+q1#_8qtvPx?TCvL04tf)^a4m@uGeIrOhs52*6OtFYu!r4p$fI6h z@~0Fc>mUND^--X4`UdEE9)=Ic=R^BV3)B@E309GR*xN)AEZF^mscf)?%kw^1PrBlO zN1RHDd`A|(bK`YOxpHVWK0w~-gb83nIv!Zn!r6t5$9+3oiPI@#SlW`szA34a`7eIV zy8M^mWYrYd{WJ(RblrqWzKdYndJ%ee&=;;qn!`8kx8%v)P>`Q90lR{f*s2%z3ChP> zTaP|dwIhZBCZk7F*n9&zE&Yg%{A_k2FCKl$-2~c!v#O1&pDP+};yhm` z%o4&uTs3MX_j79=%WgT(dk@9XdN3L`^p^|bls5cJ&-U$?gt_c0RSRaZrlQU!wd^>e{6 zCXu<$sbX(tFTnUa>Ew@ry}f@X7dJxW*FJV{f+Q5|5QU}Ln&|yX0#`+4g0tyG>zj{LL6qO4vcF=` zWONJ0&Tt`X4`~ZjQZiv>^iOW=@?+do)o!vzdq230JqYWz8o<(lLTQDtR)?|m!ufD)$tzAt<_q~=;SO4_*MUfk zGQ?ku1GD!b+?H9-%@3?YQIY*21H3Yy2)!yWEQO9%}~U`AOWK=jKFNHCr(G1`Jvr8b&??aD-)RR9tVz^-GX58aE3HzirurYdFY+cP7T#``8Qdirfeft$sRPjcz z+13P|P3FPcalvfb>lv6kRhwAEhQRM$4ajdw1=Y`WP*`%4*aZB9I6rkraMBX!ycva; zf0U3)b0NTBkM#zvAlSCa97dmc#_LXf@MH2-sQM#LtGrLc!UkW4e$@u3raBHgzdYtr z-^$?;1vyx>Z4sK8aCk_vi)R{(-Gs~z`wCju>1^2Y%zzWizKD&SDxcU5=2D) z_q}wHn7D|DlobEz|GdVCfQaXw4V!%rY&7!r+~;XzVPS4zW^8HUU~46^`v3d-zQUbG z*?)l7D&OFR!8odDH-Y;3&7~qX?)2rbHyw%yp~`QH@lACV4m{Asp9|-)hVV5|Ao344 zcJcl&wOEqC@ANkP<9TEi67=Zz=kUj98NGCG0^Qf}1fEHP|O5K9oEdbF;QQw1zj+WT=|k_{A5UG6%TbfN9Nq6Zjf!r&3juBkFwH@g zj!8&@ky6Xax+}4eQdoqAEyvh~e~ZvbCK|gQT!A2$AMDM-O%OPH2d$Yrn-+U4qpzw| zX~wczC@oBd8>bCu#Et@xC?Ry7)K`c;cMQH{Sku(H94JekK$nFigX_xsP!Xj{=X@-O zYw?A|$WxJ~KREzNJEH}KaW^5uKN>!n|HaRT_`ZsUVwfr%OT|Q%Q&+7qRBE6Iet%Y_ z3RWI8;l&fk4oCpufCzOs!%>S3tLX8tURWh-L46u6>E-{XQ|EzE^uL$WXxWnx8ue%~ zycMzKGHq zGF0k6U4EuYRK!(^1oN*cc({;hVfB`UH+>b{cwg}e! zdWyUe-A?;>Qt}a zhFU3DP%bn9`o8Z13*+}dZ*sIx`7*S0SwU+Q?_ITT0Oh?2c!Ep7_t)C1nTazrt_sGw zuYXzgY9*4tF@VWR&BDftNy3Hp*%+~7icq$t9=iwI(avcrJNYpOWM`j&O@pB%dBHcf zP=2PsIJ1Q{g$EM@#nCMH;(grbp)35MzgWmC6T)$W7Q%!CXQAiNL80L@ePM*b6;wO! z4vSka!}RF`%;uglkjIkrkt72*Js;vDeis^+1@k!|iq%>YxUbR^YGn<>vHqL;#aew6nM65LbK8`$@eUq@mI$+Qe zAlUUXnGG#@g_{3<;ctr5RZbB?h+MY7a9YZ6&&Gl{g% zz74}Fg`od=F@{eW3-=Qz!ufNB0;3<=(0%*>M62gQ`}OCbtUH=E$azE4{6%zPMLNi+ zeIv$1fvm6Cj$0kfN!s=Z7FZ|FJos*Q@yZQse5N#$$~%rLjQ_#wXf41eR#a12pIV*W z2O+7iA-d@|MDI1Enf9;YOz0y zShgVsj}^SN9@VTV^yE2dV)|CXt+yP7b~3)`t;J`7&ua6M|&#^;C;t<=yo1UiP)`Cq_Vfls}p4 z9>L`p-$vINIy8>&ASx&D zE=?QnNl?d)@^t;u^)yp_G<|ZS4!nz=qp-dS_l0HP2#*ideRE&3i_1RYlpXf0{!ltO z)T;=EIc3lpDo%$}W8u@RbT~h56~s4KK;j&N_DYNJo;=_2yT}(FeQsvItFieIxnn+KGC|7Bb7V2==O*!Jf7-NRHyKQClN? zkaU1a&Ah>4%NRbntxC2ODbedH6X@sZ;#Bxegs!dBqI)i#hiR4jVQ>CZ_#8Kq)CJXp zL1-T+-z+7G6&{?X)Lx!@B`GNLA7vmJ)&xHv1*no1qfayE(Tp{T@bG9NSt}(=9RmwtLy-iql&$b6H=j** z)54Wd$5o_r?C4|U#^wp&$h>%>{&78A)lr7PgUiWHkfF1JE$O4TO+2G-BMjYk<}Rq% z!saa*WYmu8>Y8tR?Jg3@?V-iq?<+Il)QN89&?vxqkm)GgUU62=JIZXw!%FylZybab4D!jbPwyjk`4FOBv5PBL-zjcYV2F?0%ie6p`%(9 zral^G9cylrPsjYB`*Ry;FJ4OG?Bua*pO)bDi!~tqUJ_L^v1Gw>b z6Dd2WK|Pil(|@HK*{k9pSbtKJYKNYJjG(imyK^EAbPt0>Y%MfzsDlW@V7S)Y2U(Ui z;4Y#=tWPh8OZy$rC@>xr*SE7|)$Ho$A|tT;T?u==r-sj!q+*A|6Sm<&8gx1qvJ2ne zz{59_;4yzrv)Sp6rrZ8P+afXAlvltFy1P1qpEK${X&%tPoH-_l#7LQMBTe zE!N+iDzqN;fa#Rl3P;!S{ph2{VrgYH{ueDRyg#XcFbd}LK`{_n z&Udjd;uEl^MUMqj*3?4(ccAYL8vKDXB;|De&~q9 zK;3E>Y2OQ5MB}iquAPNP_i;6=CZl%yIarusftxr7w#p&_{M}3iKT2PtrdKUzv~4{` zJB<Nf@D63I+$?G>1yXG|OJG>}h9PQWkjLG9{d91vu1 z>kp4+E8O+)(Z2veMUuXNK`1CadJE&T)0tD6BP;ajVOrtq$lLM>)XR1YCw=)De3l+V z%ePFXLC+kh_Nl4#&y-f;(-jQ!{1t@7g`pVpCm2gLHVXdx!fVI#is320Pw1Y#34L}W znZWAc*t+MS=$*mcSeFk1{X1}IS0lG(t2~vpdjb*b=h4#RMpS#L3%G1w0Gp(nK>5da z?pK;7Ro7IcUc0pDK?gaSlkkllc3psu8Ddv4@JnsJ+D~CvA%Jo%C>Pv4n8z{sd_9 z)u8X*%7C=(H+cV96kg<+<418hh}R?*;`%X(uuthU@z#1wj8DE1l)Yv=bIS%4Mb|)cQ3lxZOo6F4 zE>>Roq6S9P6Q2HA4QJMbgQ-Xu3?1rQ#KL>swuIQMP_>khHAb`2T_YN$aVUlt z-v%AuvvBoAK0M;eK=RZr@}PGkmoZ9>RKa01{#Hr8#rbfj+{z)$E0P3nnU3*iREWCT zF~RPUl@Jp>kB*u61475E(jVc^LH~*&o&Quo6q8~gZ0R9ze!i9sommQ|i=6O6BERqQ zi-rFp!f{3b1LLXAAo4mL+$KxW&Y(Lm*Wd_9H@9;|zCoZp+6we!#tK%Z%8@AZ7&haw zE7QN(2S?tC)Ajn_$y?r6y(TaR`s7vdt^66mcP<`=jmrdbmf7$(ocEkg(gRsR39A;V zfwm!E*#AeIDEUmr$xF?de9j3tVD1fKOIk@8&mz3PZUjghMS$knr{tdVNZL_69z2Bs zWE)ik|J|xkq8`XLr@w?4cTI9GL!LGrpAHjSFOi2&zr&9gyszV`G+h(m3BH<-NO#41 z$aL67G=AyOrzhj^O?MtBon1?=IaaWB-`|jw^;b};TbIwm+y#@CE|`00Gkx}W3AO&W z9|nx2>6eB(&>m_)7jAH(4tAzgr)>e`(xAiFH_)EoF*K0%;8MFmmaj2Ys2e4Q z$9^fI)8uNLHok#8*|mv0>($4zv2%s9vcIAIM`yx(duk-u$8wT{=q8G5OXAa*>t41|yCcyf1 zKm4ZBh|5;hBcu&k&-Z9X2fJjpC+-Xp5v{~9uiH3~B1iixM$(OIXVV*ntLSoAMm3aE zz+2guTCO*suMVnE$2r@e?Sc$lduJg{)ysfV-eWkrFc5AVAE8Tq+h9yfEl9371ruMq z0@uqr(9-*gY+l|4)I)$tzQr(Qv=v#OXN`m9&mn(K4qQlk1+(|;r-!UN`1{N_>g6@~lNY>&w(se5&}jAaa- zg@H{cu`ae5Lvr%bIM5vBD;O8KFl14;1`W z6Xr*Lz+Ksk*k&#le;tj-k8)ik^;#~TxRwvo@0r1&`dPSLzl5Lv%b|L;4jqV)fiXw) zs87%>lBr(~!qTxstmG9G%v~Yu5?2y_=T-?fu^GZAegVQaCw}9Mcb3A}dyWZ{>n(&Q zF8B-QnHLK;k69x0)JYY3Wq1p*B~JL>_q_0+)Nx_Rit9p)`Yo`3nmD{`If`pyMNvaJ z9$q#&ko8<8EH-T6&ksMV`rBQF;^XXvr#Um>Nr_(=S;YxecV0r#-y*^_5hYmeX(McF zdBRf7=3#QnWML1;3SIWTuZ~Pr6mHpDgB=5{sCQfnZS1mf-a~a^x8^kAtG~;Hw@zyd z>ps-rhOE&-XYm`Tsj46>HHl`&UW?(;kXcZ5GK!4cDgikqGs(o*?ZoYf7~R^_LUg~K zM(=-nNO9U_D4F0TGnUuD()7~`M3%OjqMOOn}f}J7%cS~f?0)===TL_L`+?d zC4}9Dy*e!zkQf9jO@bjNwTrk^Ok#7s<+7;vMUcX?|E>7%rz+z*Q3xFkS*hc(s#=#C z={nP5F84D+;VZaa{BYYVPtve>OSQL=iinDD=z z0Py7Jh<^1Gq(H0}TECrVMz+&A@wW!xvvU-UZJa~93S+79?sO^{e4f4xc?QWYZqTEt zPlrPEq17x57X>^aA}dp%>PHC9isgGx_ap4=nMWq(T9PTNM$@jq>$KS%#S z&5Tgot@@hX$UjV$BqQV;$bisY2IPZoEj1f?oytb$(ae@Jbj-Uvs+oI<9=w)LkH0!W z&y&wo+-W1uS$KjNR9q93{tgH24>JVsylp|NN1bOg^pdE!Pw+t|hS{G#iTLm#x`su; zx1@DAvi>UmSvwj0Z`oRRh2(J`mb-)8#CYCEcMla7tYOBOkFqYYsIX%ipEXnzswDB< zsa;CKYpz$Z>FQFfE6YP^n<8@ACyy=Wy@*lS@2cHGBH7ma3m|3HcG&Y>2_v$OVCoiK zsNXNkogSDin4y1Kpe%0#Cjt$GX7djTH%;0vJZb+|aAr1t&rTDd8$S=#ZW^{6eUwZKI>qeXyJq`}NHi3%PQ)Jc5v#>`*2;yQF{B}T?icK zMb{q%+OWx!P5}>E?wUkv`MYS#j1_d=MiF7nu|oWG=L@bsJ_nG`t1aFzlKp$X30im0 zgyXa3;x)|}Hiz#_3H@*mMwrQAWaK+o_Nok;R!Gq)0%Q|~bsGNvVb%szhP85F}`31Qh*ZHi&IQl#7ILyD$ z0T)cP@#WUV%*}oVGQBsdpS%Z&2U%gsP#@oo(uc> zKAbhzg!vT$FuQP(-I`g9>HbSl{9K1%=Y={9Xy1tU$WF}iPQ&c6$vE-#ED-#g35~nV zU_|^Wus<(G)mD^%(x2-Bm;AAC_CzExn4ttQ9&PZmo@!PC+fOJ>(!5ZAl0Huyb&^d>yP;5`_?c?^mNEi}Sm}*`RqbCwP~J zHK&h3_J7jCHAyvGudEIpSS*cdQyk!6tP{JjQ5k0+wFlXbD6s09fLF2y$h*_q!CdSi z+|i!P_dTofITaf?_PdEmXLePuwTp$0*Dj!>TMYYJ_#P*dA($YV2l4SA;LSS*0h@u= zkN?e5q{fkT>s4^sBwutdRR{T_jcgLnh(8vUfK!Uj!cPSoY!{n?1K!5C`lu9`=dH!4 zJ)WRf)ej5p2wWT`LF*sO!^oe>`21z8paqVx-PhL&7B)M8Olm8J4c7`bibmi+o`dQ5 zqL^n+B(hAMSp0nbIQHBa5d7Y5!OVADfwv0hVb#o|{5|a%+2dwLmUX#eO8R4_D_PEl z@3_I$GIdv^8D*8az_&VB8D@A2BNp#jR&KXZ63ebDLqEL6Cy0YNYG z;R9crEX(K-Znel|TBgZDY1>>F{a_~;x_UFuLdU|RyjD2fdtT`Fr2=ACK7bF09KlfP z01SV<5In@*gT)~}ws)p;9H(X`qBabMG>yaO&8^_PKm@UsD!kMmZ((xt!TJ}dU#zD2cqlQpckshj9l#s?(4pR^&Jrl^>5+L{x7Vg{4|)J zHG_1hIzZ%f$jk-$B?tse#WJnRzh zSHvYIVPh~9YdQcNxz75H5f7}v^# zGnsJGs0Ew87%{!NzL+VahW#_5;Pvw|Uhu(i_;mEMUEa*$5O#miKkc&3{2H^oU5hC& z;`0inN|@L;1vSo-q{y^8OTgPT0E*waz`P3!!D;6zINQ(ZJakTk*3fTkplA++Idhul z#Y3=UwIX>w#0I7>+QwWD8cp8&2Z8YMOelWx05Wb@F=i8ok!7w)oF=v+Y<+Ttxs?4H z=44)kfS#jZslc5%%_hL))3HqKncG08yD>Zy5j0dB;`(h2MqD^;_q+Kk9NFv)?rW~w z*<6Z+NgXN7_c@l39LxZ_c|Y_naEH0k2N=6_DdKGTiE%QOLMMeY(C%4+b8~We*X=@Z zSwkA;PB3K_=Z}R|De}1gdJVXK(g&Y=BiQcPtDxBwgr^Q5FiTQ6UW*0nwf_bA{c>bK z=aalDxE*vrg3M@Z1v7UoGD~$XcdoJ|JJm~J*2iJwklzT>c<~XuG@nMQE60+R!AszJ zcLZqI#6TY$W}fwpWMsAP;J0j7tZzDu6GlnX8u2Ec12dBGy`@1~qpa=B=A|&nH@H1; z-C)%0QHKNal8|?HKbTLRLeBowA)5L(SWCk^hPBRvhb{tk;*J*Bq~gFhT{2>fQ(D-e z#hkyR&OOjS4NTgMu_X779O*2&2s#EaupwhGnRIR)B-iIbe_kYaXI%gzkKcswPcLCf z$sFdu6FbNXjpeCbQ562x55_`{>w9anB{j)a1N*@r(d4EkOlmL(`!^}9Sb!KgbTE^Z zXo&{hVam+@>xRtGf`v?Y(sbs+?ZHHBK`DsFyF;S&6>u9!f!2o|Oj}Dbj0s&#CXt2Y zei4`R-)%~^l$OCQ-+Ey(cMi-Km&Q8NTwc}BHnwHvIrwRx$4W0Wfx;`_!8)@5=1xg~ za1TXt=)(y+i#aMJaO7j=-Qi@;w|gQnu)M_7>FZ#p#(C&}o6D>bOvSNpvss&(pCIR- z$7-zYhEX=3;n+cc-ZJqB_~qXW(=8v^nTXsOt!h5$8(j|V!NW*V`5@xZ(aQGO-N%bj zE6^gm5G}cL%&~A8*vg*AW>$nBHkq-fO|`+WJ_>@zon`J1$-ylN-K=xE1bNCHggXZ; zNQSW%5nE;ti*BsM<%SK6vG@mQ(GAA_xU=};PBPx{m!R=A)7Z&}=i7!j?}Hh}TS1fa zHPI^^4Ji}4g@bPffap;ZJS~|H5|%kI+E^8BwC)JcJ&nVaTi-HoCf($1E}nxAowlGl zH>YH72*X`snGBnC2<8Q*vo|%1+1ev!aF{og#`ra%R_Y|W_s|pEYGOoNMb2ouD-VS_ z#}S9`#Wjo6Y3_PI_CmV`eSdKn)fjGvZdJ?K1xx0l$GvUX9AVF143nb$t0&U1N;N8G zn2Wy#dRafK!B}ehgZISi5FVN_Q+TO%DBWujk7+3exKLMym{4oD7d3*ksyzpD#WlN52{zrc?ngj&?R!_bfUnH-aauGAKhLDmnCXphUs4Tm0!+YUKS1I z)yc>%kfsI2U)j;irqiB9T)rVJ4#!@0rB`2_M9&Wf=xAs`3nvFr)ep(^?sIA8lBFk} z(aVL&PX{ySJI~>yN1M=W{21)<%VR6Y8bM?agGcX1qav4A&bgMscDQQb1pid{q+-sf ze9)n~OF8X?T|%%G?7&H`vS_pW3sdqWoq4iX0mhZSz&Y#Dg>@i4p!jE&mVx==-XiLt^7OxDi+WOZ<_gt&PQB;g9av%_6I>c0+1_ zJGhW}{14ii#Pq2jU$Ji+KQ{0+6dW}r4-AbVThf*c^?JMH*siqMm)4Ii#6 zGH9DG!rBg!a>0Y&<7!-cM9+r|J<%e{*%-?oXs8nXiT_jbw*&t&erqe+zr%kG`YnZi zF3*?`gYQFD7GXXvSp$Q&tt0Bs@4*+@bm*M)fEn>-I5}>(hgMf$NUd`ptX&;m5t*Rwf{9f@IO8K|Bdhd)UQ5AT|1Ji+n@5E z>i0kKkG7`PW?cRL0{_T8@;`q5#CL42oSHWGUw_Jfitm54zqPHk#h?E1AKD*VbcK<1 zNlc8i9TTP=iFxXBWK7#eMy4c^(50uzS+@z0;GjjepN%G^wg73=ZV4BPx(I5TN{MQT2M9sgV`0u`n*EUsE@fXaM65XsEDuNmJ_`2D# z{0mpl@Ecl>iS!=o2|U9O@=dwi{nmi0M(CTC2GHf5z{v z%d_`Ja&`Yx{;T@inwVQ!n*AT?KY!lCswd-?{{im)DgP-B%m2qXwKg@eGB@MaA=Cf$ zIQ?JYd;fNf{)u~1vDjAu7xSO;pW^<1_8)6AQ!5jTzZ-w*%}M+(i?;DsM{MD{I&bA0 ze^2JyO<2kwxg?w4$NkNJcMv~)$R@s_b^>2#)-L{Hu~q!2(YyIAf;hh1u3)~yhGhP= z?s&fT(VcwRr|bDXgCqDd`p$f(OR@aCQHlJrtVn*7asq$bszv;Fj%)d2*{ZIMt>ThmoV)J+PPv1Y-eu{>z{p7X^fx?#Cf^`=X?Im@r z1!^~62-4!u3v}G71)Z~-1^TyA1h3i^r<$!d6(k-_w%0f-XFp@{+9`kDU;jG2S^*dP zpYq?uZ((Nr|A+o>W?}Ph`~Rm8(P-4{MGAvw(9Q@isvZ9Y?}UZYC)z-VZI`F&zx1Ht zcRW03`$%*Otm)SaMl^q(6dkT=LszIM|FeHl>VF;o@7mAOg!}yE{PCaH|Nq_i{=4yO zZDncuck`d$J_W(ktU}TKC$so?Wq@z%k;uOk=gF^p{+%z7{Kzl1QLEitTqQ6`3#Lzc zjri&{BL$)$EkURKFo9~<;Mza&-#d57@87jQw|)G}{qO&-egAjg|6TjrTG-h9ZU5m0 z{a<|k#Bb%lbCZDkjX&kTnm^1<%}xJ${`kN9|DQP0-KFpStM!wM!@`U^hyJVeldJSU z_5O?Xn|uC0`_TXIo^SEbJoK-g|9_J~ap-GDEQ9KlVs`X9?%Mt}?ZS zNuHVuRlC&K`9q4)>bEn_wi*Pxglix$WdobIc^xQL9cL8F_AxopPMpqBIr!+^W?cm1 zAip3BLW;b=Iv^i@FJBFjnv;bt{;h2O%u-zQF&;b{l3-N(AP8)X6B?MG5$?O5$W+)B zven{apj-S0Q=dec#t>^*D3yUfs;gOFnRkrA#a3q9XUg7w&S_)ztAolDWiVN`k8yoj zf{m&K9cM2A`4%oWxn(@$*h}Iv`9sh-JrrC{B;m>#hapifA3c4`LEDXGBKO(}Lo-a+ zahiv~S7`?n`rAX_?*oj%4r8pi@5=;scL?=+M|1i*zF7LU6hcOeBgeJ7-&!t_5rQRp6rMK~UbLg0Ycl zP<3x43g(^>nwxLJ#^HAuc62t>PcKJ*NJ^nfaJI1HlMWklu$#$wdxq@{=Jdtml3`mh z4|5t@c!iDM7=u6y-d$D^eB6te2Q#HXw#DHe`N$ zG(q1Xt6-&_AO3jgg1e-hz~JUfo)@Q#Q*~@O!#k*gFHUfnyP1h-eue?B$T1+vnm|iQ z7O&!Xt*|9xlhDTQuNg%q7$3(-gZVHXUWwj-XQn5>%8c3I)nO!Du_*%$B%iR`#Pe7kb5q>$ zCI%g^Ra7>ctWEX`!#bw?Cu6({NfeZM}INCVjXNCJA;|`p%?;|-)9Ug zym>F!R#xn)3e$Hp5F~GfgGSp4refE0l-A6E(zR!q_~);g?qH7lddL-3Onu==+g?;| zlY;c8Z<&iGg|OIL54vABFv8zISQnv)@ob!nIUStWjqe=Z8m;}D)^Rcn(7Rcj7b ztL=ok0(CHGHpiRXvjqoqn7outP%%A&IsP#TpR~u}{E^eaN;()vUD}Mdm5VUtN+{IM z@nGsF`=jP81))vC?x6PprjbB+Svd>+#R4}_y!O5vvL z8pw&y^Da___Mrczmr8SY4O$SHFkKk` zsgot3i6;FQS$R=%6pJ{06e-=q3z6aVC1qe(Q6vI$Z2Bt?gFg+;>`%AFM{`N2jKTo6=;5!i}ZyO zR80v3m#3XfMf4^Jy!}Kdc4VIiQo2|f7onx&6@z6FUN!0 zMUA|Gb@7aA>mcaNSA)pWmcr0qr3qOld$^U4hT>_$GEN}c)Q3Hq6O*PUcgZ3TR(!W(J2KD zc}F-UnGOc~Z?NqX;-GHC0+2s&g~{4<7)oUlP}jj112ac5211_D>uHUha_$5aSZ%<< z(9vwV$1A4LN)}ASzcVdAukd&-HLT9)47hn=6@>PrF}zs^nT~00pwhh)w12ze3t=z2 z?K=;R4HWRfXeZp~?1B5nX0o1a3M&8J33&xRxGgCRpWWJz!Wk~8;c*yhM>H`@)+S@R z!FF7%wh6av%7*ooSs1v|k9qd`APVC+-(Ql8Yc6I$?d!?R!uzS%*FFYoCkC1n^l82J5QW{xU@&~R^7Y-j?jB4@_t=mau_ z@29X;u@TJUfze>Rcp8fR#G0wkv*3;0PMB^T1HvDlnC2x>_;~vSFc74(`%b3euKuA= z7`A}j5$uRB!hW%dYdG(ad;36s@IIy@XRYw!>~zj^eF(Ghc@i3wD+p^V15*dz9dAf2HE4@d390Jja;yVDUfPpKi_${ceZfi- zS1`W35)JYL@b>K%M&J;FUNgBl=ZhK8q&&Rj6%Aqsf7m_vdWvb$9m}M|yRr2RU5xe~ zD-_J$g8?sOvBJ%X7y7}KHPH(NFWXN%$8s&4-{^v6D=jfSZ4h{Qr`!H`=Yref=cAZ% z5mR5+$r$S8VC3lvp0@LD+;z4PK5X3wr;l#N(osV=jPA*f@c7)_ z9Wf~TWd_EtS_@f0WxywU;K7T}Y2BB|4*qnmZtoch-be!dc@5}OlH*yu!2L9xovCIX*9_|j+BMBXY98p=N47bs6 z^qOFneHwH{AM{cf1r_70 zV8nY)&rPM0nXg@pkJks_?7AE#Fd~-Gu@gtva4Sp>E`rB{jzCP&4m8pi~0)87~h?W9&pK!yR>+9LRZg&n7dH@RLZP|`#gP9CP&f}|Y0(>?p zL_Q`#qx^6-;A12zUan{B)cnEKU?t=^7-8+cm9Xv8eh3ZL!xn@4JYh0}p&w_m18ceW z*^|k7eSF2Fq{XsU&s&+rF@d;ZQ4Yx5D8=e-L+Be_%A^SP;2IZe^s=a89*87yeg8hV z(&Yy)JoLe9={jMBh8!=EQw8YHFv8PG;Sg{y9G*>0M=PU+Y~S4djH~lJXn0frKT5k8 zUQ;f6yGsG)e^vsqH+FU{=iJy(1v}P6teQRH5{hEhovggUaE9A0!Hxt!%+rvELQ_9X z50b_coz)D-B@VD!VL(6NXFi^ngD+PFF*f zt$T&KM$54N{BCfWew4}Qcuo5)ia_Jw7u}yHG4ytwwU(65Ns{11j1{Z1ssn_^NFRj0S)-dng zcEXFLy-duNp`hBi6ROgc*eywh)L>NPxau!v#WKkz znJBC6jz1Qx$7-kLoR?uc(|Khsh}EQEHRtn^A5f0^+AB~tcOitzJD}%TKH3Bvf*ONE z=;gHtee6`;0M0pd4%piRtb%pc>3VnJ&- z{7)JbPdos=gKn}X)a4-1RF!+DuJB;J3s}`nfr=z2d?{84R{fHUSVLNkitQ-YX=w%q zHthhfYZ9E7TO3YZ?F%Oo_c5QP4#Hw-M~s~1$&}7J#vZNB$L`nTS+QUj-eUbxu+1Wm zb?sV$q9qxi!e;Zf$)~Y8w*cfNmO@HXI`iQ1F~%o*JjTlyp;u0(U7P0?+%_toIkGe! zw59W~ljU@w!5Ld__p`4Cv_X(ClshYGfLL81`$H~~(@2)*y?S2`GMvAa;@o`vk#?Ky zTQHq9k;y>+{MlGLWEc}_;0`k{97K)F8)5c@&7jb>8+$fOL1Etl+-2vBk?lKCeo_x> zBfAh3e`})GzBIcR^Cp7A8C_%@($Fj`3QkyV0D+7jQ&l+>J7Xk4;Z89|$}NW<>KTj* z>&xh zUK@y~$CO~#!e~raOW`!IS3scjFJXZAG4{m`OAz)oFs~Naqf@yObcDNuwv-oRwbuqc zRjpu@OE|O~iR3NLa)6eLpV-;l`lzxjSy<{OkG(^u!GLBaxP-(oD_vbt+TIyl0^YKV z<;G&^%H3>1ZVtNcGlI@rj-cR_jRq6@*_hPnL+=qUxGg#enl6)J_CNuud|bfp+F{21 z?kl0^G)@!Jf1z;p-2+T#ohho!Tmh==0r)v39b9P?w$!Py_2IV26Xe5ou^e1IdN*uv z(#O8A#sA!&YE>I+iVf%TP+a-1@}E|=wpONpcmJMaIZfg5C-GxbIoPR| zqkBa&d?>R=`{(kcebf*(YF;W!!gJws;|jX0K#>@GnnKa{&vxTR4;HyiT_;lb5=RD3 z#__)$S0FtHzhmK~=b)t`$;dgT(=TFbqE#lnsF|~m|IvCH9LZimySAKxv!A5t%~#Rr z@cJZ`U!RCq=bmTgYn{a7KChXH0mk&8?j*D<6w=!pb7z@Iw;CW8!H;usLyAE*YO?v ztmxN(Tgkq3%;AjA%)Mo`CRr54*m!12avd{mjSL0PXLbhXZfuj{ql{uH1!s0SY+e)mD-=FA5o(NhD(8TkK2U z1qTPppi;XVPd_||QK2Jnj>#V4|L_<&A~u2ApByccIN!@oY@SQPesY={!SSR?Q3p2c zAA`?-$^)ny$FK|D7Mek-@DLcc zR|{WBo@0EMp%*p;;jTD$5zAP zz0!D4P=U=d!LZn{5ZojLMC;xvXt=5k+dB-2^Pws9+(#AIt-b>vKf1`e-W-H_*CS#0 zI|&X8_y)7S7GMd7mpk|BH~b79Lwr=mk>U4-F*vcN_-j(R?XBcORJGzfEjYd0(5f!m~xWYvX$R8auHv{!-N0S z=m^YK;08h;4h^hSWy?rI0ro?v-ef= zld|^n6PFh92eq%@`L>q9{Geb~vak<>vLm7WjR|Y4oy{gfJ~PU@9=~s%g9YVDu<6ED zjFDc(dYy1(M^tlq)G>On(pwMXhiOrpT5V_^o<)|Nt{~^Xs^dA$+cY9?gecReAFnN^ z;BxOcscO4T9{QXk>r?!oTe{5*?~i7mf1ea3mHP%<|Yvb4L(t8K2LTTnGxQ3FMM{k1{V8Ofc%GWQq%Do zQ++ZZ#xoXW>{Hn{%T3T$(v9BjY2d}DN3(B6K4&ykl4*%-K4V#bkSJT&(>Xb9G}dJb zWzueu4bfBZ(qVi0A@m-X4^1XMUKiP}`Jv>D^9~Z4d>p4~n$Y$z84@f!2d>u!AYy1G z-i(W6!N`?8EujacWo*RQ+1R9Oke>tL#RTQHq~ghsTGZi*BJlT_0%eo@aRS#WSYG zd>Bq>9}eR(XEFzigUOJ!NUXXpku;e~xR{{M$b5~5f~#xD@-w?JS2_+lA1$Ew^XJgH z7kY7<)FTjES_WE6JK>?PJkg1rOfGYgPT6NGi|99F}S44E=i6hCvQI^4a&|$InM^X zHG;_XB5zzja~G4{T*P^3oB-F8=Xn>O+^yO0<{Cz*Jj7i>3&tSw8oR4gmYgv-520Um zNZ0}+ID5UBIetolO!U^G5$n^Ks!V%E(fT)xY2J$d!zV)5hUe__?R=r+NR}CF_YB{x z<22z`s_?gtVTjh5Z}=^(mE8EOPFA?Y(lF!SjOAN(#=vR?j689x=626v%v4ha#*!m- zKTsuiu3D03jxVsZpVRlWe2W$0Bhalh9WD+u;;!a=yw@@The^58=9w$l2Z?HItoK=* z+2&756D!I6i!sD|@o`vnJQXd&f8(wDE5750&ShV z5M<(ig8wO1yl&-yn0^mdZ!Tf`KpVBho-yO5SMj7D7U8v$2F`ECgpAx94+E|0B)uyJ z3}?vHbURPO;-rb}z{(8v0M(^0oTD+j@+=v6cLt`}DUooco$Qq+ZOmCZgV+YorW*r% zX=UnB+>teiI&{_2W48ja_iGm!zLwJ*xD!eBaSPLt^cJFT1mkC^)nw)HC=AKC1JTz* z@Wrx-s_X<89JM3@#Yf^(JDojBpl-iV!dbKTgEziKiQanb;~%uM9Kw1B6LMt->qT}o_Geu zwQ=OgkbKrN?-#snwI*FJdfBF_$|5viF~NNd#)^G`T%&2^_d6pJ(j-Mhx20)7O#>Tz zwUQrqGF+tOwL#PWG>Dv%@XE6@FQbQ$C3Ji<$T5EBglzs z%V@x%*>oH$&3xA?=Z$^$n95h_QqLvh$PPP6`uvy^{gtlF?+sL@mBtH6+9*wa{mV*` zZskTexnVwkcyGFBU_p$i-DaG~)FFh{-1A_*DJlrNqTfU$4woxR|Wk{ccXmn zG4LClPtIQ{0P!OqaLIRB#;@ok$DL0C>F>pK^A`isJm)+)d((+T^d-|%WqkVb>k=6M zYBFuGt^OHGkTwsV83=cGh%-*e12QbvQi=((K> zU$b>hlEhm&8{*x{;X=|xa$?GOn#1K@+)pJ^-}5^#BuNC1T6JN_=maK`T~BwpD~RUm zzr=wVE_CeiL2z+CWv&?HpyN3OGQDp)ROMR1=B-Y6AbKKQTyIHg&mlOuM1k5^?(Tbo zDe`4*Qpwi$%qO{MF!~iiGz!efuF%1x!|M>#9cqQ(F3!VaRXMzqOk%7YM-Z)@cj3tC z6L=cz$RuSsaxU)&9rLN0(p&549<6O~|EwkZbn0H1{caw49CwD%-1>;Eb5m5AOJsnP7 zZPp>S7D6ytkV96CQoz*1lTgW`gw9(!g!tEKkTHA5gVqcQvT^)Q(!1W7il0%UwXNFJ zEA9uXZjHq7`tfk0z8+Up&mnGc-2I_KFM6XHJ?q_wC55v{{HYW?`OQ%{?vM`#2fxJg z@{N$sCZJFAL3Y6jb9O|&12dCn&qzGBCEIkzF>%Z;@I1Gc-tj(<$*l?G?4}`P#B?d5 zTGh?gE2q$syL@JILJ_^O_B$)v%IAA%OyKWrE+Cg%wzCymAJJ(AvZBDxUm10mqqKVQ zOWHMOB$W@$WR+^ilAswqU~~Kq4cYdJKWAw!o%L%_t@@^MwdL0?h&BiA;X4F42`uNn zho6^}$h|v_n7pnL))q;U%|CnK*>4*%{K8(QZr)M&5GpH>Pt9U)9v)fSzR9{)Y}?@4 z%)}r3$HobQ-faZZtE9=GISsr$8HRK^=gBlowGaKZml20E0y5~#GSVaYj6cm#4ELOl zB980qL@(UNiafN+L{76d@ZTNIruM(fS=X7DP}!H;`_-I;70 zVm)YRG?Az$<CEf^9?^RrL#{rHhYfY7;TPv?arC7L9j+2X zpNuQR@i)pDZ@DbuvwkG$dVUk-blYLKRy(XZIS%Yr%q9IiKYB1fk=a=K8gh1j#aRvo z3~HQ$W1Fv$kdPkm+$$sr;U;{KV}pp#katQVtsPt(!tx+*4Bcfg58?i~4H51HU7 z#qYKdkdn77FJo&3uBuRBV|R}xJ`a`?Ro@#VdASsS(+OFA{eulu&xlX=Y05EqS`OfS zZyuQxcM)D3xWm-PhB56klGzB!J<#&O=uq+{4T zro<+JyF+~iaVE;dU$%xhFs~Jj9Fv3-r^?dKt#5H;R}u7%k3hrgOYy_85hSRn47|!1 z%+8g71_cG;c0rN(8Z8T(x{aY|cM&*Uu7cP#x1p%Wl2nEHk#nyV$kzgl z4^P*gfc=e1RO?0^26$?bv9~6X@Ec9+XL=G|9lisbPIEfi+b3g}%?ljTeGXL65Z6we z438D$$f);X^atz5PVG9010g-kz#bi9eO!awwwOS~{Yv3i^-^}N!CuN+Qjcnn&!B3V zI9)GS2t_YPQkCK`EZdlguRmAflyh@n!JSCZPaOm$sRY8s@1tf)1yhvcjkY-}@T$}? zG{`ap2XB9}weTvdrp0NPwoQPkHo4U4v^IKw?Znlb_S9qZUZ!E^6#Bt#8@(}kI#ut` zp|wW?=$F2C7;s6NTsff4b}32FmB&*!ZelWC^_WQA_G|#7N$tG8brm=_%@ON{ZHIwR zhNPr#Bt0cRgPs@61*4JEiJ4~{q`W)MR>jPtdX-_+LLwJ67cHd@(Z?92xv4O6U^iyn z(?s$0_vnOAGW_f8SbCg}r@xOok(kcKytNH4v2D$Mur2lnt&J_rcd?;l`&B9WxI-Oh zaQtJdej6flA&S*W%3Fr;ht%(hWL?P#$Qikd%b%>lR~&bc zt{#FNHq#(Mauj*&!JQ+c(x~M0ms~wzJjSZ#!SrXR*$Y7iG-8k@J#lpy8rK>^Y zr)d!`e97U*bmN#>y=Hczar$|$vLs%c@=$CV%Z#ULko0ps~#FH^rjjaUj&@#kwV z65BnAUXBi=#?I+HpQnkWQsr_@_^}m~Sf^3%shXnIf$s47=SsR|mKNRLvWFfDbfJ#s zD*SrU4Jv86lPa9r4Ku}0(rIR~Fsr3U6r_uNI%+!_B**fn?RCuh{n+H-zUMP zXBVWn$Fr_yqUnX3Q$-Hn3+O|BBbAstk;th2=3=)NC8g)X+%ZGxynB-9dwm7Y{`>)y z7v_RKslzAR33LSfLdPA?7}9bR4-d~q<5Dj=W7-I^u>Ungl3nn{E0GGtqp7U;adK|^ zXKoGhBiTwqns25`LsWdxeo+_pxaWXH*nP6=*CrAwt4)g*xYGu=A}A`!W3L8lQoSeM z^hIJI$r|(og6JD&=d<%zZ1@fbZUEegDgp_g@pQ~IX{MEU5O>Fq%zQ)c4z4{77TQVB z&I^g~^5+nglTP8)tlPn`AtRWtN0y?3oES|%cnaFvG9J);$5j9@SyU{L}EIxCCzZUd7{_Z^m-xrt`+w4v&76F(0Jt(Rj-N zR=KN%%^Gr(m02kdmt;oKSEf1S+De3hdS!AzeFVAZ?S#x~Wg0^sK)bsRX`g!@hWg(G zyHT#hDBv7C@-ZeIOLq!iC1#M-kH-^XzZQv&Rw18{E+<-(HAvvf;lh^=wd}(0MnwG5 zWU~303u&Hz1y;_EWS$=#N^Vu1!l&Wu7~5$-VMG(>>zcTdrsc?k>Z@aDI9?21jgTg$ zH_hQ_8{pmO%$EZpte*_G|(e2a(Mrfx=*hr_I)X! zbUg`not%k#CX9r-&Rh8KH$xK>GZ<}6PT#a<2>VJlANxO7L(D7@-Sl~q=&9^m+WRhz ziax9)9yR+(rp_p~OEC^(Lu*(Gl|1OGoCs|{waJ6)dgStgP8=?g$h`Uans?I4NF<;A zjv9TwK}}=hh`2-%{1lhrOZDl&t0(W7r0TEm)?OB>+$Pb_gC^rq*>;|5Mi|beCYUPT zfB`?;;ZocyRxE^1S1pjo@I8t6Qt+5rz49Pl8q|p^M#s^(^Yf_L`OnNo_XTA4ELRda zzZfI7zQ&@>k+^*P4q{w>lD*fSLAK|w$5UtOA^fy7Rkd6|O|9Zs#mZpR{(cL?_=<2V zDvBs!J{GOjp^24|FnR0Sn)^NHF|RKTC%aja%#7(U=XMQjQ@INKJ|WXMiPHwP_eJT9 zPnf%^2zlql=w*%von@d3?+hi#Wc4S^;}=a}d_RdkmB^xl(^5$AtTg7attPgtb))*G zEb==KFXp<5AWKJf=<&Is{W0#?$) zXPbD(oR^c6!#dbCCi3)Xm;(Q0?h+ESN0IM(Zxn=B>*AfVcr;Yq4O%r?aI}UM25(!) zB(9fbhdz;E!Z-FY(<*goN{=`s7SBZGVm&-5bp+Nv9Se!=57A!Ug2V~tkzd`Xu_Mx) zx&%iti7U3CoA@YtQ8$ye>??x_`?JX~I+1MoK8;*D@*Ph!AqJmRv2!z-NSni#lA;N3 z@p3JX+DM;(xod|4rxwEVy!8|}6?fwZ3mu}J)(Ewy1tjQF40fLvr`uTt3P<&+{KTVp zqeGk2b=fiJ^i$dAI~>ujxd+zwE@PNw-_gSM0hlPAL!(qhBHT0zdn->;QMnEgwe05n zk0mj7w=sR-S_Xxw&d|3~6Amw1Orj2*hl=M0IMF-=pO1bE9etU&d4n~k8fcP5;&J4@ z%{YR_5wPdME*yL-mYF<$6n!Fpg?eya(`C=~$@BXQkk9`DP?iDY8RsFgFbWg~?$WZR zN9;i2Ix7C#hMs@iif6)Q_%{?8;(0ll>Q!dhVgu2uir`jiEK_$}gQjhH#RlZ~;H&*aq$@>{xRmvd= z*EixC%~3@1=@vM&))_1(@<`Z-;rz-mAIXxZt4N!qJt=t}CRAP1TJvy?30FdTJ@uE^!%3WSHhs~{iOj|zZjUhxM_54W*5xJ{f)wOYm#|u2=%x_NJ82iHuvR8 zq4Ly1mJl=I7L3} z!;jr`nDFF=lC3W|Z0;o!B9|6IUTjezI~F)mkE>m1ugAw{Vq@sV=&e+%POqiZtjk7wxAe?$-Kso@4hiPuZB^b z*%GMMx01ZJI|Sp$u*}%;GQcCmVJyvwt4pEznBa&2PG8V86U4M9}CbDR^2wUC`4|%csj1@O$``{84rb z?T>FW<1cQ%&hJ*R<-Z>hHN_(U1^a{21^S)Y{Gk$4`Geo=6ihv9C^*#7CiwWKf&Y1~ zyuIi-J!h|q7r0@nb9=`z%_4}!F*I@Gf*B+`9=SytTlu7uK3|dpf(qm)8gbz9H zm%%r6`a9GBMkFQEcf$$oo@GKlPmQAeZ`|nGE<>{Pj2B#4eTw;BAcqNYdEhx>0nzq0 zr;^hOXy4)G*tvNWc2BwweZ3A;i}P<8Ms88YZZ1(eS%zbM%Se9hY!E)nq5*Pmc_eEK zEt{r9A6;KY*I6miS3x+5pO8XtI6uS*3(w#|4^!TYSO+{_ zv7Ga^$tDffC1~CwPK&o&kke96$*kx!I&%9^-fJ0OT=gK4iLAYgx?@df%)la2(lLmP zfEG?8Zy34#=nFNRu!1BMjv#Ydk5G+C^GM5)Wt`te6MZU6)cN9Oa1`FvZj)bkX|EPn#8zHGLgRDO-;X0n;ij7`C~fhd}!=}Nu(?m;7oB--6K z@ZzgQv@rD~+)Yp?bvBmNb?+HSSBe3hWg+C!l$q4@>@aFEsT*H7bimuba!7Dx{rJn;W2?L5GuINCUV zf`Hw#2J94#-D|sd!0jxk7}O~DiAE&)Sz|>6MQlV-6vbFh4Tuem1sg^Z3n;g92V#p! zJQG0_ED;OFUSeW{Zx$23+nHG(jq5WHC*J=2ztd-S_I)SYcf$yN4LVC$z~x=;4Vp}B zB^b|b5USpcx6De9f;AhK86OX81(p?r!Q}})md45^aO~nbaQq+ZA(LMr2+yK`*Y{(E z&V2`g6JM7JTkd`d7Pwx63CnG8uq91M8t7v^d^jft@~5I;Ser26 z%#_10_UswK>0~V!)AN?4``Od5YQt0^Dt|Fd>){N%kKKfZJ@N2dP_p1u#S6CIe$C=y zO9#e}(esMVSGal+E5P$RIk52ewjkxjHaKFqH%M7g#aMgp5$@pZuF&iIzqqd_6&bbu ze{er@KLG`LrqbN*45G$2F@Jz6J&-mb22UdR#u<5>xy%OzCCCLSCd@ksczf(Mb#6TwXF1Y!GikDQIBqu@yS zT+l2(Scp)L=I(yB5T-iy2IJ3W3;kxU7V_K<3c=gDz&?qYz)x8ResiXZFsM-(*WZ#N zG+CX&m7G?9ZOh%^-8!^^zmQ1$p`tmdD_$8Bh|LhIc z<;oDgcKKp{TTr;wZ})KP#*5Kb7&*;4rEne}IBg(b+jE-r%&`%?=ajDe$&cn)ebU4E z&EOO3jYzZgqGqMldmsXyS*C(Z{H$Q^ffk_nMF5P=%>kjimx9@fUqQd5 z`P?FOW_I%PNT{jE-n#^T-Z&Aoyq7PW zZ5|8#>dwpA)J`Y-xi0}sY-oe6l}RXeeQTK0Zl&Os=?!~s-T^^=I2f?-BwP|bAGUP~ z;e;c$L#4YyV7CfCZrF<5pq25c@O#KX7@61re55&VOmi#n%~|<5^iOCC0(#vSeq2zO z4_@yAnat0@&KOtjEA{|9{4m(M&bEU4SX(X>My@nwgp3oK%ztFL5Yqu>yciDBjH4{0 zcU=&i9+q$&PGrL?9UgEY(GQ^UNH<|mllIm*InRXRjb7FQp&hj8k?XE`?t({CKOxv= z=SE&`02lSk0k4|dg~oZ^;nf#MguC^5$mAx%N1pR7_d`y@UJm#XBn$`L>ND5)(Z4V8~_5^egy8Qbuf3& zXb>@IlrUkdvoZDjDyaNx4X|{3&RyZF!SSA-g6qu(3%|uJ2DP4f!W(q}NIo29xl#~s ztZ~2!O2@i_l;UW(uGU5FUa}`xvvs%-h|YHp@jAfOw#0(O`jKEp;aa26?6wf-l_o@l z4+l*=qqySLVV1y>UED77E1_LApC7m1nm4xKIn0^l2Z)!x93RlKlNTUKcNs$?PD)U*a{I`|+LJt%>LS=Zt9 zeSP8O@^IKUtB2s?d4zr$l&l!BkMVf0^-d=qX^BUsiekH>Ey|taRFg zoDaO`{FBv-{yR1jOhU4 zyzNl*`@kCq75+>8294ks(k7{7o) zO;!cYy7Wsx-k_6w?&xcLuZi3FE`9IvqbB$S9Pgh}Ie&HT=Dpxw>i1QtKCJ%CaYD~9 zi&4Bqy9IRh>BZMaZ(Q{})ev4#Yy`Km!eK3R7CtM1=aV+JwEp7!6pUE{VXrBx;qxJk zwS_Vpm@BID6}L`+ZQ+f9VoEh|GD*SjeeTX*8nqdov$^suZSH)>b5*Q27A^sgI(u>7 zyL94R&%5&ZcL(r0M!z!Jf4>gWj@$;{4hRBib4P-dIbHbF^s0P^c|F0Y+(*DZz64Y+ z(t!W0apsQ&Yyd4L_2BQXxD2+`+z3_|H>%9P1Yy7t8>+ivde8cc+)sYk`Y(H^flm*O z;JN6mN-duqZ=|S&bcjh_OI?NjjSsKbFD6eJHz~45SMB?I?+Ops)(~63nY1wjoY4O$ zCR6V!;*U2mfCsltxj!*Pp%9Z&{0GV97!kO0)PxB9?&-mwbho*pyhW+8fj7V|94V`{WF}Q_GL6Iayp1JLWO$CqIxk&8Bqf%46R=4tHBxj-Pq;< z=zcLt8CPfw7WtM`;f$;MH`x^72!N85VGg6{U_}Q#I3s?>`Q&(n5R;Ul+(%h})9FG(Y-}52BA0j+gQ<#?Yu(jfT-uAQ6ur z^$bAwib)DdB_Y0O4~s?abKYHvDTh$vt5cy0LKd&QIYkr*tJWh1QCH<5VHQ#et2XG7 zH>P(tr-%m8`Z6q8!f#O`P?YEljGnBn@{l3|qE?|TMy;Cc&*ULt5LcpB>9iV_(GZ=Y zJfw&Q(dl%kD|z>f4YQI;7?v@p-X~*=NQefNFKZyj33+qEY=jbxo@GS`lJ9O#5e=eO zGnC%sElP3;C5&FLLmTO2>2&PeiQW|yQ6YN0maJ@Pt>7fF8xT_?l>UE(DS7A^aM4xJS?eMBUiZCCeAq-?k1YPoC;*kO|NfD;wIKo$_ zMVUd=QDyC+rTFkhIqoo#_9^wc`r?*msc{72~s*$HY0WNUQgvuFH}<|fna@Alu>2F^BsBd$PO_{4Y3C}VTG#k)v%~y;D$_lsH`#!-7Y2! z5r`wuBN*CFDg zrN4;Slq8d#<{$#$%P^D*K5k1dw*Zt6Vv^>Cxd(}0HIz~QrQ61~GWFsU9HB$4j50m` zZ>Qiz@koJ~q$=#^NQ5tXxt*A6gjT;)D1#^>5E@2BLF}~79V3G{Pa;?iOO7K;HwXSI zgSbFJh`urL3jUVSte8X~H~-`~vj6GK`Z6j?2!s}`6v)xcEqADiUa0nqBtnaP$rFaG zTyg9g9bt-e#u~d$iyYFEBfBZ9`%M``$_WITDXGah=;rXmA7l^}Bm(U*ka@A7PoHGE zA$CPo+z>`Z8xZA(BGU>2!RoaPxeSf@soqg>i$YA&Hc~_)^csdT%gLB@$%CF3!&VY1 z3|a;~!NzN+{AgxcMIsm#Ll&xhUOb>8SaK+G-1d>?McCJ*3RZ_)N#lm}Zu&fxo)-@& z2wyF71db!v!u8E$>P0f4!dHdXS;S~IV}t)%x(ZVp7p!VADvg0+hlpV#m8_i$QRoE{P2%ScwC0nX|8?j#|5qg!HoOjAkl%lQ>2u5e1Y<)di zn=pr7sHWct1gq8S$u{!zL`Fq`f;Ks@ySU=D6Co&*M)}5Wb|n$MsAdq&jJelo3|)o0 z8-dWPd?~f_KgU|yWD1o;7*uLTOSIH>n4AapNlsUM3p-ZDjbKq4w5XW;=c@?I=NCaxAWMh}#pi@4hAt(=j9fOoe4Y8Am*8x&+L*xrJ z>^Y(0b!?M&M-)*JlL( p=jTiB*T3k;yH$Qb_f>xAJM#74tDxVSdZXndx{}Zz@%yj8`#-z)3eW%m literal 0 HcmV?d00001

33t)o7o*`!`_4(e zalQhw6wi2ZnH!|!W?cS0WD0^fe!U>D?Eq%2h^n0;GMfq&Q5HtFTk)bwSB=bk8$O4X ziKJ(5ulwUW_YH4iO^5yTQfoafte#Jbov5<}iW{P=+)_kQf#V~3u7wLm0eLChgm0!& zAt;WD)#bAR9~-}XNvpXC1Jhg)0@bSks3wt1I3e%9~dZanLTuTf`E1;S9uaPHdpp0| z;E{I!UFS~;xK9r1HYx%t*Mn+-#zV@0Iw7W}OCaFJ-C1c-lCze;ElWf`ThnEw>FLSj z@o*9QWJlMpu~?YQM=Ps0W%;h}XeJf$I9;x|5{C7X#STKRY-4-iv)TJwp4q|(E%(XN z31dh53!m`H7Bv-dMT!=~3p{ySplG$bak6!}sLLnEc@rIN!WoNZGq_t(bJJ%osl43v z_dh>;!-7~&<7Wo1o?gVyheLceA&pLUddj9q&x|TszWqa^`IgO&clojcJ}kQxE3%g~xT0N(3@`wyNubo38gXaQHZZbz7aBF;!G99Hg&jzwu{rL1mLw=UI2$Z+* zz9Y^&;i2o3AT=;?*pW(?tr9UMU(x8+Lvbhx>UXZRKTl5_1QQT27l`h9kUt zpHllD)94O-o0uS@>=-<;$GNxkWFOaeDg5Fub6lR38u{gbliYXF%R_nB?Mt^$BPlSg zu1PAUzbq64kvlzw_Mcj*O54?%`WHwrlbxKKrp6baxscf%-tZ%Cs~1Xev_)6)`H1jxlIt0Lr&?lg?f?H~=%Cz2pgX`N=L4k1jU=@eIjR5UOJRl+?K;66Bg z$8b;*g_e6(i*Qf&pAx4~bEp&^Mn-5$GZZjllZ*O z%-)}r-5Q8H^)|+=;)~1(@~wfD&z3Yg)M?6K&ZUxC{!CAYD1&bJ2Mo8@sIjK3kNZ$e z?@XJXCv9`l^?g|Et>DGFhVfdyYS&azm~c)y<+973*}Y{}x+Tc!JT7+nq9zfQG6;O( z;^ndhT*cg1N;K?i(QW@&$)t|s1Ja5`$Nlmy885BCKO%&gLNuR}C&&7)Sp=92l3U_P z6Qb~PI-+PEY}7R3$%NRv#8g1upe&bwTs^czF&5oq=3239zQ2h1XKbWR>Eh3&@lS_+ zuaa$EI+8ncFXQ?2p2i1zXj3oF(3;>kP>H{(8i?}7?Ktk+Uu(f!S;-Mkm7$#n3md+# z+riASx~lKmQQ{t}4kZQDmR*M74}Di-afqL0m@svzYV^WtavM4z2a*Q1Ij;8*T<>5$ z5Pk>}Wby8?M!7vR!)uHUL+e7@5A6JzmsggOCNuGzA;jP3l(*=IXw~7Y;Da2)M!dy~ zn##4=J`^a??Dc2!!WQ+7%FWW*^jXL*h6W&SRn;Ku#n98RQnx$1+e~{RI{!&e%1~*1 z=P76MaPpw5q1%^npew|z5Du+9u=6xy`!%F!x7&uxhV3~mXCHNqYB)Ip1;x8v$XiLz zl`;^}vBKt$IlwOFK5;0w&1Pqhy<@oY+`3g!q}Va?TZWl|Vyd*sBf5L#rSiiNc9-D0 zPE#J;o((>}$umUWQYjXpMC;nx{f$E<70P7~h~K(A6d^*#L)PbaD}Jaqjp}Q^=vJ3A z+-x2Ok@HW-b+uUf*IAK7b0!jzuIbNtX^yj`hCLw#u9Or-5)y1NwkFM&S%7ip@FZ8t z49s4z?h7E<`iP24V`Xs&a7F6kTwCw*v>)I|_Zm^!|w2#oy1%s?YGt8vk zA(p%&-il=nKXaik+dMZKdUBW$%@{@llPEp*lu5<$~#xZ)63tad%hdWmfMUC$y5adn?_ZaxC zT!M$0m{|8^hJB9KrKLw*zWw{K>VJ=$oBRD=EVZ4Pjxu6D!_pNojkdpoYoKZ!$Ee-ekBj(!D;|5K^9zrZMD z@U-VOU(18_ge@I8Nb&1r=Jd_@T0CEBo!O1aRRvTlcU_qQ=zm@SZtiZ#Ob;*URs6Nd zVz;ccxZv%G9_WRlb=?qb;E^9@HpEq}Vny(dwT$A9k4|b{ zxK0ZXpSl42iUN5jU^?8*uS7q@$%0y-@UKyOzhYL)UHj9&R|@(4f%E#(Vd11G@DVH7 z+(vX@*{)h{aw6jTBBdR6yNYS$Eua$o4@Cg9!1nu|bpnf{d%gJd7q*FnPKcd*jLeLp zGa?c&O_$SNw!YBz?4sbFoIY4^P3n5zXW#30wZXSyFi%ha+YlW19nv}v_7b)XE!t7S zuRMOgsU~f_3Qt$<F?e4IUH?s==^e{xs9(=Ts_~Oo?1$M z9M4br1Lx^=x{dWGsG5ret=4O-4%ZK+KX8OvXdmseOS;K&0-5Eqq)NwEHQbwp-#h8L z)vrj1sIMQ=b-AP{+X!S=HQc3dnaz(!J$hZrWKv6i#~XzH+FzvaTBi-x&?6O=OpG6x zIw!iQu50kDrRO%Bj($4GxH`Im4SYuM^Q|-wK+k(u*KRwju58;|K2$-Bwa%Mlaw1elP&$~+Zf{DP1R8lgWY-zln9p)p3M*|D=5x`-9>mhy+>rNGc9^~mpW7l>r72d zJh3n5VT~7}*nGC4f;*QPFd&nvRcG$War;S1_RcCJ0oJzf>5LcI^kI3yr0!S!r8PL0 zz6p4J9q(faTev0=NXFwWP9x=<_p+9DfrC20_7+|p;Nn9Roq?y6?v|;MO(OVRXMFQ; zHy)Y|5Lz@-7;hxbfwzlrx&KRN4dNJfA`wo$(%))V=oN}l-O0Y(O}o5szr*6S5~L>u zgMT|peZ>7KS!4k85&`H^10hy;eJ0cu;bVzY%*Lf073>5J!x*b!EzyN-gR;pT4;7BC zFIN0r$#ozcypJ7@Dj+vWtYA+|WuMrrw0Lc&r%!2#%Yh8T@DF17J$E7$SBmsi6{szJ z(54&v{A7Tq=BBa;rdJ~xsr+&31P?N9W3T>}*^~qfcp;e4hhc20-5J1AUUP1kMRU-S z5Ie|7jDC>ZrB%zGMy;_N(L~but^{I+jwLZg;*O6Ou#w+ePL9lU=9LEKxgb081M}h5 z^`T9wrlI52(J#2{mThzQw9I!;VWN5O7&J%N#K5s&bBf`X_xpvNV|S};X+%qXo8X5o z!)-X^SRTCcf4F3M@5K8C>0!j%@K`BA0 zN|oM0KoW`&=`GX{dhgwn=Xv(t@7eFW_xRp(&N$=y#+M&ithrV)m>Fx%dEeK(?(6a) z0;H8tZ1+IqHYdMr|FsuOv*|tC-j+OW?cr&~?uSn1Y5Ym1pDKGT-QJfm*mGRN!9Fri zkx}t9br-KY@yn>uYlUN(B*Phj%so@uxO#95ofj>8$q$=1tM{qoByQDt`MW4C(9Ef+ zaRY5jd)9W}O^P$fCfBdfKd_4wRbYxnt$JcPHjwnQu`xFM>tDG(lCG2t#r=5cIwTMX zs!T1dY>*a`EM3-pO0=~OtM4D`uPIg*k<-IJ(Mc-=}!5RvDf{N5YHU>hw=}#`qq(d5?Ef?so+ImGjarVR*RDFQN zwVqf<*q|VuwFPsWDZ55J_R0NvrB7E}w8fwFk=FD*HW{gLXBwMD?Keg3+2jWp@CHXG zIE0nFIGMqnS=%4%lsbBHO8-Q@N!ngyih>hMlD_7I*MZ*J`OkhoDg^lj!ZOn3`#2Rh zVKE*RvD>BXNJk)qAgQ4|n%e*gugbp`QP=Sn6N^so#eS=rQBWwzebEavW-`rajd(t! zp{>&aT+WT}7q9=+8M6rVqJVa)PTjyL=q4BgyrbH{q+549m9HXHxJ&Yol2qS!w0bY~ z4jm}XHr(sgvcJQu36F@H5uw4pa_CQ$$snWcn-Ks|k@BDDO~c0ySEKwX7XeKJ(k%zpXAuZm@VVpWjn%2a zT2%t{;7Y;#o2$kff}Kt^ZAb>PT37=PUfBh<)Nd0U_l~(zaMG`lP)(0kSKU2o+H=@z zVr`f^zmuQ&x|=_tG{(t0&75ZD4kk60_v^cH{0gG1?xVMv$NM_`qnGLW@}QVCK*W}j1-^~NgV|u^0juIu3*1o*heO8YQ0ECRIsYWCy3DFbinOalBc=^7NsDCkp_B`( zWX!W`T6OlFZk6w>z-&y#hM&3*So%jb@)59JubVF*ITy?8tgSck(yXhCD9qF#--NRb z0l~;ck_2uKxrl^Isdo%SARpc8CRaDAHMJP&>zHG1*}wu12ogqXIbUoRlK6s+0w58| zsA~oW9+hThrqD#eHg%VK>9w7m+FxgPcueaXRIKLv(r80I??T_ey>?-k+7=r3WHN6c zhL2_F@pZQATOdE;qd0rxMjl}RN^HX{i5a3NL8kRr)%6%t-a_xnhrI!F`N4-y>Ihr z>kf&N_bJGWqkqJ@T6qNg6aE2b<(k+wFqNGXfJ%IAodD^Kko3XI)U=>|w$$u9rNIgs z&xBabP3zkb68Vp)WF8(UdZId3!}_IO7(R08Az%fBWvZv z;sq=V5rKt)HG4sp>qfaX1C-USgUj8Nl%5Y5lECJ2M%OlegtB)Y8CtMfE|=GJa|N0D zIv0MJUN?C@zo^E(a$lH~Jq>@YmjM&U&CQa~l!L~UnHN&q2??xza?(7;BY~&GjE0VN zAanhDuc;YOOVZ^b=s-ra2(_s-r4PGLHuN%z^@R6sd+a-yj=UDT_4{Ig^^}m8tiTYz zF#!#7S%~$0Xf4Vy`-%pR1bN$;rv&6=)0i!Kc-ShTg(9K>t)guVU8!O?ISN4H}@URuAdg=T^%vd1lJ7(*1Jm`%Ipml-|w?dEnB0==vDr3}EgN^r5HV)5a9! zB&Ui~hM>U?34b(-VXj2Sqr?}5b;+xHIw>lyK1gXrBl|@XQ6H{CO2%Mv?4#nTQ8;va z2-;BQ>owZ|+%QwwI65^DSWL?EL~RW--e^5}-hU6YE#HF2glI1-y*XDL{SAov`WsO2 zvQ4e^?=+WxC$sU-N#Gx6w_jsczqpwT8V@cOocwgiAkx8L$0w6SI@rU$rGFVr{?X_$ z_++tqMaNT6;Bt)^?V~l5WDA|1BhR|J6e-n}eAby?x|ZqeZmwYOra7;1BNEX$7n1ScO|JgWLVeRp#e zQ4bqIiAC@r9B@VLIydzAnWDwpj77RExd_&ksn9{&%Z$>w@RXj^aoik$&ffMn;7@r7 zs=wqR4mRgU(rNf&2EC*X zbCO}2c=Q*WH2?3n?<^6?U&`S+Ia|jp-d9Z+VI5vP5K&Ci$J#tj(|`N${x>e@4t{*{ z%hUbwaPraY8BRKtpv!mG&U*w%>4Sl4x_)dFy9$09hM*LT4tP_St}*vu`PZu z1lGBZFcnnaF!=~vEX(H_V5um(X?wY&uOs%esce)(pI%wV9}!3>*+f!m-OI@|L!-4m z45w}X;{^%ja7oJeVu)588<8gQ`OuNIqUbk(?RfK4%TYqH&|+bre_}b!M*>73nAf&=z#UF2wZhhjf3Hn$!VYNB5?x+%3}T z4d-P!x6B$L4Qb}v7eqjWJb6iJLarq#WBIP2-z@8ACgZkh8eh~{LKWD|4qFaLdY7A5C+_9eB$wbPdz64h8S(Vm| zcHjfU)Wi4PeHVD@F2U~9{yz~$q>Ol#V&TEpHMP+&agK}1Be&Q4`}|SNZrZicyXX8J z?EldNw!qges8Kk z+>ULYsgpZvg-mK(4kp9gVqEhMCXs(e+cqezVxU&DUUW2-^k*??-|)A#wpK#4A_{&&spitgw``o!gwv;F^|iY` zM$-sSWN}>5`m9pP?Gc9RHq9)2f2RVbe@mW;G~51=`Mb&#q!tB04)q>;B$nr=DlDrq ziG{pY+C>X-`A}_gqX`o~SwK3B+QVy`T8!oFwgq|c?eMBcMps2(ajKx5yjq*+dhvlg zOp;%gFj{D_9J5Xqszr5O6=+%BC?^JdS&${bCgxehfdZpV?ljJ+7F2Vsq5JkF6fKSV zRc6^u6K+q2p$$i??DFv3;)asRgddwi?pQ&(nk$_Bqcajd4r2PZObhH+S9lKDUDPIC zCHMs6wlP0-aU(85sl6FBCM##m!L2q9H3%-rEqtAyG}wDb%VYblvOcCsQQe**jSPZ_ z0D^Z^EI;dN0298|%vaVh%!5#>O$+r>Od5kf?Jg%QQjmjlA6 z+rX@e58djPAGzEvi7HA+5}LaXb;NNbzUs#B@n(Df8so1=I>WFm-bRZOIrC&Nh8KGW zi@mvFRhj*xu8A$uc?EDTO2>4iBcQE2cymEZemj}iNkF@64~ z%x-;-gB6ocW1+s7a?Y9sGFkE-Y|qZ=F>G=FRs<_kGxq%Bd$7wDzCxljRpiG-KQD=^ zA#=h=pmaT5NB5jr>R^H_RS?rct+@^RH*CWqct^4#$p%ICv%xH_cE_CHb?lEjYdCh3 zu4Fb>>#2ePi5g7x;S{qtVFCfWlXv?!;H{h_7+L0Foa66do5)2<9!0JsjKcq+>7>KNFQ;O2Xy2MQ+0qF2kOor%cGk>c`;g=5G3=>w3F{l* z!lGsDsbYSKQJ+rbMr0(nYQmbzLi+?Zn0I=)7VPgZy%WHyx>{RVtU7cooUT}D`YP<# zvpyZ+GNlEX&5!-*{nS(>*)*t~raac$U9KClD9E9pi zjrTRDoX>1sMKByjKz9*Y+pIKr%RQWJAveP$mh~-Lr$_y4WRjyj+(Zg@NlWfFl$^oM zrN`0#)xJL5Q>@g}x~MZryIZF1BVhvR#9c1jSNAw`c4$Zi$c~K_%R{rp76F?CfI8k$ zxj#SU=6=d^zP)#D=D+@xWh5*5gba= zl}p*FPegLg^1p0hJHt0dHPMJU30AK8(yuW(`@hi*t%x9z=crAA(bjPE&FT@$r2{A z5BzYH>cA%(@18q~jtKzvwV6XvS)u0q3Llh($b$i_>Ha9Uw{TAzw7X9wrh>0c zm=M2k6{5spcMtI%-j!qGJ;vzvWiyQ0ETxk|_`x4U`O2rQP(&(NU@n_zP|@H zMj0UP^gL{@IOZo6eCqn-EG7|g!NR-jYiSrE!E6#BN6b^@SPgKzVt4x6ZSoV0mu(&B zBwG&4S}<=r2%TQt;N*zBOf1ixf50^^RkVLb#FR|^&w|>#LVp94g79o*YZUkw&|}A( zvuhmB|Ga*QQokR6Hd*PmDHK%rBm~&w7F`-5d6RJ(xQIwZtx*w$6)gm_h@xjp0ohFy zm8ExUY>}3XJ#*b^BND5gAGb+?&>3&^8tKA4``LG>yLS8mnVD7;oUiMFxVc3VOmpn> znpsEZn1V75T^S@|O+;5JGo{S_E;x;usS{8iK}SJlAs+@lS^$|fMf;CMS7rP0WN2yP z#hnuydng^Lm})`vfRLaYXVqU8+N4kEJC0C!i4>b_c=r6Q9|U@eN;9NyZ|)C9jfbet@3M#8qOQD9pQm5ht?U=C)ca%94fO~$$#*-4Q##>bPF#_nZ5R1x@Tp&9ycNxygO4| z3&s13g86Jc{0yq}WI|rvh?J~7?Wf(S5?%mOvx*Q9ZskD|ex>}?FS|@u)HF0c4;ZM7 z{9GPosxuP$PW1@OA{Pel29`FCuY43TSdki$iOw(6qmv0SsN(W`O@cwZ8r%Ik=uxnK zGCrctk&8fmL_fYB=YU=(i@3a^`TmIsx_3N6{Un^YRd4Gq01Oh4VZHs4S%8jT!6iT6 zwscs5jUU%3tK0UoL_3d1@NOxeP+d;0!BLUl#E-O@opqies+9G@+Ww>pMPaD5Q+my8 zoXGXvD=upZ0v8?pJGK(}LdwzdGml#4aEpnoj$R=6;=&CgD9|U6 zRoQL~DgL_Z?{W~%V#7dxa>G;Lo%X7!Q!4w15nC!s8`Wu!`Qz=SGx~ClWq;R-^mwU+ z5Tv&ls0MGI*hVG@mj}Q7JILG<6;5hsbW$!DbGb<`ifQ^$qHneH@C8>Exh19SD=e zjX3C|C&f9%3RfTAL#)H)p{JkxPW8K1xI{fu*CI637_yp%>K^|hO))>Q#gN7Fkzi^? z68SuhyJLZeNL?7JY- zuFcq67hOKZk0C&cgG*<&2R7kPk7(sM`%g|rLD{of&N~XDg_l{Zw9Bf%y_MI8Z^4oMy$(CdvB^epVa))!fk0G;?gjPh| ziYToG{Nb)?yKE5vRbmmUC7i`o*37pwFc!Iw7eR0EkNe55NSTKAC?;h-m}VhQjfOL0 zI?B^er0@?oj~4 z$bC1rD#6h^v(F1*)|ua9t`}c_q0!^)>bL`wqtWoTv|E{Q{??~r>0GHGiiun-ZM1pY z!m>1faNvDB#40Ei-f3qOWB!Da0_H?dZpp6f^l0&i1F;ny{rL8ZR}<~C zX+D%VYZ^nRuz2h(AZcooi1d#BXnabBLtS9wf*LHK*aCRpCW8SISp6-r4g`eH=%%2|8$x7l}>XKRr(w7mo*B(>wk;Yk;i3e23WnfQr8UIKgP<5fHnnF7o03)egn=Q z(v1F3MRou5r~HU6L~L+JPw#1m_1l~smBXu*F{B&`K7gBw{G~28)+;GBuEzAm4XU|_ zYzUXmOI2Q+PxeLII@BW$$xG`bILmo0LMkO3Q<;@MeTfwpC%gR3uj4dz$|n)~?MjNO zDW~F}P=zBhp&l|=x03neTJ@-nG;s8_|vCEDcnyTU+Xy6 zk(nqSeAT!bhm{{3=5Sx+rq}=7q>*CLDuD4IC#$M0cVB!XWP-VFTF)-MZ$x;55(k|j zljUGbQ;~AYU;grfP+0IWu7zAJ+pm}Oks;94P@6x&HB0&F(~07ozN*!RLb0m5xbZF! zi_l5vP>1h`Hw6U=!P2x3AIoCMa8Nn9bmV31(CvQEU+~%RdgTL_gN&_4n>krw-^QS= z?381-w7&>DVF6seQtOfyE@i&~`4#(=b*6SNa#zgxooryZ+(=2gyyWQCP_zHLKg$1S zvh#0-d+>43JGK>xzb0OnN_&1c_!j-C!%Mp~z%$S5t$m}}@`EvDRoSy*J6*F!lkCCk z3n9;lhMt@5{#|eTRi}>5xQCwiA6zdHt?l*JR;FXfg+#>p1YMe44iGRq4y1N#m*vGQ37ru9 zwGNv@&etQ#(jS_;9hlmM8$c7?VZ5E^eXfXOy5$;KRuugz1?%g5NK?r$VWhMEB5_Bi zUc&Ie(e)_fxS)B-|2M#M;hZjY12vh-dn#7#uXQ$fPMxulk+~Z%qMnjv&p2hRNc6EO*bk7C-=;R+I-SD>CZ9J&+poJ7R2tSLeGN+x zA`}DDq=D4#XIR0zX2u@#=bPF4{uU*X?y$-3-+;QJ#PUX^)gs<6ytY$?!FI)vd554h zuM@Yle;;&s4MqlW4?+I{$G%o( zJ37S$3f}LPOU+=$H6AQfEd6Un;NM$2C0tIvMjcjPTxQb$8{Bk-fBG!Z__Xae;P$8B z;R)OAWwp!SY9t(fVc41XOB`Qt<`Gxw8%d{pM8~jJ#MCw6r`S7dkny1XjvSSCb}Q26 zuEHGm^|^|!kNeLQdB+z+)?)8uaVJBK9rt%NkJ6s!@n43=;TLXfsGCtxTapS&ARqwN*65Xnzozf>#WcZ2@-N7>STGnWSsT8&14Hw#ndy1S#@^gRnV{|z-><`of@uY9DISvBSvA*SC zKam^x;R9l{W75oZQy{X=MOG<7qm%EeD2WI$LRo}W&CDfgDqwI|60fECUPaYWU4uw2t?JZl zTXk|DF2SkHPG*!(V$5>5Q{kBv-0YD}_%8L1pA5Y&Q#nswryc5J^Xy)G5h<4na#uMS z_#1H6f22xiP02-l-SD6l(F&;l$@*YHhNpPlt*oTr`@DaX)?txLgi*}ri5>{!S|ToJ zKa78^%==kwtYqY3S6`E@1AE4?1TVi#df3ij#}N<8XmsMOog3veE>>`6H|Hb^<~)uY zH|4Rx`|)J6)4(XauwQ#FbgU4xw+=2QnK9v0Gb2JqReJ^a{Jyw>ln9W+4r>k>{5=Ke9ya8{s4PF$`Z>WA{gGFxVuJhRSO37g96b0wMcE_HBAnLC$=|2pyn9zz`Vovg_TVkqf>U# zrc+AZ-reSPCS*XAaZBs0K>d$x-w(xw{d{%0;)CKhD}-p<(s5ME)uD#{dl@&o!!Jf6 z>ibV7+JYQI%qoys*`AMFDBcUT3gH2(*JrUF2+W-2=b8O9v(Zh))2WOMYHj3}jpPlw zInWCK(4Y=@Vtv&LetnKgXhSVeli|p>I!RV<=(c-p!kh2X*&)>8X*HW=_;)&;mj$Pt z@HTHiP&O!N-oT?U%fVp90V6#|s-EdG9MCaC$7DL-;@BvtMT{{uhLvOuf3S1~^ebHj zN*Dy$^t+>uJ4 z^Rg?RG;STzs|}C|=_;;dwRxvXmV%+6Dhcanxh*qTLD z{slcSLawWr&Ooort6!>Hh%fs4!c)sOZv^G`{MtfeQp1UUhI?FGv;2(j$8G~gC^bVSe~vPXm1a}a@SMe& zb%UX5yYmLdEV*28Ogt$mPyg3|@T=DJT&2zQMK|%Ld*9j8q&?z<<8HX`ZO_z9xOsdC z?}2>{E>l&z-?1GkwA~g?;(ZHc!%o`hU#w-0i7E3gjXpO3O+c36*;Q5HDK|CX>Ji>6 z39~;!e-N?;LJ)ZTal=K4fSGOAOT&na!6|jya#Q!*!Ve;!7jnVY^zUP(zr!(-P}sb? z5J-?t|D?gRdv&bW{P;O8L5}%j44TiCSZ*9T8o(>*-2>|~B{-G%eY`w$yEW4wW|)R4 zN=^9%(IywMO;-J_2xj9WvYf0w8-^A5=<#ieJtV)O_XR8PJ85#41rT_ZY8eD9?F`sd zXisKk)ifEIIc=t%!$y&dlv{>`6xCGeYyUV@pn=cw!%2W|Wmjb`^fwZi6IL z!4Z1cZT0ETIliBnQ~8YFLGJ9j96j4NXL|gLiYX(`Gd)`HU(@~7{AITb*OT(Y4|2oz z<#QZH*A*3Qm~CpmJ;r(he@*SW85TZ5 zc`xl;BzFrUW^D)bDm^vwvNMy)l(dGlcc1vJ>#`I{t5{io9cv>TDPWDjJ)$j zXZH9*LbjdaQZW4?Xam+s^7+Ti;zzV!L$h4Q2%$&Hy}-x4+<0oOF7v^}GutG2O$OFC zQlJ4u;h#D_oXhc`h*vP6(F1G|k$6v_1sKA7xziapJML^JOed0oAAK z5mrWbcVD;MbMg$pEw^E*%c?Et-SqBEf_^t7cS;=fUNX^x3gW|gYcnbKG;9hm;YQr7= zEoPtc3vGxA=<3W2KKK|rqh!hHK_G(G-BkWMXTatR(w``Z?z1s@1-G|FT#@PLR??HU zlyN?1R*z(#g@o62yU=x>bSM~&epq-lSCO!2J7ZHTXqS##;jcDM%v44*lk>RQ+Y zh+0^NV$gG<(-`7@(;CSAoj3!g~b009)F~ z;?m-_(zt$Hw737usP*uiiaT66TQ`D9m{p|fzemH@W}dFLNG7EnyOvJ4j#Wk3e~GEs z*T1D*8XsO-62(S>6>#KHD9Tib)cwQ;QZ?r!{re8$jb|p&S63j_nSJAs-Qj zH!57sO<)scvV4VsGf!pw28fgCKFnb7DCriO8BR`sb(a(U#^Cewm{^v=f(%IsAZXvg z^R~uUzr~EgRRx?f89+2Nnj!?!c;+9~a)OOrwiGyX3)d<)lR?1EhB4Qi6wDJuyFWQQVu|EeNcbas2Suy|U1;*4yL*p=CGVhb zud5F?XMo)k^#q27>x3OiUm;r<8nGigUrfzabm$o&qNK*FRXaB`_v< z_Msv_gsS`hz4k>Ce~Sb?p!7wRpIS8S7}LO*zxoIsP7kyn5lS7#vH`37W zlJVFXi{Ai^)s2AijK2Lw?six6T8G^z{!NQ#zht%tbo33LPR{)r?Pdpd0uEvyFgGNR zwBp}Q>jlX5BMNbaS5GUL72JL7Zih@#L74#e7JE1Rg~!5{F;VmuYDNV(%SN%+9b4B0 z1UhBT3@s`6lfRCRN{y(fOp$tKfo2d}W#`Jw1&UIC>wS<@UQmT@o^zd)}XHX)mjT+YLAH`n_>Xae1)RTPph@^)j zY2GRhv^|RftQ=z zS41#p=33{b+H@X&XOi6Zp5EaM`omh|Q@_f8Nnrlx1|BuJS)t#6E7-x(k$EV71GbwL zhPjY92_Q=PmVIUZ@%L~1Pe&kE0?68bKxGtfqlP*JUVZf=!SB+w(yD;$Nw3(TScMmF z7EqHMjmE-IPk76MUlu)7=skl&>D4PpKa$Oztd#&RJqTp?Ok zBq+UB75~BYH+mbcr5mo$N~Fa|n}i=$;F%UM)?WkR5pSgen1?1aaSa>$Nhj(3nb^x` znC$oP-S()k4|%?Xw^f|LUk<+d%;Ci~sg-=ToLBpIL@}577(5a{;zcYvh%2^LE1YFM z&pnAMa{FSrJmPj0wRvO(aSi@1mj$2f`5zuR#q2|LkJ4o)n50g5KObf6@t)AhP0Br; zJH-}_H}&G6;^t&|h`=Z3-YI)8m51p-y|GeSF0yWeaiyk>L&Z_p$bT zH&6`5znhYLxgY-eGPC%;$KY-EVFS$$o>@o#1jvjS)esC#@T48%S|!WQ`8qOGYF4b> zeKqyf>E1i!wuVgv4+qO(ji7${KyO;$$O%Z*r+71*Vc=eoYtK5rlY)uBPXI|UaZXw$ z(rk#D%=-b<6U~XtOZq2)Ij2T)QUng|=ut&HY##tKk!zmZoWCbam*PU0inPvlB5{B)6? zz=03H#)cy{wv+wN%-%cy6XNo}b|SB8wiKqpmf&aui`x+Y*wzbXy$`{SFrb*Kyf2zl zidg=os`B45WHLo(0aTJv*2iBe2Y0IsNE)Ue7%~-9CL6lmPOKeJ(>!u;)2^GUdIU&j z|6tHNVJb7E#`osW@gQ)A=sWbHvyx)1sng zy(Q@@Pb!j_)Oy5PC9Q_Kro9&9d+NvN=V9;9sb`y_sHk{6Cy$(^YImEmlADZ!?D?~+ z?o~8uIY%zK4iqDi_7RHwdTS8@dGVAmD)#PZK|}7sS$tik=)S*^xk=+icu#@ExcSd zffLY#X%+Hny8Jmp9s1A{zYj4>HX80)!WX-mAT6!v>S`YnXrxS^>`MEr!IjLf!{$s( zsHDF&$)PWpV570+=7B%t0k-y^RuV=a#Ee%oy z_LxwT&psl5fIiR49+dpUX{gBNAS**~W9KYs{U6c|l|83j1fo49EP_Bs=vn^Hd_Eh) zb9f$Kf8CA90kQSP+mzGLU6caeB2Y^ggBc&`*_XS!*M!<5ByIM4{|2<8y~^`;TO$dF z6la9)y$iVfz?Gh_UAaPuF__|A%E|iT&&8v}T+ecY{Kg*>0hIvs zvLqXrsH3L&(=IK^rs=SS{$3WFL-loTo9p&6XSEOitw6{h1jFEeE%P0;qyMMOcL>jm zZavAKnB{TANuu!;3Rk46(1;{EZV@QIfrS~DPZk{vn61>*;duvFjp}L-hFsKhncXc}w&V(K-;Jyg`l!^~E>>8p)(=Bn zj_!74#vc~Cw$-PeGyqX%sn~d|mFZF~!ro4JXHiR?%|p8~XP#n{#f;7wF~8G}efhDx z;|Vj$2RNd{N`H7$3IAaR5&dc5mj$lAK1u(!*UE>LpRqPMm$*N41BIgl@1(g7_ei*+ z*Lzclk6@3V4TXykl;LvyTkMbN825#`1SuHSt1qqbwMu`_L7JSvobpBUrCn(-W3XwH z@eeq6H5elhv?<>nD{v*JhuK0hRO_Y>zO!xN9@&%FG-7PZb%rJL*q*)H z9(ptZ=OJ2_8hJ;&y%qHx459uNaD64n$GFR)sNlJckvtWO$mruwfLt1wLQwf@x*J|~ zdYhC&I}8|cCFF8dBg7KiVcW19jFqF?+CY-NP650PQ|UL72KdilNaF_+3~vms$mTtI zlVxbSQCmBM$;0&=fnJsgj*p;#&NrU1(#*G2nd6tC{-(*XRY8?2vq8*nmXlq zygFk%GR9w8o1rDUvR@(yNngNd(-hv-B5;q*34P?aFR|1@>h&FdlpQ9VoKX9{H zV`@qa4J-{ya-|>e-|e;`|MG%|?aIVFdN?$G3P8$ERF`y6tMs61<7!hdV?ew7!r|Y} z_#u$JAl1p2ll-ljnWev!IXrJ~)wJ_icOOPj@smb41R8eiqv|2>CH#6`>;5zimP!*T zJAScJ!+z(MESPkjGNy@F-i-w)`34Otkz3Vt%l2_=KUXF?oi+Eg?EF|zUFn?KdnVe*^k! z{a-p&Q3?k3yH9K+>ge>)8Q$8yJLIV&=ez;u1*ieyj#Na4#n&4dNG)E_!gPRVQ|3p2A7dq(bVBd?J6+T z40p8#1hjRZDNv79eX*`w@GzA!6Sv%EM!o=>j0uhB$dJ32P_uJ_k`)*uCMsH90`BIL zNxekX_?rArg~$Y_&^C1>1=Y3|8)(x340wf!xN>ay#urz6EM7d-w|l(XwFoPmGiG;& zoogJ?)X6O0U$tzk-#=mtk;e#-x4BBg8*gE&FAnv8DezS!qRq)Eep*FJefVbDmIO+s zAZ~6~zg{^{4Jyb3t|poL`M~^@(mK_bEtwTk;Um> z5PVPhOjKFza(rnywuy-(+7)$q(=~#^eF1R@Ncfq?hl`}Sp69HEG<;;#KSr$su&E6h zPIC>Gt!G|EnV^^3c=n7oX=yA@BAO(6P5kd0puL$<6#QVeH~?WXq*;DzA|2moA(H{0 zt(M04Huyc@&A(ren{?x4WWMTzy0x4&!2N#x6~po zCz&7)=bYXjEo*Gy+pg|cH*X@gW;+Oha!F=x8Y#_DyJNjO#?#w|?M5pgt2kN7{eFhv z+}901&_tX&wE-O87C|w~S+jyJ?V61)UtOzZy;9rP*KVox@pb(gb;J)WkeZL9tbUUR9<#ns<{<(46d zB|=O{ZQt|9_iYot39ohZ0=CuQZ4k`uDy{S1fKftH=7e`~<-kytD0#HvXKc92rIRxs}O(0iV9uY}0kLf@YdBNyStw)`OFWf{Tzwn3Yr z*gX$<%~2-^$47-%Q&%>9=B`TCB#=GdWbZ$1GLdw6cTJO&5fOJ)hI`A4tHQ_0ysGo| zTGd@ljY1Brg|OjQ3tL+=E>fy>GE$P1?|Rw;6RITCpDDm!b>CQLWx8cNci;tp-rQO$ z4l?#ZDTxoUq&5D@>Ba<$*GxNX(m$hD&kA*wo}eMV+L^FtHMi z560P&e&*v#eI<#zuj@hRV$R22_`)RB3moUiotscdelj{OmR4oM82Hhy(5cMHB;#MB0ri^7MEqMu0ngawuDkVWX_xPe%1nk7S7_400?$r3>c zvszCFuXa~j%db;?+Ta!3`2r*am$tJu*XXZ{JpZs~4O&~P6fO4XO)}4;;?CH1?| zF`&dRfaaT;bN9wzJ%pgOlfaBnK52r1Qn;rQUB_ZQi>Tj7>58Wrz4=W)(|VRi(3Zt^ zIALpwMei!tt@cl$^JYxC`nr!6YKz~#_DOQt7)(zycFp9w+~0cr{JQ~XfW-Jsxpr&p z_~j;=;qCxB%hnWGi#=<5gEf7Lgmlyb7YT~x;RMyFG1J4@Z6(riA0Gpeonam~rHA$< zchvoILNxhbkg~IFwaoZXKft&exJ1r6$c#1Oc6{S);g-l<7Rf2@`1jp#x6}YhvH6c?)e=)D z-1`iFGcQ|d3fcHG9U#8__thG&u&2`%_c;7jCx|B&rfhUU4)DAC^^J%F{j6Vq-va+n z$DAC^?LpLWa@6{>0HP)0;U ztkS%4b)VFG6@K|M&shZ;ZO#4!zGhg68JabutK)4i8AZh zHs~pKRe-wW!17mZAX3Dc`^CC7v{I)bw#dcSM~*>j7{Y3~78usE_Z%_gCpXw5U}uL~ zCZTGXZIB~P3ApDgH+vE-TZ%b2azD}gF=kOkY&tzP}b|@l#L^YA}5ny!@V+!=UOV)&|G zbI8PcIgu>kXx22Fkyd&V#M<95{Tsl(H%(l^-Af~Mld3@Xzzob@_HO{q ziCca0!EZo4`@nczO8_D=q_#0obg+Y*b(iX$q;Id8c5fDb+R#GV2g zx5QVrMPZ;jS+Shm1uUuDBim>1udV&3VfW9cOGVk?WfCG*bHgfQSAohm-NC#_LssJM zXIp+!uGyQ_2};P0%IqyBu7gu$_C=y~^jcNGov6P+HsJt$u&3WWvez1{4EQ6VChi|T zlAXdQat;?PGfR7iiPOC2c^6(C2j==F-9J1vzr;nz6|_JwqQ`W3vt|}Pg7e22bFqf5 zM!r7B(|Z{kZw)$3y~p+WWvoRc%Cy zS8z8IzOL6OSeo)nLb7w+Qb=Ri=ffKX%o zb)iWTeQs}&5o%;{?Df*+UXH78X0AbB9S9$F)i{S6fa(RRT8c)53OJ1&%PDMaSem|H z+J=n(4DWa-j6S_7`_$&Rd+4O;e34k2e$;EZD_4D?_44`!OYA&m_x-tLAW_5m%t7!t zgJ{n!AnF|QO-bFbhUMb>61n`|{KXZ)w#_Pa!UZGNyq0^vrWy|=cZ=FEYt zBvj@H3jyB^tbq^h9QorQQxU0#RoZM~F(V^IU}YGHI!O*lg`px_v~-J*`}n%^^fy3Z zMNV}Flekh>9BX=QT%&*1tsu+gj@dWy?V1`PJmfKj+8F2I?9+@od8hadKipx$A}B$1 z{ekSC<7n>CH5jS|gz8KRqXI;I8T-LC^++W@S_Po3@V|0Nuagn$LP zCH?DVfB|`)`gb_ns~sOcB)~*a{Py0Ae!CMHpW&^>OkEo##2|>Yo1DT*Jlf3-dM3wM z$(*|Lrj*?XQzuaqp4f1mgT*G6Ep-01c&HyWqVokQB$hSxT0W?Jn7O4v#7}gBu$QfD z`#!$m+RyrI5J(7UCno*zLHtAmB3Nj)=Spt9n#qb}##8Losg{!@Nzv*0rTN=6(eBOa zBab$!_{Z?vR5a1R8I+=i-oVX4v5gR2rtt+tEx$j4J(jagc4#8Dtwhl@rxs_I{WhBv zH08BAknmL`vw9UP2ELdar?mFTU^I_dEOCz4yK6oV$Kxu~t^HLNe!5#vIRhUOhXH{#JXD zjnpy?Jj<`Z~WfMqDs)_{_b{n#R7LyWW(6hBy*=e_)Gh-um# zIqI{U50MG9uu{ma2G^lNH^voL%a%$8qj5P87(onz*7{g$xfpgMIjpjjq~# zY-%WewU{Tnwo?k}>h?TBA^V+mMTy5L?k=|F`)%4nZ;)*Gr+sB9pi!WPse8j19b(4L z6=j?wx+qo6dUyky7K#cS)hLABYaTGwZ}3c0GkC8McF* z-H0-jZ8?4SzUFvQ(r1_jTLNby2?z|kU{f9N+VmKpF+bp29_2dnp%Z1T&!O-}?^3tC zk?pH6Y|i`V5hO(bA3~wtOmZJ3D$AoC)wGg0Op1E2wd2I#w4vgH`239iKJLp*lVU}H ztglq?Prs^BbcZOgYbmXB@xWAK0jCdlq*eSe^hph5-S(ai&FrqqMY7vC0#DHUaE|)A zv$1srE-5BLFWBZ$dZWYLiHa8RbaF+%z81l~V*gy)*cj(Z(sxzY=fIhds%{{XoT>9@ zB~3|D!9^CS373Ykq=lp7K4A@s@O}c{A0lk6E$+>75xdj}gBPG*+GW!pi+5Qe>LBNp zH0~gOwNCZ9_cbqTs8^heR;U&O@F_lISJcG|5k=vYT`M%|n%(qnwUw5zk zL5%fe*m~cwSC~x85bsvW&eQHnyLSGr=yP7D@Pm!DK*QP6CYzqFu z$sDwh#3PYr_&zk~8gJ7sn|nz%JQh@!?Q!nL-~6=RcIh!dHqz*@gJfDJ1;^K8+v3F6z%YM@QYp?G^3bU62C?s2h!a$aWolcR?fZm)K+v zF?trKn1>o5jcbvqm^+FP4jDei~4 z(}8d9;vmLhd2?27IgVCu6*j!09aFT1qjgtcFr3e7xB7_Y58YtgKHW7H=(%?!YKIX~ zAetQmz-{L;ZhfbzVq8dx%gwNl+;~vEt3;iV`zYD+8ui>e&(E`6po!F_x!5F`c{4rh z4q84uFMrY1apv8QRTLI??KS?jXx{ z5+%{Hp^`&>9%f?Gc<>Oh6!#%oA;)&$z$He+7a98Yqr?*nf%~7XtzK$s8e(T}<%HMdbrlz>-n-pH17Zro?@O7=@ooXK=zxuOwaxIro0TC3A(BzK_sB`=b3efnIz z3x{uFl!qM5TVX)WNm50KZVD+|5;2>%tatUq8(gTYh+=_UX5gL8?|u`N9V?wZyzeXc z=wHMA(&~hir@6>ZvT+?o3<16oV*s7m+a=0A`u(!R~b3o*&G$MX`>5c8P!-fx@gZmRjs~_ zd9<>Sf27qF*t^Tl-F0)O!qmha*+G8iAYS)nbhJfF&f1%%wBU$R(zGYy#>(Do>+h$$ zdfJbBT|05Lt3{A|sSc&+2g;YVUmNrIo@Jw_fMMY_i@KtCDSCF>uEt~x)2SwH@3)kKsQnbXV(2OVQyQk{0m3PNsglvXP2tnb>OhM%U?4DwZMIxf_aja~VM43t3~h+fsq?)W1F9+kSuxsDgh-8{K{ifl z@yItW^cQhb2#6V;)@J!Wx#}A^=kmL>R8bLj5%0smq#@Ai>iy(2AHB+pkqCCYz8sN# zD&l(YnD*%b!>mB2w6Y|;IFbuX$LuzKiptcuYaVAy49gQ4zpyymAEvO_T_J{aUsVYM z`b4CmQYZQ<`#O-IIL#WAQqPInsRp2$2;|dC%b3`f3Sz8Dk*k)T_IJ<1eJ|Y*zl27m z)EvHd_y}?IslZ2?T^or$;0~)ng6zJob6FvtUSI=)0{=8fXV%$6=YcJ%n_S9TZ;Xeh zB5?|mJ2F+*^Kgx|QRzDdQMF1$LId7y?ZcIfk}*sB^#M86v;4TmK*tq#{|Hc^`C2A! zQEqEPcdB#34@#%Hs_~vXW**TM--gl&)oQ`^wtknyLC7o5#_l9|x5)o8-z@Vl z-HI1AdYgo+rws$XIt^KU@K|M61TjDAQZ&@7oM|oD#jnYZwE0;wr=$Q_Yrj?H`YI)d zYDWWEL?YDtO|+Vd#}usI=^8xXvYw2PccU{73~5LAx8K>DmVfNoF{VD0^Sr}PvMIVuIZVNq8{sx|Gm_4S?CTbsxA(!Q+?263)NsFO9++3@h zd2|ez>hsdO;>DPe8rS`3bgENP)t9%@V0^WdLr6D1d^mNqw8a>> zdVezLqyb!0wlivO7Vm|Ne&`vH5?bt7CPNc*Y2Ir)vDaz!LHp|@nRR04z=);`#Mh&_ z+4##M4px8SRKUUqb!MICc^A0cJquaAV<)fff>~lH83%P2F}8Uy=CpwAm}z>sSe!9~ znzx}u;fB#MfQ55kdj0V5Dt2k{ca3BA?;1yz-xNClYdelJrY~Rx=~57W`(>w}IU%x* zwb!A7r$+4|l_|&V81VU{x9o4OSg#T%`)#0?UGkRj|W(qoUP-TGM87*@>dsMd{HemB6k!?b0>0&qb@>1q4O>2(^ z4fSec{%HORgfAVYqq-W55;3Z~w5dd2e^6tqaiV^U*|_t9-vC1 zj_@nT02FRHI72Mf;ySeIL^^L^K$CX=-kJc-N0ahKf9L#nc%BTq_?xee_wD`zvX zXY~|s+1J0)dXi;*g-_%Ny@2qp)typX$kPx;Kw=_vOba&wUF_;=*8V3@*G{iQfJo`UwqMmP4D;c zZ=Ih$UzOM?jeG-EE0Y*dKu9Pk(GIS_(yCz~tU^}vIc(LG(?Te%l_zqD^ERvXO2u5l^K;kG6sHpeZ@T3t&Ax0l1o zqC1_m;#pul1!}PD2l0Xn)-N)jNN{$u^Vc6ohcY9>jY)Y7V|q2(@#I?c{}6v`kH zqKrSxspIeH$10lGXRaAMI&dlXyD=J{X5ld!tYSE>Nyo4OVaMlRaFKilUprKSOqn}^ zD&=Z&CbsJiOl33`lKWVcG1rWtpJq>4ZRRJfFPFC3O&;=0bAw=DTHS?%Xvxv@SHU#y z1NB}7{7m%5qXEcE&?a?FwAE#pw0N!c=)7nXgXu(do_W+BThP-W)A9dAa6FSnSWtrH zR!(8Jw%%^R;9rg~`>}gOs$=cXFWqS`6X{uX6ESzql$eL|?e;yiyEp5?F)85U{t+Q{ zliMW^%EmmZM@4@9dZ2BJ!^*mrl0uh;ps|Qis5xn#qkNd8QFl<(!_!Ht(4^dyEo;v% zb#A{$$oA?lLJnuxT=umQzWK+^mQVEwmC&ebXE2_=$PfUbonuVp-lQBB6@_XRnx$#H zm-9p(11_tB*6YF!v$r3NhjYd0KB+Ct$-42R*?oN4gEhN5Xkiz80!~E)d0DQq-0ye)eWU^(K6`=21Sa?|RM>lGr+ck$A~WO1}{JUS@E_=L#xIZ_k7< z587NR`}ZTBm-k=PPR9JLb`oL2?fG~(Ho^UEhe-K-;0oo}B)yO8)YFW13%4?vd-!wH zz8AGcBki(>bA^2zHRHD)TE%>hxpZx^^_8jICf=^OT(a;(M9#gnVomUzrobI9scPuE zcm_ZCQmH2nbwlJ*lx9&|Axp|PtSYJMGql-|K52MrL%7S_ho%ZF?f$6%G73&r0Q zXyNu)KAqVaiPgY;_6(rw*R)FWN(q&+;|lZxM=r+%*+O*Zvpr)Oj=Y#(?;6il0Nnc& zKCR5;cQhX+vCglic8|pSKF%%b(4Yq~7(QI9=er%)VOQC$5%jMAD$6BlNj~e4fSkb2 z(N$cywvPZN?t|G?F9orRr_Zk8Odc?7{kT7X=VQdi4surD z7>wyShd|LJkeunt7{SA_=v!$)(flno+?sNI1GjirfbR@?bt)##yUgC^SMA)*#Xp=h zJx!)Mh}FI`?j!_V4ZW(%wkHr=r( z+4p0lPx~O=`E@@H%quSJa(R^HntBCT=3Dn&yZArY&bZ^lUOM%zD5(@Ru*C0=o;&4p z+EVYyIVLD;cyG(|tu5X%eOLA*)Il^v~A&$yt~ zy+}mw54uG6<)1EGeLFs!!q6niq$|)~u~5ZWn=rJhw&fASbf8vyVt-Hok=@I~>W>MZ z@U!vrGw(MmB1s)!5kVgEWG$STfJvAk&JGPZuq)GB$n5Zigc7ZIS$>4WM6?Q@M|TB(dP6fkH)Cr(UwIqq z@p!h`Cxd6<{(hPB?IHVfH-C(-%so7kQ=h4r@Dll+9)DY6#4)g6$MyZ$aR)jVkp0xlF}(jS{d0khfd7A;Wqo@xWq(rg~62&CKGcNTu%VP!I4C3phIi(o(H9bw~N zuEDg8J-McBEs#+v|(g)#Q2f{Auzb zkKJg>h&#T}B*$Ywua_S5Hnk{rA1BC}!g^6V2@Dsg$=aC>xSch>kn7dw6aP~E^sTo! zUb<&wq#G+HL0_%C-Dg|eel}IwMR~0SNT|NZ?8^;5?>{eq$_+#+Wk?W`DfiNNaX>*(u?mrON%`Z3>b!^X>P`s%3mL62Q_PI4JXxt?dWPM`W!hWY#5 zY&N`7kH_YUKS2|ruL&IoMWq3hgkyl;LDg&|_Dk(cBawl&Ect93shEuimzb=$r(TIC zu8;9Y5Z_HJF3yVMj2^9_Wf2{PYpFjS%T3fCDBVr{7W>sEb@SwYykCVRP??T>dEB_V zJZ&^(jZzm~W;*!Y#yWvI(dwGx#gpfh5s%LLtg>@&?p}BGfP%p4m^)|s>(=IbQ>ei5 z8?+c5-`cz7lTBEsE)Kc4TxwN!kr=hgwB4HE9A-}+zy4MFt6ivvIvY@K&)=Pfzotjk z9<7xntip-$Q!4l$3jD?#U}RLK%So`Y`_iCH+x}8jEOC-&r37 z4Y%1lxKmCm07e9VFT#e?gPO0^l;m-_1im=uz#kCZWEIUI-JdB)JycArFuhY=%vv{i z{xBlua|aSF_M>Gc(2$u95$JTO5#6P+N(RdN26Q^_DDf9ZZJB(ryUcDOl;UfzkjrZY z)?50tNJx5;h8&Z%sQt<3^I^aWAsG?!R@Jq;VJEzM;?LU7zg$xf;B#!8u`?%~j{$pj*SJ=*@9i#}i z%U3{~7W1$iz{m7-1b#9^K3#9KE9|zteu*)r`mTtuI~~_*m+ytsy+Uqnt>2q|ubQcm4dwH_n*xG*SA%6(~EQwSA?Rrk5m=vH%<+HvsI3J|?1it?zB7Rse z!%CKM$v_jhelM5S^LSo9w~0^79UtUl-qi#mEaQFEU%`Jot1et!kzr49ua<%K^YgJ z&CM4^7yb69B5GmwKA9u0EDbwlqPoa#@oN8@0Mp(!Wwu=lw^ZJD(5l>*$cz!)SGJq;rzm?F3enwA8>P!;H778|7XplQ8!& zek85u^4rWE=y=f+<UYZjxdev@DoED>GYZKqKyQ6JMwLbDdcJKcEw)R0dlw` zkG{jAZG{7;&c_$8b`+FLji!*N@7~}Ktf&&nCGu$t^LgvMm`SPV7XHG;t z!s|d;ITQ@u-WxCTk2^7iwdUiwcJ;l%ZAWP!x1^=*#-yp5I7u(2>7x`b^p*Q)#(cSn zqYLYqdTqKcv*4A9tI1K91FqGGx@aa+)?L~kq$$AA@!_FQ*tuo*FI0}U%B>N%Zg`KD zS@Fl4-7;QZ!PU^{(}r9T-0;ioj~$}z2Ti%Y)&v<YQ@j}YxysJDlCHCP~QgC;6!61jD4&v4b%Dg|~0VM&ZlS`IY&xns3hQH+gKATG+~_GN_! zXpWROmOs($Q%V-Geo{HZd~eO;)3|2rSfb;H()x(pGHm>Z4~<2S2SP>}JWRm?KQ}e^ zJil1jx;hW*>K5y;J0=J#(8xRtVp1jR%cr(ZP1=RgCEoH2`eaL+FX`Kz;bU}>!lmo_ zjor~83EwUeZH zazu^x4KDKmNn9%mY&eT5cK;3cMgIl&)snNZe`g*17sURX>efH{1eZ`WxZoEMVA5vt zTg*mz?+S?$^RGaOUKpQunp8~Th&N7dhg<~VR^^uZ#FKXj9UjA1U03ODu;DJ$d62y$ z4Dy=$R@GPVNW#HzEe}M)w%ow4+&dD_Z2pxbcI&W=4uTVLz?l;RptvcthT-tqR00_B zq@&e>k27h047*%{kXzP>jL#Ms%f9`m(=Bln1Yw`eaZF2UO}hEztEEzQAqi0#l!3=Q z$*xOv_J>BarLx1ii*FKbZ4pL-S3x$OLj0M4J8MoFwHG4FQC`^WPU}($UyRXFh?3zt$I@G%&Gk}S&_%q zN~fbQTmkq3^Q`o7eB^Pzv77T*227LrR@TF3Cz9RrNuH%9^_tcp~NxL2F6BP6Y8LjzM_&(|upqI{ z90MAQTxli4lnC?OGK#F;X)kNH>VA}T9$vVaYMO@*+4I?=p%M+WioAuQqhr8`NWi_C zU-|?GV!6RNey3qKOJ3sX0L(W_Fw4`!7Zz1F1D=;`HXlF>Lm zKE+sPGH5nwBg$t$O6sCyBk8@qrgSLFxr~|Ydw-uZ|E>LbdE&*)6y{iOxfY*O)~gl7 z=<0V{P*Yo9m*EKlrT^W(k)Zk$nwJ+^=+qOMblUtui-2!kY6#>0nI~)D7}-xqQ+Hv! zs{A3Tsj|DeK8^*46?f39u}>8v8U0u2$c02g-CQC;J_3D9()`7wHIJ+RX1dLDe)rpr8O!rRgXYZJDRcst3AK2xV zk@GZyXzIYaPrKoH&e8jG%uDfgMy-e02jDJvRUOjJGchH$__^^l08CMnPdY+v;cf}@*>y1+VnG-?jUJdCs5zRm5emU%^-{LWrwW$ZAO8lR= z=Bkm=mGD!jjq?LMFQubKq7=&{$?Fb0M65RLhU$wDFVw8XR}y8w0_pDz`nr&ae&Ky- z**mfw+>JWA9*DP?g9uUu4o%^m{zDdv#>xBYM<=|uAyqVB&*!N0Xn;FEH2&G@Z#IOdR-699^M; zEQAIr6-Pe%sJ)>ei`8Z)o|%o^CjT1NRgB3b&kTuVaC!+=NSi5_wboBm(#Ngpz=kT# zS_SR67Gz;Rx^~6UO|n4|J06a>x?Pw6Rfa>3nKepk%mlhd*pxUbZ(`$nkN+cYp?Xi@ zg2NBddSAAd^XhAXUo59*XFDB!{R3n5pByM7od`QRtZS}EXJxYfHvgDDeD=_E$qc>N z%l`?KGcL!@`}*@G;v=U$r)$EJF2!ngJ(tVEuQl?+dY+SBi8r2o_tZNt`hm0is>n`= zYALR?+@YBAC?hpQ*%>WgTixyO4Dche+#$Zh?`~K)(!o2IL(M5}BWFaee4I0fP}i5` zJSY=MP^{*1>=CHl8Fau?A90#w=Ok#Ak7hXQ?T(30m5cM;{L;2y!TEuMVQu&Fc0-AbIujU`#0?VHYRjF-x8`s_J#sEE$NyfKizZ>2zj+{h^E zgsHH+dUPl#nbmJk%N?nv6YOiL$?5LWSypkI@ovciQ^}T3UbOpE)DV2j&X|XE6H6sDa_YD8hHtx##()wBCPT=24h}N^gpfaUZEyr9qacH@RD6fk zY@nQvms$K^cW4*kTOzLpY61UwE^R`@M0O;#W3EoyzOrj|73P@;v{U++GiqZL<7K>S zRr>RK^gIZ>w8IFwSh zz$%?H#HweRc*zdxKVT0@q#_*7BE$Euye@{|pkU&Z8r%?xPA> z1bbr6H^VQ}?rt{%%l#E#m%-dr_ps3vz~tQHJhiZ>v!f63#nAtRU(UoroL15!g9lR{ zN7!>&VmqUUF+HGcayCyje$f=Xl^6BE8O_e`S;C?JEpP7*Y}~mU2f{sVg6LW8#U61o z99azSnsJu3CJt&UCr?x?7xWle%5nQWhe-pMl%6-`3@Ow*r*u36ZZoEdab0hBrz6(Xmk=j_5*2q9-q zcJ6D*?$;GrydlCr914B!A-r@U^4NFVvW-;_5i1{cQM;LAM1Q&$uLv$i1g(4Kjc|H7 z2g>B$=m25`&F!Gf7d*t)Cox&>hq%QEuid)hqy}1%R8A{D-bys96r3 zEcgm|7`xUWjztMt{1Tr)F-T*ayhmDZ52tx5%=$LNyffIizQWX6zygWjt727gaGU9E zxs9>5Ok{%dmWEJTp?w4A>qR1BP0{krWb`NI$VR&;KQj=R3j`jp7#<)8<*ptBifbpB zh8FC(?o))mFaF`)%3_`l_XgFsJinSJsw}tB*IEl^59Q+4?KLTDRZ_78dmo_$9P z+Mdu!63A-O5ma^r-0^m^c>=JuKTAj}ab%@(OM@#!qg8Q8G+^hn@+pL=JfaJD1vmAD zm_MQgQIFz*?eP_@lyOGA)iLrk;Q*R(@<8KOqd+Z8i_i!++Q5@=1eP9sp)gs+u4Bzo zJ~$PLccL`xE9qWw=2hdd;-m6!Fy|Y_S9-_}cK(HW4l9)gcdu7GS-2fazve<-k~AT_ ze$9Lx6X)-%B-n<}&UR>8s5Lj!Ur}Ecb+UXLQL=ERWS1dl6!I(Is*gOzQ|3wslU(5d zbwVG?VIM;_ebZ3R*@cIv8#J77+6#nyovAYN4Q1J9lsQ)>;_J_<`hRjFLLP6&0X+|> zEVP^_gmLIob8jx#yo!wa8vQpuh8V2cAt0?}Sa|QT5jKiB4{@Vmu+BZsDaWt19(U$5 zTZyNM?fMrxjK;iCghGwJOLPb~UD(O%lx|YYmR&=7ty!HQ+CS*9{80XFw$qCZJ&#>b zvc@7!4&PPs)fsK3i%iD=2>71}`W+~tEd}U@QFFw;Tk}?&3{W?dqN?Y*yD=o`uzpK@?T>bo&yNEb96Mods z&>~W)@!?Foy`faJi+FE%<{#_B@_G3RRXjeM_EW+D;o@BVHYMb|}6n05+ zbJT-K|7BM6r&wKM=f1h@{^u)XS*Mc1>h9rfCzh76!8Sq;i4VNp@G5s-mB;V5d{4nn+#&!!sWc(#+7#FMK<^u5ocGFpCQeSPdh1o=%1iobL>Gmhh?E zFfPdjx$}pb&GEH}J=b~oJ<8I=(5kr4L3@F{u1NE|L)nSa_v!-ix^~BaFYOd$6LE~- zOS0}wOGxe-xQ;f0PiJF)bca}oUZ7p@cGh@7b5B3%&5C0am;Pq}6J-5OHN0CWO}QX4 z=K?zU5s8-B-|VD>W9gmv98Xu(sD7sV>kKmfN|7gQq$5m(!-Ra#VmTIUl5UbDs7A@| zEjhs*<4zCSX?{wZA*DU|XBkeCj&gwd)Q9+=&uHDo^WyZoolG1`a3UoR>iZj)$I^I@ zp1k>0&6v0XE08#wYb<|r$YX#ONzqZxkF$H4rRih|g}x^M#=yn)MkD=_vr!JieA)43@5%a}~}0W59&PW|FE?OHFg zAE*it__-jX9j&CLUq>5@s2v#y{7}K{+irdTS%PhMCt!xh%uW#Pw{trv3%AC3N{+E2dl-sSX8JQ;8dP&c5te?N#0z7GEV>wHqNS5$y-ymA#SMW3RP zp9=pB4k#L7z ze92=)Ot7~veK99!Gbj}oute=jw-?Skf9b(#)WiCVycDf9G5$SL#vE$OkTQ!ogA1sn zanR4N(3LL6-*{HmnLIQg>nS&OBjDX8>R$e0<=!H3J;I$T>y>@a`NgpERRIx9cdk=l zYt>_)!>yfDbqom;PlGNAPnbbz^mXePq;y&2^-Dp%Wh-L13vT4#m8g^%T**wn7Izft zTrbG+tyVbUPRYhkf>z`^F)QK9&PFSqg501FG{S{UIayZpXk?#qsZ8>U6QVce4=9Wf z=aqn)3c+M#l0|9H1x5b8F54v48>^wnr#0UeT5=+6jKt1YGR^JydEfgPb+ck3%mz-5 z88b-pE`DabAeHxC#FcNUNp0rM9h>z;k2Q}fs~z2P9|bd3F4=PSS*uK8GWdO@y@Qhv zDA8Q9wXq?(Avh=#XT12^Jbey%;Ea^tUvgM6Rz0VpVsio8!G6=Vvi-gy&L2+;U$PT) zroP~(J)%^dV}gB~lGVIe4l5!D0-0s|e4zr`efu!tjxEG*5Z0aGRIy-^hFND6&)e?P6Y-*K^^YxnEh6vsI+*;$=&%e##F|49fIoSKO=|V!7 z@VFyDPAU01%%H~Y?+Ku?8tfSGhru!6H<5;s|L-iqf4UEjY!)>e87~Ve&fH^HGMB`6 zMM+m2QC!x{mFg(jm;N`Qr$1?K&jaj71g_z?yEDj%gD<}tsXW%k`Z$gqhLWP-CkP)o zFv;Ux*0 z*tqO@Fk^DxvBk5^A-8H)wS8iwr33Po@@^-xO=mHNJ1~T>F?rA*(pqE@r*4?{>lXY9 z#^*wwp+v`lHQcnco$3Nk-ZK(IMAqd|l2>f0x$Ub*DtlKqYk1a@9X*MCgIv-D@^b`% zz{_Kf*UQx#;HalMi?hH*|;3RbyvAQ!jZCWSN=~ufN^dTzGY+v2BG}rz&aZ&7d z-DW5`KjZBG0~`}p9F%v1G6(rlEBhyk$$bm}(LhXsG(}~EwrqZs3KP{l%(2MY*FFG4 zT6t=o&?L5)@EIk=My7Tdd7*xZBkJ<#9M_BTqb{tMm0I}M%_bgH?pl^)yOd|dhlgpu zOt8v)?l>keFtBJi&U`_tVjtHM+*-co^Kwi5fVFc!Y`yLlmBw9MpiOF)bV%b2Woz?v z@2{X$s;j}i>rt%*WnzW(!D`SO+89#)Q8~;j%X=XNZDZ%vH5Wyjyyy|Fp?W^rZ^LBuvxa{#8Mkto=<&6dc_$~MgLF8`$UmeOL&XtNe| z^?%4hyDJ z)B19JeEzwZRmX-i%Y5vBPc7c3YX@AL6IN`8QUiP((_K9gJn~2RQiC^iHuC4kqeSwx z-yR8)CEDo2hF`dW$O!QDw`2=-lmQd#deqzm%g?DLKY_!+!@UP)tmL_22;w=lGJEF; zgRP5RARSg6C~;Rkc{b)O?Twv(Q&Rd7jP}I~imwQ}Z3i37P9!>Le*U$T^zn(FeOoRc zv|r}oB9FlLDaY88lQ`gxN0C}VLCDVNM;ntn-3G?ab{R5}+1JAvDC-huGxiwwA2rE@h27QnvGBJA<^49O zUY?yo%VFIB^4BV!)ZUs2Ii46_Fpq5e5$5YL;G#{wdVVfub!2H3a+#O+I}Miqn8#C} za`db;Y6KBjSJl30Qszf~TLeG(VdLJQ?3xfNnbOSj*#ae-@^`EH*Iqf(`;aQ>c&J9b zSZkNR#S=|q^ilF4b2Uz)JHk(o_^E&@f1a_y;v)sBG1aLJ8{6xV9m>&i>-OSJYa89i zpK=4f`Y}0L12)0SbR_e^`DwRzlA7 zjyjN)x;a*;S;pkJn|pPZ<8)!sfl8+*T;a1z@O7R2*}!~@UE;>Xw8ezw0lbR603MAa zTwUC@z`|T#!J{!rrmVTUjX?92p6*~DgdEc&lQao@T5G;&LXpesS_x(rgr%lMwi0O3 z2WDkl9~yCC)`)+7oXzUZfOxC^o8Khx|I@~Pqq9y=Jcw3${UhY%*T0cB{@T@h4KAT* zzW^+knwj0(beKaUypa6!w@e{;3VSsk%En+)?GrCP!+#Qfdkg#_{=ctF!A2;7OAGW>|P%}9SE#7#gB-BCHn)yHd^Z)w!|AN45Yji_{|9&IP+&{;+k%Wl@ zmZLfcbqA^gs4w4m{Sy;$(a0+=wakG_+5lFiQK_vp&d9xJfbnQX^l10CT)9+bC;xJ- ztmbRKBcm?&osyncR;O0$fF@e_(N`Wsd{jVDu&(lzC-+(`BR@59su(t3kpAihVEPgA zAHRMk5q5fddRnIvrf|Dj*>EHIVPH$WB&dRx`udOSz)RVas&4CZ811AlKASykKqdE3 z4|zIqeL+h%F40;CPL#lMCi*L36YqkiYYmbq+v-V$^9tTQ-hR*?S=KKmy1(Y_=x(qZ z`+V7$xZOQJXl7sC+DEb z;7gO3=msx61R7^@C-2U;@C;pfwtbhdn%Y}I9)ad;eC0Q#jscG?HZ?=`4&YZr^Vcz@ z(WF3?W)W%_CNrC~-WD z{%JvP73KSU4gS}=vvMF@K(>oA-}Rx%Vpo`&Vo}+)w*1!ewTh1nuU*7cL20=n>}DDP z0hLl`N~A8Fpkcei)$U(9)%yRE2mVJR_g_3x*3|E@OZ($fF@P#6LYFm#Z$ki!MhhuP zdt2MO$rb-J?)=A-A;ecu4edX~o>M>xoV#w0w0W#|&Ug6=#*4VmJOupQYgKJSgE6c;QyASF%L{AfU3^!W| zw_g8KYs z3o(Ns503#{J#f>0vi4IN|NSqg)t$Fi228>hVj!mv{_dbW7HEN|QNXIe z7EcdepE!M$CeZNKjmjuE9Yec6be1x1fgCHw_X$VuU$F?kR$1p~TEnv{cJ%$IvgVIJ z&EyH*lj=W!ZRcH0Z$eyp;qnuycG*1Hs4n7RFBx6&Bxo#+>Q(p1%W4Pg!!wTQ+xZ!? zyCS=lOV-Ke$=s@-Zd23quJDvQ)Frw0BpFh)lW=?KJ4$X}DOH+BOF^F(af^YgkQzw# zR0RPizvxOb+0NV&Cu0<%*0dM>XI&_D8ow_)sDNo>{(PlJdC)}a?>h#Lg46N8KSb#n z!cu}>U`qHcVl3Na%P8+8658k&d@x>hD<(d_?HKTG3wNhrp=z_uo0S}!LA?wIm{FKl zmnNuO#{glt^o>5xX6&wo;{ZW6vqWa;wB)>tu7Rvlfq@Q+zFFeO!vL;YWy&yd2$uir zmTm8$_MrEIGsmLInZ&}bu@S6^R8OCtUhz`0M74Bb!KT8u#)ybFoFd&W-%5-ZoV`cv z7wj|ta1v8tYp}9X1<-Yb=s2$()woj6!-4rROVrUIg(Ho_Wr*mW)wPqS0qk?rHRd1o zw6oV41XD0c2B;D%!8ly1f8H~2=S;I--t{~=QJ;(IQ}ybiRgxF-@(gg@t+|X{=cb`e zMpEN)kA3zlZ~ywoQU9-w{+Vd(UtWey1WWPQ7F;W>>zDTTt@FZc2CnH*9m5We0m<^_ zcHRHXQ~ckYb6Ab0JK|`B`#>gNTwu1c<9t+1smAmxol5$Tra<|1cTgQ|m^R*_mS*?D z+wq-Sw8b+B>bDwDanl^^`fp0We{Va@wRiO1;)p}L>82F&-^KvvU-T~h=F=duxq|jC z;YNuhH3reH3GH&s?mx9PA$i~J9WrM!GGacdurSO7ba4#4Myf9Zc*Ds>3qFL}-pK+Z z9)5Z6*NyKrw3ZB+xD>)1lUl#-A&lIWZDKTP3VUoA*x4Ze{lqRI65O2Xu2? zqO-Z2(lcKVwbu+{YW$T%;2Y^gQ_uzt4Kxf>ofr)2-Ytgf&+byMABG>GqxQNbXxtj7 zyUJg&|BM*pv#m(cw19+4Zk)tiJM_(Opmw_2Y+BHMI^|@t4Ygb*pXd$OxxIG;*+Xpx zz?j!WXK?aYgD{yv1I#~ZDJ59klSVZ7iFBN;b^B{fhD0DGZm_oO7A7Yox}7vhDO1PJ z|1a~Q?_Wr+Jo;@KGMC=cuZ;Y*4C(q19g;g`fujAtY>|B7-)+T|@}YOa!2sn}e^lSW zDBK^eGkBhvP%_a~zMxedl>Vo^s^yHShUWcgJ}{EZe>YG1YlQ7O+GW}aVSNWjf4)-4 zXN7F>`;MIri-A~IT>1)nk>1(?Da|fmG&fE=}sU@*dNM8q`()a64On|h=_deiEpFsP~4f)2ET?Tqw*2)Sm<*5_&!JPN0Qu{ z%Onx0zV_Iy)}v;d+#FgWWk*+IBrP?-)^Q^lnfo7u+yD08w}i0y=Terq#C!~WWF>>$ zcgFAgRbu_u$Bz!-*nh7iPn+zgvvn9BEctmS#14!!Z(PWaT#ck^&dFUnSbw6{`LsMK z*&(50;KSVK;_m*Y&V1_%w`Hgn71%p|(FAh8D|i1)>xRa`Jec}E$zc6-^fYSgmv_&0 z^uSeVaUGq7?EAfs)?0|rKUb~_0#4L4B57K-nWC46G6m`yG)}i}gy}xeMCZwJD||&l z5%>3I>9sOamonb0a4QN5u4qe7?uW5j@aS&w_)LPcXQ4;gMA03?+^hGH1)zh)aao=@ zp*b=b9^Ecc%kyo&?i)q2*Hrvar<#VdZX%$y&Y--AE_=_irFYR>h&$1~fxZ^KG_kpG zqiNi%^6a~^NJBsPaO$;`fKd*{I+U>Qi;K=BtJRm&!wA3)Ig&tuNPat zr^%lVG!G^_kJBV`)1348pU&BH;#+S}gpiZM-QIW$m9bRx+Wp1hTl|RlxM=Afu$olp z{#O#a;-j^NeaV?F@8z}nhFHI@7Uop`?67A~`ky}9e|c-pX``(n7$>zxPd6NV@(`V$ zz{CwK#y4zNgA+t`5~p!vyi&WrUSPgMnZ2Xu&kpDfZdne9MqEcJ>Fc2mJ z1nK}49>36cFg}}GcK(rlB98J{3GdJXO=|oYpf>aKP!VV$bne4JIju8e-_~p^95sU# z$>;rV)a=pYE)JmNUIAJK3z;v7ECe`{a|rX1+PM+lw*^Bb9yh|Q9xks5(S9zKsO;}9 z_@BlHiiv~$v)y4sXxG8@@NdfYZYLT4;FgLfHLO5J)!stcx zc8!o@ginj|!7HtN1Jv+T^j7+OAPo*p=V3xg9A+`_)9qcU!jW{gUCl5Fp^(qz6zyMf z`Ri5`X3HxQK^T6u)~iD72UjQtohZUwUE9N;yvbU3Opn5gUn5?av}ah?a-Z(E1m-sz zR=Y)QR3GYy(fWku9^Z_&88grA0QEx$jx}06K95R$R0MqB7?7ROWW6?d>m zZlsHH7p*yS*B!a#h4>)5BjtKrQ!E!->uhP+--D#44 z$uXUBob0j09hH0_*SFADIu{IPURc3B@yR8moM|^v=7sSZGN3EPL8kME!w6*-d$0hq z)k!Dq|LM9;qWr~v=#fc%X<^lXz#9L*$1&r#A#s%JK>L1f`aM;e!u9H)f``F zoOo*NXP+2xc-(jdorLiVt^CWC{=I|0k^28c3XUIb5T3NxLPh9>p3-`5YV__;H3AH( zTwmso*ZN!g{6@c=;qWy7$_zKnQ{*v*u ziP#1kWuqsg^rlGGqu3py9?!@?;Xl&1pKW>j!RX$6fIuq<9$t5_*c6|s*)qE`-#(q6 z!YA|e>EJk9Zs5%6aol+Xw=~#v zvwkaObqi6Zb4lD(QesST*5orPLfWptcN8X82T!5QIH}Y)o_V&?_;A9}_p5&xzpt&3 zzC;xFT^7lD316x_yh3=4e#L-ywE^$dgbr&)1s3-H2OEpQQXt_=OI{^oC+MnC1bRli=wS6p-#`9x-BR@6_orcLV*UbilrC&#eWd7~vnc0!q*}84C5YHaR zrZeU|*_S;%%%!(m7y)IZJ1vfO83>yp;c~mOR%Z&zcRxUHSbR1o_K9~qW!aFiUMm%T zG!5Eagl{#aap@i@CheyeHVroHPdJtC9GWmPT*f8s95KUwfMgUiaO%`{Tqo2|M>(qo zuD(+^u4h?8-Tj9cy*j> zxmA{`ADc=!xv}K#hPiP1p=JLCfi(LliXhNSoPFY-LgV+(E*`OLLCGbNFv@G-vxl&J zKpFroq|xqUA3-IjjHVyR!~fDsBD{M) zH&^$KNzo_P_GAM43oQjYBQ-}*sGf@oq2A$2X^TF z$X~x@5~fZjF453iPLPJu;OH8~Xs6N8I_t4+>Vjo6fkyR7vi6W1w3S0gHumSAoRIAvG~iB)4<}5# zpgKBKZ_rozU!Wyd-S#^5=-(DHyJHp&t9|Wr=8*Y3*$FLC%#X6KxmS+4+u6ohNU22z zK`DIb7*@v4Asu1`>bpA*hi6Z@w{7a}yjm)RkSA;SsldKoweZcc2IzYFm~24pv-O@q zQG$eNX@e26LmbbEI!fA_+MKCRIX9P7jbGZp0DCgr(ze|DPC3Q))1lo%=;oeTJ@a12 z5o2oqSaxaydX8RIcQ@*h2D)nR%a&)gZ?E2pWTQPbf0tK^+R)L{LlrlfB8V}PRHWs4 z;KzH1)UkxWPntj<&#=EHrBR`{hse&+(~%9B+HWy?KVB}PHe=3~NI$>Hy|fT(oX?je z1=;i~ih+50O(4L&#XkvCXm&{K1<9u?mgzQ++b7W?86aY83xz|ncu#Lm(6w!hK)aQq z)4;v62{pD-EZ6hmi$L{*?hR~kt=u!dL;I?~+- zr+P;Pt{79B1Z~I5iJh{|Ry#sEW#Vsk;@=VnNhXkIq=0Galsbvr1J&=y6NSvK$S6pA zBRP8x_*)N7cu)~>ZTmL<2$y(zJT?VugyRRINKHHm8tBuAQ`6I>FUg!+lX9(_X>!VQ zN60mM#UCI+aa56Tv<*-Q*eJZcq%|d8b+sy|#w65>OKeweC};0e?#n^1z^{1;+iI83 zIoeauNC0u@d5cNaSPwtBxrR!XXT3ua@5ipb3)Q|9*aVYfAo#^m!MIq84iqV8ai3Ke z_fO$%%f15t!{q$u>HorXY@G=U7Jtojoc@~WWY!vP>?Mfl8m>Lh@UN5XgfWm|=@)$h zL(t+Ah)hUS6qUqK^59EzE5dn}omsg(R1=SeD-sPXZ2)l$$?BQxd(K0jH@p|@i* zrK|shufJ{$`T|m{bg$%&EumL(MbMqTctl$sqg(t4jiinP)-^`msv*OlO_o+qDo z0eLZI>M66VsBwtAkLYHk+Tn+s<+?`26ns(E(KO(Z9@!iIZbHQZoOlm}gM2@+Uh&)C zYuq!tDm4T@RGxK9IN)ZTjbbd-_fC>1JEXdRfzbn+b6yA4Rfp!fbXNE{&3``B|J3>$ z1}di|!VLZFB@$Q9RS)~96xT&XM*Dv_bN<5rYwcUVK_f$&rD`#6UF163*C&*sx0%IO zT|GPHI2wJeSHUQ$(;`)J__4zNl${!14$ZcYfYf`>-r>gh4WgcVloNlpBL+TOvpu85 zYg4|bP`(k<)|=B|N48W8ySBssWkr@PwEYF@#6)P&OUhoCLQqX6H`VdQmk9-#c`7yx z5&3ejRtq!)su#ZH)H{oiEwy3^;7hp~wXBB=XQ`Jf(1_~Xx5p7jJg&l^KcoS1Q;o|S z{o;N3fb2wG(Xk)wBw$i}I1m`bMlwX@&HdrLVirK8hd6j>KH2KlJUG zL9NSF3t1FRvj%7@#;;p%6e|uEUp*>t?op)i_F0=T?~L^{EQ&)TDIAg69?#%5?lMA} z94#s*`tO(g(g%0vVEYgJ$_^#2^qWVpqy7Afm<{Q-j1er%yQkkis2k_nSD=RD7Xv;siI|A0E{ugk6R6%j5;=VBQyD9){4>2{Q27{b9{^uveGa#G~=ZW%1Hkf zkET9iS2BK!hMv`u*IBt^q0N-^$kM2{^xdwO z_gv#+-xfC!8*)}Rto4ZK@_`J`u1T0HzDqB807*T!#m|A7Ufx>498YH+&{59eBB#B} zz3{Rfe;(2QcRc|Kg$NhiLfN;^B8U8r^bx^#e(_A9r8fWPl293Sle}namrBNR8(Qs8 z6b+UzhQ95+L#fA#h1s}J&caFyeIF`bvD=>y4l$vpbiQ2_bP6`LCboRDYm;MEAyz5@ z;G>wP>Yk6#tuc=(cPIN8;zoN$xvWuaMr!4E?LqDS!9G#r3LATRq7TO66p%oTEMj}b z`h-S9D>WYgasQ1@VGCqD+fQfPn32nh>=TqDv)hk{72pQTbdFUf70 zp6~zt+eF!pOzQsI-nb9UhF(ryGW>b-xQVE!@cox!+^!GFPje@iJGYG`Skio`plT_U zo0!#;;k1JY>H_4RT~VELYRynznLs#os4wKee-UdigRiTT$(nG)PZQ%BO7UhQacF4c zkV}MStKtwBj2dfrVIQ+?=)3I)jXLJ)ltr>PCJmoVm=F4KT^w*+=XakcmpIm|T%TKO zIi=lfFjk*_1LV*F$rP}PitLivfes~bg7}$b6S2fWCugH2lS~|x8h0AOQ5S657?xv#$uAfKq1vVM_0RSqQnvX+U#u)(=4yM7G>$7_Nr<#THMHd4Zj zY)-&hmSy6PjN^vXl?USD260o_PU=Z@h!f_$PL4P9$gbomo-0%T;E#q&TK zm6DH3HmMAb_0`B;Jt^?Xk^&Ex6hQ(LWVFp@ZQI*^_h({)+aw`8?AXAFPNuhhhU9cdxhj zmarah{Q&h+rxA_Qumq$WZxJrOBvkB-FLX&(416YHy@ZXkH$RuOvy=KI6@Wer8zZ|N zq{-Rv&b@euU_ybDBL?-hMWR~QDp9EAeSpHJ39R+vju(03ND)AOw-%i?gZZXaa`4%e zQ)1Wv41tcnZ|>y&nrsvSR)#)mKl!c!h;zIr1fzX9@x<9>C)T7pF(>3P=1nqYdnrQ( z56vk&eDAkx<1-?0j$T}0Q?B@Wx&uGQ1)-(d;j*ooqSO=a)jt!8|J3tWW#NBu;rMv# z?@5Hy1DY>8tgre89_vjCzsjl{dGJL2NO(x2LOOI4`M8M<9OSURg!(knkbMn<3PY_G z{s3_Z-O6SEd@dXKUS{5WnR9Xt$Mlm-45AgY`X~E=5v3nDGEd*aSbRsITWZ zOBybTE->hY&(WzhVg4_2SB3e|b(~roe!;4;?nu?kX>ZQpYiDFOi5f{a?-7hs41L7J z78_WHR%KpEOKprF9h#Ke1&=C(mLwu_5xxzda-0#l`EI!Ic3>ccR*#&UO@)yL?4HJV z5QJu#6IY=5i(!4WY-qO(r+)n6!Xv7+X-b3240q>*P5PXUnaj8aofFNKhB!h=q6l{x z)dbfD?Ul=FikdtQ7k2{|RY-_Rny^)Y$0@gQ3x4jTIy;9xPfvr_vad}ISK^gKc3E=% z#U=I^2Uf6NM4Ae7oH?@#pZ25BGG_K1p z7dNeX^0X%|+wbjol#NS_U_*%IIV!4lQ`1nYSNqZ8fHnX#er3KNC`AUdW*Cq~&wDdi8>WM5tr0jJ(q$MSe5 zwtWoWE4yekrGX7UtDZ{u4}>6)r=L(GC6ZUBp61dj(=$b5x4ZL#q@_%k{A~rSOaXHF zj+9FhraurosH;D2+eU~}Q=rtOFUSBh>h_J#LmfAawtCDYg*>XOoLcx3+m@z$p*!^} zs3A(iSl23Df}j0JR?Qf03G|g4ev`;>yg+iz#`?=>D^W=~bsLh?tKM%wskT#hrI8OZbXpLtc4# z;ZHJ|;N|Wh!tM*Kq|Os`!C)u+Ggq^5YD>J&H%HX4*>H;8zmQ4L9niYTJvG^a1Ydcp zA-dR+jrDw2i6lu)=4H3dJL;aE7a@KlACCd*wiNu`f8#xMv&N~1@A*64$#)B?28V*| z$QFGPt9!)Wiywa1`ndqC!UH5fhdNP&w@g&;IAS^@)HTH5xH`Z5@a-LSlrY+I%rA3K z+SB98?iZXy?-!F8AS;B*83UbN;5iL1(zo`-_$~86)0|G2?FVJQtjOi^iZpCDx?INb znWXo=_Ug?%g~L@vnVBAM-6f!l6zS52rd)CLoCoeXTye4n$2Yb>AkZCB4xH%#p61c3 zjMZEJVG#W7?tsWj_*R1P7sS*W)#9RKlCS$GWI$!70x9f8_Lqp%=VI17TGS-Ez4vv7D1 z)Ff0O)!1pjYjupWG(378l>{k%!zehlyqVy}=8zMlv^q;Dcv$^{^mFsNt^wa1%535x zZ^L>}h9X+_5CT~${L8!ALo-U**x z*`2z=i_Gp0flq5b628)zZIOJP+4^=h(uZDoySX&m@5o5<$DA& z6Utc5m+-7QO8NaiGR4vTM!l|H>3Ta8e)0m&MEo%uS9(@XdRBOB?9Da`2&J_mh_066 z=H(m~>a2g-0d3f{t;yfQ4>je9Ww+tqhmQXL?EXmWWxwlMDEk^s4Y^LdOr#dd!Ci z{;hbA%w>*E{h~ndA6eY8dalb*_-^I+B>Kd*L3bI&2H$A?tOSoHbqm9S z-8C+uLRKPVkc^@GoY6m2g_?#<;a^wZuFDe5jW z!eu!BLmwHg@>s`pl{VnY-mJdwGcoB;d?xI_uF|^1d{-M4wack3X;o6sAu|42wzceF zhanI6vtTu+6B_+>=l%rm1ub8)A*zHqY-GYp2B-4Mj&#hElMAjb>3MLk$JSmBOgAG+ zVwZ@!bEEy2W(vBrt44BzGb<|N{kJWB#rI$jbiP4v)IVNvKB1A^T-Va@f!n94=hlnt z)FYN+S9=8m(=KEMVz(?Zvy{(WmWQi|9zu~ljwoQ+lfE#X^q?ibOk?; zUGzW?Qt);ba^}gxRfzTG^5Laet_mOtsO8o21V z)C81PSH*Aj+d40Kl&cA-7|M(-Bi45Up?I@*LY`!(aUP+0zKELZ? z{LU!cGMS^*|C$-?HYpZySYNBq>IkR@Hw=p@8)Ge!-^A3wyBy^^#1X&CzQA5YQmJ(K$$ zSB{^K*!Seezn%2@{ShA$*vqF!V6dMz)wLx%C0*6X_t*F0G?cU?u;Yh+JDKdTj3CWy zr~>dcB*8maZVMPPYrzj)D>Jc`{Jab*%}ZN(4t}O}5iesw^6k>M4NuRlN*ZRZC>Fd7ZBXNWZmsD1sLszc zUd7PHDSJf@!5OL~>>8GOv>GpeP#nia1F^1hi5=$r0WvN70qV*k(5{8KXr6H3QS!ia zIwg|6{qwsrU18lb%7weW>Mcl!EQQ^+#0nQCZ$D6mkge0tRkX1G;yIVkBPd54kPJds z)Q`0pkY-56d!^6|_6zb{AAjB5yp%E>a@A*f6&I%SP?b{WArYH1>*tS1dzE%DCW4bD zK=yt=)Zoz^TfgWH(qWHBRmbFF5)7Y*9aeY|eyz9z!0)ey;~J(*2WD_JDRb+u*L!*K zetK1HCc4tjIkVu}=@tI(1wGnTPZwB}ZGj?<@ma##EMI|Hi(nG5_+Tp;&TGO4w+kOQ ztwMp`whp0cBq(RZoS0sdICr|#?Pp|+F2N$mx;@J$y?{Bs_8THNuSF=TG4`t(rJO_o zV*{ACRW8HReQdwa>R%z@CxHA82^v37w&H%n3z1!%G5{wsGQYuzPgEwND(r10W7?t1s53^~ELNFGdiFYeKrpK&Yh*9Y?x2Y@iJs&<8_fu(L8 z{_jPG>LHm?S?Z-B#t2(h(@8aso%LiHs<}7(ITH6?atZzX!JokJy~eA{|smy96Do8FCSC_J^)^dMoakrgmed9%GQ9dp!5&8$m{w$E;<0X7zv=#FSrOSblFwRk%Sq0 zbLEvSQcHLui@)R?PS3zg-P+tcnd3QI<5x4nmFkWtascam9iV#}8pm*xG>v$=bikNo z>)1Pj006ZS0Mzu9bUj0iY@6_&+*?%~0I9%I9X%}f8#oVN1{PETu%KE@>{}c$ws_NP zamo2Vi_U6qBbU^-suUNtWaMNfyuTXnUYVs^?BZ*xf3|D*;n zl76MCVL{UlF=3`L+9luiDx*{r$cQ@IEMu&G=U{(h?;gHd?`FRO#3U_DwEOX7^m_S0 z8}P@CC-A=IKbde8e2a~-jCx~6%snpOMk_QQscCP_A!X`VSU0Un^ra>=Jmgtj%EPC# zaVJdSL)1FT%GV&ImYa^7?DJ7mj}5>7=?#DHFpFh^IAn)}k9ApTT~>uqv5t@QCX;l_ zzgsnUXp5*P0L2BeGbzx0Q8ir^ROTJqBYHkU@#>*de0Jbs)Z(`1eu~L)xn22+ZRw=+ zRCe^lrcP~xFs(zGsF+)MuOm?~);$iKjer#ht+ktFhm1$4NXdT3O>(41DeHYt@aoe- zt7;?dLCDH$M8P$OaZt5hai{91crQQ8w%B$33cCJ#qhI3r!r}e+IBKd(L3mfSSBuzv z>9VDS={&qpqJF}FamJv!k(Fq~@@(z!V%dQR4i{>nE^g~vEPgW zFT~=4oO{6n)n=}2wAld}dT7y#^2qy;_oF#E(v-?9KxGdgz-Sf;uGcks=JwSiMeiHX zb~Eza!@vN|+QvYBYkeSqn52vXBteX0A6V_o8Dtn8zgrW0X(rl`y54>1dc`V}mXUY5 zEyp9;?UGWmGoexvpzwb0?@u59{+RxEU$u0qH(;Mdvpxp=0MUno;>DfL&!TLAR9VCi z(9o0cx!(u#pI^y!^9FT|1S})he5>w1ROv-{&S5t7N$FUw&jsAE<+mXu8tHj6^_2}p zYYWxpL$0428akxftY)dUk7Ex%FK86&;&v@$1+maMvp9Yo+RcWXv7dCi{t?}Ef!mBi zTXa>4i|d8my2IC|c41GD{FB##sZRz%mWIz8%<{i4p%*|p(A?cMYfat!Lwue5CDEdC zqb$Hf;a5IZK9!!HmR;cEpw;Z~=~H`OhcMCWi)!H?37v%d8HHbWR5=RasUfkK?@W;> z>oeBLFWzN8{8~Ede$_wBnP_Rt&{nrAxzc&)jMVjr1s0q#l9(qr+0gM?w$~#slTkHbkHAma3PFH3r{cX z+KmxE&LwKQa&`!E+`ejWm~$ ze{g$^GI<1lm&YDK`zYa&lXVG(niHIwRgjxIG-O{nKFuy_kzA|uWQxQ|q6DVC)8OZ6 zwpzLj#M*Qd8gxAu)|?J~eh)(lPk@ETN?JWlq!kE53;cB$ic;2UptX!arpz1ftAlX{ z{BIASZ#=H3rmwk6GrD`bgkn5LcB7dLNb8Ntsk(TEKWuct7aVif2&)P4k0O<8rNitD zJ(5IHJzvWw{WN|2-~IfRE{4eXah%=}5FkjKx?9>!#8L8u6oSj%;}a`)gVC1rxC#ZH zzbWV;RokJ}>x_(3eTU^ruM+p~aMWQj;NEvkc`t0+8s{*{c}s%kc<1obBQWMXaRfU_ z0A_^L>Op=Rd}{e_f&)d)oCQ{e?>S%trAF8($X%cgkftI!BP@xcxmsC3iFBTjQs;eflO-sdG=&rKI{ zR^Ac~|9Y1Jsc{DNRpUr?Z5tYW+PHe$C2G{QNCTENjNP;b_|n3o2{gZ__HgZj052e{8)e*zk;; z%z|Tt(!#NcUYrvoJgv0Dh~NvCe#>qO#2Yn4upC++Pbc9`j>F|(ym$J+g8k<=O*ja_ z-zO-pABBr=$hRgrcEv^j!n@#9kWk0MLmy8IQclqAkQ+=|H?i0o$EI6fYSM~>VAqJ4 zP~4TshfVvQmkf=rO)^W!v|IqWZL>w311Bt*hV|!3nPJg|J6oE zkdw}%wh400VdhKu0K&XkrD^zqX*`kw;t^SZHSXz>@}BwuI-j?lxy}^E)XY0<5oup< zh>382M^0HCTU$rCB1+ggXF9VZeVBd|st85PDM7C))KgL5f3cyHz*pGi<`#e~>H+FG zT85%m<_xEu#{wyD&*l9JMe_LsU1;JS{A7^@|L*&P^H0%blv5xlWAn7f40qt-LC;}+ zrY!6bRdN3}v~Lc$6BYv?ob4c|9k`AGduO|1d!m}ueU0bq+P>Dx;_Vk6I8Cqxq{=fb zGuAILEz2s+w2RkLTF|qn^U^$8&2!R!z%~)sJ@q83P-%Ue;qJL$mK!~Za-7ry5Sw?$*dqmU(+wp$wg zci^{Hd$n6w-IUlmr^-LjOSu#Zt?@ms3RUP#z_c(TrQ;s)m8K*{2v0Mc#Hdk)%4Jzm zSLFNveKVdmI_CedB?oXa{(Wr=eHoK4_40WINM*h0f_>}3VQw>D$_GUGLNg5#t&zgT z!u}YLGtz&C&VN77H|UuNZ-9)RMxL!KxlGFw-HEvbu8c@BNc0!tDo2kwrq_#s{z%dQ zO0|9=yt{|o@%cu$72z5{yc@d@r|eHPSbBsLGubcKMxg=@#{Kfu-!rSa8=^6F&JX+J z!+qK7O&{^SNnvV?=7sp?i+ZHf->2_o z*F#FALOMru9+DX8?vSg#BnA7`_Dy72-LCm44!a)=N~@eIpi;!hH?=pBu{J++MEO%r z&d$r@>^CVV&VeVIZ?$|Kd{vTPU)--P=|-KW$|_Rt{w;c6L{8}>jfpM$A#6y14wbLUIw323 z$;kzF&llxWEvFxlko-CWHTu@k zqWL;R30)!8Y=SiVj+792dT~ta8yezd(gOJms0G~(Y(MWh(e`)WKdk&Lsb0-{zRrh4 zauPt67Vd_N?&zz5nuVb&p_V)WrSAla#1|Td!9GfC*G8w_iSYp8iL~FftqAS9 z==K8}M=38@@&u(a7&g1<9k7K7`{|?F<9z>{k4mV=I{cS_cZ&L76!(bkHW8Khk_i(^ zE%Br&$$Wc>Wim4TbWcXt^?}qGo606G$pkC?6}GU%!H?A=7UJ}doINUJ)MR|`-y}tT zSC;Soch}Nz5ZkO+!B40S#mn=gw}fRrJleQy3nb(iVRZxr{Smw(QDqgdt4kkP zpYJPn$VGcUR<=#F!KhhCG9w05(dharSj}@LVc4S+Yp9dB`~0^2=hT0n9{~n-CvJGL z?Kkgk%BjbRyEv8#GgHB{dUwr88u22K7ekT__xc)crGoY;_piq>D(xAg&Xs$~E?A}K zXNN1B(p^w|)OpwLE@P3UJ)e(fYQGVaTVO?4k)`CuLrRR|*lZTUl}>w2yVp5sWaMNW zUxge3;jUwcYE8#(c8Q!M^p>r;hR?pJQyyw|Ef?6ncJNyD^ODrHsdJ&*U_~b~FqML$ z6}8mKWATy6y14RGiM ztGWIFaSWXT&fd0L(zxO~l1K#&mOK$h6bd1GMZ}>^SOYS4o-JGjr4JFYy)%TrWUoRt zTjQkB*6ETwg3V4~eE+FCgwD5@UuF1}cTJ+IFC+*r1QUW0Eh{_9S?XV}{ygSG=b>dXikVRS+aw7Jl2!7@It{*NGYE4$z<+NaA%<8`@R>+Ic=!5p?WP5=kB$ z^QvIFW=9cB>Vu+`2qHoeKaI!=ls=ovAU_|7-L!0ySJmScR+~!Dy<^TSRh$)sD;}Cy zp2-#Jd&B}*kRb9c$T-x3e&j)(&7RJ{q}A=QU9|^GcJq{TB-;J8841hFh9fWWsp#LFbm*!I!x(EbkAH)1k3Rc75~}$$*lcZQZySKcPR`9$b zadrSD)5Trb-NEVZO_sJrB0jTqn;W~NtK6gLE~15k9nsVK9e^Aqkf4HxrMv25@AlJ) z`^(I7+&^!SKb;hM830SjIg_lN6OTc46=sGX^5Vf_AUBP8wYDKgd_!7M^Yh)j@`3oY zkFTYiJH;r)1(Q!KAfFA6GQs9Br85rJs9=hV9??-|HQM7`f%>cQrZ!QHlj2Uy^7E?7 zS7vHmm^Lsd^4kP3Q+F)_dkf)t9Z*tQ-4Mpy5%-YT=eR#AZ^@S)}NrNVqK56q0$t zwQMTx47**kb@LMJ_JE?%Ro}ke&)Iz)o!1sOKj(kZ2(Um^>N`2YlrMd&&Uo*wbG7Du z-R*lLFbbai2P`g%&v$sn2E!kh6cV}C9md2ae}gE`oN@EM=w@dZ&U{PSNs~n%#F)dr zpFiR&unlt0jvERw!O?=5>ijHJDwEK zybE26G|4h)n_9kIQ}XUZutg889-Tp^H+j<}RP?onmx}6zH9P|Ht&*)PSs~?S`5^vz znQ+zq)GUkwYDzJpjd&?9{nlEKuo=Ym|>!c zqqFm{5?Q-n_8nPMG^abg6(X_rYg%)w6UgB(8qGavClUvM>_BoLaw4GUk(f?dC3hXf zO_6AfJQ4RoHIySiMi@WzZSv9=*PM2V>ryGiiR@MedgrJ1#5bFc&tMagAt(cFASzi3 zYpw3sI%7stOP)Bd=`y1r=pjK0e(i49hpfJWYZtrUygqaG=JbP-d3z;v)fTAs96ZFT zdc`bADY*{Y(iB;sDq5mBpuskeBG0s(jlu?d4dvaKUGr(B;-!B!uJ1}1)vD9?N?YQT z^Eb}5f>R>oFDvY-mb9t*y>Tg>d;<2%CXpil5Rk5#F<<)p4kX*DL!r1D@_5 z@$m9F?%(5dx1G843O>ad%0Dme#4UbkSSLf$my&z*D{b}y)0zGrgYq{jOrcEHUb_dj zKO4dz2s6%DpAL-KVeLx7a0>L#e1_aEyZ*7|II%5uiC;%q@lxddG4I!#>@#P^l;l(0 zI3S2I-9GERl)SWVCh3DT|A}X4v57NNBkj`I>wB~`^8bZ`5r5G+&B9JMWgp)QxPg20 z10-Hge=Pn3q>E#09O8Da_w4)D`(Xx8%51cl+IynjF)|r$2t&VKnl!2N-fB-Bt-o%s zzp1jE7+cscM$Y4)pF63kscQ1z(1>rPbJE#(!eO12gr&q*xuQPP20dAT8DtRkkE5!E z=eVYu$GSQ-u+@2C`@ed)r)CcvS)dc_ZKI|5$HLMFM-gw+C!H(kD!5cTDNu&W^la`h zdA2VhWak6BV3Cfcymf1$3g6Km3aW^D0>9VGFuA3FzdF{1ZXmZ2T@Dpsrb=!OM7m?W z0}fLzR-3KtqFN&xj6KX(3sJHo8kg4&rkhK6o5+3d5D~%cXUIoa8l8g|r| zW!HD*vX>5fta?T02ubHTl2|eo_cFGwum8cg_`lhdS2P;(P~&_$imGX;9$In%|BQCB z^ZOa?Bs+~QQ2e)wcmMck`C(0A;VorNO>Wj8(YOXhK=sFBPMPzgJlL(dGJbU-O2g)` zpK0G!qgo`#cYbT~jq{GZGZq{|CB-_zj*mp#yv9&=c>yngd?hAF9O&@l z%}B^rtxoeqg1020NGGzy+<%B1%U|&#TRjoTaHICDvPxXIk{+w3%uUbnC@~GYW#wEW z)gyJ5yl23+T!szb{yB3XmN0_jO@Qb<^M&WQ2%sYs2Ul8}oZHVZj1UfSk z*vqfYh~Kl{He`u82Vb^6wUad8uWl@KifbAr=pDZ$9alcUnuyH+vSr(+P+-sRJa=@- z#YFA<|5wCxcc8d_&q{DbiRtN#0IJ%t!6@f#XW8ScVY7Ae9efhaxLk3R%6GB|R|HWo zMcTr+`l3XJcbmJ#PW~vE`IQx!t)i@fk6rE{nb|Z@G?8^IVE)zB4lgmi{2RktbZ= z)K`Us$P`{L5Z+u(oU5vgc%`FO)gW3v^ZI-*i1bF#WH%|85!t0P&V6MTo14`7ELM2C zc~Mih^VZ8LQg}17A@|_Z*)?x4)8|Rpmd=>vLrq)wbDDmo<%sL@Y%-YJo2xxBKuAT1 z10!2T@{%}dU`R4eL07w44qlauX>h28U0_LS{wQkRxJYePR(qu$vv8~kM80J`gV8-x z=*%9IO^p=&?5Z=`&E~%qm(o>lA~s-RzkXOb;G;;tSA=(yvXK1jAPL*t2|nTSl#$*$ z?TpAd2-kAvK6zTWxWwx{?>ry-jKk31A2QIBL%B zh1yPw*fTu#;ROHReeoX_=?glBF>*10$I^Q(07D5pS?nmpj5=$Qsp;9)7~3 zLpGWgwc^igSa!MSBz?~1%)D;ja6`<{-6(uYF{G!!+9}T~r(IgFHW+fS)L#mhSZiaQ zgo`^OLk42Udm?!XdjbFj-N#vo&hfNM#Do)me!0 zQjI`l?)vI>6UDiQ+;cvzj9HCZ?w49VZ9FTV}gV;HS&T94(u14X- zuJuNRBm}Lc;hZ0w%rsx$VDtYPceN&&Mzw0<8yM+5Om*7|fx%4dUVS=%RTrxwKG(Or zOXygkp6eJ+Yli*0OCLI6Cq34zOd)uj7A}ii?WGc#{BQtB!(UVx{B;dyXvxxBI|GM$ z2A{kXzDSUaD-V+j<-FzyB5oeloE7e2(e_&bD?1?1p}SWGc)LEH9T{g&de?G?I?Fms zGWKu{%V)Pv5d;n=oxEcD-d0nU>1zg)uS*M4=(gu!Z0*f_#0BPp&9EiAiyLzi?Ah_e z=|%^MmtU_j+;JXXFkH9enwTC@|al?KxYHflBfDDJX$(HFHcqUCg|WIa9G3pP7v5t>PZYoSKlnVQJW87Ue;s zutbFH?(NTUU7u?|-(=$$8V-V_q&;M;zyH{{{Y346-&*max6zyWUh;ft+hGv%G^f=k z>x!EmNs5WLVtVt9&Y!#VX+`bkgyr02@h$~@Dn?|Ar=G%)jIIQC=J@pz ztJ~wI>FJTB@Q_q72b2b@C0o^}HeY5ry`ZPK9mOTj(<|M`PG{U9)K_P__WmG3oZ;v6 zLqx?5m|Q**UsyS13!MZ?*Xi)S8nhP%vOvxc?JJnhK;JZSE@>@!+2`z;^!ah@7vZ1p zhiRkAB1O3lWZDMQ9s?fECFxVy-Iyi3Y)%n#D5rTN00fkE630^pb;)Owq^LdF-OU5G zWCto>qr8e2EX<-BUF)Q~aAR>?S6m2QrREZ~RV}YOrK`Ai*5pK`dg6$a4a@I}Z%GyQ zQh4g-&={LE-xaP0>xn*5W=B}3Iq$cVUYrqFoGb66Ka4R^%`E(CyBc2Khj}dsI$M8< zpToJ@^22=#b6*}B*RXfhnRMbyU~%)1dI8BDC%5o2@y$&QMgb(S#42f}UzW^CQ5dgt zEA>2}IyZw^RDahfSf%w;^7FTgG7X#*vAcw;_RM2R3C{S0N{6cthD{yMOx){575a3f zCQNI^Es}b?A$8~g3n4Mjs?gb*3ak@z-}NON=CA5&#or8T4Z;V4-J$qJy@v??7;MB!yIJ5EWYh$eE09|3P?Df>DE3onThv z)mr+N+TsMYqK&ti9);J|xiZIR-dE3w=VgtrgqllhDNH^Qrr4yMqUX3`p6_iQeR1aH z`s}y-!kc@C+#g2JZhJ{L!*bU!6Xin(JtrJZ6kFgcyH5_hSTp1__e|yv6mM9>-3l#0iN%Wc(@+ec1>2t?I=x4_;;m@y6>%T(D=h)Edsu~*UaDeZL zBY%&tP$B&8+M4 z`2;GGvt7{mi8M=>8eKYmtV4}|;nBcxsui_U;N+Xo0Zgtr+8>~Lu`S~90ly{cE@(Pt zPHNcg4YN6J0;oye{cJHEAbS4iz69dloeuh)V|w?i#o&MaHy3>30d7V|6x{fM+!^gK zFZHPVX2>5(yFPR&yb(>VE z-J9gkvVgOeON`nIsZ)fJ;yNcggq@MBE%9F|M@u$7J`?7-G(2=3t2Z~zoY%emqF1z) znr{PZ-a&QI=C=jp_pRVBuNPHqrx8G9u{)p6wXF=F+PTTiYBvr=U*pWnCuE{onpS{% zrX4r!GJrCDjRC5_Ku}-S$*>ta$`H-(-|u)3UGBc}+D~vfWoGcG$Ud6+7Pq8;wZYUk z(ZFZLzG*6pf)W}9I!{<=gTX<ZKi1jncs|w^WVlD3C7C8sW{z)!qBKo6J<#BT3@`4e0Bk;xkqD4o@_yX zb#y;d!OZaUayqo1!FD1&DzJ|uk&KOk+RB1B5uC;EtN&>zPjhHnI$}rLzd*Mzkual+PeDpYm+Dw&AON+DsNeVS@}?~@b7`@MR0S9gASIqz+o@Gj zB%M72_Lvp6MIYJRDev_TeJ=LFAN+sVd+%_#{)Gde=byEF{bAPE zy4Jcs_x&m2{DK3gI+-&QzZeS5K+mub;;`k9XYFoh-quy%Up40Ol#Pa zj_3O9CvMv1uFEelGQPP33z9lWE6%iz9rHJ>7}anTEyC9M{8R;qC*=lpf?L^)79m)( zvY{b;HubY{E2ekF6rnZ3d$8#B@LnTiR674E8RG`yqXF%ZJ2q`1`ef( zDLD@ka#JQEi){x_cfkMpa-9%kL|rMRNnCX_jdumA{3H!``f$S&c-fg6_qV6IK!ifd z1VHoVi1@PI;)ygl!6R>f4!t;d2*}j<&ZC zAj`^EWGEl?u?NE#ipFA7Sw^PrFnyNMx)!y|{sA}Tr3rtDF#HVoG&DooZ7S>(qm z)yBKYBBCv*c5a5C7|~nE5M*xj&k5m-7E?6d?O?nk7WryHG%JCBv8fd94o~tzf{1ed zj8gbzj1wGpkP4_dTy1P2GIxTFejV`E*!6CAy?m3YTr)nsVKqJ8kEhQq;}94)ry*Y% zYD-VZo}CWM8YY@raSQcfGZ-EwB=^%}Qc3$JR)dCO+Iqn(iHSPe&$dqzEZb;dhJw)S z#F?B4OZ_F&sCrq@kfUmrN=)A9ohmEc>}E5!*GF-W<}ha-07vKT&5?~QUjWiUJ53}- z@1@?!3Nf!UNCkm(?1D~$&VT}(BFxYL;l$4B4hASA{ho$(jv31q&gPU(*s?fpowBf~ z$EV;<8J{iy)8#|GwZxT;uaDEbr~`we?}>lZRuL9Fx(q)qMgHQ~c++U*&zCjGQopa$ zbGE$$6H6}=^<8nd#z7JIZH<&x9XD*?R~Ok@IKk1QNTISJ$t#FfTQ3AoT>y*bR>ZY- z!V;?_E|-ufn$?$Q_d{NESvEI=YL+iZKxHzAL+GW^6la|C23B(Ge0JMSiU6PiUMKEh zSQ@#Cv)x^ByB4Zl$x+dE!Oi%^_9_+(-fV zsI3+ZaM0N`6!u#f>UlvGCynn@Ge@iBJv$#8?hZ_uF8?n$isuV zciimfD4aaAETSP{+*1bID_arso2r8kDL7=Y|zwJ-ouxr_Azpt2^!h9RfuD_RJ z|AI-P1|_||ls9Xti_WHyJ6wEAf)}j!8;91wa9#rae38kaVh8{ zBZRbdEk6}a1YexVT0NkbX}EpOmkrA0>~m&zqU76@IC?%|)D<|A55P82 zZ=MHVmedvvo6Ot~xD|0ZW#O;&AN`ijrgecbiz~EO_SRy2d?lUxAA#j{nzR2JMOG!c6OxCRHg@IPwEinYv?f(r5F3|(Ptl|SbFdNq(3x)MO-nYvJ1?iY%=%4If^GCFb? zm1yX_HvZOlcVMJx<(c@5D$4Pq2}=lLiNHGeUFD}xPJKI%+)YEEQ!!ItwrQAyW6G;ypi)C0RqnAz7Ld%Y%WuLy{8{-v!mf~ zc8?9DTu#fPV1dvw9icj1a0J%}okzM=?OmzFCPT^FL3JJ(oP$qtTwFxpV{~+vmNMWY zFujNyXrkAr25afAS@CKwd_pYMBqH3XUxL{$pmdlTG|}qe&?&ok-->f{(%q+%3W>aL zE*x$jq4o?Th8NL?4Qfn_drxO(^Qddr9sm>t3?5~*Cvfr~j18*L^~iwf7~~v02bvR*B!%&0;6)HItHdU-vQ)iJULTl@D+y5Y@5lhvyA!`8S7hdpFd$90Kv_WW zby2;*6tg;zT~1!Evt0^+8jaq*zkZsq_=}|Hfiwq^Syqv^^g4^vSNX&0FWYNnKet00 z!VwS02J{-1DqCv8QiOr`lr@~tZe)kGv#H<+pO3mPk=aW@a*U~wRdQBL)&prd0rUc*RFLPbY95>@pcs`DNuCO}jKsXxl1r)C+;WU~^i zWLGj);^A{CXv3PP+=XE%wFxV2+cgDGoaVuF)C|qLJp*Wv=7^74AJ;qwP7>?|BD9WQ zsyP`s5qXgbffTz9L_Ns(^iW_i*v*}AXTCM-?a$9UTm;roQEr~7>6Sav&MXrbAlMU5 z`bQe*NsRN+BXl3V_c$kSK~F~zGEPRbZz?r;5QsNR4XOKeQQ(X`aaEVW(o4J_neF;G zrE^??HPSpYR!HVSjLDcv0zlkF1YH=prv@}2)L4sgvoMyJ_uXod`6G#Mq%z}#)jT;* z1~p}8`Hn`jlhsDGo{gZ$fi2>Zskq$zR!6bS@{;ZD7X=she*6 zZvbBiMVDDVdV~yEh^zC83y5eV#OG|y6x`gk-kH2JiGU8Odb&dji>gMYiQdCm@q%8w z>vGG9t~OgPi%X>FrPF8Zly~dn_97duRHRiVdqLAp52IpOSvgyl5GjA)O(}fud0Hp~ z?cHD14-_Ntx~&{0xR?}S5k>`ZQ8ygncisPZBM0gnhtnTC2|LqIxYp0*ANUNOm|($?uD3-VCb5n*s8$@w4ZTu-`BoJ)+Itk(GAUT(X=!a-0N5E=O16y5sH0d%g_$$#rkQdkHqnn#-j?v?8(Ly0?EZ>bk9^f87yi44k zHmxmp@!?Zd6-^L?;L#Eoc5{b0-^9To-6r8_$!Q9rp14zGV|p0kG}+mccz58vo$kma z0sO{P5p9+NvaiFZkyh#-qkd0v)2~K7bCubm|eu z6|e6t>t$j4`A~kmp)S}R`38*J_MMZ8?y~?5TJv>#R|;^rj@`+r%i*@~?M|y~x3Y$E zm*|gc6_1GSdQr+U+u}PRFW$aj#^A_u;*#jUXSp-LQb&FDg`E12&n4@~II1=8u_ zqy|DY_e;CNl4?K39jr$qY7}2j?Tj>S4%#?G?>PgZ-~+KnEfQ}NWde)dKe=JcOtG=tlp3Sl^$y0> z@@R2W0IhM6V?~>RG=n9OB|NR>sB+HN)a&Wy7Kl-gPH};Y$gWd!Oh_}<$AI4sK~^4A z9(abs6u}MAI5fC6ur2u9zc^Vz_Z#Oo4*#ym=5up2dsdJoliOVr0@BsxZk4U+ab;;o zQ(?4ClvsOA^vIIeFAZ69>Xn9)FKL-u^bu|!UmRg>q}80#GZD_zg$Y>$OS+wLxEER@ zw)SIC8UFrWgtv59PUKxw*ZZ7+M1$i;>%5t=Bs7;@NiilU{_KLca-tByFnFPiIc21rGCIzOf~d zQ;hBhrY*g+u(KMrT%#my zKu++78B;MG4c?|`gdtgsY?kHpDhzgWl(lt!iX4HY8P~|^HKRt}RrV8#^Py3UL12c` z?xu3=S}M@i#wE3OmpLq)KJT*QtnM)IG`x&A8z_b>b| z09IRy%#LhionL&+!4rrah1nf4_V@GDF4o%n*`K{(9Qlvw&p)2Dx|Ua1iw_nwlDw5x z?u1G+lNtoe`5c@TfO3|)B~zVM!p7@t#`eZV5C|(Tu3j)#` zpRJg^VB~P}2jYu=BfA-_;F`|`i(^1I0DLd9-LZYbLg@jU#$?E&roiU zD*wh&khct{Ji*5e+PmNSk{iI^Ue&dYf z`Q<<3meA0QFhMq(NBEE4h(;>^Wgjo14aS8&9jOzAoR#Gl zQzx*X^}OwGS`O~AI(MYK)w=q|?MFi23GwKh zrivi=e>aXu%8{?0e#Q{!DKadt8nu*E89WSo?wqW^GB(3N z1uOFao40>4@zlSCUDDZeKHjg(&xvzL-tNPAxV>W=ad~E41k2Cmh>lDC^v*ps@Zd=0 zd$NK&BHOqP?+gmKdqcJntmP9Y|A~sXi^>p$9FcNb@NY4AI+wTZZsAmINF)P<D1%uJm*5^Qa<1U@}@Zt0p%c52DQvHx=+ z-b66HZ~(8#&4b@w<)@x`KnC}uI)MBAV&(y8S|f8)3z@Yt?i^X;r3Q8eh&DsCHZF6FhFf<#!v)mW zxG}OQxGGZ=WP%u&kuHdkhkOR8&sBkf%;{ z5MkeTwNbqcZ(gt7uIXyQO8;#4RPi|(gM<4%?aLr-^6>CP`Fkw}Cv~O9$5HHa0 z>+WuZB+l~w)0jNhs7P^&I+u>=14+C@WY8Q{^DbdX!hqPIeP=c-d%Q}Ap{zwwnv@1h zd*}b?l@obSBFZ^N<;{tR<)9X%--7p%Lo;+|=Qy{}2%2zcSfu34(OeKiw9qBaqhmQ7 zWM7l$voEs?ui#4oE3~dR>y*RmE0o)+mhn6TP+S~+)6Inss=YaFWTmF}=mc(i$O0X7 z@;SfFmyIQ4MYQT4Q4alAc zG(_W`6k0I$@D?lVjIfWhe-hEIr}v6f@oMOCE>g8WephnBL$o;bCUexN#O8_6DSSTtV>%ZGT7%DSeutVQwXgh=UU zoXx_^gIF=$PRFU$#^Vl^wJrbKph@lsE}XndW|>4&zKpQf((JgkgyH^0_TMYa*HyZ! zSlmN~^_f1G#@+4V9)$yC{i5vY2^KgL*J=Y9D}aTXA;H6YCov-u9i>H_1v`K6R_|7A zknyEi*2m*xGooM7Xh~sS;2iFuQ;?I+khx zL(=JKehs)^6~bvhrjI-Ltcz-I>GjNH9>?)^sz57@Y7=SxN&}fpz$PYFJzAlb#tz|a zj6eMF)wBWp6iGn(C!_33;HN&K@|#m@Vf9@?Uv`@ThwPROg)zPIg0Ifxs&(fbngZ)< z)`%07ImgsxbEer$_Nxchsym1uiT%cL-W3naQE(9-nd9IH?^Lh^-heGEnvYkXvZ()< ze9i)p1(BF|%oB8Vdgo9-KW@uAn!Y1zI84Tl_5gxVRKOt8%uPp^{#aty6YQGATUF9| zjcm3Rd1qqt zT(A$E%)(NMT%!DVw|pWmYP>LGhDY~WmV5h(U%FgV)oatVy4@~<+#B%j#y%J8HtY@s zm6r*)T*1*Qz5*ie#|^%@1#336Dwy%#a->>D0dVaJylReCf3ckiWDDp0fEbvV$pj}U z)(u8DcA)Btgk4>cUqYXj?y_?**vFGL`)&o3i|Eb-x4h3T+%jBOIz%_GRkPe)ryh)1 zQ>NIN0=BMQ%k8^82}AsBfhk0HC8F2&YW93rGbFgR$e$?03m44c7~}Dhv~~TUm^rhX ze{7sU9Vw$C9LXz+Vmi}V?B0z^YlGtL1q33pMtFl{1$NAqAC&2Z;Rqi|>n}O)nZ0<2 z7wNrOO9j50qRFv-whNE?8b4pSXnQodJ zZXXzsO40a0sAx~=^U@`SFJaO})^H)b@?MDONJcn$w5K~gnL1^660AxVygne`tTXFH zYaJ?sQWVv_KC`pyaw`vldjLIHjP0^56I~~3M8Kcy7;$R>;x>mz&urDy-lcy;o%j#5 z2s6N_w~roIo6z{eJbYLF4{3TEUXeQO?W6^+=xXWi`)svH_ZG z%;tx?i%lT#?y)-&2=i&fpjOtH<11%D)D)c{&7AM;4UuH_s=Iq#kNHTuGx?J|6`TvZ zXVv7U(g$_OB>O(6TxuLfXs7azC8F%c}IE+`ps4 ze*wIz3zuGQPo8L;B&!JRd)Axm@Ag0@jE~Op8$3?2%(MLeO!Ak^LMm@=)^Hpr-fC&! zSi98irlvml@gNyVyY8{LMzkkcBB+SfAV_6<&*r~TaGh3YZ3ZRNQ;6xet3BV}DUA2MdN z31x_WxP>No{7z(4Ph{ga*V z%92e-Hs$ym2kLO50t^5=qteYYbS)lem8F^CCO}WNeO`pUU#5*E(UXNm&-_IHR zsy^d(J3R!|5VDr_Coj0><)#z~%#9+anSS(JmrZJ6_Kg7(?ZPG=!IrqsEH?6fZhXkh z3;?q(zB6&a3ZY6fKH?Bb0v!JWn(*aEAe6S{uPdB*UjU9sQoEX7uAv)SnhvbEb|NMI ze{`;780#rmr+#c-P(3=@sQ9@IPE*xB!1FGbCEo33zG+Mtpyuhd`Ci*7g&Yxo5?FowW?O1I zJ^zw3=jfq?v|YP+&-14AO+TJH9D`Yn9UH9l0%G&)(5Q?jG+s90UiBZlXcod!1Ap00 zYI$kR#M))TLgl3O67GNm-QW|%MK9YQY|24iSB=pc1xF089Ce zQ-PhZ^#q#y`P1r84YMZyVwlzY7sITNx|TT;3K}0})#o2zyClW228xp3OoYCA#b!E~ z*zSM%LfA~SeZ)||Q59h#*ykTX@bw_T2tU%mH#F+?>O~H+n1P&}U51+8>2FPlxeBc=->a6+@siWphi38Gc%-!gg-1N zV5*G}tG%N(ZDYsaq$t-m=Oc>35{I9t=NIf-w12#%e-DkN<>rHUgxvRpZu`TYJ>SBc zl@#QG<-&m%&*8gd?AGXppcJs0)roapwyomZjb-Z@Zb=B>&JVAmI+4C(7;-F%$uGM) z;*ci0qqD3i@)d9+9XB&Ta<#>pra#sur%`9MN_i|nak*3eb3f!N)zr##rdW9vE=BRvToh;G`Yy8>w@p*_R1nGRyk)Dhu zXnERUr!n7?C%Iu_O|@*ohP^DVZdyh%v+vA5$*3I3Q7>aNajGgVt?~@)7d24?Fq|+L zYmF5W!It|W?t3@X`UO_^1)3X0&=i{IF@Rs4hu}fnL;K`w}%9M0}}B zhuWy~V#$nS|IUJP_~uUu>|EXMZ*z623q!#W5-A4%Owad6mLSD>MZ(qK&8A*;EBdiIb*LxWD zqAe+mh)cN$5tM#yvj2sOlUul@cpkTnG1O*UPte~;Qo}kc2%c6Z>QmIo*LIse*`5}i z%-#8Fk|d})WY>UXUT>)eYh3w+l>v9S9DMdzTC;V|-h{}T9QZsqtaaNp4Ma{-dA!?+ z%j9tU`Hpc0&O@4cgPx33eOkUi1Om9ukD)vjqF4A~Afg9NV~V&R@i-@FzsHWINI8*G zgyr6B7{MbAv*eOql7xXr+$(NaH;9S>v!fE-Gy}D`lfuW%?^2r8tPqrZo`#G~`)n01 zTAD99aqHz5+-j*&WED}v?8g@#^O&~|Q7anI(Fg;gy}IR?3litu{ZOaJZRaFyJwHOS zrOWeUK?1A0ac?R_lKYs^!3;OjrXk-7S`YZS{C7=BugEcETT8X{m6 zLK4a3K-9AHnuF6aQF#O`{2M2%Iyj!ruk3PbZn)>?4{iM+)ZOzs435N;j-r}@o_wG2 z-TaX9H<~UCb?#!j=uTotp1oP7(PHiEiE*B9F3^5P+IrndA|Ox9L4mDv!Iy_Z-4+(~ z`X0|=o1CR1JqB$=%_xGfJ8G{d6-;o8aBEORzM2$?Q@urt{di9(!>4EXHbk*;m#+4G9HB?EA! z&~*&StX&Z+YAfS|D`X%)Lc~)WGQM8v)AbL1expGdLUjS8x!t@D!5RD&oxZ24Eo05> zW%WUv(_?>yLU1CPr(1a|M$X$~D;aAf2VNBv9_xO9*k^jT*bud*If~q4qb2hiyluZ5 z>3(hboMhV0iI$o@5(j6HY$_`+j%w2cOXLx2U%3GMikJ7|Gk2pkofzRb?c58_g}?b zFbXUkbyB-J;!HE6<{ze@0fDd4xdnnEv;Cchh-et4B3m64@OWO8K~x@}KUlU`+OBNE z&9-0@zuwZ!`^^-(oiAvE<4~aHomiugg=Euz__h7Tx6K<8N-Tb?64$t;tSX=F+)o^g z&KJ6(ODQz*`W5DcUWNpP2^2x(R_6oFd_VWs`2_kcjTy}{{JWnIA|c1#GpFBXWxkII zT{B`_duYm;U)|KIch{g%1iNMG%k8iisnhV>qG&|zPf5u z9%t|y!^ky>;DzV&%4_*k=i;faiTB1T z!&pjYHhIOLGW@z^bA5cOrgcrJaq)#dz4`;aDY?BrT@SSu;60qZZ=99Z)2cE@SD{j(1TQLUj1~+jY-(8Q00w7|^o~9`M za1m9!M5vMC?4T|1_PJP!+c;H~;o$yR>H&M2-LkPZ4cpJdqM~60P{;#0Du&Nu0CC_P z)f`ty{`uSQIu40%ij6oUOqIsYHI4}|80$A!P7tvnk9@^T@!c4TWOTPAr8`cDOR z4!*DRuNGNiyk2|asorqW&k#2Umj07t$N%%f9kJKn`c=o<$ij&a=8if7>pj#^ai-%D zO7UCgz6ziIBr*5lyI=2SILgguyvO=$)tqwgRA~N~GjVHla{^c%-=;A#5e3)TKEHn2 zI60y$Ku~7iL3&P8CX6Fq^|%)g&JAXWDUl|7SVm=RqK0i{@PxPN0&sAE0YnymG+G}E z$)!woUjN#rACn0jXZojx3ebd|q^3)kIW=j6;j6Jz+wt$~rzi}>?^ z#NivdN#Y@cN~6!m@x3fJ9eBr-w%Ut6%!l3B#B@ot{7|vwh|;iz-w3oLg}Og4d4-r^ zQ^uD&&}W-1eIjNWJwbcD)G!l$f;;bj_~J=GGJ3~MMPKYd{M|!2CW>E$csWj1d2~+- z!rWoo(6gdLu9Ph?&`NoH=$7!(wcq_tcl-Lob*mb|QkY2?_ZX`6ZG>P7i@V;jZ<%L^ zLyxuan%`b&kdIMfrI+5{O*{Xqqm+c^=x-dig=;JXY)#Go*^hNb_>J>R^|CKl@a4ZW zYL7MgW7ICnUj2QeFtUY-G$pU%7L^=Elw!@`d#MJ;W%!7YSCQS%PGH-&O@1lwRMS_g z&MQJL%`3(cM3!TgZY7(d#`c=(BB}2y3EXgFT3SS6vMO13UE*gZl(lHnGb}-xEGg`_ z_E>kfHLMH4+S^%^_iOFw>Zqo9wp7P>X^7)l$JsP!a%dk1L+dx6ejJYX3p~V9XkTyW zSXZbdWCs_B3{Zo2cgvD$u3p5}hBx-jvec2)stexl{*VdH%{J}|*|mF+NPNqON`3h~ zd%jYi{|FuO2c0%I$$C$$fmveWoA9>gg9FtMfyFJph?^pvw=&=mBBuxuB6Ue2!XD&D zhnejga@ppYozVs(E{L&1eVyn-Cm1|y*hd}lVSE3e)c>dCT#sxG={?SvFSOHc{jn}h z_!?^ZRHKcZDb%P>ujtHsa#W0@98MKHX!&T)OFz2XU6dpumZl6QyW9YeVZca-03mlC zXxJmSn&p&7@YZz`OVf#4@8|7Q^m@fv-!Pj{KDYSHUpCy!L}cM0rq?UC*o$jkQu#)6 z{)bgG#T!An6biY71eOb_p|8{7vTDw2-K>W|UGJBE&l^V7dQ|oM0)314k{pA}msK`5 zqea%cDRm44Z$MrAuEbBU=I@#Ot0TV*FKJlmAz|Sokr#L`EEri}0IPgWKzKhX?99HlxD5Jo&=Ly>pYVh8Dwu>KG4Mldm%uQ%cE3DXHCP zrTP7v^hbsO3+#J!*>%FmXPLgsX-onc{`V@Km6cyMGrCZ@?$JHmqi@bS^kVI`Ej@3n z?&0gbB3yV`$N25Z+_dhp{Wk~de#XX6GLyd9c_sR^gm11U`Y;m0&J1CmdgqVOOg~Iq ztKEe9l-1>*!dMqbRKy9<|=wOLXUGs5|YgGF6h1}sIdJb=&HY_Zy) zy916R`nzviI2|NDKSJhb(^XR*G`DoG@0MhDi{_^15@1W~rT!bMqF74BFoFOxYMoBJ zpqKy^(FxBG3JVvls@N48SmhL&Aj~9M!+K1dCvv5BEh#$qC*P%B1O2@WxV7D+%(nBj zwS?Fmcvgqt+@`2)Xqf(ub7Z8@OSfUFF`KuMjVvwGz-250mjL%65ot~Xr}p%0Co z-0|*=2JOTYpmpyS$3m0~hZw(Fu*S%D^fSyb-NxbqTw&W)qw_-X`=;;{^m1?ERCh;d$RwlrilMqj6 z?ggW^a|y;8^SXZt;G62i5D?w=pPKkcGXSG{|7o{JpQl}Ty0w45ycYrH$c`Q1#b39s zaWCDAmRyEWD<`sA%z{Q#vO`)0+ogwv= zUjCTf58nDk=#!x;>t1vjF3N0-2R7Nmn*v8D%nPu;Q(MT@#V8fwh(^6%sUD}=&`g%J zg?R4cm4I{9opU#ej(uLe7%LIQAsH+cN#D>T-}Eo7^UX@wUY;t}REgKp+FW2XMk6Bp zmr-3g>c@Gj4MQh(9Lbr0TR3Ynj>$5yDr0YM%0FdRgc0z^dd6gVjk$hx5pb}B=jG;Q z*t|Q5CB%t`y90@Y*@oj_d6nr_p1Jze5JD=Pnggn?uEo_s&;Fg&JhT)OG@h>N8+J#b zq7oFE!0Kl+`{=0|)rWJ&YcKY#+`8mg#8SZs@ld&zE>8P|4mr{EtgoC-SU+?jx>e~{ z6w~>VE|t;lImA4jM5<=)9;157-K%fWEV*m`vvHTxLWypwT7%`aAJ)T=Rl@VW!Yw|QBK>u?>z`K$9Ckag{| zOlP>@L83Ylm@-z@HZdW=jnXUU+Tm=~I-)ls_ZRzVZ@Fl{3zLf-JPuB+JK4$fEqblS z#29CJq}(RHw}^LYuV6aM2gHBEo@X*1Nir_eWyEOI4lqfcf3aR29k*Q6@4Vnr896q) zS*ne<1no2TsH*`FTJ>cm#~x@_d-IGC?&DQ^{g|p4h^O@m43`DmqQ4*kE+zyyQDKB6 zv1&BKST#u(PVz$0#X_D)$u*UiUqMi@oRBtMaToGg{w54;5Ln@l>Oyd;JRYuynT`4M z@*ZAw2()YQvoxYi4J0+Q4Vp9wT-7q{x|>I?<>ps)p&Bzyb2gKMBWmsW z6;w|9`RNbHCyZ$Tj@Gmo24Y34UA&qD41P}P#U8OLn7$mXd0U9 z`TfWul-jjcR&>{d|J0ceEBkZ~D}&bu3%)_d8H}WJ(Q@?(zjEawQqh{DL404RXBXa!|6TXa&!Zx{-XE7LZjZBne=)nRiy zYB%mM^cy+PY^nru6&%moImCeIGuo0CUmQ-pGcWcdPKI8K25+LaROQc_D&L-%#bsn= zlWzP{A~!KF4An6q!s~JiZm&jdHHbA;#!xQ76R(q+Dy>9&k(ae*Hfp1yes`1XANCQ@ zv9PQgDduQY2O~^*cTrZ1Ia`LCU#N(j8p8aWT?;Dq$~9!{*u7t^1cpIAg2{RJC&aZm zBl)%74Z4M&(sw4c=JCxQk!5 zkFQg2A575n$StqX<4lvW$I&2jV-1HQ{qwZH_A>?^-_0*5bz(^h}{c{yEed|coR zeaFc(dYnBWH4|AmuthtAISp8=uA!(YG!H{n*Y$7s$mk!gju!YdQHbn*uG1u9Fm(PJ z>|T)ai#)jS=pSqM7uR=Ywa$&?z03TzU%#0VA+sg2suJAFtLO*uh>K#pN4o$~*@A&* zlD8A4IGde=x&!m`=$U7JF$yu&YL@UjKK^*oE%sAz^MP_F%+o5+v8saFZ#8X& znO@<-Fn`q1!TeG-JNbHj9?L+8dpqq}s;#&6xG0D8rHZg{j=$wD+w4XI)|k4jnD{r2 z(GT}k-XEc#e_H%El%9Vj;r|%-{VNGy#P7iUX6S#>XorDDq zkxfZ7o(x)T_>GgZmM@$7PhUtfWJl3Jw}L3qX9Dx8lDLRac~^* zh5vS2e?mX;Gon4)EAdmKA=dn-JI329u`|A*rO=|A34`+)Y26!cYB*H%NSEVLuWB~N zcgMvEj0Kh*)MpK=t}(0q3tTa956|sJBYK-Z5?3KrLnC??AJWotU~o7^5Q_FL&V$&x zJtNhK2s(%vxL+<;?XQ6OPUDun^RBHHR&N#M6?_Wzn)IL?Jb}Xwb$UBok`8>EK3@Tk z+I-gIMYX)FX@0JlYiZEm`v7U#qmyou-D1hbW?PlR&2N5jQlI!*jqlj}(?0N=#&_!2iNLNZUVfj~djp_kf}xY@X-tkataHBgGK?$g2wJP}HcK)tpe z_dGziSyav4>zPKMG>XWMu>Zu;1J?2Z4iK*L zRB){c^2Zc{Zxbo5n)Y_X*0s;PVamN;zj35#E9_FdV_d4vzq%cSFL8@r;C^PwU7fT^ zveQv@A(#1=tJ3ImIEZwb`|qQ1Kk`E-kE3*L;IIUefGoV}$@J3bLpGv1kP6*?br z*E@u?iJcqyeH}A}^ES!0IjpprvZlHF%X)i2T3@P`t>zU zGg{7uvbH<}ZT)V7N24N?_;>Y3^hcAT!33@jDnH^a6pMCxuHWZavmyvNIw|6-o$u+s z^}#t>Q+HTpS32rkHaM**B+4N$(Jbp3?hA@Zf^T0)%w;>C07ZVny7+fOc6r6eUz&9j z8Gis?td}^xbr}iDQLx+$X^+uk{1{gKu%_Cb2m+NQgEXSjE4uQ;Y>S1dyYgb_KTGXv z5RzxV#aKPdvTgwr=R$B;P#E|9?Zb<4BAf}OH<%Y=m8a_8 zjV;QvWpCsB5>Eg#24B9cGY$P(XqH^3@XHt^Knh>FeC^XswX`5>9;;w!QaCO+>XBFA z{W&~g*O#x|VRvt-lFOu2al18Y?ZuQCShSF*BHAnBH%_9hh>>3YnhPH$JsaT`=4QB! z1KwX>Ib=n<0IhZ}L*L?xW+R%hS${`nyQ^9 zP7@S-8>but%g7uTF<~Kqh4$zO09YAjEJ>S|0gP6!ewsKEcUec?SfsN~1P7f}K-_b> zmr}T_I;=ii3i>FkifNXh4S!}vLIj5PD3XV`#_<6sKjj!27S53CAfqN zmuqyw-5X@v&+S3q4gP{8B}e7fM7Yn}LTLMm(ZbtH!j8ar)Y+V`Q$=0Wp+b!}@ZQ(A z>os9_SE5!9pT^`M2eor5R+TX0v($~cCcLje)WSQWnWTaK8%C-lS5o2<(*vhIMzUMG z6vn-$e#7<=<}-G*fu=CTDz$N$%r9U|QW!zSqlQ{H!>)# zF?n`#_fCBpI^i?N=DjO6@Z|veZq)|rfL=9r;2gQq08^<>N5 z&720&&uX5##SEW7uhCNy5;ZSR@w&rL@;*0qk3W&HqRz8AAsj)(X5=Q8naeIMcW^O5 zk2vIu`V6lpdV*GPzy#Q-q5x9Dw+yLxUL`;tYAe&`GNhZWT<|l|u=aD!*hC!E)&?&m zIipPGfa%ib9BK<<^{ccB7nAiZ8yCzDDiS-N7lxfiO<^4Iw;58Ae<5y6HZaJz`g+GY z_-fKnDkoX7S?=b4J!rl6hvGV*qu9kDMcUG{LCPxyk)2~7I=s8)amG{PT9eYFilaaP zFcDGT^BQ}!qiv{BS&f`JW;SjR|?{%;7dQd*R)s#iQ_26%GcB@e3JN%`R z3~|xP#cgn@dyK(Pc-jwl-i{Z_XU(U`>KSuHBXsi?NLxT}w%#tzwxzUdj%>K4S58@E zI)8ifb1m|n*whvX-Vy`XxtIvH?b))fXkH(ezwOZJE%Rt(&0HAAse7rQbK#y%xN)U{ zHTJ@Pn1YyE!eWa^LgZ{3v7p+B0xY&44u1Hu(#1&7Hq|OV zeh0|EIJS?!7=c^J$(*Em=gFjXZaQ!9m$$O6w{q771i3u5Ni|$Csp3ZXZ8{Y-z*|GB3w|GCJ0}8NcWK zEeJudUhrv82(&^Z!Mi2Q)BW{xn0i@ky1wv7Ibs+-T6mDLIUgD_Zov0icHEyfxgn-r z->D4!!lqPWb1YhuiTu`!9fCr|kjoQwpW(wH}CXeg2o@Nb_)1M5#A$HrXn^b{VN92~tw2UH8 z_bhXQ61KAtIRV_AyfSvX6$I}nmdh(vtqv6CA#pN_cSmiHz*TxK((Ewk?U37Hc)_Gy z@OdMVb$9!6KVJ4a!*Mc!%MWpSHpO|lE zN%ATNCX~4QZmo-g(3>_J`nH!yv@%oJH)XsP^n%lD7hH-8lPo`yXO~-<7&IpC>R`9Q z81ZADK3oJAz3h{k=gcdJV61CCpI--KVi;8(8E_n+$ec7~>xuR`&p5?w z(5|fG)1Gg7w#J(#vAXWmHR03>{xc|Juzj*fyu#DXS?es1GnNoAP<{pQD|S;QUQgiT z7r7o99aHBiKZ>NlkNC@Ligx{+6b~9^s(#spjAg3#YS5ZFe-fB2g5KUgq{HO6jM>gk ze68k9l(H8f;KWQgxLb{S-dih3~;h9Y2@)l4FCX9h7bZ7GX#adrhG zKfOM&lWGkM9NItZM+JjDaph}QdhAa1IFYWo+Nj&dC;Qd3%{+tl809l%S8q6)nO%kU zsA6}8GAt#TV{AsgE^E&W>1s92STo2EGf{tJ>fYi&gqirixO?xgCf0syIEo5xDRw|Y zQ4o~gTLQ>dDbiFxqy$j9v_OCa>7XDjG$Hh;NN>_Z2Z00#5b4rF2_e!#lV1F?pJ(sq zoPExD-}9F5`u_Ol5AK;xs9q=ELR3UO`ocS4%$UTSZNB z3IRvz1L-^{+#yxo-tq`H>_lW24Zg{;nL^S1-wswsf)}XiK=Sv^EuPX4+Ym~I*#qPBd9Od1Wy6rqU%MuNXq%+JEP1c^@scXuKS6ABP95A_|iS;h> zyOFSjdJWp*vV7xy;pFQz4}qKjfv8~qi8NLHxE^&s%x0ZoVC5+@RDD?3ukYBpH`EcuBj&i~_>l)! z${%;8zb!v7BLfpZvWtr|V)efcP#P(Kv)0r0w5Ty$G+rp5?bMBgAC1e{h#kx zIeCYYn=dD1&uMp5sT3cR?OUq9SSw$vqVe;@k3vN6y5l*-o(V4dS<4K~+3Usig2#O# zb`D(i!~O}Sbx7~KT?AP_e*8xv_ka3_KIK?WrO(xHKd*UcMpc-`g>{e)RrfA>{q5NQ z7dLW>9lXPX^S@oD6@=+TH}4J?a{0T;_cg*#O1|@Xq#gDvD~(={UMtxwHqLc&uklIs zy7TQnOn~6tqN>}4nu|+m)N`9$OX^+{SyeRAo!Kc>poeqlevOWwZ2r)vM}7+G z{G^wT?;PyscwX#Ju8G;IoqqCEzg1J~nuxGO>ltB2r2GWUU4Rh)mi_;L3iZ#=Jy~l$MA78Ysz&{3 z+i^4|bO*hi^4RIke`1sWc!8b2x7kp_pVpYu67uT9pKp*;7my&>>>V)op37@IJ27bq z>M&`-%O$0uBAK@)^Tm42wF1ZhV|eWKTfs}WQE{$0XkKxZ&J|IE_{P;qrxiX5D(Y$> z$1aWKiY!UuZQ7l8Wh7OuueKOFnpn`8ifBcBiOK(xM6JB&`(hEN68>bzf#j+6(l_pY zldm?0F|Nms@|F2`N1t97D^ZTVbeInEcK=CBTFZ$p^E1lL^8{kAV|hv(;g*SkF6mtT znY`;FR$XqkB%vqM#fDyW`3{0s=TxZ|Y+B&{EH8idy$tyVbYNSC?-ynIid zezVwFnygbxXL3vI3@89Jh0(e1lKdf9Ra{~ZH(Ae7-%yX?R!OwVy0%o{usYxHV#YEU z;brr315zWkk{8O5h47!5ni*`8^qqBiA>bwYY{zV6Xn31dp1110aH7wCcwF?H8K}ty zh6mbiuCmu^`wS(Q8EiXc2S48x0-AKc%Wm6+gf!41p^!@GM@ML}JbZ%6xNo1XZ>{8r zR&?KM?Dm%q%`1IW)fru?cPNRT9w>>S?n1lCLe51-ox8hu-B+llJ}i+ZYhw>ol-B#^wU zp;$lg{@b17bKW-5Daw?#3WBf`eoS3STC(ZUtImwa{JA{kn&)G%D_{i8Wu+9}|El=I zVy(RhA^uL(PfOSo!Dt>n5T4V7d{6gowpFPY!Z(po(&_M7`Nz3npGTP4c=CI%NPlam z5^t{?YE+4>V&9TOyJCZzPJAxya_JH+J25KUf{PN#6)sazus6{hpP8rwHQ-vxj$>TP zhGBDFTo05^o)3y+zA3qxZt+qQBA{2`5+gCOEW{JkBwZe!J`$AaZ-@s)ZEsmspQ)W_*mJ-6&@EK+WuDFb366PJ z`W;rfcvJM_dQARd8-^Ew4)FoPo`v!4t8?q+M2$fn)k-bKUE%BKzBKnRjPCPV9);#{CSD%KsbrK!a^pmyf6 z72taMKH_R6QZJJYZbCw3idZ2q2bU2-UQQ=-+&OnbEK}te?gRN;#U#ivk{PLH*?B36 zqUX%qh?hbWlHAWEbcUd#eb=7gmSEL-<@;O}kt6PtWjKi3riZ~Jid*ib#u$Gsw{{@S zm&(@Bys)Y(Hf&Jwi-V){l)1Sl`4TYpnVx>ph(0 z&E8V4eFB<}n`)uXNsyt&FW2Ffq}>fPc~zsaziV2(Bcag)7z>$k#8W({KG%)0v^z}j zdYAJ*V?NrgJ5D&%^#1~ECk+I2l;uf%z9G4FR;_LOeO>6(g{cbs)V=M#c>c>GhRiKj zB(mPy1@d^8wFaG|X65G=eGV;&M^JK8f;FWYY$tqAO9pHMYeP-fR#Fj@xY#7%UPngviPU7+xqR@+3cb7ZneeWYbhCJd z6irpHKqdNV3wOJ^W^L`Qc|U)+Y)&k!-~`w-fzbnDNUGV?JS}Ul3H%%tKO!PDEtMhN z=UWaFg_Ucr&iM%yrCN1Q!&5%d@qV6R;K+)g;CD>gx<|U};O_64kJimNIir#ULh5-r z7oe(N-`BK~*tur>Y4F#cC-aOTQu6wCbQfpCP$4%rSa@d9$~B`q8|n#>GBLAt0pYG* z&Yo9gh0s~>9(;Iy;mi4h{!BuKP40-|t4J8+Sxa{YHcUN!!7d1^PB)zn=PS%EU$iNo z{1`X<^JT6tP{Twk444TTTPW%#%?c-mPkEWV60EQ(WyHThA~pIns6=2ORbgILki3+0 z#T!Ez3`<=q91|@F7SP_C@epC>&(xt@BGThFMA?1yB27EUgiOs^*=mDD`}{2L#KdnG z-5U82fK4j*TNrLm!NPvaAJql!5Mhc4-=elLZhP|@^z-|I)mG^eJ#UfKR>dr+c9 zs&KJ~WQ?tlQCf{se1#$`Z)-)ZPT?4@1XFuR@#~uhN3{}*HRVSuB`P(>Jsaow!iNF+ z!2=X=%gXwOxR5q{%Z53(OxxY*x?$<~y&hyqVy{*DqW0&cW`!Az8NH6S3*5bJcjV3v zsEs2YxT9X`U8G(*jB5ib9QiFa!e34yOy68%q}e&;%F#OAEu=p~<`G z{_QV&Iak<+V**-re+UZlW=1@B*p&+ufGWL#iO>=uN(M*Q$7)p2Cus=LYzqz;JgkXzxQ#y~!PJ zM5KhQe8zcyHo63y9K7&i{zj;^cjet5$eUlgV|H zHr$NvM=RAaSPKhpq>joVI_FG$7+T5uS2U{(MIt6|9~6N)Nb~|eK<}u{d$N&Eo-B?I zypC-cKb4b5!phmBwVBKemi8>V@{1B*XH-5k zp^%8SLe)>YP}W=1cVdN^A;KHph8hpwS+MeRQ;z5ZZ6Dkp-ZXL!ZJ zr8GDBBIoxbZ=AUD?LLx~dxvGJCU5J-HO9c1Hsti9kUZTTjos!zS~r6x9X@8ai2NSw zG6Ew2C6>CE?%L!@j&xcR&q!C*+PBUlV0{P}Ip(gp&<3+gw(n$_!a&7wIz%eu~740txY zYw-#4_%HbSzY$QLjpA=iE`Uzi?mh-=G!(ctrAtlCr{Zxn!_yb=bB>cZ@i;1^M{qIJ zNZ6)A*Z$uO%|cY2{k>_C;f1f(P)hGC9;Ya`MW@oIc5 zJf4C0#Q+8E1RVbh)YpuU9#SVavEoyrf08gxcajxH)d#K zo0gNbbj*Rf`+m|u?Ede6?e>2-{?qT8Soo*kH4S`4;&wv*&+-&iNALI_`4qokpM&&x zC%F?zC_a24rzVY~`2BebZ}O((k3Lfz@ELi~`-KSV2T4yT@_AQ}b9#-a6(rH=0HH0} zm}3sXi@f`rR6$XwU@`AbPH|DD{M`>xUBadEjyKL}3e+?3p8e|BH@%Z|C!br1E1?>6 zdk?!T6}_q8S&9X$a9PDBT<6ef>afeHG|5lVQGe9ZndNG^rZk_)m&q6Z*yvB-$iwqL zCAEFsm>gj50F3cI7ahkBx~D#v*;bke_{pZ_`jed<$(+Kj_B=PWybLwr_ReLBLUR9QX4`9 zef>M|j*?nB8pe$>D$^kUOa|;=^s)z;PZ8_ zO8eLgGfiin0e=uCJi(!&vgBW90*`F2FE5~LhK`kAz*J2c3CJh3wjh;qW6%*K zbm?4MhdX{0O7Q!#+=LfQeyCG7BS?o`e!;sGBLajYsOYo>Bksrz;y88F0usH!cJ$gm zJ_6qA9!<>%i8RwRBQhTKKMG#V4 zyaFy-hIPF3@p8f8Nns|;*0O3{HgV3_|>I}Uo#g4ls| z&e7&*_O_XCycHNX{j;f%*|;C{{Ij3o1v%fF{jSaOQ)f2l04PgRs8PkH4 zzC8j{TjMl!tPK5_`%dF7J3l14bDo{c)8AS*A}en&HI%hwQN&%M#0!!sz@^Q#ZO0GF z_)fSmXzcaA|B``1B0Phd-+t+g@A*Tksd=Em{QO!T^u?j%h~>Co-Zb#)22Nd_qe0_C z47>drjwWntD2Gp#>NNG6$g|>jCl}IPt-Usm&~F4mA#*UUg?LpqSa|C!A?C#sgNiU& zqcXx}kb+$#UMZvk=+75IzVM1Kh#&&BI`6Wv%HBd5N2lH?_4;9iZI4qI3`i|DJB!DU_!4A@V|^bxsD z0Zf2CaA)GVK4UY9*tz>mkz1b;AVWRd4t4wk`u|?Hbh{uvWnO*gf%@fH(j{cyn(ot~ z$l|)mP7}o(_S*rja`GqFK08m{R^uJ4ywuBKEM>f{28wy_wGK|Qc6E$~rt)J&s5wCs zEsBz@Bt}|QEq7kQa7b3rPSHyyZLClHMgwhDh$0&ney$%7MLEKH=F>(=1`^aRV41?E zL@)MG`!ii!3#9^m^X<9?s>y3P7~JRZeP0gGym7_Vu16|Xe&?D`(qXN3H)0%H+v2+S zu_S7?k2guR&wziq#DVvX^7V&Oz#gXWS#wl2%DDUv*?4@l2wrP8i`R~SH*YyN7|uW! z#yPUtIoor)eluxR)idjJK4|^x>|J{%C>;*0DY|;wgG9!7d9;Dcwq{FZ&PL>mE@lVByMvt6?W>0IiD(p={vkFZo~-)BwKO*( zC;pS%LupAl?^3H!2HwhxAzF)qAQI^~7E>u-n`xqoQ8`0q1nGa_ZBWs2$%-=VD??d>gIf!LwN%aA6>Y%N%%AIIp5Gj)3O-I_G+nYuvQt zJ(F%#5#|EDzW$Zs8Tp*#UKe?dSX-fA`$a#DmC>^tE7wS0>!+u;xY^cZw67dS&-{G1 zyQtWHDT8C)&5cVcfX5t{KWftZ1D-r74fRs(5<&}ve%bseA--kLD-`Jx5n-<(A|XfL zS&{G@$MEAWC!1UDyUR*Hp51oeZi)&xXz)HX7*Kr6bTgxQW@R4XQiQKwF{n;Dx9+4( zxBB}8OF0%BbuJK$SMYYc`Z;TPNsyEuOb8a zt8rtmlP4I^1~~ZUehMrP)tW9h#uU_y;?K6w59)hbiL}wxV7B<;5sbb>!!0Gf97+vL zgpjqcb>Qzzg>-!Vq#^iY;tnI~wJmm5cFT+bCo;*H4%`I#MlQHpC2^K#5QWJJ#=1-I zvg1?Z1|QDMDD{TNsr7E+Fav?v zc{bCo`_b~2Vi|SK9jB~hvu&F4P*o3FT=K!gxeyQzzsZ5Ii>%{7(gWO9^_BB!=`M>= zm<3P;fjl%g`}N?hEQe*6e)o_jP@n((|2mkjBeB zPbJB8pO@}NzV4+~s*jxRopg7N&}D&=dad^5N42ks>nEtA^Ve*OqSmBo(qD$QP;dh{ zd^TE7&jXAWj;^48jmj zyGyjvSVr|FH%i*BU%KBj@R47=(f396k@EW^dmpo~afi8F+B2fWwU1zs1us6`I@VKH z#mrrkgi}ty_vKU;2{@MDmqDf!+p@exD$ptOhC&s*e6{4hVk@mok@sUz5f4g{Z%b}| zhB{UtwM^Bq?IVngp_$L`C<;wAySaJ9*_c<}o@_ZH1L$#Xtm%d?SB ze&^k|!BM9Nw|kitxmav4?2VaNo9Se40DmZ)VGy8dgThaYN99rRwyeLsfgTfs`*mW#_1bwgQ zR{6bCVIDIl^HEp92zc#QY8bXNbpZTQPSTGJM@R0)Ohiv^Vr-xlcYPJZ-Y6k2$J)sA z8=qUQ3Dp}R$^R7DbSHPg6FnCwgw!=q^`%N9VoG-Dt?Y?!nmRmg01_xSG+_ICqkpQ~ zG=w%tD{Yzw!8hr@sIr)N2LkHRgEZs>K~k^Yac_3xmM`4ji- zJ*s+bEw!m$fxMtUg*^5L1;D$qcpn#-{|9> z3<9%Pn>KoH{DlXsK)S;Q2T~6v#kO4PG>q$Y*na`ur%bX<%OcP`cf|XmO>{pEX6Fve zMK6k(ygj)l9Pd+hiLXZ4=(4&0cR0_)oxkBbhW}QJ?qM{d|M-cPu`!4z_igs3##Z3B zYYBc?3KS&UWO-d&(37VltIV}1P`Wz}eDe`MXF=Nv%@j0wb{pHOJgePyGA+ayCAarI zDHBKp+5&s>pEz#mgTG)=U|{edG%Gdr8$}$Yb3zm;2C1<|>ukLG&;G{?+|2Z84{`z3!|@-sPm8Z3xS-5^-^EOR^e9 z{!=ebHHCZXvHJjDidc7G9PzNXHls>h4YRhg4K`G6cWZ~+hRLidNb?~&EF0D+yPm^ zYDokIHjhoT$JRc*C4i@s_8jr&^1Dl%N@?`r?st{EX!-(;zfA;XrCuv7BFzRlUbE%Y z1&>kGjqb(|lbX2sS2CC~lG>7;SpL4&nb1~HeOse#qK{tFTLKL9uEAAnm@ zjqR1ytgw2TUP6P&fr_!x0}NRveM@Ecdz*4;uSsL^yT2XDf8O}JRl4C%+hc2*7W_E( z*w%pK=3kfc-^O#A6|TeD7LCp8JmYzP?(i-ZJ>OkQwAjl&Bi(Nb&Mz61tuGW4VNA_H zUUUJ4yjxps;SFAn;ZMOh`*0{0q+Smf^~mz!*?VIbgDobb#*`t@s+AfytY9R~-4%2F z0p(Jr4k@r~G%EAPVqx~VUS|)P;*z|QeAtIXWH_xjg#pe`6y~o>4mYNzMUB71T~%hn ze0wgJ)!7Ck+_n{}8`+giB&3iBW`fmk4QR4&ZcrxkJ{4RhxLSXyUn*{ejqxvvPOSlP z%IvMT-6^E~bT})^la4I}Rj?j7;AuO)L@`ua6Pb#gQ#Hn2}9xZ7t*4pexDl2cAZu=7FZjkIBSjziIEua%ayamj7hm^PBfHF3H3zdtrV z)p^Eeb}Z9zSb?&^iX?$bU+dY;eNyzv829?hc}MAkzZBoYW6~|%h-=_lA=n~*$GJJ|gf)IraQC1V%&eWnqemFY`#f<3CJ|6p_rNuL&V)o1MPl0S{=H0kgp!iAOHga*tzBtN zeAOgeJ>kL))I>ef{HlJ}&^wY%eqi12e2(ceSh*CqFt?tJL^lZzdd6?WQR|VDw5-GK zn>|z}&ywH4EyuMv+tvdv^meD9$LqB>2`W|29y)v=tfs@5?yk5?xrwC}eHhb12%%Ys zX1bM%nJh`gp%oNej4aYVmCWCr^}DzH35AgPTsvR~V7ZpkLMB`YU4<@AC-MzTjdlp} zXPsjsyrV>kW7bI_NFq_|IVFkJz2D)=6N@$xC0i%~t7KX^@7uKtJHL8hqIAQCd= zDe+|xvld4F3{bm=vpg{JCJ!d83@hC%uzsp7!JBEqL0|-Awjj6!Vp6mzs{%~N?^c4Z zw`l9Yg8H`7XA>I9N|es5tTYQTi@7hd{8mitSid{ULpDWSt$a3qMjlA%==M%hUW>)w>;5pFMfqHUyjCCW-WYa{F1(=`hc&zhaNpd_%4gP_n z)PD5^WpVZS$R}6NKm*Y0>g>bTmYz8vktn!WTxVUB{Vu7=memTBg@w1v7xcQ>7$jKg z4|H#|MPh&OE*f&WOV+`zKGnU&43GN0pXryo`9h}zrFg;P>dHYHM*||E2d%JRXyX>z z;nr~J8spiOIc{EzOm4S9H{6l?TE^ni1?QrTOTC6y(z}2=hnbuqv0H^q4)OX1E$h}+ z=N4xh&Pn_Nln6#NmGhUSAsvy6_?Uox@C2ZIgYL-kl?dc0}a5$wG$zt7sa7bd$x z$|QtrSUi!ei16|DND=JSe?H8|F~C>823oSg+uhhQObh%4j=k{(;%&$Suvb*e@N>66L3 zw2`_y+`R85r$of)!T@R-ghW=ujl=rN1uu;*^GU?#*y%g2oWrckxe`Dzr}x8*QB=U{ z&KDaRwCoet1-T{WC!(NhppJO*%R!V{+1IigCzG&=;MO8X-N*L#sLOm-JwOd76d|eJk zzwFSm=#ISE8Dywk+e##zB>|^Gb3@NjMK4!l7Z*0?zGQcLmCa~6`fvey1)5(VCNSj8 zL`z?v;8DWEz1cJHYM@!Zo=4Bo%`+RcN56(#Xv?y-PF! zf)}WYI>+$SodqD9lUi;nO%6rk?6Pe{n1C5r1)K|t-6&K;&j`DUN9V*=pAAq;+{zC<)TXmtvvG23%Z z?7EDtm$Ga;!#GF73}E%9USgEusz+mNS*<86BNjN49+%1eR`KTWqdWEm<|m)=+j1`P zK6(kkJtS;#UulvvyH~?di-Rej_~{GNLeS9=GT5K5+bW{3U`!T*{=WJoA}!Y0I?(z& z;8I8%5~QviaG3&|cHl@}OisN;XFlnf?D$-riMT;lwveQZ<(iskrAf7asR-zB=yQk7 zH8A&?8D6V=?3o~&u03X*SZo=qEBD=9Y1DpB@9b8iUBQpzbkV|&B|o)hs|y89k8GXK ztVD!)y$-lU5Ec<@;oIAwuJ0-ZLM;R*l2&&R&ef2pvn3u9O3|y#A|e-tJ3@<^Tn8&g zaUJ8PC(}ER2Nx%-4dVJkhqNGC*EywfV=;C}Rj^z`8(jsE)n{o7mE(O7aOl}Eife#= zsxZD)+T}l3av<|4@vqN3$CN;aNr~}J(%UqJ)=yzRBj3aPy4EJJ40%r6VHR-@x_%ORT ztGg1bwwb;gqmG>V{ZGOtbl1+ueK|~4&Yi2NXCvZJ3TB%_jijU}uj;;aFmCqiyQ+=4 zXnZ&3HEken!u4F-;vacUhY2ocW~wLQuJslnS;MXyU^Hf1f@eT1Tth3p`n@vc8Kv_%2mGd}h!1ht7cC_w2Oyu3=wI=1*m1yGAhVDb;N6h8gfhu9_H^0E`hikOZSEjfJ2 zVd9jDb1?tjw_ZqYw_9?>^#OintCicRGCHK5e@RRz1WE#-EOuN(-z38^#&6wId$*%! zcB)zmkULVs^6UZ_>)bMG7CO3{XJMwCo-U3c#8Zb?jHY%diqCTezwBjOx+V`)a8f3;i`hRXtiAt=EPk|iLt#&ubJ zw}xOi&XK9NKcz+FbMoJ5Ol_oNPSan?T)R2DAtq@`Ki`H+AVH(1_hAbV6Dx>d4;a{1c+Q;Ry<4@Ir-FpC16#In$!7Xq?UwQ$AL-lP* z?$UI7)prL6rCKnH>q~oN_fx*hNlm9WTNr#o(vXuuEw3*L{fO&*VQDRrz#Hkae}&cr z@OWfsV=_A@FXFd|WQm(Rh}st1EqLw0HS-i-WliYKj^I0)Q|l03p!gut7%tUTCSAem z$hPRvQ`T7QGli`7s_|hXMKN<>fIfCZ8Lb>eN zg-qzTIMg;f60+kVWu?fB_09Qqq*ZU1ufo-{h*u>;?~ zNX-9gh4YM5ThP+{^wRP42npP=J8PsCG&+4cbSJrrcpBBCUZ8M<;`V64RAxbIr@l$Syon7 zCd%H?L>$0IE7lkD*Q@`Ly7jN+dRjE_=kPhQv%Ms(75#qaBjv=+Mx&hhIl|8v9nc|x z*6EEBE-T-DSyD4{AEL|uCfyyTC!0Cf*pxQ3ageUKPP^Ui*C6%pV)D#G-~4O0|Md!& z-OtHi0EI@Qg-^c#`ax$Za(@9>V^-<^&qCrta@^0v(aA1AsBYAwNOtdxNd>1At3#8u zV+h`5j=6U3a@B{%m9~)bwkT3XPf?v6_;oI-(;7BG!dija0eWDs>{N;FX(`>|e_tbc zr5soP&_AhMO3#=NR&{o`K5pC0;>?4Y1}o%-vXF1BQu^=BStotG-^LxkmRzbDod~(V zG~M%+_>#vro#4F&;2HZ1D$@}2|HPV%n`@ygdkyMnBB?14xapF*NisI76nc{s`JjBz z0mEGnG3z_`7q$O+|DV*pdA%44H*tR9IDmm5QYoD@&X#BIK+4U1`>_n$8hD!Q+_=2B zK?_EW!m;OH`|a-q6rK;YrqK_g@^etFOQc=NQ|ZV#(C_Q7n;&kur>A>+P?TuYds!04 z8n_O8{c!y=x4?xMntjd1Uw{miBjd&SgUkzldrw&s-W+q!ac|MSxA4KP?LYtX{DDfl z3WdhqU&&2aLWu0nYAEYo`5Evopbvc_peHc2Zo2k0);C??U;ER|)XSf#nSRT&FR#~s za`P8JF<>tPO#3NwZT?Ml6N=6{x_?5eO>8K7E9VAJ`(F*2pH)%c3p=7UVa$1K`stl* zI=V~W_0>OSgJqwl7HR+g=HnTi*I9b^TexjRIsZut$E_(Z&{r&c^uS?DvfEA|g}7!|KZBGNEnv>1(@3X1#tfb zSkDtYkn%5A3^*A)sSsp}{kM|fzgr988>?B$5hG6TU3511b8lC7^)_vc*2IpU21_~Z zWU4q8iWuxouFG1h=`z^QyKR+bpi7hOpxw&07MGLVCqqlF7X1U&_b0z2Fp{>7md!>+`;HSZF99MyyMUl z*De0t1YzY9nW?$8uPnWq=<*O^Xn4LT^i{zt3wkR}t6VM#FZFZjo1}$qqO6{sap|W9 zgF3CB=Wc21I1rr-nGR9}!hK*kV7*}yDd`BLR|70@8!VS4Xzcd#YwH`RU$EdUpH0eS z6JWw!N6VXb|LoPJ?l0+$os@Lfs~sybmgW+XvMvfA(<-hc1j1Qv#v`~+wu>;HZ^~B( zm6@!fw@R0f6R#$XWqpW`t1$HJfmw$Si^3!4Hz4g$aG%dGKElcqMWNk5N4bQiIgV<6 z0ap9GMRgkL+k_t8zB}dg@Gww*y$cA-M078930IVil-Cko?Ph9bW|s=#FhsZc@;c4MYO@EIC>0#tk*leI)IH zC24ns1krCE!M?k(AN5$O2;s!!2-tK%`rpejdL6a=%CSnpZ-kwLb?CmyNwqQXRBI=I z%dS(;HG@4PDb7sjm9Yq4nZAL-M9%%X^HZHzmP?t>7gE2J=`b2fbvi_vK8#ZMdaI|g zR@v<6)snYhPU0usf*W$R*fbH}gf`SgzvY;lA;=^CLoeIoSDA9X(uT_1SLW<6bRN=4 zEX6b4ZbxAK*ATy}aYh}tfyd8ZBqO37&GncE&adLUsjKE|ddmvXZY{V9YblFqFHWYB z&@ttlvX+yQlX`E*k{#%4esV(I7APVSgd|rE{1ZkuY+`hc4Bg(?L?e9Q-n3pV^KhHA z#Gh{67R+(s7a+||D{+A;fM+s~^0NHJ#dj*BN#DU45zilx0t7{!APG_Ee-GZd>dAB1FPrim_E;p(1^?3fJgRZJhtP z7>xi|cF$rcmx=zn@yS!|jRke76MDLR`Ek;~?$VF)Vq58<- zd*>uYV@FXE{!YF{5Mm|wlq``}U{@U%ID)(D5hv%lMe`%0)GksFj3|EUBILgLqul%j zd|DFO*XM4*t=#-c59gwMt4^Yl%MS;EOmL99TbjXKQc%z5PhZ{D z-L0>F_PE-mIO9Ga8ylaUvNjiIxNW>EWGY~$^nH1}UA4KA6}&97hfFkM=3LB9%d`*_ zTFOq)hfxbNcjf zS)-?^ue164;kXDT8=Hd+U%qn@q3ct5F~AFE3<5w&Rkkxc-}A(s>ljzY>$~_=Mr6*w zKFSvd?rKbb4SxB7X9VO8m(;xvY21zXW9uIb3^FyEYa;^s{{N`cjCy=}X|gl%y+=GW z<%Wrx!aDmA&}WqFwBxT_VwiMre%4B8?8*Uwvj;}FvZyd~-U!ZtNhYJpTMct>6&I$p z2!6VH_~Bf*qzNgVd84hnk?nPQ?(5YUCETinNi-eg(JsBrW?0Ns?C}n*tx)j5H{eQ> zXy%bWZxvEYy5G8Nmi)Q0!XtW8%$%$F!cNw3Od)nZf_2>GvJ62wKB>N{!A~BD^7T`{ zZuGQX*B>h)bv-o} z(tc&Z%mwB*kz775lG2p%&2{)ox#s;>8P~Ov`v%TaVtz-(JC^q-7kzEZUhxo#TkqE% z&kKa_Y1Q?Kx?!0mGJ)dswZ^p*V(tWDj1jv2Q9%t!R6vSI?e z?-$?;LSjc&$QQ(Eh0O&F%>-|ptWuakA>pdJ1&b4mCMQM}W0sz@PhXY`iDIUwLn6Gl z5-Ehy_1SSqt=%%hjwXt`y*c5UQ$T#5vN)aoF6y}`6KBvQ3lO+l3f@bi^-_L)eNuX9 z!nw+{AWxtmC1G&*cU*`8X=pyyeH}{g${WjyNuM)AbVzAI@tgx1(+!y`Qh3?GBOg+rR>+NW^LR!GF9s2#VP zjwm7P)zX!1cbg=Lq>eM>@zS2?lLQ%XoToLQKiqtV*rLlhfs|(#Dkidf!z&chr_j`; zTqVf;0-?pb2XS1SW@a}4&@-FhuGIs?awx>CJPrL!JayU(ojTT&E6$}XaJr4C?WY0E9fzRF}%9h0C z{RK|fB1Ex{uPdVsG6moxH#zKLR$Tq+OIwn83J?i<2ww z71R<9YPyrl6NTvIjY(iY-mVGaKlPcjLDc}>j!)+4yF1>3AStL~KNyAIfBV>xo`2i7 z$x~EIV&YS3=%WwR>Vj;d0{;Fkf`Vq`&X6_qlSz%|Z5);%0O>N?kL)7yF!yy^2CzXv z->*Fc*%vG=Ka>#x$9GdK&&eswsca`k`PeS{-b2h@WKZdS8ESeg$LEpR+ppS8w+}(;t*U3gp8$sA2x}=+rh= z&OJY(RM*vkC;IJJE)f`3@1riZk(O!r1}D_Ore7{v;r&hev?dt-#b1 zm>27ET6e}F24H>B9r0#pM+=hMdUrN%uxE_+T*7B5OkWX8$sC;5$XHIZ%JJCfJuCbs z39y(oBZ2#JeBn6-S|MyonkU4F=6gQx>%V(ykTsvH6=Zy0<=N^kS82P#oSrfeWezMc z`#!M^|2bw>Th<(Uvgrmf=MMZ_BYysjX#HoI2>!P+Q3^!{2i7Yk1)OWMGQpmc_*iV; z0Q8T$cDOR>s6mL%wDi92vMWtNKU>IMSTXUqc+pem0@nf_Gpfa=WUTb2 zP$VN6f8J%AsC-{s^x~r(#63$`>OgVkRx2`~&9^@3-|Xg}%beub{Fu6H9DqqLKQ|{I z)Rq%_n8b2d3G^XL9u z-Q$1kPw_wSrV#!=_oi5D{I7dt{w%lreYpO*&Y`%9rSwBolR)~Aeof7;&Sq&`Z!0=$ zzTxN!V!A5kkkHXhg3<(A`P8fWU&pfYBR$)A#Q>$QtVJ{AuXae7(T0m%blOD4*Tn#* zw%r#V$Gnj=u*h2Ar*|RyxPoQs%|BmY&ff-$qIP;zysrG=OsrC*m^-vyXE7mu{9SKA zzUk-5mnF23BXG1*0m$Z`*w*B~DULOB1nMn3Sk(%~`x8Bk5&cRI1xA29$ zxxu3KW3^zca`jsJVj5phc2JqjNj)_oi15aa`^NrJX0Tl%zK}4pZ`OPvJsqW7suEmY zqvQOjg#Mvu+!v5f3`Z?x`m4CVCt=(AaC$6!Jw+wvP|*10xQ|qQmJ{GoFw=Z&K)+B- zTZz&J!QybgDyB^mhr3N{0$JD-Hhs+L+yu0J0Vn}E_MhpEM>36i?CHG%f+6~m|_!;JUNWEmW zVD!fUe@9N#ZQ{jRlZ9kR&^(kX;&~g*}9z4?Y+i8_6}5u2jsH2e9rKKADis zW}Gwjc!rLx3?3=pS&+a`?PIviADtAY{XfjTby$>J7dJd6sDy>o5DJKhfYOa95+Wtt zD&5^MqoRNkLkK9T(kX;vzUzADANIbvYu|hA zwbowix7Hfd+_Ll*mIqE=aiQ<0)ws!4HF%_9>ia(6_O=VZmF(YoJ`5uJK*Ct5rnz)9AnyoBE-mg}ql4 zE;`&@YiCa7P~v+W5>C~hcZg_lOgx8xT5xY_%|tD`^)wX6ST^u_D)w9(J@o~L4;}SM zz34#!RiElFkBUhEGApTNW@?udDjDEX=l4|WOs9+>pICAL<8$&FkWgNCY6sfZ=03gX zPcE&o{Qc%u{;kgN%6k?S3C#zfiSV8}Bu_th4oI$yW6;po9ytJU?dMD`?D+uM@;|4c z9(!oB7nvlBrLnrHlz&`nrn0{O9Jp!gTy#UJ8+R|YCnT%7V(}U>Qm?zO^V1T90*HY8 zhT3>>5TqAllm`-$C*wP zmWmE=HC)$p<64^WA*osPp-Z!Nb`X1qvr_y59|?1IqsL^cV%7G(L2?g3S$iVa3YXOZ zH%UE>bfdPQIJ4iT4)v^^nv6IbF4N06dZGZZo0q)xw^|cw%6g=g+2q*1SY{QAzTj{M zm+OOBik=7uoFrQ+0~YuUbxrO}9~Ptc#S?V}qj9q#-k=LFLc~61;R*?P0O`KNYXbCk zIsy5Lc;mgYC$n&XhQ&|Z5l^L%3?Kz1hNLHfPp77P4J#`!7$ctzNk*n@A zi=U`O-wO19g+$#qkUdo-R%+q1}^7XfaBo# zx=AHT>irmWmLgTxZ9C&RDqxNdK#Od+0^q$9Gl6@I?LIC9^2?W3+r|`>2XAxOjGbsn z%!tdGT15u~#Hzbm4h`I6*G(xYYMy*6CT3#nkZ8}jPu$^vdu+CfPS9O2^}gp5K~|%YSwm^T;Ji+)q5&FtJSzV1F@KI|jdDZ!Kl{pa-u^eq z;2`}GnC!6r+V~6ta3kUq;sk~Af!I{LUGchuk2Tj8n zN>R-21=@>_J$cz?IF24H)7KZFVAIe45}CcmFB~uN?7c~@E4K5);Y92nx8TpBxo_E& zttOY2y?%aVm=*wrOQ_CflsfU2^y`fDrdr!toV>6IzXObrmZb-!=B;4m+!*!>#LWdJ zrdP}%tpP@@-ay{VFF>YeyF0PpGu7GX;eZ}ZfT}ile3_3{R6*;fOA!akX&Di{w;6w~ z1QCW`TP5TG1R`#?@CNW{6lTwlB*%oQEZu7vC=GDSlVRK@MCC0EZNm!)8Oyow!-sygg+Weta54sn84OMyf#3_5^9~+2cS}dzB&z;h3a@qvb9NF<)_hV@Bv68F^hGS z&?ZiiHw93beR6lK+H>1@Armhdt{p?Fog}6H2n_Vu{!M@iGXozk-(wY8LyOQFOsu?~ zf~76!sUFD~u6h%K#NqRGH&X}nwgoLvOaOpsc8=Z&D-JO@b40`NOfz5|5J@jfYt&8X zn6~pwy1G?+aEz{uGmU$HlF$J7I;>w6C9#wad5_FUzeLLZv<(3HyD^9CU!pl$D69)_ za$F8TW`pSXOu;7>R*ZG5`vr=MPKX5`G=v%$CTqPhL1GEL#ZXj}su53@_BDL3lz-*! z%D8aNZ|_ivhc6-bZWL;wN8+@y-K3>kkvF9qc#I$$_x&A~4OOs1!hlnp)Tu;_RNre= zK{q+|vQAUmRQDs|<0)}+X%SzFhXgyxm>pS8O__Mk`s!PZk-eqt*0V6|)5}?Z$&wsr z?<6bg5NZz*J%9JCPg&4X&&;&9#6a;$+cd%Splwme}$3OEZ(4`rX{ltn_1qSP%hk;=kE(g7yBgC?;#BB`)FXUX7H*&qVz2_9t9h5!FaIF zy+$gx3XZBZiTQ}5*-q@I+aAQj*B5NxA)TE~qY~wYo*I=!^JD!lB^YDnaHWL2C3vRk zwi7^5-kCkIDlu=0k{)WUc0b>>qqC~2(!ZdIb?cSD6S83S#gH)|^H*y^yYavP+UIF< zFTby2@XOCy!Obfb+z!?7azx1K6)|>Az{Svy|LU{mVu1m}zN?cP0A%3wt zz`bLp>6Pfp)nHTE2FPd3>_Se7jh~FPc~QS#&~4jr&Jm+HL3>VT57BptBr$`UTM`;d z)%bTw3dQL$3LPw^l=CXsA#4Qe)kUd}4+^+Q{c zs|v173iwtgvi9vbOieExiq5g`KoytmElr(ySGeshYvE_j^IFn0dmVZ*4sPnGSq<-- z^5xN6cI5Z%D?dO@oR^U)QeivNzP;QJF0?UW$7s_Sr|GjqQL|#@`m7Br#r>#tS3Co9 zbSxrRN>?>z6BYd>i%D<5*6$o9lq4~IZ3anhdi%q^07)(`sG7G;ygH}&ibA?@d8D%W zBAt*$%aaDkrEn0t7EREc)_zs5DU^mB?hE!)xRiD-@NVR2m3;(w$3-6>XCFPWhe*rXqh57Uu-oI{ zr`St6bn?7=4v<;_DFf@UNnbFm+CxhQPJd zdBn3r=tPQTSzR8{C^pc^jUHRBI^RWZiqS}0D9>?$8pBBd#(y)o(5eYFPH4JyFNt~Q zZspqCNdLC|?2$Img3GmAhMLfoDlF@SP)%*|nA)4V^Kaf2TBmx8bAQ?!6t%p$8Vxos zwRJ&ySw>#)<9RrA?buLlRh+l}V{|Y&?YfwgB1x~V2H8n;mN*e3m)6u6?r~(sP-Bdt z<=yaQc4G%tX51!bsmnfE&W8WVY-jS4V?H8~!Gjs97FZl!Xi|AM=H5-fd2)`(BI`iQt2xKJjmO;q4Ns4-rq4|px-4pp>oo0LOWdaD!nxir znyeqw&K`#DCT?HuN{u$6RS8`y(XJXThdLO2Do=Q86SypVQ7K2m?4nbm-WTWvs}$i# zBjZ@*I{LyP;I11IE9|N2YN(q?X2nrRY*E`NokuOgjkxz7_CXSVybM)H>_e?*L3GOl zBl!rbPPBKge6dl{Y~S$x#1!k-_*}|x9>N=yO^fAByNk>0M)m|DiJ_~d_lt7-rbj4f zG#Yt~BC-R7F)N~pDGsXAeVA@9MH{78k1ga+iM|Q~28C*8syr>q9K)X;@zCa;-WlhV z;Bk^Cql!FZIGu?FK`vhOXj0okwYc8SH&dOr_dk`y7;_4ncFj^!+6r&VOS`Wx48o3h z@Wjz}2v|22Ne^utAK9Y!&fOI~ksI4UH9! zUQ4e{BiM~=z}<&+EKUa@Q(gT_bgy?_b@0jTB`~;+h@PnxN!w+~>GV!3KfU&=RnYgZ zp?&23VUibc7Y{&jD`5wq55>;bHm_LuQyD=`n2qBu|3- z+LUAKg7m2e^14OBJGq*I#;LvMB_JVT`*b=oY|Qi|J*TfY zg21XZe{qhv)m^K*wIKU*fs1l!e}c08^5maQ2Ks^Olw5Ns*}9X)6t_MosF;YEynXZ> z%>i?x?>#251cZSZlC&*0LJvTR`+@|_x<0M8?A>db7s)S7y~eU;OcXi^;f>PNa5X#n zT+8nvORQ+Hp(j+UT6MwwPX}C-GA5kiB~SOh9F~Sccu6 zxJv&Ep_MoOFlhOHBg7`o31sf~87|l}Mge%I$u<1PePWS6+g<;+o^uC{$*T$hQGa`; z2=5dlHUSYq#}-F~I|jb##!(qSOe~xh+!fHg0?vdFR+Pget!FPIi~NV%12H zrM*_%xKLWic4*Tz{b%Y~-w8&NgkvYI`>+%u_Q+`+&k>%chyuZi&#nwt6a}5?Fb=fY z>n0=f%r2xHVx*TZtJxQvb!W16kgoH~2a*bjJeM5)W3z!ntEk$IdWLdj; zks{7UKoQ@H9I$uM{!73e-c=J8vUr4o>sWpVpx}tj&7T-wUM&J}jdnMp*$j3Pncb+c62|(51 z$L3pSJd7j(+<(lSIYyJGSiR8yjTrxWmZd@lI;$kQ&&V={{zI?ky)M*Djz4KxFPSX} z+R95ZM-(b5d$rCmkB=oy(^@$50A!rLn7*KUE;fP8sABdwf(&t@7FK`W{0dl*e)6T- z@;ObUvvhPiTz}NFY+v@NU1fsmiV+aiF$+rgO6A&IH6T%EQB_;tdmQ)b4|$7dt|YuD)UOb z)X9@{c1D3QTKI1woVDAsb5Z<5CWCvS%`7l)zV=CX!6zvOqOKF>jJsR@K61m4qzz}gd1IL_?$%6c61}-r=I-ygyTc z{|;ZSyq{~*F$aE!e0D}4HN@Si$6TgA&9_GA`Rj9VGTt(I>Yv~3KFuI@!n;57mK=}eQj z0mJcaT#eK`o_JO%&&0IcA16dOxH2h!93!wq_e%V}{kqm?Z)29J0;Cx$x2gw>j%ktuHLNxHX{lh==ag*Nf z(bZKl?(IU$vw26iVfwV1%c?`mR>DPd#Tf~jjwESD!t{xf^A%pEi*)v}mo!@iF|9J? zM5Cpl8<&vErs;ps#(xGw|AvIV`)kcE+s8T_JaS5@A6=JStORLF$$lg``vVCr5sh#` zh>qn=P|p%L7W(*LKSsw}N9Ur6M=#Uk61I8$!N$Y$7?MqDtev2FS ze!p(SQ@^6AZ2|-nS~6Y)wFsUWw_p5(k4$vFB5uo|73;50zLbyeQk|XH{#1768S8P4 zOIvl?Ew9&}md%!YK2B`55CdJ=I{=kKcho3+sNvdl5(glQ1CVy)>E_=ZIlnd}!>v(R zRZ5KAJ~4mhZ{ZO~e@Wyu2)RWtOr&9du^mI9A^QL{76`960J-6~`~Ca>ch>diGi8>u z%uxw}8ReR24Wow(L;{1BlbK)L|`i=tuv*sP~Wjm)I* zgf?l}UjA~Jse8Zds4fBoyDjP~N80*}j^KMC1@Fc#@s<|R4X(@i0sDEwx zzFL#vReY;Kl;3cYzCT1!)ZXD6_JM;g*U>JzWrTU+tFkVxy5AQ~uS=cMR?bur3; zNbI)D}p7wUqyJ49cu?aL2N%!`T5w(TnAm_-QriR9=zRO#mypKMX#DTM`I_5gW+&h0`o zcM`L)Lxceh4APwdi;ceSF{qg{=!B?UgvL6~;V5(9b%uRSV-#MT6#nLLcAmy`Mazdh@x02Arbmz6| zG18sw%uT&;lgKs(59m;hxc3*huSHKMg*vax`ASbA8gTFESwd1no4){fx_-p~lX9!j z;d{l+eeV~zVd(LDU?Sb z5qPWf(!7^wg0oG)w}NwwXlV~?wVW0Nop=5C%PqfJK=oTYC;bjUT2~H0FV?>tfTjUw zC*X5&)%$`wWT^j_zrPXsCzHJzRxh6ClsIT6@j`LWXshA?M82}DepJPiNG+_)PW*gR z^ODI|r(>G8Rtr6z<_z9QF^)y~i{y@oim3H!IT|HkmxuZtb5cunGi@ot12Qr`JNJsN zThW|hog_v*cJ};~0UzPoQ>pl>tLmBV%*){>h<@+zV!BOd3(_Un7nPM!3kwm__IZF)xL)*FYn zb54E_eYk+|zlSnGG)MaL+@b!w>!kXx1{1#QCq^_h13@65k||&@$?eAex;X!9o9N8v z5cBxU+2lrk;2uGWUwOLrM7TV2eZr>>pX#{_58dCxs@)=5Yow_G4XMVEWsGhOlK6UG zf|3nLP_SD4lK3Rpw;AB+dkB+2t+5ADud9{GGNP~D_8?o=Y}lD=1awsUj)dKrDZ+~A zFr3qMeV|uE-!>wAH`CHs)J-=6c6S;c=jfTIz37CAY&`%;Y{C*9JB9ZaZN|1D%{FW` zHyL!df2>DOlp8)pdmk0?$DtjYZCBDM86D8_!f?taq?CS}1fC+ygS(lH^g~;w+g|t1 z=bcz>mOBZ#S8d=sWsui3Ct*2+;Ua8Vky(Gq$*{@xo48M*M|3N!oNlTao{m#e_0OC@ z#FA5N<{!dq&UN+vvzDBJ4^OYN9$Io1y|bw0%7+@FseiTP0CGooF1SZpr-km)8+sm( zEY1&YwD0;Vu7)-nkl2|{l{!wWR3$Y>nIkwbh53izL>h)<(t%Q~#dFdv*%x;q*SP`{sP{$KTMz;W@6NO-3G!@*g0+!O5;qI1O-u~( zyD_<+!Y;QE_z8Kv<{VJ$X*AW*Vf7p5S|uEvhs~wW;%G^Ow6R@V70&FbHRi@X3Hu5< zwh!lCCXjFLcxUfsW2&LRhPVRv$TY_^YYS#{p=y~{9#zcb{Ed%~Qg>E&Kv|bUdp^wLQLdyxDFI`2naBPyMW6;g1jgdrO#ok?jUsysEA$g(%1DE@V49um;v?tTcvj0`IZU1%{<_Q+=6d;Z+RuxP?>FTLoA(*6LatkV}wCM z+eq$=q;uM8AW+Eb&er>pIQmHu@_5rW(dsI_eedsBhncc0mA*fzLjT&4OyY0JUZL@u zaOjEA4vrc$JFYLOCs-umMUrN*joRT{UXxuCB31NtUCMeqQdEuO_+X_iFmneR1DRC{ z)K?n1uo9N!C;EQL!rf;27fT3LB-di8=DzaS;_oD?ccnDj7tS7 zNBPVO-d#y-QgU9JgvZoueB_2&PKyI`b`4c)OpU#nH5~ z$Ijlo3K8zmB=BM_Dot8moMRpX;3M+zA5L*dQ7ChJS|r7=1{JTB38j6z*D&ViJ|~=C z8S?dis1p8ns?Pa-EUuwv=&SSsY*7hRoh*rN97-Rmy*%73?JPH zND+N>WH2&hBH7q+RfR>s|0FgWTq8wN`mTx2gw=PADJsnvh8%z>)`#(KN<|R_3~Od( zdz3XH{HBk<$($#PtSlH;!31XV_gwu4AirvUuz@ehG$v}9kf)i}^oYfneUohRIH^}L zjqK-~)Xd-)xsk~dClZ7x_76b&hUhO1(PVmNULt_))4zX;CDMK9U9Qht*_P&zXGF;+ zKG4-@mbUI;yJDBk(k<%8c=?_UiPX8>_60Z}B`%JbC0=5u3TiHKob2l_tK@%e((y#S zxpw+-y?!lu?)ohg(>XVK-RoKy4xlpLOzG1fqK8N?pIhe6N{5k<9oRubpC{@Phhb8% zD2&6(Y}oj#aei)ViI3=YYJDp%&Y7sMSHwKh(Y#UNWeaD&U3n~}*JMU#)Oq^0$M9Xr z98VsL7`X1@)@#VO(!l)?FZ#8{FVSX9l^(+m7@c9p;lB{wzYX6fI^QM7cI>Nx%At1hmGQXA|5jhHB&>*zGJ|(S+#jx?JD!pB0n3s4CY(r6 z6r`x*&~Sq(t#oS?@-2^nIdG4c+-|uF|G_|9j&jSKehlTY$6e(e&b8Df1~1vzGI8H! zHXQos1+|%5YF%5Gg%?V85yEtBjoKLUI63UcC10MG8D-q;X}J|KWNsGOxGtweJ357w zmt;Bh>~{s77~b1yjzpOe8pQk!7dYq{CPpdx?}RK0!-ueX)!$O)O+bv|J;!pFr)|NtkNF!XMyc zi2m`>%+MMeE_fS%N2qVoK$+tX(BkaN3;ova=s^zQ9>c%hri=32ElGy{>^&K1jX0J^FM zJuC6H9{{J+0h_H20Kou9(^a#6hsT~qGvs147TU!MeJCHZVHLA8F0b`XiJwwxm8%*z z#+@3+NRSjB|SPxHx z20@{SU1(+90-?{4-wGECWKnaQHgwu&Bi!E|+j854KaJq(ss0DendC5YCwZl7w^eS9 znMPI)YNBIDC{mWZJB!+s%?(yW)>`ZOcUL|3^#iLS*h;5%%RR&xI7Kz#4=VPvmyn+P z{Va)!y(*nd$?1$OB5_L*Od%U(yJry5)OrP#dA*(tO74Pp8ra9$_ZLx>f-JqaPI7B`j0 z1@;gm`h$>HAtA_QjaKdHs3;HW3uJMksqFb(ovr&hwgN&~ytZG0-&Is}oUo)J57ed{=#v>GCz-0Er>-Rp z`h8>k@-5yrWZ5jM^x*ge|o)t+xgqZ?KwLakA?gO>e<4Tneq)jxE&cbP2~r*oQ@tc zhZG@m(~;NbW5QqI`prhg*+}U{>Xw?P4nR7O@3i#aDWx7Mf4{mERO;^ak<30Yghy zJ%B)Z3el(DS#KoFgEe8xxfmV&fGuGqVd)*({Q*=tmIX zi&VsuM3!gP2Ji3Pf;yiUo`;&iR$iXWZ&W##6qXY%5Om?&`TQ0H?79Frbw-{gCPyX5 z!kY}wA{f?bq&3pM^2F%*CfAH1!#JK{U{uJBIcC2G_MsD|=xNPCfs6XIcYmi5dUuED z07Tcg3$6Crk#M6t_u7T7CK9WTwSQb&7cIy8BADLMo$Jd&iIxlG9lTFo$*8ZyE3O;z zfsV!6u{^=P$NuFOv1q`J+xh^?0S8-$U)z`10bE=u`=eZ%OIbs9yVugTG0l{D`wRq4 ziB5d%W};~U7B`qN3svaci0y}1a$yC}%L_x-+zDNflXL-pP}Tq35}p|wgE?h2dE2bG zuiu)fZWnTNIdp0O>c82u-t^xrI+^Z)F>?-80>DbE()Br|dD%Kj(h$@{Zm*#MtaOmcSGKFe!=hDbAscbkRTC5{pH9QkJZP6lDvM>@dF~P z)RMWOM_WEgj#5aaXY5YB6nz%DvkzOk!)zFEUh@yL_un?a09=!Lv^_Tpcg{x5B{H;j zP9e&_@?>z=%UBD_vp09sgDKQh{rL7!AsswHT!2;=L>MCn6gxBj{@uWVHfXatLp^M= z*oS--x(f)zy*!+ZlH3;8Y)DMgh{FJ#=#a(RHFe7nlqrLz?{O9Cz@`h~WQ*|wQ(o_> z5n!$Xv4@0kk+WaW3MUMU#7?L?7g@4jU)GD*aSj(wy*&Z1n!D)soMmXaiCp|xH9uv> z0ye6JcQiTg00hqdY?MiMCpv^oJe>Pwpk?CBO^H#Z3Byi!lLUNfA3idUg<5jO^5GQ@ zK!YOdT;+tzfO@)**%QGTerbtD8@%GdDoAYm9Ds)5`!~8=m(TB);s~ZTcR7?kJWyYc}*SsE~OI zkKh>(K;JYo>G-z9Ly>O?bF#W*LI4t$eE;i$zk)7j?9=k$yvqWX@zi#Fmu2ouPL9(d z1!~d|L;*T+F)V|3yA?o)X9PD5#G!WKZE6RNV+i3S*rX}pTCQum1rCmgHRXq_`8@b%1{GKHJpfj)LcZVVIq9s8OyK4Q#y4KKQjsE@8lujX6bjHn6m6!x82*>4p7)T`9Z>a$1oan}oe#~?kP zSB%B(i9CoMxDR`P{dd$l0 zn3*WaoSS&$sE_}Q2YlCKw{z3BTES37UY>%bsz@&jD9<8iyBZW0{cxgz!{~neOX;l> zj^|!Z;^j}z?>(TX;c$>S7S`R6b#uxp*~6=uBrq_}Jz`Xe+m`{^-m1$FkHVZJO^|H(f zK26Oa2J%LJ7OJwzz~wf}cC=`iF^NzAAdqHfSWO(X@tl1p*N)`a`*>wEK;Ytd1daFz zfFXG=azsUIBTSfySVBY24&n9@nVOG=Qx2NB$?Ap>nHN+DfNZZ4&U z*L)}xzAjkCBlbKpRdX8P)KuaF*tX4-nuHOvR7yG}7pRKmN3eXHy9;c^$Rj~}CY1ZG z;}GX-8u5NHh1PUE7rJ)B1(!1V>)PaW0}%*^az@9_OE2O;xkwQA^CdQ?S9_^l?5MJ?1v)Zk`B){ALWSwGNBi9#UU+owHLk46;SNm9N0t- z)S?r~Ul`m-9N(7r+7XX=8Y)dr*X!#$&Gh~T_vYc7cJvkVB1I(i`B=nmxj1&;39;sK zu+pz)()|i6X(eS|2^W}+6OryB-vbt%Stehvp^V(QHR>$}yIn7U8wyYK8UoeSaorI~ zfWMaO2Pw?Whu6#j%bI6jZ0vm=u+HbvS0RjHNkFY(z^e*9nwlaWTRsO%Z9d{|XK`9) zeQhAnk*-2S;Q7Kv^^2gn@WF4(Y2lvqLY+P`Yub7EeNDS=7N0%x(tTi}3;XG70Dj19 z2mfViSDnLaB49@c;78NA=^O^9ma^$CB6C=xSOLiCbyKE4zyqOM;;19O4J-|=v}Cdr z@aFGa)gWeaB{U{1jYvlKi0=-P#iT_f`w-YpuyhY>oxrZ-K`@B&I&Ie&b%Eq7$@Xo| z!P&4W%0mXMj3$yLJ-qoJ9M=bbo+kQ`t6u}Sdap&Vo{}twti;w&Hs7}p2z*Q62z2Y- z;Ez)dIUpS)AKL-w`;X;asA&qb!^>}7{lT^S%mGsF14iA6K73{@FMTM@JCgXTR)jF< z?DckG-5w_8$|zV#*x2HcqyiY|rn7&a6u@eJ$g(s&gSR+9nB5kf|0&IcC%Uyc8?%xt ztRBY3C7o+N4V~hfbN~ve7h42CUX$=y)^h$>w9qnmkuFi;pV{Zi{;caGa zUvsZ0WV!#|XHWiB!co`+)aSFvdBdDrq6-X?{XkRnUjBR`aid%VCGKa`S? zhULT_azgu&Ksj~Th5zgtN=VTs17{zA4uxng9bfIHf1hLuLRR;-h>rt6+VN_;v%VAuq14_r}JnjDP%enM8az)S2ksd-;AE07kq{QAK*#RV_@1lPVd-?ME!(|5B z1{ytR!>9-J>UCvw#u<|=7oV87eLUKm_?|#Dr9eIm71vv8iVU7zQtsxfnQyr+E%Q#m9d?75 zvy!9tRu2tX|1(na7~=bx#5i>Pl;~V(6Em>i;AUfTt9Vr$!g&heCUo{F+p~zF+l^%F z98OdFGhpeww@u8~q zJ!oc+T5}DBt)RICL8G4mE}BImft+rFGikk-F{4SzZf}1DJRbr!rho_+&MLqa{=@M! zWn^Te)#O*41UmNo_$02!s>oSWQ>CkEi2bI~ix9z6bD(!L7z_1Hb*!^(QpQ{R=3%hb z(o}%to1+&hv4rFIJu=I~@v%7>F4c)fsf-Q(16ZaSdVeKm^Qa< z0vQAyK}|%(>}dG3ALiWJ9p$$epP+`$R65Z|DH51I=QsT5VxOveN(ak(CO2lYZ3C%` zB6rQ(I0K3mYzk=R?(;U8RTPvwjE;Un?sAox3|uwOL8}fVsb-jgJlKJ*0pNc5-715; zAdT;lWNt{R2xeh z-Bis1sC&3%>G#deLIP*;i_bC${}WN*OCgOWy+Tv{eATybaFt$*cvh!Ailtj2Z&`)1 z9YD=1kIeVX&Wo{`204~~>owRk>Frn1V#iibQ;uN4E9qSJlUGNXJxb%`t5DUgyr}uV z7zX~0Pm2LOJ`gSV9Mr;^fBJ&Hx@t}qgH4GX^A#$?N^Pyt)5#$YO+bNZgEy>~N7i?D zO?));sa)$1>s_&Lrf~2*Xw|{VYE#q%*POZ6L?UovM9`zta&^k?x|=W}89{HL+s3-o z(TiVX(@#{e1l*Guf&LgW$<(eNYwZ7*4fRQI(y}4Iv#9Yk40D7|@~jP7b`$vYP1uCY znof;BFy9GK{2-nwEqRY}!?HTxqOvIrHJgCqOX$~jE-8saVTv{#sIMDKogdPvYy95K zOeW4rxk#VVU_4EUg?GkqPyHj^AL6 z4-URkVNK@n(!OkF2E}kLLTB`ey|VXkLsbCTle*^dmyt^gPRtygUNV-SKMUP|&P1CF z<_=f}#TgY7b%_wGIgT(jXHwNp`mUfQH>f0SGSj)6p9RrpgM~&2cT<)MY&MCJL||94 za~$rD<}EFoPZ*aL+5&1v=w>e2<-V?bol8v=^Ldc(*1HhrcMU#qxB_=ik;u{g!W?%; zPV2A|EiI+cEswKS^3@e}K~g8`tkx1vT-ComQkmDZVMJRtk#JMpS;RdqqLJ68c6w`< z0_+gV9WbA6LCQHgE##>4My*I8yx|3qi>{rXrX$?Grrx9;#&ek!ay(K9nh zTO%;D3smtv+$07M<~rw44CIO|D=a=nO(&%~GwR%=AG{(|*RjTA6*nns$K@#!&ALEE zUuT_LYH9O;PYv0_+TxZO9xn1)?2$88S@1T$hrkpmcN{(E)nTHOS4Juz8Jvc7v^#;> z_z{RMK=SKl5Fn7Z@L}}Uc{0l2JyKzV4U7!MDIVVmkC^xr#G;?OkoM#DT(xz6bKjv* z@~7kXP@J{>L}S;;LnINP4V6bAU(B&iYBiN_+j4Agp8LU^G0iD-*)Ou60HKge^>3${ z>;@8pi7wGP$~B8iX7C1OfSnvl8@xwX z^&P1NVyrCf`uN`KEZ%GrzUFOJ7{Lnwkwa`KwRAS6KO|rsSyt#-_;{3Hs%+bLN?X15 zPCq0uGOiGwZ+k6WGtgLQnUy4}Rq8G8Of+0y>j8EW4-vm(Z=DQmSejftJP9OFV#zC^ z@{4EM-#*{&mD%}p%92#OSb@v6(C|aiGC9a)GF%Lmazgr4$9p3te<2zovfdXVjK`@v z-t=w7KTSp34QS(#7O2Lwk*{kj@7KPML&8EOB|U*x%*DwO3WOuJ)8To+C$$njgiG;! zBcswY>CKBQ(4Q5_3U!>8G1pudz}mZ#ALkkNed9`YcQX@KZ4~Gb9;06tygczzcKwyi zsLXCPmdtcp{Oa8cTSij~WEp4_ z(>c8^9hvh91pfP!ZC!4TUjeCdu0ukO8BW z$Eo0@J4J*mT&9N4Bv@9*2r_`QTR8x!H~ENZr*5UB=c&is!6mdq&&yvf>b`%gFXB#R zh|vco|F=sKRpcb(GOTD6y8`byEhlTBK#O2hkIy5aq$oWmmgjMfr-p%?pCD%sHjjw3B@FX2TxOflpJY5njrjBc6__-E@PEg+GyBB1`kgY}Qi52s5bvCCY#o1$ zvc64DMnL)VGc=;AyI0oQ9t{=8P`TL;2KSJibNEV;`Axm})5nWEXl;wN_Rg!YYh;2Q z+~<85*Qq6kz-Hoi#Gj;Sy1(fl13L^$Uj}Szc_G)nKYdm6G2}iFBCE|GmC1HPfLxc2 z>)nRK!fjl`Lwv8v%fhm zUxw@vr1A))tds9(eu*gj7sugqtK%!5P$LGyqaEJwwjKL+V+Tv4J##-F0W3%* z(uoQop&D&Ba4A`Gk`w&~*nXutBk!rN;{LB_UmPP+%Wgw4I_*D-A4nkE$ec@{n|-{q zg)5hu+~Vu7FbZg~m<1HqisTZDKMJJ&)L{RE;yPb8@QdC$S3L(hjMHoKnEDMb#b?mX zc}H(WxkV`jJytCzyXLDi(JDt&wL+Jb1Lw5#@cwqYZE%LC!|FejGvz~ye{68gBgiHb zE)ZHIbAP;!E}!9o!SeoDyRSE{aY=P<1a>Djz_50b3*5g0O^%cE;B29Bv)LOe(2Uxb z+I2W7sO5jf7J-Lapj-zaz`VRJ1X0B^2=o!wN{ciXbo`gerzrMd&!KC>hS7V2rM}w^ zv^YIOX9doIB9}sqp_?2 zS(5vfa6;04UNfAWzztNQh6)7s@7>(eCCFyr_tsA>9)N(IZe%B5$2Y~Z4rNzEiWmOT zDy+lZx32b-zp8xBpg+w{ZRJ$y&#Cn-fAnW*l;1x#DMM*#dp33@X6W^a0BhJPDgx>A z^}ZnW(i)I#-{M)p9*^-T9uqViAVK3`0ZQop^vA2|+10Omat%u_#yHo1`=1QvJZE!jn~5 zs*dN}xmT~IW`FLT7#Uyc+TvZY0&A}V#58*oGZyVuW#Q);^M2dI-u?U86AyK7AsHl` zh`_Vw4fyjC7&K@3HU6{LrcHB^KCP)ZXPc4ywj}m+H8O4YA#6KhM{@(S2E*(Cmbh(q zF+*hFY&%pHitX4BT!FrpXoiXqItbBA+$K29Pb7F%CHxq48(0x%U*;tVEHb45Ar}&h z+#iSjvJv>%ts+)zFJmAf-W_7P5VQrdfYYoUTnz}`sM?|%(0jsvY zJ6=g7)>7m+W_ntWfq3ZTdB*b zHliCVCV~RDPoEhFyiGdML$P8b`eu5^f|Kb7{MIZq>t;s3FFZ017ZM!V zm<0CtT#?LuCz*KI!LP-1FOCl)5xhf`-&!l>=4h8>l*2`QmC^ zs-*=CX$|!xzrjX9L8r+q(rs%hGAFeY%0k3~8D8*FR`^+>x*)n&5$~^mwyn&_S_ztB zDoohIQz^c;%^J_j$@um(hzmjKh?vkW;N#G27?7zLti`ZdG&4lcYFmsB8Li2O2%5pj zh(#PnZR$E5nF9Uksl-hv8U!b2Um&W9uF~r9tk^4~7WKMB-A+#xBdFEcb1lZ(lAH=0 zzS7^UduAi#V)T9>9KbmEf3mV}&NjK+82j}!{iMgOPllcUrSio0d1)rvhSH>kbF4Xd!9ywHXMa|5%;o~8a z6kYP|{7z{$X*JX2t4%zv_)Nn7Tppa_ACN)XYxO4dd;>*g^YSxfQ%>#;&TwDtK$gC~&xT{F! zSM{MMmwWdT1TDZ2<|W&j7^^@U`gsH0VWP`1A{8-~I!fA?Umc4B-K+3hyjs{>{N=+r zR|Q1~9i$^jZ_*+38j27)(joK`dT-wNo$s47bI+VvbMCsc z*5nWNUOOxjcCvr_ectyeO#D(Rap97>tfiS~D{{7X`iLMUrccWWJXol6`N5jvibl3+ zQ*H4lN}kN16f>U|Pj?HentC-P5>>Qix?eyN{;JkSg z{O&E*5TI|oZ|r35(~F%+xxMUY$r+2>gIx2S_1YQsjqme!%xccCnmaroAFP~CG&N>7 z_Aq?O0m)Ml#`A}@V~MhD_#Ym^7GM5YVrIq{EvzjhvQ5Ij%efYrS?50tIs}3Xgxy-R z!;^yVulZYKa9YKl<K?GUDO0FUxNZ!>@_zJ$0@#8*lx|q zZ2&*{JsL^aMy&c0TO7~C`*2@$)h9KTM7UOHn!AZfU~)eepU&sa#X8MxL3_*|6CiH| zsxRxxZN)gaA}t{l5^0YwUMV=h&FhTK98R_!cPLb4;Hfo*O(!(?yi-v1;anBbf~K^6 z?SS!-u#|nwq7rbSnZvEEEiZ64tJ~~psyUO zWydfsndYVDk8RQY1wODSnRBkKTT5g!P{?O$S$3b{?|IZmzmF9f z6gjsNM%z}vva=)vZwR{3Y`(3|w3lq4e#~iegGG$GGuh+(*B$m>=@JK~)TPlG($e&&be^pig)E4Q#Wrw8nH#?-^Jt^Plf87p=3^T*= z$wYE`J+Ui!V?E0ZSPnRUX&bJdztS`;tIovm_(8KDr-#Vmdy0!c-Y&jn;kEK?bAamE z2W;8(#2bhw{~6?_cwIv7ua5+SoB!Y*rHrNhje7)=Qiwpy|5u59LCGTAD;PJU^c#8Z zUcao>i}X36lhAABm)Bpf-Zn$_h;PI`V=4>JlRe)Z0SBZp?V#t2t!cMG{YTv!JrsRR zX=TMe;`i(62YyC`uBDSB=%X6L!b-ny4pfh1Rhy|+;9pz(0;t$*dK!3A0w=F9hN8|JK3%7k0K{{CtwLGpxFheBz&ly^@@fh0eL>^<=4kwdk>F z1mo^&46EvDGQ17EJIfdWeOi^pn9g%oU{~H#|Ck07o@oDkk@|gtL4xMX5NC4&2GH4; z`HS)(2$DJt;p*_9TMp~g>3R89pNN?qdMZkZ_OuJ@kP;9*gVkQfG2w#XoR-9}w*JJ3 ze{TMPd-d;#R|3_;LSG&7YeoBHISvddAiA8qx5g+gx@r#`J(l7&m)dh2&V6-JQgjQ6 zS4F~BO^v?*gtdd{>M?1>M>Mo?@oetN@GhZm0Nk0PId%s$7;&ZD`F;cOxn>O$6GJgA z$bXDqQbk7jjo@=(ZkSd?{@N^^b4Og?k?q8o?fYK(W7AAQba=AZ`!BrtFCnZ~rMuXF7KNe#u{PBmUj&i>e?zP-q9)>5n$ z;43?QMbjU?u#7rQ@EiAAELHTg?6Pb&$I#COt49jVl1>SDYeDTqbg(u>&{^4j=^7ns z$J;}~1Z3v>WA|!aYRrPm;FS&absMZ4Hi4hH=kZRD7N5`C3gBKkj5)J=wO3NqKIl^U zoTMdt*$d|X33On{QDRY$-eLRkHNxsn@40IlIhodrRrfWQwEZv^P@ld$t=>f4+Q)qZ z^#_x2maLC_Id$#x8y_K>)KeO)Q$%MbVYiBNC(E+Aexg+4h zL3oh`G}_@}hAG(_qqFyGl6HQ8L3c&mIhOpLjR4Dw$dQ}nVf!DBWnZHCe>kD|f`SV2 zDa1YW#1m0P$($NZ%fl$v7H6*+zbB2XHHMo{V;!2F^TP-iZ;t4Itqp4;*#pe(3DA7) z&i-if>P#U4Py|hF*Pb-^)3wW+ZA=m?kCt%(gLO|kc&QP@T`{#iztn*eqENnk@xC`T4_xl7%%{(L5+zDjrRZKbTy~>Ii&^(-|^K>3vGlbOAtPTm}R&<>j9o| z%-CwOY6ahJbH6Vy&QZA@HC(QKAJ^0UN@?AD>vK&_V(sG3rT0TMFTFEvJ?7e-UBFFX z%RoUZK_A{2J zMD2bCG~8FFRGZ5`2El38`3un=E9M$5fqgti7aii`&U`VkkqWP7Tz8oX(CAwSFX zD>CNFnu&M8d)yc{VNXrp>Z%bHb!vtH00003FiRPtI+j1fF}>y6)!iorc+S}{m(IM? zA(^v)J3Y5>?|pom7pUZcGXLH^+(U7)QiAcv3i@$BNOiDJs7ug{GtQ~|`j$t^84%e+ zRuBT=t(%Ri|AI^}>j+-8A;K6a(uW0#z4VbT6;-$?_l&@_&`ZLx-(%693;1HJxcf!XhGd6&UnA`)*I{B2nSpNI%86U;Z^a9PJ|@Z0sRFvJ$B&48pUFS z)I)irs@Q$AV(^dPCz{6i)o{XT``xRH=39 zWDZD=#*>{r}a?v{Xq}vE?CocxFnM+pi!ec9FgYXS7&)@ieI6JE3~g~ zGdU(KZooes=aLK|Bm|>(+KA?49%sCU^k|dao8Qa-#37b76Y)f?D>gWkXXinr_Xp!7 zun)Gwn|&ZZvNu_k)jYdan%;+F;I%j;u4GK`Ej)hFl$KJ!KEa=BcH!AB!qLj9zsrlG z_p*YMxkz7OJ&|GcTl^EzL<40bN$&3YH)%PAnC{^HGhJq8ZsgIa?gjLUUE;H~Zo;1B z*Ftge=I1lD;v$eMUA%h7VSw0v}GT3oNXAJdxvD9u zMk;^q(-2uedsmnCdj13*WA#`~L{M!FB_rgXi*{lsL1l}87~}^RHke|u)go7Unw=UY z<_%K?qqk9^xqIuA^uhA(%L@cy-tUe^H+5T8+5KbO1)N(@n%SbMZQ(FU5w9zl_@iO_ z{@5WNoa(2QSSf(K)wjsc0TFEXbh->qt?7YqmwwbM_vV2Aa3o7t34kfn$VP!rVd|1;$=DH4p|-5#Gi}g zBsc^S3?`6LLLCg}vOm`tu2_Q@cdaN8bk|@_ZRo>Or$hUKcJ&Rlfzw3h*d|h2CEx5~ zsg|!-&+0|Etp94c{R<);SK5j;`LKafXu^cmx@ObQ>yqZyslvCv%XLDHnmUVSU7P-7 z4TVLfgCbQU1NZW1h6a@Pvbl%;dup{Liu`<3ZlDl?K!qSYoPyAr0^s?#5_QW9Xf#3{ zByLw90;lP%Tlp|kJL}^|LWx~8Zw;no=%QfLYw(T{soj?A__rbyv-8hnJfgM*8+q0% zMMY_#KaBn)e%d}mGcnEwJ0pR-br!BqB+$gRWS_@Yqj5Axb*5O^UPNm~JgB0#nk7Y~ zTawp|T&Nk(l%tP)HOHo0q3)b^BM$ zFsWTkaW_BoK=y=NSr6fM*ET2 z+c_-ior^V(zH%QHu65DXj~EYmaR(5{A;pSjvoFU9QK%lNv=&iNQQ*N$$b}s#_6nJ4 z7T08%TJRr})ZfoO@iV19-Tm&TK}D<;dEXmCXyg15KoIS9--f1o3!aqhQLS&ZYMAX2 zYLJuSy6lxxbIMS8g2^Q^me@^LZtjpG>4kVVag$fy6wz54;M5qXizVyyvWYrj$B;Qj zFC7&8d+W$I1cR`>r4G4|BASMT z{6cJh0g~Thj!WGzxBmk0Vdx`xClBm+qi`|`&GuWGaB97uMYN@hUXya~rIXb=nXZp| z_Nh&5&^*7i*9v!uTHIHr17O;aP_CaVd=Y(~^NM|YH@=^}1`fJx-xLXse_=CnIu#~5 zgx&FQPJ;W%pIH?&6%H@{rQ=e;#q(@d!vR~z5sQV;-o&E}&ug=@ce4jMJ}k7&dN))x-udZDxc?h| zF|a&3C#i%M9-qnfv8U@woyfs^5!dOD4$JM^01*4Cx9Q-Utwupq@8)^JzVq+MuegU} zB(3!Ec&5~d34w*uRp4Cm*p*bwNp=^~@2bfj!6jNtDD8=Ldqv|^*{{UM?`o=9Oe%jn z_;fE-ewO`WYvLE6KX(ARd3Jfcg64GX%?P^8PHE!aDo<*txybEDZdP|6tdTc%4lpyu zMC+PL??q_u6Pc2!d-dgh)__^_8}<*Kr9O_;v*Q4y?~)eW|Sl*Bko$h$#Oyu0~#!jBGzw@upbsPIX% zdoy@M3skiW@R%15867;92P;j~2g`wd znKar&b?d(NcT={ssD?%WzPzp$5)(i0pkK8=u<{h=MWg1W215&SgFPl245<|uop%o2 zs8U0P!mo%fFffmjWo35YkU0IZs9JV`Xvn>^?;R6e^N(`9B4S}cO}Q}=-Lhip%7gj{ z;De)_7{{jC;blj>B)qk;6i>}>Q{}9b>{yw7t!M_UHC6Vq*wPprUGTQ8yZ7dXkfME{ zoU23b8;pk7NmsEdtx)M1-Nf*ZGax9^IP!VpNO{UDZTXiB(TN@Rp~iIgA$`me`FRe7 zPpWl9g<@zo#9N_sN&`t#-wZZs4aY^kpv9fvZ-}P8GF;6`@QL=3y`qa>b2$x24;Qd^ zvd1H&6_GSzmL9#BdLkl4dBChVdd?}OgAf^D2F7HI#_q|#?Ao6laPl_oixbXhhx zgd){}DRj^41y-HrxZc=$9f%aLY%=HDg*`lS0yz>iz_5m5qwSILbD0b&{}Pb16}l zALPWvq}pCzJIPMq;c95Gz2DB4EKrz{Rs5-oj^Ivh_uOaZy>B}vz3sAMA>mSVm3YJU z6HIs1NqXZ0y->&%wU~TmLuEYz2wx^2rbgL|;JWdCI0Vm%Zim>p2WJu-_649SVGj&S z%5IVgoXo0)mm~v|gpK)SwaNC9;&oEoAdB;@s$9dDZ{~~1zT9w!+Xq_)slU6p=+ED* ztE36cG4SDcbU%@H`nXgAmO>4sgHYZf-`})Wb80It4(QM zR$u=eh9bHv@gAEBX;o7g{C;$Q8>uteBPh_|vNEiJ8kN1oO8t4V2k;27<)gO8Y22W@ z=zS+Omw5vhc#tPaku=^UkA$#KA}DQ^yT@ zfjF5p%fYQT-&Djdl8ApGJ)ZK?z~$G&Y>kV_p+Cgx(r z)X-)_N2o2MzF`MOh|^^o-_zh!@Ks3>ZxtkU0IM?jDCUHtopDs&WA)V;3fSv%)?Kz# zzoy<*23>jR+d7a;FVF3R4X4v6q*bh!iJfVG_=~{UB4Ak_){JC9?KI6h%Nlgl&+(O$ zL)^@L2?|(Oa$Y0#;o~ri9+G;yo%r~SGx6;G_?WtA!yn$t?hSJVzHQ~~KP;tzdvJ2n zz%?`Il77WHI^ts;Z%iZNsCb|ak4aTPUR{{xJm6Bt>>$p?US8k9*_@QpWU*(m<y!+3-k8+@sTR3=^jY7g`%TRHHQt(d;r&M$kF&KqH)V%vg=g8Mkf;y;Bw)Y~@!4ioJyc#%a-CM4APuVjgbGNjz+8SbJTyb=b=c|Fi6 z3{MNSs_5WcLb!JL)t6c22#)Ezn|)$5d}h?+bc-P-Ca0*^tN7KRiM{)t-Zz^8Wz*>4 z+|}l2v|~YjJpCqIxMi35euY8k4p)mUp2H3_Ferc&m+n!0gP5A8ZMNW0+}khxinW%n zyKRG=mle{;;070o40F6)Bh#n{=i22Y6JBiZ@F+L;r!c5c%~fu1hIc1TWJXFUNvI$< zI|@-8DNz62sqJ2T71|LtzE+p5g?~ypt~6JiVbKxQ-pnFuR`M<32`d$(AK`z76tqSY zICnu0Mt;s=I+f1D9Xlj){AUlzwq|7G3(9FC-$HTeo?u30Nd}t7+%`9NFr%`uey4vc zedRH=@Dtr%0Gyb8B|^r3$G-W;-QN~oK$=mSol+Xd+-PKdeD06A#s&-_wbAAe4>jom zp|=vTXe(XYkh7y$H8Mlny6|yGT>HTGeLuIC_AY-QLYh|<2vT8>0b2z^q87HgwFuw3 zRWFSB@oM-Y{OY!0N@SLvMcw>gX~=(q$bW(#MK`U2lW>vZ;jpI!bps#(t6hw1${~UP zV{-Yzaf7tTb|)_O#9AfxWOl9|yvMh{Z?rf&b^G*6n6}P?<0?Jsth5A~%o>J{xVT~W z?LCpvE#j1H7@zsj^a08FQHb-L331!Qe<)ol(X;N_2-S#D6$CAccos=o>c8VJ9mGVz zJg)T<=v=*);?7#X$ymBPx+d09FQ*PUR8b!}xS-1e-CPsP7jl8#{f9%gvxVC^6)%S5 zU2F{|a?v zwYPL_IOzFzrxgFcS;mVLivN)r68qA$$mfOMUVr^e1je4j3Yv;5Wm@D%XxOBM%*LA7 zqHEXLjpN^Vc6@=@8>?SYxp*nzTXrSraIPsCOZ>m#7w@#fY=8a*xaB>G6#nd&NLDWT zdR@uvm5!Wcx1*Pq_OEDteYxtUdkbLY1yPqrRV2^VB@kxp=QB+hw@&jp@(Xdgst*_J zK9O@bBzc$F^T!jV7(8TfK6$NfF5LWnQ*uMf*b_teuEZQMrSWS7y`Cw!D+PabWj3K- z*r&O=c5IjvcOc%wK69F8fnY4$kfh$cdE9r&cY5e}JwYpe&i-Cg6~AvWZof9n0!F_y z*j(Vrtr+rc0TDv{;ApSw4J@mE;@&U7^qAB@{f0?SWc#O<4&LbQ?F#YIko=3AY% z(~!4myhxzO8|=2+MeNs?L;sJ{!;O@h;t)QG5HEj6W{-PaIu20qN<|^fG{(Qdw11|0 z=g+AYJ^cvT+R=s;pueoh_KsTf+SR+-=cNia`uiwtnF zkF9UJORsN!_5d#cs=<(CWs8+Y-4|Nzg~Sm#-DooI(ji;~NHBYV9>Ax#E&X0+Ol#}i#58BL;+QMzQyLjdV4kLZ#%V8xWe$rU^3w&AV**ti#b7f5P;x=dvSf$dBnaBKYk}n zQczz?t}7sOGX^JBn#(lVhD&`!AZ<=)Z5vmAv0($VC;TIo{i}sZgmVnE^D~ui9;5pIx(`>O&*Nb zf%RZ|{)z9|Zd={KbuLD)M(7uno@$yPJpbRs#V`rM6ZvAH{B7l*A2=Crs?HqWA0Kmm zrg7A$3p>2#>}H5qmz$PqbxYr18I*c1G=c`$~;T)4Vg~_buz$_1$T!Gp>PV%rIiZ&^ zzDHQmR=tMFrYPjG)dz|>@7H`FV%}~Y1$$Xt+roHZMODp-?X{YgvS?|O{hcKlZ-?N;r@QuwW9AWpR zz*Jt(!WD6QS8>O#edk+9PnXWklC%8jvBXprlks$lZhSr5m=L;_x}P(Bwy7d6Xq!MR zMu+9qgSMo?DrHtCeuB<0tb}v1kRL@|*<~Y~ve+-lo9Z%n;z2~rUZ7UsVO%j^uFH{+ zrCtvcQ&!hZmprWps>00Bt&`gjZ|3!S|;Fmd(d8o3Bd=GB)ZHp%0x?Xi^9<~tHVo__0_ zndlNXRk$n0Ku(s{B=_P(fYy$ap*bllg&Z$jZYi%l*rRM-;p!ej(zMLDV(eOD)6ZB?h;t%3ifoe+?sq!5pY8U7Yy z(U?FgWQ4PhB@QZqDTTgPm7bZUj!MIJ%VamCPMK+(Ie#x(aEd?6$v??rx!s<~Aj!J8 zvMZPMc{=?OdTCAigcZ;y?RH8cjqBfgZ_C|w{jHbq)P%5Cmzz>kkMU)F9sPqqT#mH_ z+Ivr?bqR*F9RpEVlHOUG?HRjxc(^XLFn5OZq1ZHPS1+=c=yzMz&S;la1kbQF()NDkSdf18&Os}fv4eAp43(_13~8d2N~$wI>KE! z;u0GaY;56GBwBJZtdq=cL_TcnIl+csQisMgC@G_bvn+QcC4E0=IOl%5Rma!EJRQ)E zx}_@PIw8P`I%$1+30ii$TCcyzM-}JB1)#T*h?{Ka_@H7WT5syYE5v?~)=dtntAiol zrJwe@mk^9}JixOjCq7XV3KSGS36SD29QAaH7h2O_Yn57=3^OB63Ev>U#c513@l!FH z0b7HY!&YX>qH_{#s4;f&;}I%;EXH@L~tWc8=SAB{RZqDw{tI#Xu-9WZtJ zJv53pP+B@^J(c&}FqKnMr&UN{uD|;Ll)U$FCv9nJ>1NR%@LT`$OxkP;Fz^ARyd+0r z=uR)CIbHMzVCA%z-gIMCcP25i4IHsbiO2Tia0f$)c28z=Mb%fx5!MyjRk`zedFyWJ zaJwu$qi>~ogGoPJMRR`s_@rK2`%L1;4~bkLB6l7q#8F{)Tvy}fnEZGs0|v{t`yMZP zcZQfqTnEk|Ve9_k!@$1GGjRak5D|Rkq3V_i4-_g*C)&ufRalZ-QH^%7zZEw~&f6K` zXy(6=`apCutt1$&`0~Q$aq7Vf^u(T(RHD2m<09K4X*$v6k`D)g0_orZ$w2*`!jV zGNzn6iaOUCMr$qG!LbiUQ`xs9$3Ub z*;(LUUDg^E)+wxC}XEb}5 z6=9pglgg}FV(8UZ!3zM>3ufF}?zwn4j8^0%BsG}mp0HvRXaJ>2*#(752&fi{`8$y9 z(eDFw_B|R^uS0OASqqdu7f{Hk(*i5z;}X2R7D0`W7kgCopO} zff&;a!MXP?W(Dhd^Bv73SIEfT44Z^&-ltUxwKwL8`>BYoR!~dpQL)))%9ZVbskXD! zT0C)`tz?}c$_5;XgJ+yQ0G8nb@)a24u0u3l*MmnckN{~csN8xOEwJv6izpY7om1BY zPjEAR>dcDld#-u6b&3OQ;1;U;4MU1Q9iJAgLYAPPDdRhA{D57UVzjq2P^Wi1p&fg2 zK#c){?ZYm?l?<^db`~8{W|5dqt~=X5%pbPj+IT;uK$ z=Y>he4mFA;OH%;t<8V<|%NsdMnVvQ&=w2@$ISTi%8q}%ch+5`7+XUF!2r{Urlyh+( z)5Ao6ZnI1%cyRmz(zoPx_wYbdZdRDu)?^%BQqFU0ffh=+Z=s>ggsp)RYK)-lq5@$X z*MAN8;y30QRUa0xgc+jB)U}aS65n<1X#v1?KkpR|y>so(X&RN@Qgx;z!q0$)iFev& zsT`wuT}n4iMy~GBb=>9p3yR$R7e=?5(MV#f;ux>OYwj&bny+g*3d2cF^V&j`fBge! zONXMZG%g=auAq((JEQWqV9CuTexXQ7p!DJGAXspYJ;gC2R9v(pju;bc78;qK^L-g1v3chF zdyWfK3B$dErj4~Kr7K+1r`rxc8<97W(j7b@^*>2hBIR%lT@L?^xFl&G<9u634o%p= zN$uf&+M87P-a5T>cw6(2Y#G7xIq^b^S)caPMoG1CjkWehG@Cq@?I1iB1CWK=@jb%& zNb%o!L)!?}#bnJfzLFB*PU}z8gU@zwGEOAg=T7gmDfdCWCEY+PTTWZZYSKTFJmpKG z#f8#e4z&m+-3M$_n0`Gng-0N-tggncvV68RiXHm44YMe7dk&XNlQ;dmOuwC3of}C# zeOoKBjq6Bii|;$&DBMq%w^39jl*t2JHcC|f^9Na>Aj9Hlo#B<_3s0vsj! zaUaXuC(xa>`~u9WFPrQdU)FS-k)MA)7xFwOp7?#r?s6uT9&@|h+!01Sd_bOQb>6v- zTtr;dWE@leUH^y8zQO0bx7DYHtq5q;V-QeSTae++|E7BV zUqBZ)sS{Lh(OH7VzF(T;A3~|{u$`+#u%_^=p}0ieccsOSpqq02SGS2brvkVCthLK} zdLn2g^xc(RILtou?#Ae1#wzDz2TKU4Dj|K=n7KONPpzlSN1y($`rbl+!<~6gecc6_ zQLo52`d<|I|5)<>`y;Nsrp>flUvMzahvpt+PBjpuSp5E2`sLAIX-=5Wl_Tlkk~VRu z#`fsFU%;y-IjkOJ7sb5tN7`75TzO@Jc-4eKq!wOry~qSrh*)x1+L}~1;Zbyu+3zcK zD@|CD(w338cBu<1w0t9_tlACk9W2A}%_bZ@&M%1%>y_Y6GV1yv655WmLX245KQBv-he%^U8U zn0ObpZPB&LD(4DH*geUNZ+FiNzj_fhtZ>=2k5Zy72X0T^0HTU_+lU6y9`k zH`6B^YMnRuc?w=I=UpaTyxib4!cj|X0*HCvHtknWMx1`V;QsxDwjfRKp?M*PU6sJF zoVPnuH|^Wu9B(7Vvjk(dJ=9+qi`f$D2c1kR&6{!t z`P(nR*>S>Yozz|9GoN`(wl$eglhkTAT<9jV!0$u--W`}D_tzV;UjSA=A={GUhg62j zV{=c#ew?+y(r_;GS3L+}yerNh@neqi>W1l5m0y=kDwn8}&h5afMYkH&?W%~qJ+SJE ztZk{ps9FL|VG07cipVk9(z6Fw&_6o{eyhLx1y+OU%Q%1a3ovN(uYSS$?>-<1tms4R+Oafah1>IZ2Q_7mHb$t+$_DQg%QB5s$H1v!?>Bi{`klotO8^ zWqw3ZUJuCOeig9qO3V2~9#qU39EY(AfY6iE`qXvnVwh-- z4PSx`3B{h_LR}8l+M`{P-6WTLW+<6}ua}rwQeuZj3v2G$62D?edfU$YL| zw+vP%;e^I8q@0?Gh4)3gz9p&(FR&|(7nbMc)og5e6XNuo_)VKjc7Fs?Q$oVLa;O{C zrLao4MgrzvIbc>1&8O)>d&!_+@>pTf&Ns^&A=+-`JLUzvXZ+NGI0iec!^o$mWxDSS zC<-a8UPr-JcFN8{*$f4l+nksd-#uS=F3a9>&ACWJ$I-piw7ZuU1F=+!5>v4Ltr^J-7 z#g%(m1+WoDrygd#HA?rzVNk%VzdDgmY9D7E6*Di)UQT2mdznNjc-EE5mrSdwKUAoO z0&K&80!B{5y=XXi6L12$3Dzo?8VT#(!gOgW&uN63?RrVxk4HKGBVm!#BVkh+=1%JmfEA1954mn(EMt75*YF4-v2Y8q75W9ySNt)n_l|N#Np;bT&jVl;cq-qxNM#1H5d@d*8H_Oi0xeP5g> z4>j_Mz~>6#nS`r7)~U-+&A<1=ENR#SSf{F5REW;`df2rC*KyBqh;DOE=X=LdaK?&d zWU=`qd^mhNI9Os1f?QGrN~m5(7o@hne_=FHdq`crYwQD9?&K4*vq?pafC(0W5&Ou?v?=)= zMB7#A(c0VibjH*+HJtjOv11P)KzjBNvrcpu^9Xwt!XWf0<={0s$wwQa5qB*3!^(eb z;L)xs`9C`(8XZ$bbYo9Y8q;u;3Gld2zFFGXRu){I${n8?m!nu;a_&PK?GyYMoV17J=&L1%O?b%2@%otYqXEn+n$3;KI zv^|@PD4aQ!GXCxE_j7mR%n$mm_#@_7LCXhs~+T>27b=>_C@9_N0zg(x(*ni;AR z>@8uVVr9!d<)B1(Y~NcFb~*HH)(pvB>`Rb(P_hF}4j*tLC>Ml*>@=crld+PHm)>_? z&5vIhj(Ps5UopQ>r#p8;YRA)L5YsN zw6SAirlP3;WqX##0B($Uywg(L?wMcLwfwgMmGU~Xqvq|Ov4`>+*v=j3RfWOT^v5QK zf|J*DpA%?}n4gk6ow~8C(|5a!$LBS@lq_MZ{c6j^yHocq#h=L6g08^;eG5=yxot}HAjD=b{XsNzoB-RI{37)6&!sq zJ5QVn6Y-qEP+i zCzD^>ZcDX>EVBO=elA~gw@dXdp0f&$57C!z*86@c*YMmg*x^ZB%p!4+$7T>ovf7_@ z#Ofvi*Glx;RA2PNr>Y$bEJ`zmp?#dPIR$Ka>)78%U%fa>nNYy*A#u2^xWNCOyyU&< zD%$MFy3w-YHxHJKcvv1FPN4G_V)3)@|9oFm zG2g_aO;(35C9*w8OiMUjF~KEM?zOe)5nktaaDE1|EPRM;>naCLQFT>uz`@^d z#I=vq+!=`8E}L%01!^a#tc3L$ovN;`A5o>{e*ELY=zAK^vvh z?+fubp1_5XGhIhz;l9s^eU%;B7%{0+s4|`WXIai^n}?|Kr^+-O+<64xZY~Ne6tm<9 z%peI$%Z2Rsru$5*t|{7BpKYPC_i98@LxTg{N{YW6h0#1w{h@i{4!h2ho%7V)&YX3L zk7w|$9qvF)7_p!)N9%BLiJX%Z4*aFJnQ&%@L`&7TR3+5?Mub5QLL1i|Wy|;Fh3aze ze1qPzF%F2U3iSD?g&0ofP|`Eqep^T-$$g- zPmZgK*jJ26W`>uCG$x05oKtj5MctVNMBZZb$0boBcv4a7&mH8I{QPkYnbN2iQeA)cyhU3!PuRqGg{#q8JeZ_|^-~;DOWv)1HUftOF z*{e@oC979xZ%Cw$Y^q9Gy+;xoyW|Fx>(sthFgT~$&98A6W=Q_DW0an4y%X)3U`Ng= zQ*kcn(7#^f`f#FlxmuoPnDT?s<#va8wM;EuOHa#EKX%Ea;F_sPv7oa(mZIiH($BTo zz`O4zUou9}uGhi9t3d`XDc4#C7!w&fgwqlD%$M{^_r{F4?|R$^@8+4+F6@duoqNis zd2iyJ@_g*v+1LMXOF4G+>;-z$aS89fXKAjK=J@7V{dPW@rI?_|veDppZ^PVV;CmGbus`9JRc zrtHuvrj^Fa9no|hXxfOC77Yg4Y>!HU+)z+?B(M^n`Zl#@%3X?KqBYBs+7U z&L^`(*c-42ZU|q=h^m*-tp@G;a-M5zeI0qjDFGA9X(AK{8RvL5wP_4u{c<9bolxyr z#_W6-&b$Ik>J~Y=u(WNkvi?GP+1;I(y0b@ddJy2uV%o9LR`!t*3*+VjtQxo1*uQ1J z!TprO-lfpY2oq7^oyC@w!i3DD;GCK5cJ_^Z#Kngj-Ugx-8E^^=-fY_pwevq<8c;-u z>psS*VfcLY+5-bNw%coz4fw>A7*gw!E5ixzWB~5=KAIamm16cs+?qb3&&qRPhKK{Y zHLOC&2v7IGsG*h>jcFB{MF$9$3l9;k)5pA9m>d|yEleb*D1MRC3oC!uVlD!}hw#d+ zVi%%3$Wy7}o?TtDrpBR!F5%>kNaEa3MyGr)L+R8#IV$&)u&;ES(`g$KSOFl_Vo0q> zql3|&(-889PFc}}F=5+GZ~in#9aD$HLfS9DSKbPX1SQ21xBXY$JrD=u#xI{1qdsuy z+UAlOtz&x=WRaL1RrIJ8!1Z_IM$;(a6LrNiJ^ObZoP6+e9;IaK&1$G~_;-rY3ai(N z>=;bhOun1l+cawcY*8Y5BC{Lg(q1e)PTd#Dp4Dhqq~}uVy%4m9+nU5=jk#7(O;`2C z6~pBBAC4{sJ+brv1JXZNFityU{BaYlw1uRSd()h3Mr_UmGG)Y5VXw*PHGj^yDbC}z z{-fX%h)|*-RToMs9*>{wf8>3?9N+)VFt`e1cVRvy5WEJ_wfw}+a+)%t zNopd!uiT{x9$7uIh}dt%hKZ9RL98Rev8tp4 z*Gt%`j$~B7tz~NRQb2@Pde%T*t=Q1MHnu<3|^CGpkIrU`FOsj;@M}$4?7tvBCHu}*$$M8ip$*C}& zrVAyP0yKxHCYe-vN6|<>!wzHi10f^7<(r9=(k=4WzCKIM?cFZ4<#n(%dIDl_iRjL( zN(Dgu+xiy}I0S3gy#fU@7YUzh6_>pWvfwEo4SvX%$4x9yq7ERtb5qL>b;bb&u%5IH zL188~-GUW;-)&-7h-{ev50_D16x1c`|3>0W+OxVJj~nczaB#|jE_`@`kXa-WvA!ru zb9B>Uhi_;r6L81tW9d=H!1>&*B7x)C+XMCa^KMl=G7rBWf2eN(zF19xAhAAp)>GBL zYIV!>wsXGN4lxr;O~1gG&@PD+^cjd9R9Tz|Az0YC@9W4{!L?yVT~PFmk6@rHf#}wn zOS-f%lyc1YC?(4M1;YFFsmD0~URjLpsC1IsaX2#&5ql@R3RsZ+z8W|%#}GjKe(D{Z zt&jzk7u#bArBOqty1Ufh(r|^Jd0kjwXCl z_GUZir>J;yrff2(+H~%f)5L+R8h^jK5yhKPboYzRFM~T&FU)vK~;d((~cc z{S@wO7F0_j+(O*~T$J1I^J)CKI+*Qj|FVk+YjtV;j@x4Dd=e(M*2&0+3xxE#`H__+ zSdx^v=n7XQH5FtxgFRVH{Xe|DcUV(zw=If46f6`$r56lGjbIy16-TU5i*B|RmR?4%U^}Op{ zbIdvB7&Dt2QA>D#_agfZq9pIU8ig=g#t_(Rf3n#ymU;%cblG*4-Zr~>9q=gcje`lZ z3TIp)!ehVGAt(fmSJOB+b4PZAb5;=2Me_3NYtx5y}Q;GJ?S4q zknDo)15ld|rt}gsmQsHq<-B)hDQVeqe@st%NN!v2TxP!BWtUYxD3ufjQowzo+ADK? z!XA0INN!9Mq}4C;r`+i*`A?#9S)y{hZaGVCu%G&?$-1gK-e*odH)(=iDUKnIr2j2$ zs@vOqkC$l*ComEf$|-F~s7S7?_{sitHFr?)U?A^;ntsmIdf;MBmJwgPr@I?|QW`MY z*h*mVr)_l3JKs_tB#01-*khhKtS$4@`L5?Hx3=2le>c2Cuix74@T&G(qX+d*B4}Ew z&i`oZaj(cKO+f(-KIpyD*UaxmZLgRTO|l!yp!if^&!hC>Ocoo<2z$XknzM=feA-d0 zo^`(AJNx+;Ni6ClAYaM>aqyH_>ojV>AdZ|vc4YVHcO9?nvi~jH`Ts<<^WQgl{eDMm z$1x5_@hH1sK(B%29{(@Z!0c}D@;huWJ+DZgUGG^rcf)@ir2YGl?SFnpbP_&@a+cl% zPLnM9t`kKs-CN_aBk;}CUnECPOVyA+!67ksnKckJVKQ6Ep9PC}p8M4?CoIj_wktN` zArRX$7v%W&W9{x*65kxIgJGij1-P^CPQqG;-gf;}pvEUOG{-3X%X(L;?7s>nLXS?4@m zHy?_QJ*5=UeKR2Ssph#Toqge&{stZusrnGFM_?mrjLY1#I_Hu#SWBN5ybwM(6~G|7 zj>k?6PdYwMD4x9eaTIa*?!cR95X8(Ox;_35i9_c+j=Nyu8to?J7g7=o^>$ zX9|9pxBRbM-LijjbrWB`)_kSWuB3S5-n$1|rQrhi&9CPSvH0ipwhi zv>Y*a*^K_6oLd)<%ZnpU%4EWuzUQaUI}t8{lTpO=@k3L$X>a+`EKN-tlW9;Li_5i* zE+UpuG_Kwlas(D|Nt8=jTqCaiptUt- zJ}xs420r)bVTEPv7hy$4a_K}FHzxZm+*-yM;pzo2Av2_PCw-x5kHOz`t9(U$msHjl zHg9y|KSUJE3~uT~_Z6d(_y3;xSGlUT$DB0-7+wU8_(`6oRsABl{2Bk(_1{)J|7yGG zGxF$M*X9?=+#U8&u`94=M8aEe`Z1BG`~L3K3u5qe-7v4jh@0R%xfh=Hn+R(X{Qh74 z*FTT{M>yu*Vcgq{UWM}$s(n?IGF%e&ctCIbyG67<%e}bGzT;+(YrC-AvRVH4!Jl?K zsjAN(tREdEG1e$R+JfFs^0SeP?zN3J4>dekm#m4tL}EtWooxKbY4k=yXver;0rU^-Q4Fb9r%3G4c9hM$QL z$E&sv=HE!=FoLadbVwiBIf`P%Mnn5+Gcu$%j!rbckGOf`6x%a0WQ@=A%GF+BRt(jt zEJ@wJ(yVN$WoE@zCxfZ?R5!*;zt^y^eUH0l@01E1kF%FC^Lwrc(u%8vaD@S#>9{^;>WgN|m4XdhJmYqBITt0G;1%HRD_$?2)B zuhiF1dAnRN+6(Sb4Pz6E&5eUSm-+S;nZYNslmW!*w%crxbQh?!>yVefYz39NAfl^w zoRRAR;Vg6Ebm6G@;m$}zS@et^FkR-3;Vu+PtU>?}dAmk)Pa=Wu;W@LC1QxqJ zERdwSGTFii>=SZ=Y;A1@ zBsz;UT*TDQeBb-h0Fn^=UpLnNEN7GfgS-cc!=??-&)sb955vAQGk_Pq+mg#>$2I1N z&Yg|i%7TW$oxJ`UYLQA%oAhbF#U11Qt%lEO6-~vcmNj^uc|b|YxArKwzI$18J_-+o zOJ0$J$NM}vMN}GQ7vfFMmxY43N*D2a*aogKZ~KWS=Ls(djn0bJq0Na`$#I%QKQf|? za+cuJ)!gBm$Xk9xGYllYPC9zFc7=l;k6!;g*S!2~8gl#j_;DyQ+Yanp4vd-kjJh?B zt?x*Ixx7ZvJv8dpjN#-1hu9~P0giTG`MN*0c*imi$FV(>TFCWh(bo_mJFAuLe&y=x ze(%ImNR#vZb!ntmb)GfM;AG_Kgw zd&KEbvMpF05z}4p+_8hZmDD0D|4TT(b*;rLJJ8O2Qup?JaQ39r9 zsH?G4`B_BV9GNv>_mJ($kE!Xwb(bNr(QB>NYnE=!JG5*J0BnmY$_L>6r2tsiU~=f6 z+j$7N0ffa=Xf6%DgeuC2gzp+gbSN3P3bqS*5Dcdw?X{}eZmN_`GGY%70iG3$7bH0& zgMLm7&TqTY=bX_C#B@+_Kl2i=zUpHqC_&c~m?YPNO>xm?T;l(p6ra5>q1n>Q2mhL8 z9YOBpxu?1++G&%$&U2{~^kU9c^1e>_w}4|&73;d01t>m0zb4!4Lpz+>N%AQ6xrMxI zXf24T?=pqU&+GOn&B7cgf#%(vhl<*qn+_jR$ktocuF5|jth;w3H0rB+Q1xXhMM+Kj z`?G90Uq2Lq*;W@pUv9yO<`si$pMu}}y=rHMAUn)%2<2yf6Q3~TP<;;Y$&PfY++1pO z`K*5>C-_m)N81d0ifDjP5osXWmS=>sGOQ?PifkaOu(UtXnKAY3gjF9{h+AB)_d1;x z+O+g6JC2}Zv_qZW5n81b1gT#N_(V;}fwn`>WvR2R52~qW3dr?VPYP+3IT$G_gaK8O zm%;u*OItG9oBNo|&&d^=#sEJjmeC%)RAm+xBMD0V;Wmcl{$)zI284h!AQ@U{Y^?C>s5Dr1LNKRPXfX=iDP^*UpinSP)@dX3H>L z1nmbLO?^f*Bh;BHhK?UPyGBPmXsi%_7hZUzpbwuz#{Pv}k@Fp(d+62|RXJ|f;&?~o zJ~U*ki4oes&w2XFy9?T~JB22}skxl2c=;u<4YV`2&J)=f{3d5`&B zLiKSj2s-x@-4HO4?q*EvMQ*w{A)oVx`iNZ6o`ITB=TokGZq@pQLq{i)mmS~}@-aDrK_dxVIc7kkYDY}9lkx1aQ(V?g7&B!3Cq#qC1V3zx&%A>WcM@e)hmWd zrWKz)B|ZAMc25*fay%0iNz}`P8fhHQe%hT!tvTr#_jQr~PY89`_YXp)p7Ln@esGal zZFlzI>-WLQqG?j|nxWQF=gO@3kZP}54sLP~9PpuK%dN?x4y|R2Nc~~!^VD)*Rq63< zAx*>gw|8DF)0KHKuu$~b-fN~MQXpza;1P(oc?J)@XCpc!tO#KF zB87W5fTeIcgo6MdTC=FvH9hv)&%wI6gZ_sy&h5WQx-AJ!Bdp@ar{4m$`TwwYTaVd) zvv=S9XV|;{ya)crNS@HZ-_!@x51_C<5c(SL4Lsnmy14XP9>L>xHA8Q4F~#%1a-Ofh zT(D{?-D~rh>GX5{$3I!n|ME_1iGMc2eZvNQbIZD?JpPEKmfu)!4SjwJr2Bnm{od#r z^gZCMIs6HE5QMxE=dpBlAt$v`^ZwV?Q{cp6r9;__hGvYuJ9JA-0EAgpGav$)n-0(Z z{FHcWUi60$UKL6rSN+rT#k~Evw{tJf{#?Z_9HD7c%3Hv{raXWo2A}jhHxSUf(@1_{ zeWI0adhhhGYEl8|kaVFO+GHoKJFHV#=*TDCgH%@!e!HN+T<5Bwc6j)b(sJOl&N|R! zLd>fDz!+n=LHE*HYid1*UE9IY*O8LDg06cA8D-1ZanqqOI=#?ceJ3%1(fgc!8@x!c zClnH}hWk2jNio0v7ajGU)Z7&3o+ibnheSO~(xVA~r3d{?qy{9UfuyCrxod6z*2nCI zTXBq@R+pUOYg^HM;woH-ncj((>}cKg>E2hd{%vGdpOT)1`QrY5&%f!t@l>8$YFe7q zb%RN>&SV73?bZMi7+H~yW!#M2DY4bERqBD}ZtApjoVM0ZXaopi8*}ZJhtnZh&|svPf>_1%Ex++NW3iA zga0+o;756FMEculQ;h7a>rw#!K%VzgeZEnYa&~@Ts>k^ik!_Z2@|HCyZR?Sk^3s8ntnWFe{ng0 z6*bU0f2@u-JqeQ)IMUzeKDm_M2;3?1ZL%d6rdmxGt#P_by{CUq@yoPRu=VP^rZ7&q zwZ@clb;E#n&xz`h-v467|9$wX^je(%kBWeu>k;cr?+_UQ>+p5{iuH2%kJ^er-y=E3`*cQs^P+Ez|FjY#ReT+aB$N97BpO=k;I*hT$p6vsL`UW=xD zVUB_DF91uvp4-?=k>3Ycbkrqa1Act??YaOl9- zJdBFn;I?jyGIMHLksxNXKPct)=EoGVn!QKjBcGKg`MqUk0sJ|6zR&6uqM>bAzT;XL zujFGXE`wqwsZDw2(9OS3t+NdRGnUO(PuwIQ`d%mp!)3Y#&NVdCSG_BFqjGFF) zHpwH=*Qh{co?bq;Pwaxp6!CNE!f4cw5mu|o0kUJlu;r`&56Tv_Qz;e zKL(G&p;QOwqHJ3fi}ES0B~V={(kVqeC^SbrjKW`sr(rO*&RJU6#7EV}9mwKH&* z%J&unj#N=NF}l?SPv=kOk$_vvfaV1q=R1cUDG_z)ucvt3vVF|*$gG-S95i&>Z1YjQ zZ{}m|^L2`HoBAeQPxywe>TQn6x<$oIpqBM#L<=*9V{Z>u4vO1+HZa7BE`5c;Z7T+= z49^?3ErLC#IV3Tc*;t!m7Kq7TRGMY|CA%cM( zEXi{1IG)HpI<$c)U4y;X?6LGXaTuW6I-)Qm94n2N+dHa-*NE-bdB0lG^ED}wi&-YY zRo6a1(VZ10I*$pmdhr}%O$BK23veGOT`NTsRe; zjJ-aJitLtZ5scy`p7yjvEhyi_WWJw!AKb8sO z`8LOZQSgCG)(PgOk&FsQOHm4E`X_AdB~G9Gqr#;+xe zJ$K24TPJ3^sm9W(T|>`b$K*-es@#}}6%PlJ&?uQ__@pAez9BgVB|j`IrzFjqr1?7u z_-CWXm!kEOiF!Fh$cBkw65k0zjj7C@tNKE5avW;ytCUnLAK;co#kK`2#_W)^8Pan7 zBC2aMhSjU@?6vml4Zde;ABV)HcVL%1SR*0Lxb!PU0=iwo3D)%DP#%v8q6j-+VbV*_ zXpoWHL=AeebjZ!sEpsTs%oWD2J(>IU%cdEJaJ3u2yci$CHq9O}m@Ha?;RLU`Y?S_# zi${cb-vH)>X7We9ZK&6&0(|<23bgUrYojZ{Vi&&|JGgb^zaGDeHvqxF!N$noSJr1d zO|SKH3xgMNRXo#3u?;JOnf@&*BpaqVRYKr$nU}-0qQlQ|B4#-Sxv?*IHV2=0%});c zh6;6?Y?)-B-hGSpm@vElNXk0lFDgAim>0QsuLrUX5}`KUW;rlrJ6lgBuSm87l01Tg z8x&$q+8;Z|p?Bn&Q-el2c9~=XgR4&1B1+v|Bd#R)QtYHotMgx*+g*)$sdvwQ$&XJS z!=z-B(7|3y3Q{7ZIfMh*vmb8;j%pz9`Z{3D*RQqUP(86jOtph8ni|~i6!aH9+famE$%pKhf^P?juIdF}1ay9x`B?L5tNPGAwtt zJYGx2ZO^Vdy^c8xo+p3Ex4+B*`igpR3`BF{(VTbowdSMCo{Wl;TablOJQ828@FRhQ zj<{k;EC9Dwn~{AbnAqE=j~?kAQT9k8w(cfE1C7%_J|Z9Z5_>26Jiroh!@7D7w{?=5 zuBTO&byDpyj$qx6(zs=w_wC{5fn)sYnyn!|(c5>7qGgP`*g2Gdh~`Tep$OD;y?^HL ze7rQEF`(ceMIXP9o$1u~LSexX0N?7O zCNhn%Tn7{*CZu7x>FwunZj*LBmVS!wdj&%gMNW`9AN<=T-H7xE;N+3}!hx?*YW7xP zZmC{|SMv8|QYc4_*N(2A^mY4Go#ZNw(dV4;bKd0(qVEV%5w2uDafwqKP72}Sg=>bb zC435x;+K1dw9;1mV=F?-vzs)<|B#0@bZ`Fyfc$5;!%6`k-i|8P)^7PDByr1{Gw3GM zwAq>I-^SoU2KH|^LL9u6RU+7u2D=2}!Z$F^q2yVhnB|A!2LCpMrO>s>B#^}}UL<*X z(>t+?oyg)Xh(&iKv4~d=T0va!1f1_uHy?O4q!6QOQ|pA200ikOeICDd!$Wbuj0yW_ zymPjBt<>m*A+z1`Uy6b?h<0F(po^yqF@<0?Wfi2edCQ7E_3mb(POG%T-Pb5FcOeVm ziV&d_>dqF@gf|pZ=HiY@xgHv3rE5r`F>fZPoHrBCf=E(l8KCp;nbxzm*FFsqXlCKM znIY}|^aTC03t80pM1rDch6g%mhWW+^i$sV`=iJD@ODR~?1Xt9ykw`|@%E~*%+x4nC ze$u=ml2!DbeOIe@RwkyCUpJX?66RTcK+waa1lXN(yYoFe{Zu7<)EM8cJjDs8RgO^q zbem|Dl@9OIw_dA#uvL;i`io@3ZYPyq4&diFG-fyJ$I-LJ-8s-=&#nr>5cQRM$5uRx z_Rz%wYc=7T8m~wlrJQiDWGV**pQ0PFd;Bv}dnV~ayQpgVJ55vPPtT!-El~!JkEM(F z)8vlHdx|&OW{Vf`Lddh(Ge9_xsdfiG-ziQX$HH79c*=Au-$(u+;6Xs+Qul>%Mp=a7 zYPT-A_}J}Yc2h}V1QznheauLPd9`GFpb6b{nhAUH{eJGGrHV^i=a)JB&CzPo=+ldc zBaM^vFtE^pI9O~_;-VeyVfqHSX@30jq%rrX^3*vvAg*=S>PFD?-Mh`+ax4xxn`y^Q z1;nDRItJN$+;pPSlyI7vgKE+eIA5BL`u~qatn7ZtwUs&UBmoNjss0`D@V|2~{%bFS z^3A{8mww^Ty4A292j;=UzRK%IXwh?$UC?$3r+>iC3S>^`cz)0c+nfl>-k zLF+LO$@_vVG&JQEpI>1GlHPkK-p;HDHV`By%9Z{hfDv~kjyDeO5p!+2f9GIM1GdYT z38qAgZPYn9GvjFev&7CdS;ikT>rF7i>%;C1y;M(!x!v zeQLzPzU25L+X`JwYs6jMPX7jrQpchpSmt!@!0AM_%RrNZAKa=Fc{TiG!G(_Ym)OVnKG)MiF5!_0eN#c?4&NAQy^IsHM+gQC2PThv$q(+nc- zAw4`Gt|`T?FI>XVJyUafjb9t0`OKzTKFuo?-wZ1@EsCEPJx(V-U@>C(V%Zg+lRR$! zQmTmVv*RFc`q(ywAt2U;zGvmM@n{_+ay}|)d7?HuEJ10mbuG7SU}^&GU6kn=A@3hM z%DdO#6kvTV0vE8+wh*Fi@4dRBN@zC^i`N={{gmTY4b;NoxDA#v4?9oeK>+I$A*aQ< zaY%mk@uT6f{Ub}d&9v2|7g&qfq0y_sjPoM3&D0W?_W0>zcs&lxcOq0HCKCku${sPh zH-1Qt)e;@<-TL&Pdgn^AqfgDT=kan$hkEy;SR&8I79QREE+Z+#<%J!O67<*;0iOe$ z{M>BySv_&atLN12fKjr+M;8v7;AFX+!Tb5aIEq0HEzk>gdU}Novz^V${3(gC% zy&)j8$gyPQJC@&3)#yDHr2{!PRy{7-@`7_;*n?Ome-Jt8lrPn!DTQU>4^9oEA=(E= z4ov!H6)Q08_sY`aO-)Y&zMn+fd4?sZysm?Hso&~gQ`ifEfOM0ix4E|)DOZbg_dU%M z(q%`WdVX?$!sP$2GZ|M}`DMR2ET$rCQ=K~z75|+0|A(bUNdclURHWO3oL+pE(Bvopgl zhs$>>cT`iHT*9wqlpi+Z5qyz9qSfq$tKbO1+~k#g>8 z1EYCCnB_z`%nQsdd%F95*p$aQDTDrc)xl+2J<{s8PM)-ibFW?vPdOfhwL1b*zv7u| zXYPVY;a)cjsyxMbnd&x9lfGprYn#7QVh$GD;BRIPf-CrR$vADA_E)b< zUdeP!izr$+dC-hM3SL3GG;>!k>k8<{;cu)#8yQE#`*luEf5c6am$7cN)8Uu<)l88I zG1Zk`e19>poBe$}UQ z23j6SZq8ATURo~qF?K}p%&L8CeU`isPhJsRdG_I3y^kVGx;lF^++A5iUBr&$QwF^> zQL1t7326z52>z%TMqPlUaF6vlmUaSwhhi__A)mg9WC*n!=&+6nZj*TZ1^uvs9K~C* zrT7KhNp6S-R)v>qR}zV8Gyq%7P0J#F&Ez&;60x z2CgUi28ZoVQ9+DUE;Cff^h+i+NGgd80j)Z!7b%p+p0oUy6`5}kZCe*y$oUs)F{W9t zL_fP#&!KpPe_UZy#q;v2lv|wdYjC6=H^@JA=uZxJC=^H5M~?3rMk;lHW?%LgoB?rh zh(2KZW(x*JD?LWKmlHKO`BLA?clYNY&MeX}s_lsC+P9zEj+u!=(viY+D1O!vQ9&vy zz+6&LXtm+gC0koQXO`_aAn#|#+eLg)1#w^D3{m6P;We9h;`>Ou>7|G3@4qSUyjiVQFckl5~+?)sazV5o#zop!A&KoTFm+d8b>ix-{ZW z?NM#__kwKux(@dbnQr)vR}OrV1&;VZ;WWLa3}%cZ6xPy=q#B3`>I@^DjcZEqgV%KD z*{|AtX;L!2oQ))>qQWlg)l4kqy~&FKy_>kqzW@kM@g>9#);QNo7r6A1;ai$zPxrn{ zJ<5L;cXQjU1VZlSlmt@<^pW91t?6w52+G9xL19Iqrv-(54eJ&IC)<2PHWW1m zE}no(5;R%;d$vwjmy$FO%zCkPqc~1i?(#0YfH<);?MOOJ#`L4Bb?t(#QSgIM(nO;U zAT?iPpzqw?a(ywmOQWQf8JNN%Od^ErZBQBj+eo~CEKu-=YJpflDx@e|ROZqPMZ!2(FO0-@-;hqrJhp=&4g z4Vnuq7XcFo2e-uIRk~Lh7UJ^5Kybtxf?u#?#w(|IpXKVwJKmGb;LlEz@VdTPeAIF&( zh43Z5A>{}FTWo)8C0%0h)@puX&+P+8;I?fuI5|T0FBea|vC!g}U5B1?tFd;AhPr^x z@r$^K)+AFndo2IdYzQ}+&Xd8DWWFs7OI~X#=<0;Mzcy8Gz+@PP2<-1#B#bx;qGwtE)3arsH+iulxVG*aXO&ZqzH6~j= zw>>lm%Z(`p^hZyYBMOfq|4hjc*2=K*)#Nn8g$a;AT%=q`I1&&-@?t?K!8(FwX1qz# zOMr`506B`@HJ;_aGa|ATxn?#hbXF#rCX(daM#Zp+oh)talQgvc@YtR9AXTgPy+RN6 zme03|i6y;8qYbxS(XG@z_?u3H-mxmVEr2VV02^V+&eHmQJo=8a&x4RQxJ38Zxeupp zb2BrtnmkRU#ji;D5u@_IG%kZ1k-THYf)OHb$vpY+s0L04iM&oW|l z#csykI{K52xXt@gde7)!&m!_2_WO;iMLmucXN7$5yF%kkl|MF6RgYltbAdpeoZD5B z?eYj<7XK`Ul7WMvLw#wN7ci9fYP`+qv4wR6%R71{PNGDv)@xeJyYI-hZMAU+?3Nu& zUlx1_OxEQccjw#dz1Us?!3)B@eCpq~nBhA_jq;mwH(EQn-_Fe{+Tl_=e5Am9*7z^a zq*XM@B?B+<)}+9Hktpb1U)zv&G5<@4b{b16DJi!bua<8u*=uf*iJV#9(mSrnK~T{~ zKFoc)$((ik<#Yf?G&@|5)3d}USKFps73#XBNJS)%k}t3e$7dk99`1Z=?v^}+FO0P;OxR|^AM|5-}m$tX_#~q4{~j7H^I?c8rFhfJo+_nrEH3)x$$~vD`fFuMFcrYdr9ls(Y!QPP3T9nI zcDF!l28N#=(kt^CL7StH5f`<0_C0G(vbRmPK$5vhB><8!x(X+7JC!6y-xI>;iCJSz z-f`jmFEwP`jWR5Po&q5E{Fn2uc-G4FmJf_P&9I-+bbmUo1`PN9IA)Rkc+=?BKllhY zHD&`k<9?B}WD#BmDg7TJLE=X%e8dJdsx|Ue&voe1V)+)X_&9m2I{gq6bPrHSaal$Lf9y&}cKc zIsf*c`Q36noD=wN?mXzh;F*_1xA@TWa%qpL9jA@h2g8RQUBFb4l2HliqMwwtmhp`~ zs-j0P^;UUJ8Ql7XRS!F`2Z))PZMn=kwTthCvMsE~OWpuq-T8p_^d>A(;zpy4Qpxk% z0H#X6KuoOcSb5rtCWhISoMLxl+o*OKCNSZ4EKrEU?l%d9z?Wb?XToTMgY2c2BPlDV zy|w&DFfe;(M0!>c`+d{u_*u>U0OK|O6YJgT>izU1lRVMhy}X;K080w#Qo}sMn`fC= z{_;%50`Nr0H{573x5_D)^WwsIXT_dckE_VhxKHEYAWk4=xsR@HJxBKX{u#!n`$Bx= zFnG%Oo7K`CN-+_ijL<^DC95eDj0~HMWPwo3?x$?lXO}P21Z5@W=8w`$uNpp}@TV4n zx{!{)m|ro~?Z?$S33L;Dg8THlHg&_pH(f_^E2edr31XKjwxm_?6249`DKv|k!>20c zs2_BV%y=gmHXbBuV_as&;Kt#(dRIz))3@DocJ%{vHnGACp86r@KbvWyHKpN?f0uy<9gao_ll-29(X$A57rHza8me-qb`g$Q)!!0Dk3 z;VjjR#Hbkdi)027KhySiIKfnREFHNYQf7EQBc5EPZ2E9xJqH+0-c7dtjxyt)H`Ke9 z3W4DduyfPD8^?*3zK!T)e84WTbR=*9hku?edOX|ANw6x06`jxS`3k)KMe^lBn|rL& zzy66_q0~$N$`RS0<^;?2eba`B7<}<=^l9c^wisc)n)ke9im>kEUzA ztV#)H5+pHltlDZwG#5+-9K*i%6SJetqe-7K+PQemazB~W08)27!K@fJCY+|xjDLaH zomUF|V48TUyKw0XH*1g(ni;O?TEbftVap#q%R>&j4-*K7A(Ph#5rxENV^n>EjA=LV zdOzO~$DX}O#>ze&>x&>Z-M9PcVvuLQNX8GDA?Ky4`1EfwZtBE^>9n{Z;^-Gi$qcg# zI$TqQJo5Jk`WJT&WKMp2w^=UqX4~2vRpm}fe@0A}+a&rP{#hp7Wi`fX>zRq_0PB$uf^N1VuH9_9M~_3rU1RAm346tQ)w zM1qpz?fj%JdhyI1e^MzaY_!BT6L}U~aVvoa-B-?4t2tG>24WS{nH5G4macI zqelb{;eb=Q#h*iDCCa+kb|3=&>k;?H8wS=Pae+VQnO)|nlvqDYdg?Dd1v>!(Yow$W zb3+cr@w+@ekKNjzt1RO`)L$b!YAbs4E*7$ul*H^>=qUMV}U<{H)v&oXVE z3v!W62@DDo6K>%&(`>DqrgtW%_i$l3IZ22ZcG+E;WkL9{@%!@|&N34cyzK7fy>rAA zdyA)3sV?tvz@M-n=zGyD_%qjfFO{tG?@J2aiHkn^mmNau^|qMchM|tmuAvRU?B&<~uQZA4YdYBC6UF}f~mijpHv7}>; zG$w&+8o$)Vzqq#)5%-|!=oFEc1vfj?p5O2=VtO-kZ(5FVlTAC+8ZX3IewYeDDb5v6 z7sQ1LQPcoPgql5@p&LID(IQjEKXMuk0C~?^=A&^l$S|c=22Lv0)S1xQV%F)cif@jV zyfV2Y4hlNK9UU)bri0KQakIT|YR1UbI;|ld_t$q#Yvh}`Lui`csl&W|Hj~-8JXE5a zan2HaYm2BP^2c*5-;*>OdD5xhckYgn(@K4B#uGgx(!&`wwX`&m2jnk|e*R=4SWbIx z&Ed*rw~R}c(GeSCCNf6H7rjHFUw)<+OaqG|?$(e{TLA=qtTt#ZZ6+iP6Ah*lZoo~9 z`Eu8pnNveVA8F(#j_xeAc4s|2ZcQ>AhqTzTUsg3oc~ak}y3?K`^5ChXjOjtDVC3U6iH7+O6>(RxX z*P~gG;Jaid!q~Q~Y!4?1km46DR~usME#vD!sjR3lFDkB}ikL3%rHuu&xV6(?j78CO z^-V%;nB|==!smnsh8wHzkE|ruzWTVzKjC=WN1qPLVVKVAN+G7p4>cM!C{(^=l}P6X zQ1t=4{8)6m(IdM?2oGNsqL)LwF#^yoEpJ>S|M{ebCer_|jM$Q=L)@XQ6=i6|hhDB$ zHwFAV$+_>*099Vn*1Zr43o3Ak6OhJj-8amPHlfB@bg6KrWiMz+N3{sBU0xdaa$sRg zVE`-PNrRN0Rx($Cqk>$Wxd|fo3||aT-=@tPgf(FI;-0S zo4&LQ7Uq>YkLIcp*RVHd5d&p^w-()&dT-SNVcjpgxF>fr@}*+}%f?|B;Z9Q=*~>o< zx}d*SZ=CkoQDYV^YCm%DVm+;EWNAlVuW}{3D>TdDb>8&1FcMV`oP1F#MM?LQ9<13| z!dY>_pg@duJBUsklbjUqnYVf`rBfn^~=XRz^E=r>#Ka1TBKHQkp} zxxco~v_Yp7*ne~>9)G$e$wKJ1j7?oL%8{{ew64=XEdxkn9(E`>Cu8;NYm^Y+)a9SB z$_Z6@w?$Yvh-~c#NNA#gYNqm}oZ(M;tSFi~O+RsFy%`mS} zXVkig%BQt-t8;$u@vLr_eY{C#^f9|tRyB{7}A~#yS%gKYGT>}8ueM-jjd>9Hs)>nhA5=El%a4)a`lpx(}k1wG(ijUWIU)| zvF^3e7#+~7-qlrZvr9S^CHnzVI&#}Zie3}hmf#fi@GiL*$sA}}lF!`RHU5m@qVIKK z<>RR6P>UEwMtkE0>weD@`sw-Q)_7<7nRy(NIFO;Abv+SyuhcSqOp$WpT89AWsE%n~ zol#fSyd6RnR-Hg$f!ESo-;WC}>7G~Oq;^3MU$X5)QuxFKZ8{M|JPshrF&EA6|{D zu5SVpDQ{$9&cj=XD&_}mt3@;uTLYtX%5uESh{>T8+z#&uZ^-wKeGy9O%+>qOrf$~n zQFTV0iZ$dVY}-ZC%V<8(R|b_X?#HYVt#5oFZ+er z)&k(<&ZJDB$lIR$D~%7f$UjHF?AM>cu)70oKa`fLz`5@$v&4#QoNGb;?xF}tB2lPGe8^KW2u`r9SG;m( zw@l|_GTjPzCQJggxL-{FqZO|912~2{Ao%K`Qd8Hy^xo2>9IG*#6GL~bZf>DF8o>+4 zMS>+tqaCde?O$~AW4H&Y{6%>;B7a&q0DB=IgP(&Kl0%4wPu=NCr@da6uyOl48Pd(T z1Xb0(Er@57$Y*9wrg(OZ}bN*}xQxQpM{&80$-x8@a zi(yyVNwe_|m;&r0o5_u>ozoPN7#Lz555=bJ%{WJ)X-RHKH4dcREmlTEg+?s*Ut+mB z4foUg46Rt^BvV@^0-1`f4n{23hnE`3RU=odicHlnp(1_|2&D`<9`yGPp=0Z z5)GZn2Vn=#Z7;5FBY6i}7n*KdJU;(L!oGB|F_u}pPQ)}02|Hrol-lMFP9fMZj z2MoW_GyrPu(&r?0j<(*rmgIOK*8{ByC6gfc_wnc2cRAQItz=Kd9aFs~k{(di3ps~P z2>;2dk!FI#_=?@i5P6Ncy%qF@^_EUaX(lMQo++ zbFUHtUiyE-oedF@z=W~W#33hDaS@dbNdK1C=}TOC@mcB0{4u%TuH`vn`<=(P-Aacv z6*xW#1y=~9$LsReos-kkf%JL=lcJ`}R{q5C|5tRnAp5&2VnSnciO2sh^|^jS68CN+ zcD9XhB1hjJ(MjiuS^km0h5Es2Oth%`+hC2TSyxc?aMsxQbXHHcL*hnj9?!IoSuS%J z2Ri)=S?@pbhTPcqLX}zvtfmSF6qgmu2yR)t9Eb>U{xsOY7QY@Z6VMK+^;TIVHtOR) z?z_|sO&!MFu(NP*%+HM`t3{G}&b?jjpdUC$oUTF0O71u*h2$k4CB3Y~rF zTxrZ%#>QLxUx?GQGhq-rNe7{4mq5$oOKcqajkOsL8|p?49A6D3u)+${tc{1U|1w+kUAUBQ%R{q zaWETe^QF6&=Xmn`52Qs##NcB??%ZY zRAv9;bP$l3U0ohe$FJEIu42!hm62=7`6dZ4q1KUBSUN{`0Z;ng#^<>f^6cJG|<0g)C~ z6`b0rdw6UK@a=ryJOWuA!N$8}R7OA+MYUOLy>CtZEx7s=D4UMG9Iu<*RRNWqZy z$JrAg={}cByG4?_;B+6(B1RSHOgW--81j;l*%lW}L4s`CV+@mk6FI{XQLbfPG3DVM zen1{O8)XGTY2VQ8WPA@B+rm(!B0tOZ-WW!VE=x{5Qv10y+hqs0O^Ze#c*Z%*M?Fl~ zM@9_I!x66`56#HUg_>S=3N07w<*XNLJA&AP$|uP$Z{`AT7w055PpRIK`=lsJUj_>) zf6F2$lw!7fZ6blum+r2yv~pOO4Zed3EqK?06xF~v`+lVHwzl@pO;gnuc47Vx@z;R4 zArx?F0=;2tnn-@H!ZsC@b%}Vgb~BusRYd{$DOL;QM%3JK2WdU zRZWKLxwIZ|c%b$@jgZHS^VWF3gqhyL&3RPq{jvK1JnN@2GDsiUi-n+7ClZ%OrletQ zv;&CnmKh|E?_&r*C37DiCF{~XV}EA#2$~LgxJKBL7R2wliA?qlFzdFYEUiOS_vpm> zTC#!-YS|}{MD#3e@a4X{9Sl0UZ8co={JEk!#k=^7OLYu}ZGm1cTP6Y0Gup%2E~*c( zMg-DHYN~zSB``NfLGXQ?v*!l)UHIP0jRbBgMpVr_YW4VpYkK>@^5|T_MxofzP-s%Ju;1x zisibEU)IdJUh}f$*RAmRpv6|N!@aGi#~wl*d~?ThRCn>#948uL)z9K$h5&W?^A!9H z7;{ech-d+o;>tV8Wq`^k<*2tca?NOA^-IgDx9A^srF*|PZum;ZXdqz#jS8dwoK$A$ z^SEQ`JNDI!>X%*lYU>6H`b#W|mrzMcmYky|%;ax=kre7A6Pv|Pxz`x~?)mB z0~_i(&b}-w$0Pn4T80}JRMMdGEkwvMr1h?5zF~6OzVT#gLZ7g40P-~fVL5kuE-{xRn|_W z8#SlR6gEKXoGrgA*R3MgGWp3b%7DuHY(EZB6v8mmd96x-3#DO(t(I{ts%mXWm7*LQM{56!9X_YY-w ziqa3q8F%53jKr6CbC$r(m7xmrq7NbN^)gUZ__%K`;|Ce$zJ@1>>FH|j_n;q~zldJh zDTba4a~19O}1pZ zwWBTy4Dnjcf(3)#5sBN=4@E=a&U6C8QA`Os;4*fF0t)p3*@@|bkQ>(0S}UV#_4PKB zD5{m`EuL-mt%^{JDOaaXeBMW4wa$(TE+!L-L3Z4z`R6Te3!O}iMO@5Zoblu=L!6_l zUNsOBypj}UL`JZ(uUE?1qv?wr<~`hrP4z6Uh~U^3U*bjEVtwCdw?wHr6-B8V!OZhi zCBSfdO-fH7`=YxL9EDR55@Go?+sVq>+P})@V$l0O%Qf)T>n6&%lAegFmNQ`;wDB_Q zQewO8LM6xyPvs4fZ8@Vy-`Yt@F;ERzYHA^uu%vqnD0DRK81Fzx1UqY4u+!uFOK}R+ zXQpPagJjMbFv2_VVh`f!^6Z?@B_7s_OSaQVWy9r;QaR4{BUMPOhe>CctIaf0tVkzE zz-Ic8-|CtLiHYZ$+q(|wmMO8b3zWcD>3W}xti`~1ZI*ZL!OX&L2>+&n3>P;kh(>== zw&^-eOS!O=UFtGNWOauP>VD@9X;B3U2)#WTo#+*It&cd@>hJ*rUZSYuGgT_~u%i3n zIFjZG?sj>WtjhNhU6mqrT3R4l0KgqhgD?7-pQ}116O^hFlqbr=`jeUqC8?g+Dm38e z?rgH)YLJVWG3U8T8mo}*FGZQuiF<|VQa;QjQS2pqRS@El$jjA-w@JVhG&(5|Wl1mN zwAq!5ZR*+wW4Z{*$l18^Qwj#O%&1sxrV=t-dM+br%U4BvNkvL-4;9SYfGj`~rdt=Z?{#r+EIT4U zqO5511QBbuv9nIg?jZ*c^SQNlrpdTTI2F%lQ`jSQ!Xo_9a7-+CZq4nrFIb2hfr@Sm z#1@rb)Y}^~B#sUY#M|GuZ3_`J6?zl-aWY3JFUVRT%%+oW{0Z&1jaI?<2OR|+PCHr+ zv%ZNP!k06J5Jo1vqy}<1k+1CLpmcH*6E2sT{RtbTSn+{0I9$w^G-)`e67guO4!@MZ zRq2V?pYNz=7q5huiZkM`wayw|x3z{=Qg%4+=6j`Y55OJfCRew{vQyNXOFEOapVF|= zPDjl(8BAd|H(2H;7dfX7dAA{($Z*egjco$o&nX4kX4Q@X;<9+tVHHk_0jm_zq4ZA{ z?4ye^6vBPwJbyQavjcvQZoeqBx__m1k0&YMsVU>X)^33-w2ZY4bxZ0%Bt0h;z(I~p)A0vP!GV}k3qkwB*iPu}&ry3u#U3c;Hvy zs(O6Ei>|4ZQ6#(47rX)y@mJyFxB7+p>^n8%lvyi(JnqNtuatrMvp?d$UP!Lx%v$b* zHVyH1`tKLb{`uK|cZQI#Ag`VczkRAl>eiIbrLaWstx%sqBO7k3Rod=)D9ws{ z0jk9)2I^(5FjJ;~dOLo$nl^sK6YczS-V@4p9o)kj4G;F}#6y<(zF8bH_ip8%lV!UD zgtnnS-Ihq=2o8Bj-1oCr{2r8bu49j%?%B@{lFpdwKH474BnmR^Yvatzzv5goabqbv zIV~&Yb7~ZUBk$#yX%iEgc7}8Ai)f=!sIal~sCB@*kw-&K$vqV6hJZenj;YbcS7u|z ziy=i_53Ly>`wUPAN26<}zukew?(Mk}jk}JsMW5b%sn5*IF_6S_zd1+*^95pah;2~= zuJOj{umglg0WWGuzIT5kWBy3j(M!!WzgD7H#70si665()Y0HxXLDo-~y*j>_mXh2j z*gD@$?zpQFoiJ7~(@C;fzDA_V3d!gWvYFdfcN%+fmro)kwOdf@S@RBB_c^XKPjX{y z*<|C)=JZZ}$f7`vmFA8oa&iprs=yvMyKijnJ9g^A*k>4`0q=wRIa8T{9D+9*N)yy& zo*8Bsi6~!%DEmk-lHRaFgq)*ZKSTIJHqZcRWN2-B=F@1=XpY@%Ynz+4=C;$F#e+Yb zO+FVa5!)l*#+$C(*w$6>%*d^+zjgG$r~2m{{L}q8y6q>mFNVeT@TInc#kIS|wm)W^ z(1=Z*=j#EO$DF^aisry1kPOggKIM02@~?l1BaFwhVrt#ICd5mAH`*Pv#J=A9X&m?a znRi4M`#tmbtLtFLPmZ_Q%zv{e<`%Izma$vmX%SbSlIZW58@7jpIaEz}qp=M$SY#&` zV!1?R$W-@vvt0mb=_dM2!o8> zT|YRyo!BN~(I2G|C*0Mxw}BU9XTU(%QLX0MW*xJIUHr6>=226y%Ba*l3t#={l$aXA z0aI`H|K=0^X)wcwqS8v-J1yKDU3zHQ1G9}&Fw3g=%Bhh>Lo-UPHH*XTOGC6a+A9KY zq<3BWQU_%Z$v2_Yx3zyI#;3fLi0)OF&j$ixvS2!`AI7?)S~$lnyi)_eK!_to5*rgM z2OjAJQd1A^66tiXft+)xgv)IvUvXll)#)Y7bm_K2SA`(9B+VqW6 zfF*g!3+{kBnH$Zcvk5(1lZgWK2h$X+)vDJ;myH&kGb)!JKc@jiAbx3NGo4OfZ zzMA06OVqC+y?_l0A8##4YF)_?)s1%CIzVJG7|}Aw^U6z1M)C&V=H?{9FebWl54+e+ zl;m)(-i_kEFubEdZ4`v-mAyLe&D8y1z#5{54PAG!!*@A!6OJwmA&sqctyt8vy!(ms zQE%`Bc+Z=Gft|T!oyBeECGcr5YbwNUg!29CnNHKi;RcsI|26pb2l!xb-jG#hX1Ih6 zN!zPc2(AM81tg7A-GH)>k&_qqamq5WyfnGgs&-!svmB2ro~xR6%7>E)?V_$u%^*UgbjRN7lHnI=B+)kvOE-P|0}qo>XtU!r+GRb7x`~L|@Q`N5DjD z*(2(~yQyyLucpL>56{pGen2lLCUyXU&-bjZDh7ntNh+*Ho?PRM-B>b9QWn+ExQFGq zS*^=_Vcbr9!taEF>@`gE*GBNtN@q!UE;Wi)`9B7!@4=T z2V}&q#H~Tplerl(BL&kV1H-1RG@eroBVhI4Y#!g%lxCJ~3Ae zv?`J|h=LoJnt@mBPY%w~RMXrR7;Lh?Q6%zD=%c5ZLB~HYex$uMNi&Z zY)#hp@Ko2Wp53Lmg6X^Cu>G+ z8SOUmtemWz?Bd_mTR0T>;o(M)pooi3ycv((B|JJlSzMwhrU(kEGN44=%Id&mzsI{B zDe$Hp&WUu)VTIjno&<2vkik^zS1)LFbLNjlooX-Er4W~7v<21 zgl({}SFu(Yz)D1>l5z~Z&C^31%A0iTXyMKsgh@VQS|6ZMOQ+Ga>^W7Xd`)5+)dENO zfvdIB=up6edg+pqwx6Y=0g$cbt~lA#Cv4&1<=OVbmLu4W)~7$N>v`O$RbLT59Mv7* zB%o!zEJ189KML-;FghkI#EA@8!!8w+smqIc(SNnAE`&Su;rH@g(2w&6yM?YQzTCpL z`{}TZ`18~0+?!WxHBrD)5!vD>xx__1!R}Q9(u+&)ORNJ_%W|$rca1TSm~$q2WZZ!u z>JR*+$EmN|y1^B|kafZ`h*r@owqc0{gA#j&^3!Oo)Y+3GG3tj`qQIcdq4u zYl^_k%P^OH4=YILATIY!9(i}6Ys}5}?X*wXZpI71S08SiBqbGxu(qvbSoZDF$<6iXRqo9|%K=-LTux+E}d7(UGg%Sj<}(vAo*bD1xZpjQUDbS5ft@ zS@hZ5WMX4*Va4;WBPJHwit6BybGW1{oT%cRb$YIFSxg1(y5b}DCXJZ8A8ukU0|nX{ z2;X%^fCprt-MzGy>W?{NOEX+yQkV5eq6A{+2SIbbNKqS?+t*iBD%baW^J*yRBuuae zZb=68>{QGLC4*v3Zlkp+fl{1{iW^(-=~XkW`OYs3^95 za|D@aE3eeokGdwjsU)yb1;M+jMJjL!tf;4ucL;ajew$&a7_LNV<9}PEyGp7b=Z*A< zu7=8b7--`+q-3sJmEJBd>2!zbD0LWo z-pG7m@FcB?AHJC;Ocs+5Bv}s;s9xB1_E5d3@w}}U z>5P=T0p+>y5b`t8$r7p1(5{oNJ&q zP7#g&Y;+#=943zRxTs4cTrre0K=ejoi>GsOJzw{u|oSW`c6)ygJYPK+N`ql zvQ^Mt+O9!aPZ?!S_`T5iI-oMN)dEnKYgALp+Hj*%&?II~xO_4dLsvga9wBQU-#smO zefkRb>z=#1SEX{m=&%Rs1T1Hm8KI4e{HT$t%7?k#xvD)}pdJItAG2u#emZ!~Xu zK3>~worCGdp@oZDN2@AzWv)GHGd2eURq?9zkk(`?Y6*}l%#+8|;M|%>ocjA%NH98RAb$fN_2s-_;YDf;&3G$R1=?)q=eVXYDBeC-iNqhNzvFk80ljsE&C6eBG>|zuhg55$aI{F zavU$OrzBq*x~q*T7i{szRMcJ}@%zJ|@LkfFE9cE+2ONCF;ZKbaLS^4jpNX>OjSW2{ z%F&nc1ZXD-n%2y$hu1yo#4Y+tFUm`#FD@4mpup|xTHQD>#NYK|`B+?8ME`-Dhc1DZ zx?3tiO0Qsq^eASMeEU8nW?S&Hefi`VSb#&T)rh{`L-FIbj(^0?r`X-3U8=kiKu^ZV z*w@W`Xi*6Ae7#qen^0qUlBd(j8$HB^-rq=|Jf_&L1wv2bys}>pkE^y*!R4jw?G?`o z?%D!3yo+x1Fji8H`VM-b6WmSht1=p^d2U@vWGFVzIH5~Oni)fm76@|O5+mBCLqs%2 zjEx`TB2~;ic+>l2EmDnVM0g%TP*$K>_v{uc+<4C(#C8IU3L(2%m@9Q^e-mmyT2uNW znqo3(3c<&bP~oP0)mQkO?{RdACYsEed@^A-@b!ZwA$^F|&k#OZh3OJodav4nzC>6 zsq~SQaLWzmRgGzyv$2#53)qY|AHyEiHSsus?w=+7dg`8{AkvOnuz$DF)gx%kIg)p? zol-R1Cx0;N;~wvKPzU#dc(KKOw7g+T#)r6Y6dv`?To}mkM(%?LH!k~dU3!X!7Rzny zTRLz-HtjQq6(=;7THPwf=!E8|j=>%;3*E`A_PIr0FQFHc7(#HJ^F*|v;6RZo`iZuK ztN9$68<3OblYl{eKLP@Ys|+U7{X8I1Cbp5ZaA*5xkAQc>t0!Rd`qqChj>%H^+KPMO zgPj5dd`fyk;6~s4c~OX8arp)w)0LsyOX*-a!G_runzs&~98A_wcCo#PEDU;bEcMGD z1oj`d*s+a_Xf}g9pdu%8EPLyp!=3+h=AW%cmba&8B3};v*y&(Jat_N3zGQMp8aphX z*D3J;!}6Hf=PLslzX~z7j1r{mKt^CJcCF>U`>V2xC%#)PP-F?L z?>K=EaXYt!N?kNM6^>Q*s*fGbJ*zGDU~7skUveFfp(WfjN8c4IthwqFen)cW7kVY2XktP-{{m837aTdNgcM$G6qN z@Wn=Na(ar)tily+7jEeSx$SyH4tpY>(l0-NO1bkf&U)k^`d9~cTn~r_W}7%9^Z&l*Su-gP2+c| zq3u4}Yzz5#;PUHXua9*_cXyy$^ar&?`Tf-?mDvs2DY;XU6U8Ve0}w;;WYu$bL67O< zvmP^#F0DM^(tnn^(o=CV*|1n&?nZV!@#m!J`gc~PWE5NS2{64s&VOZZP}{sLp%M}wNulTveYuJ2Y-4+SRi;` z$kqu;ADp#vAC*BXTG?F;lh#?eDZLzITUEBHY}z1uyW6nY6Q07#fS-d)4 zB#SN%-_Q!2%Se+T7uzr02tTn_ z;)#5jZ&_BId_m*KiK(J)5u$G#(1j#P<~x@RdwKF1Dwinf17ayO*f@$W@|7!@pxxc} z#zZT>M8G#R@}kYKX2TM(cw3GaY^GPWW6mFblj=4fR**VU{8+cVjY;x%BvkI#PLu7I zx*eMAC>$fAURmT#TY*uMEqg2(H+&9$r7>ltt8GkyLd8Jz83ORRj4!eG(9>wLhbDWH zDzLYK4)|3BY$~w5?C}*}s$#T^`oHxoB&3Lpu}7pCkezM93{rd0WH%nv0JOR03FtZ5 zhh8(ohu3@YA%3)X#c3WOy(amrU(cCvfgyg0&d&g5mWgN8aPe}8!8Q|vrql3B@J5D9`xk6 zrr5W+>h|#n!KK$fOkHDvDy~=_NIt!MAbBE{yMD6fNduoxUwq>;V zP%b~^$Te*?mY45yoo&v!NS&?mT`2sS35u5DOzcJP@vA_34AL%{<52MOSUZp`Bgc-o z;D<|_;BE<;4f)Ihw_;rKXvqAYI^{dKvk4?D4@kOQM^4FYIr4-AG{1OO>K1z&{c?U1 z(E0e#My-ls^>Ko|dg&V$tOHPUMb7X#5a8HG@15ldtmjhQF>~kF1@d2!BoDKQn{@Ng zRCI_qL-D59Ro1p#^mptBPEITh=IxQo8|vRdwQ;#S0Qp8Dm-&LO*wHT`FVHF4RYR~X z!ZWqg+t?7+O+W{YK2f$Abc(*_w%8PzVn4PVkBP&;aWiwXTVDJu@AJhtQujY-<-%Tc zEycD}(P@$hEydu9>fX3fH%YzXe;rq)U|Vlmlhv(|R)Q=13`6#paQ@QkTK1CaOoq z{qy{tog`VU#gLbgA?8UnvvCM6ZMX|&YhzV4qD%k%Xr<|DF$ z>q|&2u!23(;mmmb%OgP@Kpb}*+;vx#v$0g6wkFKzQE46m(uze6JMU~>^vq3iN$T=i zwBw1BVZDNod?r}zba}NsA}F=!SoP@W+}j-xO0m-;<5ia2-J^irvP|AHMfe1(d_%h;4U(3R+6r(bl#Kl@_k7uW2}1}xC<+MZF`_5^gUkW(IDB+SS5v5?BZGoZA*mcgY=lE)i^b05D_ zoBbWMCAW*K7yteLh?Q`VpApLVIt+k9(}LN5b*2kTP_A-P_g3^ z;9-TR(l-yn%f5j{kmJQQ{nCL!zdM1(mSH3wK`^{?(feF`x`y-LtL=tzw2~3l(PuN8bdn#no`NI4C zx);o-^=QKaQ_14#E~Hu~HtvK%{h+3@F5y?BAX+i!MUJX6Q_bEk(>$>#Y+kwh2z#@c zV6lzAeJY#KI%hla`Yr(GaA4lbncEwhTgWT#+%nb zwuP}E$fnJy?V;OOwCV-zALM&CX_4g_lIjp_MZm#^hu*HLihmDiUemQCD|z|L%SLgg zB=39N$jYXJt}bQs7tCRlfbrHA9FzjGSq3^R(In#k)L^V~xq&PR5P+w2bF6tPN1kG~ z(ra@I`ZTFh@7%oFu(x~cWDp4RrkWDsMzc7(-i0f%?U{#kIY7C9aA$s_fD5J;k>tI_ zd}^7g26X~R-vHP#U-1H1mbw~So( z%bWH(q>&Z-J=!rwc5(d){ATlPQCW!hG8mt5!p@sGa}6y|y=)6v{Vnbuiz%PNFJ68a zZKjU2!?}*l8)9}EBImgs09*LyM&T;Y>z0)cPfrBgTjEtH>taLKCl{AgqG}}^(qd)Z zVw)6DknP|JJa3WDd?`QyxDW%Ko`GTronBCiI>-B~IXnK~%7KS6D?G~w*D!W9aehFJ ztdp?Keoe7@9(rbIS6t=+KiOzfkAReEiR8rmN~E04iUkSb+U>PZ9)z z;nTi8eIwdy+YVbiAz9gxkBK;|rYEoAMBt86UqicYeWPo^` z?x`<6P&ob>kIlmcBc~;rpm^wqhC)q8s!oB|i+T4YC;BU)d@=+!YomH}jg|+uA>#tD zyqT!4ryc#+uD7cmL?gV;#;spGAK1-(G_?g?!yapPxd#1V=Ks0niyn*CoukdE_2WK> z>5>(pJqRoE0{I@4CL;h7on83Ke{K=NrAszZd{3z9ldjbR)w~~esI^rUw4g$6S5_m+ zQ4EDNd|0|E*aO)8@Iw`wj=j$3>$JI}zhSg&Tcp zp$v@snv=#=yGrqgL+6a42F^iPKbITm>b%)K6|q^x9w2Q5AHUk?*$fZq_?Fuz68yGx zq+1keKjHP;o}Lz`_<_J5SO77=7;GL#w`V?{(6$q4AUs_}yIVv5a(r>5|B@~oG9Boz zDz~^X8~jIT&G{QqBemMq@<;l&$X;yCExL{zUE%n8o~7%*aBGRLDrawNr+x>$Qub2& zb`1lRIMSf@nk+iG|NGQYMmD>d>@hvFWCHcl4W;O4| zz7N^wUq<`iHw72{OpR!l#k|i!#F?G=?29zThGmY;yNsHDxtI06XZ}60S7a!npyQRJ zL}IUw@ssgg9pgw8D>3odm8#yo>b zE%uUP=#5_@PX3J8|Ln|PFH8z}Rh0_}rH5X%<(Lw$zXiK}E5dZLGF2B`uZEb zQ6#YFdmOk-8OiD`#?pqjFHi4x8PW~dyR*=5GB1e74t;K~8IXTuc!g4ps)~TiC-?8d zW$^t?#4;}eQf7(T_c?$s^NG)=_HKmvB=bNBNhw>uCGH{<)vcYeZU`TA>f#^RLu8zN zEQ_i2mfw4G?(zJG6I)mAJ=>Gqc@fFK3zz$c1M!(v+5Am-zb=yMSk8ng5q>N^RQpQ& zSo5iN=%q^(bVTel(f^Ssuv0HK;TNH%x^WP$JZMsuuSrdIe0-?s?)^!;QEe6tA~^1h z(vLW>B(LcAW6yTwwO>@h?$M>%l=dIEr5aZ zH0F)p(kUZjfb5DsHV?TL?Xe4_mF1`({ndB+>Oby0o%s>&baMQh=&uxK;gXN@%zAkY zn8)4(eSbHD;xB7XGA(p1`KR8XB37_RWAsWV27&wEK`93ak%oVO#9uumOrVZtzJq|*bKG}w`<)DaqlSOy zha5J(!Q{1ODn_2%BmE0Q`KL`@T*kYBghJCp3#Odwt{3tm%FAw4&t<-)ztfg>7uww^ z%!WagK)lTzSVm-Lhmo#srQOMxzMe1fjt zSSvV+r>9q5*iXeT@e7=C6Xdh?%g|4ozRF`IZyJ^?qkLS=RHWFsW(f`T>vocE5!;?2 zq=@H4xxw&~>>kz7I=H1L@?UUWF57B=RG4$Ht}mr)udc&bOMmf=|F0}9w4YjBIL@_R zlV%V2rK|sWbCO%I8O@AxcdJ-y#CM3vO#5;>SBVn@YTg&al0zCLQk`<=FHi*gEnn z8Gm1>2p(I!u=Oo>wkSoLZWW+T+CotN1LUn0^(pUxvlG$8`M4?Yj+-jJRw@pRqN?BgA=>& zAixf;1Vqr(UzIt3{@=f0egbQNZ+A%L38FO3C~V0pxQ0mGsN^Zl3#Pe5PC|Y8W7!MZ zgjTJvWnX%OS8qOVFNmVmK&_+^sm;p2=CMdG>n>&?ihijtnQq7K(iFf@UZY7r%H49uor*Hc>X*@ z6f$PF!;5O=@|}A|xXgLn{9y6Mv7cDQdD=(xUr@U@@jm{@>0H2JBwNGx-&q8XG4mbjffI=I8+Lk^iQac9~ zwKk`MM|bt`*&?c;tm_TdET7A0r3}x7Xx*9|y>JvrFGQBzegMlj?DTy$MD`t2#jqFB zl_W%#d3p~0hUo>bmbN9&dRvFOL17tJG_u?Ows3?q2JznFpNjBbPKuMvQohGlG@gqX zbm?eYNtBWYTq>tp-`_UYrzd$CCuhaL?A*I$8_u@hK>}WfUKkJU#L2(&9{e~UyznW2 zGJ&;+i;w@EJsh-^X_2VJn$GQ%oA*scGMuD=;{o#qtNXHOKJWJE)xG$MTJ>3H1NKX+ zbebsGTG~v*VV-D_FH2^mRrY4+|G`%J$3vgQ8P#j} zmFbnqQ`9E9JpL8A=aOP>G?sEovE6RB*ia5xi=D^l3aoG>%qk@z@Vb0C#e0Pxly}ll zL(R|Y!uD)Y`_d2ns z>wk^1{~Z!JjWh!rf|@2YtIi7x^}TZ!ocGm~rBT0{Vq#4o6!!v+7Je>wJ3Rr-_V#ZR zeqNN00iW=Hn?LHR# z3JWBj=Sfjaz-I|;#YksgfThOdl4n~9&zp`VhLX0fjnT7nUy3g;+?2B}5_Z|02eQTO zfBNiU(aV=@#qWM4fRYnaSvTHXyjbxk*75Vi-W2r(MxgT1JBtX%o}CXZ2C;(iX9svk zWmJ)HwK2`?9XHrWwUq6jN%g-xW7C-(J}T5Qg5a;!|0@|mAN)(J0MAdHFibq(+-%X3 zg4*mZUYZBq%o>bNsNGF+u5*inR9%ZTNouY_fNSe0X3}kIRkst#-MeM?boiqWv|;&G<7viQ@u7B+Ts(DZlM;p`< z&gzI-&b9RH=~T|NFG8;$I@#3@ZNZb$;OX12r~oSZzJiVBF7Wcz5c|=K3kQ50s*8E_ zx!*zK(;2;6l{8Pk$tW7tik6xT)$BChVan~`#<}%wSt#~ti2j3CMoY% z{iJyP#k9Z>XzPXVpng?WugMKl>{N8mLCrfi-CgL?@Zr>-l#+iqao%2qQ}sSBZ2ZkR z_@I7AyXA?@?URCL?$>{y8~Lu_GfnHnunx8*H4QKs!=Q>CD$BGpE@W2U=HSb9Rju0< zHKCjhH5#^$=3tj_?0f!VPu91M>;`K6>*K3F*g1GzOAs4BY4?@FGc~=LuFq~EM|>`k z8INe>c6yRm$OS)cs=s-ueg!ZASzcOf;jxUF#hZeJdU*RB*l>3Z)ln6{GZWvqF3J$4 z6+gHxJ5si*MH*BrMde6#1l-WjH0m8-p_T8bcjOK7 zcegH;tbWr@#Wo>SdtSY>7t2{HV1L9NLMIf(hvU!`%?VHG+GDb{&G1~3*-f*de`DP{ zQ{|{#Lxr}VDjzqNM%0A?2%6E5b>f?QId=&ilcq!iF zJlC-Ftxuld$P^peLr)L^GjjG)I z3VWZs==9RS4$R)W(f8C_Gz%`AA0hNf0rnQIv_22%@D|#a~*01NE0SP35dnm)sb}|RQeYw^M|}SFGwvn zlW*X!3T&4;lNq3 zK_&AH&eH4(AnO~o^}^NTSc~4(GI{K>WZc1{?;zti9yf)Lj{X9bQg9 z2@@O2-InrDMV5|~+Ad2b{pcY>S?SdbBwUsQJmafVsq}_zz z%ITN;7X7j!9lW!}4w=c&ojYc!#g>az;RF%B{@+3O#fDNAc1NZrcbEvbyieNYV>8Mc zkz$#5#L~!iOpDTM4&6pYzfPQl0v$c;)$+rzGt;jtB!&FA^R(-^vQOw`1t24`~)jn;Z^E=4q$Ls1!j^d0CgM02@9SQWFJP8*3 zn6NNA z2ES$rPoT-gDW457>&`9%m_=j@Cqdb|T=ts!u{5l^-XvOij>7W#9eQEOPXh=&d(vr$L1&gKqaqJlyj62A9*oq-}CdXp$sLb8GG9sruXdO z<65L**{ATZ+gYtVey8*uB%QR}n@7vLJ5sr{!}J4O3ZESY9wA`mUp+I^UYhKV(bxHIh?}R% z@w+t@8-!`!cPfUw~T=cjM9=r2!Ox>RJJz(7cL^3tnF;d26S6I;19qwyh6 zf+(TzsDji1P<6Uw%V=`nxcci{zxsy06u<|G0IS;d?ELVmvXzx9_ zaP3P(Lj1FRrnvQ1;)NfK1wYV)Vs|0jYPtih;;{KgF|x>tIg4=?|C_0yS7U*BPnKSgGFq@us2DqwsS{+!)KzewWYPX-(u zmBBX&b!M%w1N7uh(5)KhiHa?3-?vE-_N&pehuO!KxbL8sry~d8)SD%=Se{U(Eoq;Y z*(A0P(D><`UoIp1IFpw7ld3+oK3>R^up9s|q)_?CU8nH!0I162os!on(qu8qiy+v4 z13k}TU@w5FfAqn#_^wy`8jWK`UBleMc^iSL3B?nQ!sUXl_S$}tkyIIE5*BYiAoUBt zI5v8odP&nSe;fXlZSa}-T2tTwo&UJj3kAB~Er)LZhFtMIkR8{x*~DJKNc(z6G{6tOYb#W)T%2*kF7 za6(552NdRT=TPNcvOUpVY%cAz%lz2u;IQ^wS)mmjEX?hw8N<3nEeCZ$Vz4kUTpB_& zcxVx}Nu3~|`uxygXP?RM;U1KD=?n=2`>1`a9cV?Eb5^}`d4SyuW3;c5<5`*0b526m zIAG$QJCx$vwr0%as)9?tSbF9A&6>+%Q0B|O37sDtU~5}ypwDAx0RhnXkJ+;MiBErU z4gjBiP&-gFePTeE6AeG4;e8U@@4N)t|J}S0)$kNLaAlz>||J4GHM;*=L(;z zc{@jH7JgwC$kL_!!S@2+K{$X%0a)T7WX(??W+%@?BovrONO(+*kQb`1vT~~c?g_yH zgq-lq)jXsup>tXC@*E&edb4PG8%LbVizgO-NC~qQK@$vORFRE|>{NpAnbo+tjoKfC z`yK#mYmDRkGFR4Z4zK)nCr8?ysRR|s7JzOndVw04CR97jq+&s2 zfRw5vsleQ}+T?i+S>?w=9aBd&7g}Og27Z@=nSG?OZjP9fuYU-MDPa2XM8BTWgzZlj z!f#n-fR_FpShT!N^5xoUJ=iq8x>Lb;N)${Z!QGLaNrRvGuo~K7Hq75aY}&C_=GwB^ zY>_2adcnO7EkxoS3-;no9`{l{{;quB)9xO<(>WKQUHewd75G~%0ph9~C zv)M{HLIb_GB_F+13hJ23d`6w`gL)9gp~MeLQQa0!NDy_u=&i`& zs&3pBNA2;8Z=%J2AHiSyg|en|&A8LyH(_0@3L`Q~f|fiV&;R1G|5py4zj$8!^$Mf2 z%E#{O1s$3bnPTSWuC(mIo*G*l=x9uJY4t`$3@R6@a3R4Z7OTRL$2ai{6=fV@~8-7Z}~_wrZaWTEbqSF*krTzls894 z1nSf?S~9|}@jyuGDaUB?PjFC1y7oRg>A7vYT1ScY^P2^r?DoG0_2 z%oojw7$BXM3}4usq3By_8HSe$imhHz2sw>}k#@LUH<73#9lD9kz&c$|36nx{bryeMB`io>SEzjg`KwkBHPWuj` zgxGs#BubTtkN0_ZhO;af3tS^4X~LEecHF?>*2J5w32n}sxLbx^dRTD%Nh`NJ=M87L zC`afn8@kkC?kWLy(49O5TI7`YSD%YyA8Q_gdgknBeXDcOEb8^SPGxIH zX&rM^ubEG*UuB*oCNsk({ZqJQKj*$ZP|&w-?~tNo=fjI8$@Z6-@4YAU(_PLiv%)Hb z>p{NLECR=|Go6Pywf8~}Cg^J7R|Aj5DU9~t7+=|>XL(XF4d8DdBX@e+liUbLiEIqjSSzkU=kD8%)GZ=dIKjR>mv z@{IffIlEzG2I*K7>$>phwT(o2V{4LGZf6K769syb)A|fbU`nVj3>-h;H)rE={vu17 zZ~R;UDRb2|sRr(0pTtyFny+x8XR%ld?>@WBA(_6>F7EHF!sQF^q+Tw<^Cy*!v-Wor zxcT@(Gg9#!I2JP|Aijq1gFWrdoMXWMcCY<(#eJCDJb$CDS0 z3C#Jg8|=iNuEkF!#b0jPqkVnq93T0y7XK%j{<^2X&_Mb&b|KA3qH?fI+*(Dte&c=i zNKq8mjInCj#AkJ&cJsfrQ4m|s^glo8>}hh}rSKy8#lP_XYx91!q~LL`DJ3C2VM_T6 zp_T^9`oj%h9`Od1=%(3{M)=Q_;^nB@{Hzwys*6hwEAR4`B#;Jp91Py-OADLJb1oU+ zYPWB@2Nmy9xg6cb_-0Qy2lJK3V)q9f9ad|~j^ZE7F%^^xy@q3~NsVL@`DC|^UExBU zh|OV9!K~}0suVVFCyxY}+fcO=x=N_qD&s{now-oWJ}3$^)+BUoF|OB(pROi&cVlAs zv({ideS?yp&1^;+s%+}(wy=|d(V-5#yxh$~2;#LB21t>>?%ZPCRg(&r%R6$)lQjA2 zC$dV(?M1n)nrAKVzARV?8`nHhV9R{d{?^|ndemk%twYwuFi#%x?ezrgb_$mBXS)3Ab4C^DfN-=2O)INznEkJBk zI&ix3MvvO%Vm?h5Zt>)QPT*z1mGx<6@poB?wd2o=#CODT(e)fo+Rp3sm>@y1Rl8P> z988_q53At;eU-OjT;$!a<&*+>lEoR!n% zP~MHX7ick*7q0l^Rx_cyoXCrbQhS}B91&S2^`jeS*&26#b$j6tv(6)^)yl#M@0|Pe z^z8dEPgO>3%*VQK=E-WW&XJ;g6~7pHIG(71(r zLU@;F=7?BY`N4PW`kbfT8PCcgXG9LB^Ve7f@Y<#rSN$6 zM}ia7@?e2S-TPO2aR||1gjX9!uBZNONLY+qx09sKciudEo%29+w+h$sCqWuCX1SQk zZq($=ul}rZLqgnscZgrF-by^vLTR_^y+eV2R{j1L$NwR5f%9qDA9!^&yWpU>li{I$ z^n)jk?*6TPy~R^D7l5i)Qrx!lqVu|QnN}~7#~O8Bt;EzjR~b2S<~TFG(5p!)U9_}( z9S zNW840<^H;7^A>)?!beag0(>fG_xNjN7{I1s^9i;Q*sws%9=FTt|B#53AS9d$dvoB;@nHyuf6q#cRKu$)fR~$V)%oH*g}haR^!Ec%+k+| zMfl0l_!TUty4|-q1;6u9@?iUdq{AM1;3YBNzpF4$0KTT$&kJDU?>JLe$9)aWcHDXFi_`&W#y-^4<C)mK5w3(Nv4By8 zH!#dYmvNocgCi4u9J)LL*t{+v>SPq;kc%R35QV=mco|oA%UM?B06M}8H?p4=MUw%p zX7Agu9xF7P#!<{aH%R)d_@@L);_E?Mrv<=%mZD9I1YQ%JSdvuy?0tjm=Wp4F=nhJ1 zH0$hQ+IzH^5VnEMWoGNKO7QIHb@uqV@XiwD%mAny#pQ4w#iZc)zh5NRpPK041x2fF zYYe~M<{Q@Xjq5-&GztQ+Z^)|s{V);bxKWsASX5*_<3-AV^X1-G3S-Nw%*@R(zsKv_ zhvd_!i*wfGy{H0&V`v*!Q$tL$;Y@U_b^w=^;N|9G;=6z=t_KnLft7F1`W>dxVWf=4 zOuDkJKB}fJd7+l5p`M$G$=i^}d=3RlG?V5g_8j(A^YcE18JhG8E)I12x#dGX={cgn zf_;Xa6Wl;_&v}hUK)4_zmZhZCIa`_&yMt=BXQpa5r@vsXKu>q5s}Pt zJt$?NwOI6zv}kkj@t@}q#jHWUBTSzNuqNT_POonHEyVAz%%AtpqHt+#3K#3Xm1NXL zK0L}u0(`-xhI|FT5bPTE+IZBNeq6!Q#2M(aUFGTm(ehuQK6WtrDqkAD7rQpKQ6FDg z-iW6_hgh@cpleEx2MkiaP&wf5qJ@UnubreUb8E}Cm5~8FH@G&ffJr{2mn5RL_+3HC zFWT|D$|-sG@C=Emsa13rt`0Tpv!sX;3xYnV)0+)57 zwX6GO?g)V2eh0WWL^PGU7lfv*P`B)DzIa2x=dwpq^o}`&h4EQG?O9BK9C<$^??K*E z3IJ%Y=Q?+HO@k>Ac>*8~9^hd+2WcM zr@PtekFOR}?k`@N))5*1F3i8keER212brdHe6rs~8+J|K04~?949jcw*wv8-B*z zh&rc|isZdkmN#*oTcaRGHkF)~)us-U{iR<8B)w^(4%&s>!G3W49zAoqf3fiRsEK_+3G-PWi^##Q3pyT-=p0FTyH2E+1I6a$q_UXv+qLQy9x#xY4*E2NL zE<^(x*6Z=Gt!uTxa=pbt{>@_B7CMQM_zygp*SSlz;|jKy2nRtb(lD7>5i@OBNmQNi z-4)Ep&`x1JUlDPz(witDw|e5x=b5;dSRXl9*c2ne}{V(BaqNp54KJ{Ox^Fz z{nzy!K+eOf81&Fc{nRgH@xXOAp7TfPvRhigO4GFI<*D%BpxSTbpw}0Gow<DI4J-7|I0WiCVYwf{Q%f!yYlKQixEN`So?+cI5f7oFE_=q#CJ@` za7c{fFMOf;3lAQF987F3Byl*$V_GZ=_~#wGM-W#de%C(#+_f{ zh8<4aK<3ung~Vab>?q)tMd!adHlj--Z)_ZJ7@C?EK+CfznPpK*_!M4f729>lT!^VH!3Dlyl!So z@>FF1fw!5~9r@pqUjLupY@8_cQ=|0)7kGY+Jnyfi(?6@`Qqg;M=9E$C(SAJ})>N*$A~*XI&h7>H=V)d)ZlnmebI6WxOGP<%vSh z69mPqDN`hF!xhM9Sc=h$%Iwnwvm_L($Gh{_szLIEDFc1MPkLe=Zx&$)LV z_o+U3J3DI}j?iyjIlr;o(K<3KX;*mY3fDu0!uX$e1eVd(Z~j=Z}Cl5~BrfDfz-UTw-RwR>swHRG12oU1TBq{VIf=ih~|U zQ!px87<8L=h-UyAUNE^8BOw>DOwXiC@7tjBZz*caO1oY?8?>1j33Jerow3a}N&#t; z5|=9jJ#P1yKJZZnB9CQX_v>%|{Kj^t zqwLG}9<5T}TRLUy+2pJ#wXKDbsKr&{VymyEV?dlq|3_h=|0y-igvnpZoqLR5X@~Dp z&1gQtd<5>KpY`@7F6GDXgU9dxzTt6U6>LKD;G`0l;pZJWyS1r&GZR0N992y%jp9Uk! z?5epQr0F1L8xZZ*p*_b;y!&3vkgq7DY+00$&y}EtwDB@zu+A<@cLt;vMU&jyZS+9m z=IGLfr@ZYmy=J<3jrIJo+tGuyN!2V32P{$QuLP?M#NXGJ@bBF(`obEcKT*768+WF9O(C1)*xKPxc42($<_uYP`-|{5P zx2s%0(#Z%ScZYbe+k{vzkU#Yb+6dhAIU)?iH<|^Amo@o zrq`9k`6%H-khdA?ta)rfyCfL2pSe?g(MMx}swISA?N6@5tTAr>oF!D}yPWKMu~$Oc zn^i?S`e!25HGPj#H|iKxN43wwu42pqaQgOdFOvW&VbKz-Jl=ch&9I|!W$y_k$FV(C zl{G9+%&-6>ZwVj&>O65q=mX9Eq(j- z1W#|JMiG&7mI8r`Xc2A+f{FDTL1acu^!{JdjGe4|^;NyN=o+PdZ#bv#V z1i^i=R3|yfwXz$L}HDVG*r3;vlV7OlnW`}|_)1+#Be zR5v&VEy87iz}o1Uh)2;-JV5fUZ7Bmaf}H~oLRhMx$6R~|!P={g(}IE)RSeD#92dv5 z_h-pMT9Wn`Vspbymv05BTxDSvG%FeD=R3*8Jm&Ae|5S1V!^Z?gIwELv6al1sc~8c&XKiHW%x zpF{GICBV`6^d@Nj$qZo|msD`|0s#+fzVm3q^uYueZ&F$~W*&{i`+pkqC z*Ndf8P2bBBm54x47o&_37av0AtjYK7Zh2orh*u?QzA*1m(whrp@8Qbj#JMb(W(MFl z^X^HBLDeiwAb*o;2w7KtX+_LxuxzG{@$mo+utF^6ajZoQlo zkz?O6`Vs0M@R6#Lsxc!ede)qiBb_(Nu6(r;uE7b0B?yyYTwrY)^>lrkBbqj>^|x0A zeJ9#n_Hj8(%|2|(y-4@2Hl@dDcQi-T$sD@7w~H%9PTp**E1--l-ZbnG4xllPX(4jSZCBEI$H8vchZTbbz`ff$Hc|CPnj!h2bi?M|dgjL8R%HpJpfM z$;>=lzf()cSj=AWr7-y7IBV9x?#>1`VJXXwiF#ZDn}$D41d4)@tRhQy+_TM8UkJcS zmVD7Htq|V!!rjfvBHY z8^;0^|D6~7JTtS6=8)SdFHcPj>$JOQrF}rM*RV^N`mM|3IMDGj(cFa8hK=DBQES}9 z)4%jWA9C9Sx%-`8DW5JA9j~3j(V4;>g@`<#7C;3D!M^63q$LP25wP7Dxg!upbTabVr*k40 zwfhFM;w=>u6swj!xDzA>wu8fV_swvdbe5H7JE#TgAo_OMN)Fzz@u}&}bNwd^)w>!4 zC_O!JB=4SllZpruU!Wv^Ass;HxCM8YR!k7uz73;rXlyZJlX2>Jf)*f(>~(d^HAGFKS{&YWq?UhhqwhKf5 zw5!ID9^!nCleJx21lFdau`ZT$FC&4jg&jH)6Bj+`fl06sD%^cZT+MZutorqH^G5NS zN=$B>OH%u#I))Mdq0j;~o0Tq!1wmEiWuA@WYKU+Hwr$4+;`Q)BnS(PKPC+`c48<90 z@~0b>z$0AUL{(JtIi_%KfYwUa|-J;))K$#Tz4q`UR_+kT506N;a7QP z_J}NO<*{2u+#aR{uUa(c8;@kEKAQbhyb_M7`2%n1%PneE??~?7dv3br(%&qZ{|({@ z-mT0rv8mD?Y5nF9=8E1GPt+@CFAs3l`Z>+yrqG2I5l}(tHl8ajF5biM?|b^+_V)i1 zzeMXt$gW*wijJv6up8Rsls#x^>zq=;sN|AbdLQwVgt2(Si}cHxxK{v$_T~@5{>$Va zPl*c-XJYh@Vejib1VC`B#De8*NBNU|Qj>snUP^S!2Tn z_|*g(7x&oEf_xe^B-&tqGRPE8=ks^2Fk)rr)4$}Khy+tU$0JgXpqFzEWvw2S&kl45#*ckKP&$ZY zF^U2gauL=PvxFPfvfl@vt=tWyxh9NMp+s!YJHybdGWFWap=Sq;I0t zsfoRGlFsb`v;KczoBiJI|=IQ>OD4~p;v^==}sTs9Es)K_hPg8m5Xx;A|gp9G=J40xirG?~X~q|4RyhtGF5M`ZMoyFvE&&1Dq#Mn!r=Vaskt z1$CDsQjc}l!;iF-7{IgQ+l;)uH>v|Sic92GYrJ@OLM_=hmWtvDZi%P5SpuCtO%mON zH~TrZ;v$^Nn$Sk9Wp~63M+~BxdS<^j*W+XA;>svKgtmrvm3v5O5ahk@wOEpS$R2Nd ztln-X4F$+@61o}>JX;iHqWclRtnpGockENLpa{hOQ(vcI&e^=Pu)U}Hv^dm=_w=@w z6Kx#(5xm6iZcLJBHoP?E5>&%>U{)#7yq^sl_P#J!XMMxsVt6B1 z5~i=N-)XvUYwgMoyT9#d6qEtpjA(}PwYR4vuD%aS${ z0-8e4SJ5MQi~BwEfc3_eYxfrETF9c7G?_q6+IS05k-X^cG?c9paCRvACK57tOW=$I zE|0g%5CDUCUk=MC6TpEpRblP+IcN4k1z(~c+U{H?+a5V%4rf#Y;@2)z&py#Hb5W}xWOE@`o{+SweHBc%Yu0k%l#nc?|t zFHS?6m1i?HeBogK@XL(ur2Qxip1Lg3p)76b+O4s*(Zyy(L2Q^k&?tT2v9SnA+FO%x z>JdoH{LUv=xlgOIYDTh-ox-CEVd3aj&AyNDh;uvs0sGjHGUV@*_uy@IQt2i0W*_7+ zrKF@q`dc3&hW;jE@X&PT2Ndy3*;Vp2y*^*`BQEo)2){OZY0D2vq8Q@crTmP^Xm?LL zV%|jrbyQ1PM7V%W|0x#>?ADWG3J+Pi?gWFp!U&hx#=6(rqGhX6d_73W$+7+$7E~`D z$YtJDODD|I#PRf`0}X)G_&GM`Rb$|jjhGtRRhHuq5gn|Jf>J8vwXN2ajX?msk@e7KB%sC8Fx#^iYknFG1G zWZ3oVn&Q*rdukK93k^E}FO8XpNRCGT{WnrGHB9ftk-1ZB(m=LHdLu~uW~7%u2F!`O z;n_{INV5nU6wAsB{d>q&Y6Zuh_!E@~qy(rR(T1%oWgTeQ#1LQqp_s#0)k{b(%(#U% z_Be%h6(OGz4pjM0^HwD}gYt0mN%r+3f24zRsqbDc&g019p0%xU7`W^hlVBwN`E_R_ z`$a<=>1O9t;#b`0(x2t^zZocAt8t6??-EzZ$|)boEyf&UVG|0V1HOTF>` zd;Npo{9i5)|K*SW8*3wMtl0LqV^0Ge^pAWbt@nPUHI85If9As=IJc;Nb-dHyCutE6 z(Ke^2g$<(^g=p$N6=88sPA&uq!X>a2Hj?v2sFXT^#1~@xx~gWnRdhM@h2j|#!DHeo zkoyQj&n-$!pTy@jNP8&Vhf8n`umOc%1>)_#x-Kz!?7`weP_2g+B@tg_j;?D&68c6{ zBx`8w+?t~c@_FX;QjawNVkf%e%tW`ew{I35UUdT^?C_ekl1x0}miKJhhG&A%uvgsZ zccgfclz%i3(Pi$(zJw>@+a1vvIQ`i&Q~{#1Jk!{F1L#;k0CKuMpv-K~oLPi`9_+q) zRz7l@+vEM0a8q$u!(~V2c$fYssRamsmpurlODF1IXq`4jGy9%WXG|3jFUiFn!4OHM z986IHHgXSpLdF?%b{a4^14t@3jy_}pfN6L45ru&$0L=#+D#%RxVrgc3p9-Nc5K(HT zwC#(DOfu$Z84LwOP38m>J<$H>%QricW_b|NKF~fBRZk~u6!17~)pdE|;Fb%QWFHPU zAGtJQ!miZ(ixlPA!iN-|HyjJZ{h$R0l$MIlP2{s_OWxi@HlE%=H-o%Q+J%E2R}97$ zN(xbsV@@@+9F=$GeP1?cUp>Nv!RASiiY5JnS2gQdo7D*8AXKL;awMn4jqD3}oqbSB55#gXzJ5%!19Zq%~VhH=xZh(p^MP^Fm^ zpZU}WY|cs7JD)Of{}5A!)v2g}0Th7)Sp$-2-lYbz4aia4=~XD###oNRng}#fJ3@lujre5x`IuRyNcU#I=OeNEkjn(Oe z)4)*}M3#?QPQ702Y5N;GcmzbWw__1!MX})21BJP#){iFnw&3g)HSpkRkyW%`K@HwD zInm-hUaG!gqUj0M4fvmiD89c8QLzPqf}U&6`W!fZ9AP^-qvV?}mMRraqtYh+bO?Do zQ*l*3_U(7bn_x2&%lDb)b_%B@UHFSm?*(G=(Rd=VOS2$v@7@oa=Zn(v(*&KA9+8!@ zBr~)u9g|=4>DNix$!Rs?=kkcmfYb0klKa9b6HIaOrxPn8fMt3I^X@RjMxZ#cCE(ns za*)0WVzifsT-RO4@cKxnF8U`K64P>*$UT2&2oLVN3yFvA$I?68e*UpUltABLd|~=F z18gFFH%M?3KVY{x@P>=dV*FX4;L$12UPC5bU$Zzpa4q^W@GFqz*TkPX##Y`BZ*yS9Kvxx9v!q zHWwdw3@~yQJv?R)&q-BlpVpNYhBnTC)HAS%7eXo3MmI4qLkkX9^!F39P%Aa8rd!LH zKnL|?|MY21hKGlS(317O5Xi3O6fH!===D?)=+t3qHLgFt?@CoK*BjWW%Sl%|`fL=1 z7ZPMOX&ZfgC z!|wdlNauxf^(+RJHLC`M0RafMgY(utBgLqN_P3d2=0cE;Z;v}ag^ z8z3aO-W^i9BBNb|(gIudMD`bO_V};Kks3R-JIONxKC0IexDn(%E2lxeOJUWI2oN2P z_@8FqFC|?qaS30g{(%R^`3d^9p8A@UJN)nZaFBaf^yN#Z+gx5g($cGRK2mj(yHfEa z!SQPU&wK!R)uC>RI+l5>p(!aebZl{2fyLnjY%M8x_>*c@;jvrUidzqK=E{!a{1()& zrwB=m@dG%sJGhy%KP`$Flh1?X@cd1GxrMA%YE*>!eJ$SWc>oR>tcq-V!{QGWv68z> zjl_fB7aVO7nn*_!D~UfW>5*~D>dNDe{barQR%DKrRkXGe`D`A;!d&{xfAj6+H>)YZ z!T7TRu@72PTd4cGV+yL0yKw0Q&`^?5F!%r}2beyVdQ>&Zlfq>43V5ofQEGj`=FOd9 zVYph=B1H<_S1z-TP1!I%*Zx`9$#Qz*h6Q51_!J#prYz|-nj^jo-b8K5DQ#F<6(*Xx z<#jm@?@cY|WQ4x{-ZVxgSQJAb?z{6=1k+0RW*wM!u4)d{WP6=GN|Pt<*=DAW-k_!( z91Gkr@*D^OHj6ON1oQt;uULlHta}>5YNoAt?!27-LXnc^ta$Q{zo(Zq#hgv--*zmS zJ9Hgok?7f(eDp5&Xv}RY$|b_tQA6d7Ks0H)ys>Jl%>~@9_U}De-zC1BWQ?0AO1!(J zqkpa|*A0GO+_KIZ_mq^}O3s#E1!w&?2Xar+#7(|R6#mJff1W4%{O#wGXKPELPw=_n zs02F<<5(_YP%mqoCAB&#r(I>$Yz*Qp*92F5$}F*#oaXPUnoO*3)rxlGw^p*+LrVPF z{^CY}nvRH-Dy?h3OH{Xfp!_+;&PleqL`1CHNW7-S&WI)61zI3zrbr&PeyXpRJL8h% z;5YI7>_crYm>=Un7V)-5t76MpMc=L>QQ4$A0a-U}W22t%hMg9@V^~EngQSym1m5{) z+cQ!9B>N=7ERDym99#H;{7z$mbztnr{T_A@-%y|cMp7R<(ww;xUTvkv{%J7oX5qk? zc(?>relFYsm(`L*r*;4%IzHP=VwX%9{mA~o--wVgc# zO*2&L63KbHrI&=)logP-UkY{tcQ)|B z5AIc4ZRF5{hIELWBgpqs9W*B`nl?1$H;g7b##bd8@I+SINGsr}rP_t+_&Kl!9377C zZ?t?UOpE`;qFh|=@sks|-LEx9cHv!tRHT7AU4d#&+kT|zccH6Fj9U0;Q+kO_dSmB`P9#72*&7k<<^V(+Fls25&L5sWX3Lm|}x#8+Z5J6c&8 z6Y=OaaeVU6hCxDO|0IftsuwZl;uZa021auV6IA^2!ppWOyU$n3`|J!^AT)Zff4WZw zjccOLWqv3Ue{)y6xKV*)CNjb&$e7nOBIL7kV$6t=`*jz=~4f;c|W|~qj4Vd%@-sU+OXPGB#&7*gcSNtdO z+dIjliZ|j)Gl!^Kv&)XyI%Aqa1`o?^!h&!S#*L6-|5Prrq2CXf`Y#^fyD>W~*;M#r zkQ<3FxE6lue^{w+^HuoGAx_a*%coNly_!Rqx2`7wr^I08hWcvHjV5|0I#|NOqO zq2OR8eoA4wJLI%V1`)VQD7F3!mSf?l4fjx!TY$dmmnP;Dk0mOfLe8QYmu|bvz*r9; zx3xqj?Ny||yKBmsfbES=5?d-4uFFX7dZ@Ub@2a>0xL(+2IeIzpNpjC=tt`NVG_`$WcY7VHwV`<`#N_+yJMXNs^d$n~7&&R!Pp z(<^R*U}#G<`yi2>fLSo+54@s72IV-SQIjEA;E3?&g`Q4p^`19&8}}IRl8PYg_fi#W z48$JA3@MO341HBMy$k8oVzjt;sNY5w;3F|$zyfbhOkAvK1;sK@`RL9PL_eq&!niXN zlLpa5`xluKKZE%=NZs(u`2O}ZJvwLOj)76Bz*1CmgoBO2yRV;Cv3si^lwTqf)B;Z8 z!h-*zS7Npp%@RuS9m7F;0LH!rZh?_>mn2+tHMLjrNdC@Id`zTs#3M0H$BqYlJ9+jq zToi$_QQN%^Y6z!-S&_*3{YAf>jJ!1DJcc!#E;y|6Os>Bm_uU_OuUC$Yg9QA>-k$7o z7QcT&e2e7ZUcD^QnJ8w`KU_#S)lWopE+9u-0v?5YXrn3ZEKds@Z%|Hf9(+|dRQxSB zKEIbLJ7D zZMViHZ6aiFQorG5VaD454u5|Ug>v0)=*8QTXe6o_kDC(k8qv{Iws4ZE-jg?2psDT$ zifc23?;!zp4>2DU8qs8dJ-F=%nul4ZF4h4M{Xhv^ZF44`YWo#Q)LA<~ZnE*pLgD2CS=ve1F;pG^@hqz9GlzJ35Sdvyq0!n{nWtw_wXy|Oo|DPw zDqTY6jPxqE50w({0=0c(*LUzC?>}$#xb%4VWj!U5D{l5Pkc)4olxjIB(84EK04OCLdi^eTwbO7D^BaC=q^j@Z zvb1U0D}!w(@~kgkeUI+&i`-%f59fg+MdtAo$(eJ`^{h=tfISSO%WhG%pJnW#sw7>V ziL>wXt3+IAWK14Me;alba^2E6L~-<&h-TfAR3688oi*V9$T9-C!lA{H{~pQyKG#P0 z^yvR&)9$&+{gwNPGvv;R8jgRQQDkm*`ufE5EE?d_M@R|JNU2|^`&x8(?yhBJ>Go<& z-R0Tq@7ql?J&S{44Q=uOxrfIAxI`>uN16tp!(?Tf=Oco*&}wIF2~SUI6F#dbKorTp z{{u++L2OW&rjZjr&kdwZDt>6_uXosJslU9J?TZOqh;f?gWk@3f==44zkNs|tUTT>r zo;}iC22_Z1ee1-Vvw>0q@YhvOuXg)O{2G6S$5ANmPn+jkY^my4DdMWOwz}b{m&y-6 z*>|~=XQs2%2GG((tZQZ-r3@ETb11D(CGAaTJF0#waDPkXgBEu!4#&}OPU`x5zP8m6 zvXU{GT~(X3q`%MfLY==f7-OWAgh7hn-SU^i+QwY~%UYS!s-}0M%j`|=5KP4!4{lSa zE%x?Wu!nMqL2O=5l_#e*y8FmoA55h*xIgKwkO)HCVyeo{(2v!u z0|*Hz=PZDtnNWpRftZVv+|^S>4~XIW6K)2(-GA=fqJFLG~?8xB~> z^sjlv>pdG9ZM^@bVzS$DQOiz5?%~IM0qUt{rdu~p@}#I$+BVgrF#Kw54IY6h4&JxH zUyp=7hbLLOif?Z*-NxY(#j@Xm-GBCV8}%XlPRf7|qDn(3B``GkNbn!a$1Yw9i2x#K zT{KH@bbL#fSYaYRZ~cMWRmq0hc4i@V!NaHI-pwSy3g6Zse+SV8l;NkEo>Y-I;awsW zPq{%ZR;eao{#3Q^ffv|+HTS?wXv+`ipV+p6$jP}M2jM(f;=5Ma|UZoaUl_p(jP=81Rr2H7Kc<@4Sn{?fk@f?vKmVG@Q4U#X;5B+>s}B zJXW8>4yGmAA7A-YyZwRp1|_EVlaRV%$T};vS(hv_k+s(@qgq0B!P zVWNyFo<@Xg8E28M-=1a8(Yc~D$SLZTV$)z7WgoS8l8C3>ZAL@zk<{1CcRUdZZ0Qwa zzwt`$# zDMKhTx2%UWa$u@R9jZDi?mD9eo9@^Wuk3&ddaB4bBUqfht&VR0fhQ;-M*8@lThyO% zSoiKTtXQ@tmYgYjd*qS1QFZ}JMj!xyXD6Dmdysa(VLU8JJordq%4b0}pYz_KP@(@m z_{iWNFN)j$64xJR9quv z#4Sgba$abgJm*>8Gc`B9f3D5nj{Wmcmny&Gapku7jz6&7bYB2zhG{A{OIVTE69kLm zbPMU=Br^Mz7Y1Lhn0sL6OyBdriMK*=;kP8EcyeU$(?ghmj>~n^+^4W;W)u-G{DB zzLWw>wt>oz@nGlqSFv|`2D(NfEjeI>R7cWXEPe)5dxZs{d^591@zTLOQKv^y4Skvd zg?R2LPtZt+j*P#mW<_yUaZMyu^h#CL0bKvemU<>45q*+<^hP3F`vip!cpGL^uzbMt zCIj|U`{yJ79q&BkR`%LLCg0Q-&u9KgwlTzv(nw1jr_|QY%kz3B>mMWj)4OM>!PS1< z0xbu%@VTT%`Z0RQQqFj%1eZlV>W9ipA{dr(8PCl3fmy=5y{pYmOB79+yTz{7fOd9^ z;;ADoiq7JRH((#$rJZ*8_&O;u=DtV;mt4JEr3_1;b0B`3N62RV_7~N=I;4T0my2fG zt(;XsFz|xG*McF1hXVpn0dE42qwVb{s>|=`C*|yn%$Iw788NvwVS(Rjdwc4PrJ}+ zkN}IT{yad*ZVI1URyR%d0;;x?=4{?xSPI75Am$HCVy_T? zhtg+i{ocOU#T~({Z*wiODVz4ECkI{rfoH@yBAI*e_`J$(%)Wyt(2MDkFIgSy z(Jfiz_*j|T!#0|4a12K1pc`FYrKR}kUbLKOVt+e8Wu04eXQ4;NNK>tA;pJkMbx;Z` z65`PbsQ+>?m)&(DFDZm)9E0{Y8%tSw1vMJFb8^EFa=jp6l_K_%PZT-$%@7tNtNFOH zOPx`7W+k{eIc8k+x-hvWo}ZfzEf<)#suH$Ga>->qSQs6Kr$3NF&Vc>;1qpDkWE$*b zvDz#>swws+co$xx@p}~{q!NEkX7yqB54;sYrcqI%rL{%xMNM7%P60ifXT=}yE@ zkviIT^k>{sweNiLKr^19#e41-_cE^@lXKHDRCRQIU}CXv!-b&(&_7yj;Yr9ju6wx{ zA2jcDj_mwOOr%HfeG`{klutxNbhO3+Dp1zrvpWojCPm?==xPq%{jVY#G)f8&Uh|QF zk=}fEB^%W}!-IE8Rkdhg3vt^7OO4t#6T>A>2H9K);x+@kt`#VruQ839#Po{5H}q9t zt1t9ZL6sJ}A+z(U)Xe8<5n(pww7cg%;`R%NTu7{&D3>LDvp{tFi7k3m{4=CB#5xL> zL*U`ir0dp(%s^(bk&jVgyvMU5=R{ISv1?_v`^T&N)Z#>1)|IrS)x*9M9`Aq5(+RJV zMj6^Tzi7n@c%)M$++&*N`|4sRcKGL`(9?o@-_Y(EZ_Q_6=bu;RRIjQY86-IEm)GAH zo*9)Lt%0=f14d#s^xoovmDnO&*y^H1j8@ej-MlMBEFzlljzns|mnqh)q`s9hJP7R` z1fN!s6udh#%$$x@I$?<|T8Qj9SZm5TBP2J0S64DsvKSJQ5zW_pQVxw9>^-a1#z!o$ z(23H4G$!+SMzMKZvag1P^Mjau7^lOoo|U5$yt-~5b$*if%EJTTVw7TY#l^`xBUiCK zm}Ql8l~4I#?8N8KF=1g@V=Bj5>Ve{Jre?iGLn_o->Y|1B5cUuk92HRR(ePA8i0%{n zg%l&sQk7K$PT?QQv=SY|76y)}p`qcpscg^Z2(k0L?%lQTPwvBW$@Ng{Z(L*00|+`$lr_h+*%2at$P|M_f!m|3YfHAG2r zM)WG=Y*tf__xU=X18Z~+Q_^SLf)J}k3kHOp_MOZ~OjZ_WpAEe~J6e@& zbXrN(OxxG{&D?U#Nj54k3#ky+6Kx*x0Z4yB>_Gh8IoJAFP$P=>@L&;_tblJQD(t?d zF6Vs7LQ$f$Ik2}dKg(0&Ri~MXp^^XdARj9SSK~1K_ z{ALJtt&mSFxxfzQu5uCKWe@>g@+VE7R2jIxy0I>}k`wrRsVd&0k)sO(gR;8uALjl@ zR+7mSiq~Oi3aoh5sEUBocUYvj2q;wJxsx``f~k_C<-mzK;67y=4*Ln@$mW#Rz@zBl zjgLi+gG0Miqo@xdpkfvZnthn{=Uz2MK!o^9l#P*D*~uDxr~5}j_33r|pX~PdtX>Pv zZ5G=iD>ul)e0=<94k6=S0i%<8YFKg$!@COa>Xc;U$A-Ir+U=8rnBeK@r5_;pwwm4A zx!C3_p>5O?z2Kk2C6$*ZYmmK324v_QiW{1JKR59@A${~$BndEykNM?Fc{&Qel0*XF zEoT#2SCega+z*LXlp^Ri_xfBzF)?Hv=1LBTzVZ-lmW+XQXX zi+IpS_bmwB9BvQ`x7q*=SZE#{JJ1esHXK>v|EfFCn8Lq4<%EKzZm`W?A9rkO@j}MesoS;m5Lq zkU?Tu5W$Bhy~3&jbg0}3#+4?knG3e7FLP^enW6}z{%!q#pFu-y^xkMAtkTU!#6C2I z-&VDTejKptV42z0#RtRCd{6e%8qNi6>J3V!1(ni=w#xLj09m(NM;MGtj_PckPw_~w zjSb7V5D4;KKZ^5Am~Xy-{(wA!G@pum;Jtp{IOgvCV62mZi&7I_JmSFABZPd#vCNMWGPT*carS;E<5)ER;XhN5+Ex~J@e@Xz~6LGoas*S*INO2dV}=2-8W zPqBH-k~Qk68%W3)#5i3Tiy$OOu>^-9Ps`k$J_q+f1|8<`SCr|PqIp=e(&$-^$dvIj8Zi;^} zY|U(@Di8SCHhKT}O+sIUIuV!qzsDzQ;rcsubf)#NR_&ra16!d6nMHTL)Y}amG(2v! zAOYKhN9h5&85meW<%C*SosPVrH zk^g&^)YHP}YSvc9S%XrHDQW6JkA+5notYBhYbyg7s>UD-#utQ`G?Q(vBzCzNFB^>M zxqWT#BT6~DoY!_#C7V2dCojd!r4s6&#(TVPo1DNE7k`AlL91~H)~Mmu%NpVmTaaYIJQ*#e>bY&0Aw8AF*-h$_@Jvz-RkS#GBR_vUZ=X&#sD=PRh|CLA0tTvz8TG^jd zoST_mY@Nl=avw%?D|Ho4k~R{NEK}CX17>8uN!t^PVhM?hX!eh{D9kEikpxY?VpKBt3lCKey@Coa1pSZEC)f2{eLe zTudqHhoy`}VqgM@`UxXuWn2+^X2tCmuDxj)KyE7*VX{-l;U;8yOY71ZAms|o6u5aP zTkwhbzuT;&ajN#~0)Uas=NpkB;jYeh&hNI%lS6bpjg|=m$9^CL)I?lTb2Ab%%81{V zb1U0&0XmddmPVz)Mbif*KE}E1^Zuq5#VY3QUe+MT4csb4^^IgZnXy#Q2`V*_{6Kma z9}Vuf2>CZ*FO+}fxd3xRPnddX_2W0%)G6!oTax=JMY+)aetfnO>Q%_{?dR`2ma~2? zFAUHYN!MuLctLJ6i!@dfiOPG_O1Ue7Nu75JQ}-ZJH#TH@NppR8b9eH}3K0b{h?pXF z7|^m6FxH}&z`4}R_AR>-SbjVrVkP#=LQmozd zz;FG3pC?NEo%HwoQ0gI+V-3U(L|=WgZ&b&~523x^^Rh+UxIq&pblPtmR8oVU7do2T z`o;@~$fd~ze$$oCY7c;kck*%kKmtQRYRt?ZZGsw}i z2&_S`$S2GQr&n1kJTh?zulR`NMxvLknx8rN6kx>*UBrZY$1rD z&95i)I2vqe5MVa;kXV%(#Rn9e9Xp&NF zky5lQxJO*#Znjun`};bXjGb#MaR0Cu-acymnAA(HwD8Q|jrnnTD}L`3A z{uYCAuw+BPTMNL4Lsy@JA9p!!{DmD$~gQU1@% zH#UrnL2hV-QdNN((le~9dBvUxO9_YRVhFpB8n1S)mH&~bko@_=8*_s;cnjgHQ&v40 zpkr5D;%c!stzzgMB^`-JZIGqh3$Y%+`xSUNBHDF$Bz)ftCUnGK~L<2HQ0kWz(7>PQ*`j8mp=>*xr+Gh2^e8VaHA^YU6$26#tuz8^b% zKhR+C+-fUo61g;%i6mV-1MNFfYLbuZ(L9PU(Z17j^gq~k%k5z*3F4~(m+kJUf-kbR zH^HZp?a25aNfT8GHT4r>%CbjZ{8WSGXFdvnu*oTLsYeX*Sud2GkUQ5@0Tp-svptFk z%)oV+FmSmk@(l6`vd7j6j9(B`WbN)1l zGLIAFR3fLm4SAy0EXQBrzhhnz_b%bP3%DKpzTlMb)n@OS@}~CjM%a#-sl~`6(0fT>!xP4Em!oK>O}dpAKa|fr7taFBn%3O=mz~Zb;?GR#Hs#L zYgP#4dhdV*E@)aZMD$Du1T=_7%Q#A*z|yx&bhtw+*m`7+p89b8FK4(4wuqV`4SasVzW$)T3(y_&cK2#}unF)$;Qs^O;(=P%P+&XPYZf z+G1DQ`}M{c{d>m;@1Sisc}{?*$7`Vg(AND=kA`m~jY}W*Hb>JfmOYig*I0hmj$IvO zB?t?(yYwz;hOh)U>mef8qko+aaYijReG<9Ij&r^q{JgYsR7~6Yj5d>)aIy*jCHllM zwfP&GvhJ`ZlAtXCY46*H$zE!~tOfFr*nF?_QeQMEOQM;7nL^*pTx~XC-lwor;U9 zmNVu;kA~vPP+wD1h)zK-rLR}|L!^b6=oWFtzFy~r!m+Jk>+rtHQ+mQ302%wfA|9* z?x$;H&13doUK|NxbkXh;m~Fhgy131D&;pCqqBnz*oq2Y&E@me!tI0rgG)CH3dFDLI zTOl7dH(~;k5)_|k;1XA{&5@E3n7HGI0je!=A1Krwm5#OQCcOe!EnbX@1a9R?7GUvjZIlcbs{yETw`~hHZC;*f4zRWtZCodXP$kf>ba>|1 zD(W=YL$!8%nJZI&J)wN%u$mxiE1o0Bhk@IK{%CtxIr?DO&3dH;D#k#_9I=0oj2&o0n~wP-jS6oU^_; z&9`lo*FJMsQ{}ph59_W?eDlooonBG+OQ*|~oO=Tm>Xcm@WEq^J-xd?ADhm9qxOfk~ zbbxyTdDBvpw{TO|dGRS85dK%wcTl^@SyyXK(V(r#J|2wGh-@0f1rOo0jQpsSWuIYi zP-R|HCBZD`U7;+`DPVtK#;OeNTNIP6uyVH^Xt!%ocxladH%}_-9w95JDRjUcT?9W- zzZXZShClF(V<27I(<#avbzG=iOE~9YHqrXu0uu3fkKEqc_CwsGKi-j^$6n75lv+L< zQGGD!;!ylwpzwbE2h70HY102_b|C_ltjS^MAD$BQoW!+cE0(FFWMa}GI2__=-w0Zj zAMLP)g@)-!+1sx>9R)E3I!XaY^1jE%QT|KNJW7x?T;&m~wfn%d4-G%WY9(IBoD zBONHSlzY(oHzHdt#n99+rWA1DEk@l7_=Mfk#ZBFVEH27xa286zygaU}tH&q0w!8ys z*uBNOrBEj3Zmv7R$B9ZAzu@L%Hp?%#?{v#&XJq?leM}-u40F@VfR1PyeAe$r-vSl_ zP+DrQ(CR1fhf6)Mi{(5=ns0yUB%Skhi(-~i*~o05xtnk0j0CG)L@^KF zxB~qMe%GIZkg=3C7pCB8G)Ks-H!oi<=Qw5-6=@(p(Ixx+B;9Fwdyvi?9BPCH0OW(N zntBscVbxyI+I@@D4JDrxB34j7gALIV=FHVwmrgQrz(-)a%XTu2^NE)zIL@^&39YU( z{hTZ?`RDrD24PQG-%wv&mE{<3$YUqp)Em2ykOQspkS-D^dv-i62Ugdk{bnDD>SYv< zJN81PcBMeTo+IGF57gJrv(#Uji>~sRX}tLzWfX+ z2Xf9Bc|&2e4Wi=DT~k8u4#^I(ieDuXOAM@|i=0Dlsc>(CvJK{=op=*qBOBmjk(CxC z$GV2;_W5onZYZZwOPF1e9_;`*3b2^f4wFgOkOee{$P+#O5e;Z*U&>~Fep$k<`KC?r zo9}}(Gd*kbubJgs2{M6qRt{9|r+arcq)bKiJ?UV3e--t%l!OBv)FcoKrm`=|DP{zH5I#B?;)B0HyZAvY`W#I^>Ou)q_gUKSq(KD*1j zp-Z!DQ&L59ko=&+U){9{kD2z%CN-aD^JU?mN8T#h_tJL(^74W>EoZsCgcp}Bf>Iq& zQbQi>a6}A@^**gw?;WxivQ#AYIj+-#SU=$d*UKjWOFo6Mre3NqJ}>qa5k{&K{kY&IzeA{{C(N*kAx!O;N`7JaxSCem}&35dv4RiuO9iPD1wU`B;a&K zafDj3+K|}3{UGJdY4unIf6geEW;eD*RX7~Tf#vYn7kbgYOArZ z@Xt}$1z%zAa$d9hix(i3M%_y;QkwRuyY!+zl9nY4R>;_TbhYT` zlQ|xuvHQ;VV9728#XsMmwT)G5X&=;_!~x&0eCau|jz`mjvmg(sGN=^;W>XyudkvR|+@2e>yKROeU*d__>_G`VX%l^ z&qDs@{{8sbV+G8nR{KaY77RbB%m2G0#_&?Io+!V01eL2aEvdu=u8kT!b)pOXw$ZrY zyX)XgvP3CV?0-^yt?cDN(O`p(SHYutCOs#pxE3AVloe+b-ni!~vr%#9a&HnhqlR%E zOIu?KK0%>pX}|(n2M@qtRv_uxV@d0Yf}$>ux*kYakT&l}T;b$o>Yd&*aF2!hx7=Z* zaN9U+J!6Vp+rSdh5h*5i^L;t%zOOUAX8}3e(;GL4Dg~IUob%+=q^cgd{WGX()PJ}@ zJNFNl>!AFT&tW6c+OF&zU6@+d3W)%s(Rc)5?`j3q01BFeHox|Mk-*Lyt*D~ z&&_?L{-U>eLM!cgNadr8GMoR?KxoDaT*BYQ{^p(G{CO~3@NsBiY=CmXw3TIW=fcMX)KRUeWL)iurgi^<-Iyf+aN zI7|P%Neb^aomOnrimPx`4pX|SjguI_MBkYqU73k=$mQ;ld^F~(n}ss4@U+OA)dZJk zCn~Es(`WC8L|Vwzug&m&go@6;v8q!moWNS(cOV6=xZUH=xOiC2_iD+Jo&aSqn+#R> zN(UvC3i^&cbNX}3B`ig0ttV(-i#JB_@A+wz{a^}*6fE#*=}Ku4Om;E#`$0cPBf;yg74 z(UhW*Esej4V2QlNmd-o3>sVWtD!SYhRYN|WvlaWkKGK!$0D26R(cU5!B>!mQtk+x^ zyFNt`a(}9ygQoCyGg5JgqLQb9*N(C?N@M+V@~hJ}X{0O!*hd6nsAajid+Umb&xlyu z)ONPI2eLN~X{1ZGa9VMutMuX)O{F3RuLzaL2|V;bY1tWJGw4^yRhv6jn>q3W5&(9T zb%-stYAv}5O{t#^s26*4owVrM=b#>zmBB3TVWdqR+F~SrD%e!t5^*4YJW81*JAPdo zHW9|n-N)!>Vr-~Cp=oTc&#Z7eeq&IelXZMvbCJ>PII00{(N?sgSGa#H9c^jVV~m38 zRwt$JgW?aCo8=L!dc3TsB{B^P zG1V4$6cLEyH4s^=a*I-?YK(|jD3cV1qcQtdetd)lmx7VawEvbuZ=)v{f1gY)CfPT0 z#$8fTrEX4jw#VGF%;){4YC<+;NS+@Cf|(pCLBpW905=jbDY%zI9GB(pna*)|B+mWJ`+Lg8gc~5`APz~u&z0?}v_(tT7 zye-8a+f74))3k9LkwpztY7<+&Z$n+A-hZ2v64G;ZoYtLx3_|KH@)u;(NGo-X3iXYHmQ;6s3ow`_35})}wz%UiFFwuuF5$Hsho6UK z>#+D>E-|Lm4e${Wkb9R6OON_bwFPu7D~^Fv!)$qLS|sCKmNogq$yzB(TaS}w3iGOu zQ`y(kf>^y))O8fKsnXv|$rc2~(99>|)CNvGw1Msx%j1gL*IjosfU7|SH%B^Qr5B9O zo7B`2_w=GXeFG2yEsX{_KZ(df#3c;b3{y8Vu|LLM2G*V?5&ggGBP?@2{Vfdv2aoOV z7gyZB^ZoLThHi`=gbTthXKpjI;@CRkljX%up1_+t!{~2~dg=ad*2-nu|D#*zcU-~5 zSAM7W^HNQ1S-Hc;DfCuPQ5_kdjhmhDnzFc~(eAxCizS$@}Eo+_4P4n12(j5gq~E_h~TSL(hSxZ&`-j zc+}`6*K?7JvHykTiV^|S*HeV?-nbd(BzxAL49NKckz(}8;m#T zti87cs%gRuOE;!ds{Z>io7<0^@nT|Vg>FjI?@~n6&WGQy(9ff0O+R9v(mgYI(MQp+ z{k=k?^0(Y>P_yRjTG5VT*&YHp+}4(jt2H#Xeh{NELfQ%2xFK`5Ya z;dfm5Ms@am!bf=$EZawxvkA-U)`!8blnuV@aXgE_ugYLW# zDymyGw024gv0zQ(T$E8M#3b6uy%?_kEiM-k0_(Zg+EMA!&$~zx$x*$tcQ0(}&Q|85 z!umPFElq8E8DM_S^(OdfcqIAOE&Sf6o$voh`UDudX%d58MNWr( zt1X|c|K{9Ui)J_$R8Az0Y*jjzIH;%fS7d%*G|xn37m}z_#aUBZ+OImt!pqMSl@%ILB~?q?^50QSk$j>IG@`{k4?snH!&ELQ#8^2|%1=z3YJ4C#InZW=9#>ZCAFAJ+9XW_nW+wGjqAC z_b4x~pXHuV7C|!V^pLox0+}>9C|*&u4MK8c9AQO9neEvB^K>?!Z;HiFmrHd0U~&1Q z50$3^uOG@}b8t3eWE!*1J7(tT6~w5is2@vx9?QcHN=&gc7+G<8eJva+M17g-A8ln4 zt(;RbK+7KtQ&w)))him-TIY{%4yzcOTt7Fo5IRYb)a4!1vTkY{CJ5pKP%evVfez$c zF}V}?C;p@KeZHYg`V+mTCBmN%aNm=U>p>q|1=?kWK))Adp;V+$GV@&lhdOz?i60&U z9_eoId}5Ru6z}F|xKtFy?ZrD6*Fc`=g;})!+OKfqs2=ncMt@TDbX$V6apu`?wXG+! zfc;QrVX{x2ZgVO=eX@-mvfR0`^1RqKtouE7A<}|6g=4g_iC7E_(k4^rF4lyLkjj7& zDm(#i-#S;57tFR67gnk@)zP_?ZazNV;b$`amYW;08sGBTgEk@Xo_zp!+zq{Vbj1z$ z@>ze)y!g|#JLLjTx$GLos+SNY>1@mI>%zf4Kfs+C+}z`qENJ%F0!M|+7uaiTeZEdi zdavumah0E}lP;4X<0KC(9Snn0#TJROi;t^O?^>&gvO;)w-thI<8Z{k{_o zlwfZ#a>4rV?wc8IVf$AhU@t!&S4%!w`xcYv8iCJv3-v6+(; zcvJwXXL99bWN8}l+$}xMChIJRLz6-D zHMg7+SXY$9&z%#6E*F2ea(%iN=mFKS$5QZx1%h5l`fnK4sE0K>1l{+31EkAwYt7x| zaY@$SH%2SPl$WDsi-WeE$-W7Vh$#=+$aj!Ob}1_SnA>{hFGn*>Hn=6Qm0$X?x1RU{ zU%dQ){QZ`+ZNotJ^D^#uhS4^snv~rD%KqtE&;L4t#hllIr1f& zf%g>i1}O(Y$ojz}kHgl9Nf79SV~CzhoJ&m8^W9CIV&4zi0j}DXRaYdBDh=5oyuX(!s=jdH@zICtLos$U%a*`uUPJ=;{cxvmi^bfmB*%x1AO`>+_ zTgoHOXfV%55+-j(lVjB_s?Z7cqJ?}(j}f;hSXC-=Ow-`-47UoVvvW(}Dwm-sj`T^2 zV|?l5@sQ5cFi$wqC3wI>@zr^FF1&z@<9>^nhLG2p>^j3;uF&Ji*1ao@h2?4wqFo4W zYRWug&l@Y6Cu?y{!^<;~R8nyA0Pcd#hB^+X0bx|R!Q4YXYlr#-ss=PM81$3wme~vN zB_awNEJ*s7O-^jb+b>li8naLP6?Ee>v*Y8qNFx(T$=92*qs_ zqo}%E2WSWhwE|{~v*B6?xwGfkhPO8MK#TU7YpZZH(Cz```m4LUj_?W`?LOp*NgPi$ zBfn?lxwuO9B8<-lQ2v8&X3AcRqML@P%3VCg=3haTWfvLM;3@Ka^7paicUiClF`25N zO3Wa*)lIf&yYa?2$6*;+5(gRXmfcKXE3cnXTQ~AiQIqwfyaI7Qu|V-vcOf53cnvr? z;xxfmk1@i07mjbRh>x-@ty7$PMk%C zwIl(Ba1T&^QY=+QD0(8-ivMkS$9yoXg?dl<<8d&S7WW+MGIe9tIJ8kyTT)R-0HD25 zl1}Gzu&k@OOAfa#krJMedX6>)GS}=V8omuPBG~y#ysT$|1vW*g(-RXZpZgHLZa^ax z|B?KXviwPA3~C(LgAh%f$Sag0rf(=Le&UKd7Qq&d0z;%rV&76O)sPRG-uq zUwg`2?ovsd5jK#y^IsmUkDb70rKajQ^=kIAMzxDQSlGXomX~#F=lSNz(gs0Ikd0J~ zUOn{Y{a)0PQscpo_p~);TsS0^DL8K z$&I=wL`<<C-BeDm(aM1scBs5@2dAmwoIX=?GJ(NQ8+VG8Y3ALzBnx>O7K)H&uAbP4eN9g0GKf^V$#V_f zt~S`re(VsX&@W(NMfOF;o=R{vQHHVz`%IOt6evKabAmuFly1#9mN=q-obncwR(rkG z&F$}3lUJ2X>%%Hf)FLJs7bNPic?-rIA4AMmriRACy5d$(;Vb8Fg1^_`EwvH#Ar4c> zq;L66=z3GN538$Z&z#d4=-Kvu(Fvjb7tr@R2@UZSr9cTb~#eh_p}5I8%}(ZTI4aDsyum z+YuWWs&AL9q!aXWR1YeD{xMhH`bBpKUG6!Fd-OeO(5X1)r_uB;$InnewwamSYBm<4!<;9W zn(#d}t#7ax5$F@OQpkI!-LW&$YdwA^l3Q zK?Vg`(`2@ym^>AK6#0aD~T8R-*}7C8MnDb11gt>oixt4uQd-Glb^v_{>Y z?AeDMvH?zkNYa$MZN=$3C;ETX^{*W?6ls*{rLK_iddSKaw7ay1jZ@9+9}#`4veLO% zsSISn?n#l2J<-x$i~!{kH4%;l-Qy3l6wpD=8bvxFg3f7YTVRR#PG5+X4S_pnZZUv_ zQJs)3f3w=1s3Hw!OOfMLD5b>xyPen%R@j;<=EH4%-d{?{)8tD&?upAH9SvWBKa%O?gZ~I={-52wF z#~(-Q{E;kS@$lld#CpG@`!_!LYW8VER7fqhAu7l&fHRQj8qwU{Hz*%%;wajnKu@6V z1s`6T+M#`%d5R9yhDx^2ii2Xj(eeD@!cJiL+w=?$yxbk^+ z`7Cf`5jFGx^JB`$2-A--9=fmzvGQ)(Y{^gwZj1i zh_70S{+_-+>lc9zl)0}p0TTHb9aj7ER?K>tlEMwDY^@>-s(U1fRi6(&LQmrYQuXVQ z#U{RZ)QdC5ckA=}*YBCxt+v+E0`)#gmvCo~wrQ8#X`<~^ZO?#axSUurU{;WS*^VT{TVX+{?=2r_aVro~{=?ZU+a#j$8 zJ~UQ(>flOdZuJ2F+CBaYXvo>V{h%Qup|45L)Gc~+aI=VI08|@`=cjGv@g+N8_AG51 zYq=0>6)kx3XnO}lo0N1XO&#tKvd^F7H8{1l;;=Sw;goIkj-^KC@=G+y5_bGttR-M% z?r=K&74D#Ka|z15aT{fw_152uMtUTxCi{5H-fULviM^1FTdX#?7YXh^Ud$K%`aQK~ zSvHSv!D2UD{s-lI$(`jB))h!a@OhYtjD0z$?wxvdHT&3JAYRb_H&r_5UTByeXF%^1 zcm`=DQCH*Tux&O=ru#eg!K`BApRbBeOk1%#GG~aLyC|K4+nNSTQL8tJF_2tVe^s|T z(;TI_;{3Aa%GfI<{bSVX64j;DQSRZSXJ!P;ooF5X4yR^4dDy^B^N(3+gvf(MfvG!1 zh~K~`JhCMf6c>F&sj$QCc`vGw>L8`0rsye4-|8{_t;-Aw`L5x(zzvpTfdkmh=R2NKF~cWlA(*|n$phYr?~{{L6ltE!k! z>o&OYd+P&hF3y@`^pA04!X@}`Wr-B@f8-mqD()@*z@RIQ|4HFw(^J(Lqgir0g42^< zJbxOQmxp@|VgO0AvQCrGQ))hcDd+=@Ng*V+=z1yGLn9L^E7(sZZ&VO!mg4C-wQXG{l2jEU^84+!0ShbD)tF% zk@n8Z(-rQc`(iyXNJ#e(fM=cz&Io2oOJ}0wXm==ePxccVu$MMERD|k13H1m9NLzLE zQdI}-mvyYRHA862-DvC`lye>IdDe+lEX?XO&T(hscW+PA;XaktJWtTv`)Aid)0s-{ zwXmvt&q_w2Zv1rTAMJD4eDqkreM)i8>sDFvk-q!idWCsuNqlA)dSb4aRaT$j-7+C0 z&8)2V#U5p42xj=`?mN*~#{W43TYIeyGSJUiT^#s#9}mm_2^cc7Tp__M!k1=Ke-ew% z&(~}I8HM-`d`OLm9_c!T9@+=@yvTb$#IM(o#`dd|JvG>;@en|%@Q>u>F*q2Gm{qh= zsx8}58sPYR85NgSJpxzmPeT6QXix5JP7A7X68E&VQJP9H*^b%r#!88$IA;bnUYcrt z5;k^7J=8i990^Sz?nS(n{Y6$5`>c(Pq!8_#XR|(|zh<`Veehp7MqA&>>rus6cqt#3 zAw+(EZ9My~iU=ea-{+$IJ& zp?)#<7JokdH$NXxTyIu*pjY2|Zo@Rzqb{CET@n_iVsHyQ8VM8-s}@Xks2ul}v%;0Z zG#_*)0Q z@A5U?-&UOZxz)VQ=dasUZSy znH)n2^1~#jUhAeg&y9UxvqwTX$o{#JA3p}j40gS;*ce?1v8ylI6QB>%P?(9gENN`J56zVWB* z6?{U)FWrN&^MVYh!QkD%MTTh!$oMRrrs6~)cpm>jYZ-G|V|AQex^&osA4300?9d0}w6>@`W`PPX_5n>XnSAO7B=37M;%j22OwfQHs znMKL*G~QR%^~#unA|oN<&YeHpbQ?_8aq`ib(C&dLs2XRhfFr%r3(to#L=UpREoJnv z-;*X&DcYY06^`)I?XIxt+!VDVN?P80pd>PE^6Dss>aGgvby8e$t?~`d`8625+k_Ci zAkWcHTpHY`{JMtq$$FMRGd!kK^X}UKlJ@5h=>tNnYYsFQ1Kj*Le`N;BmzI63sSWg& zN02*Gyd|L}4UeS65lRcjah#K9*wO%6|BDC3BnQ5S^azpXDNE~YieD7wXShb(PIHjW zpsb=8y&Ft75rz#ZcZYexW_S7L5(FX`j7#4}rKLT!2*lkL`Jv9i(O*eM!XTntb*W99 zG>~ErR%B{N`R5u!4!IAPJFTu94 zI!^l^i9E;jKN7Q_*FdTgBB@3JF~d@b0tz8<&sgLIsscbYd9bKY@&T1FmxViGVVlp$ z4;LA350iIA=TivRAl{eY=*yaI>-fwl%}NU0@1_jzMu}Khqvo<0Ef^G>d85*|RL3I{ zoUta>z&wIvoqw6Bgy}ejrOnJ@gYqlu>BkoQGAX%(vn-DcUF3F<2g^Z7-MlZ~dW}Vo zMINLGdtqgDzQkL1uzKyLyX3Mv&yz-S^LfRy(>;MgL@;#!2_ypd`ZA-BjjxieofDxD zzQ@ZQ)hvXVw0|2=qi=LAC;A}bv7g0#WiTFnTstB^5Q>SE`zVCOuhY-81 z;|U6rX|}`B?ZN!&!T7uz&gj=HFRjc0yM_0nPcj}d$$IZ4UZwKM+T`VPXUsX>>E)B0 zokCl7H;3CdRn`MZ(&fdFl8qhw5cL~Ox6<>3BPx8)=&V0XVq?xs0=9Pw%iTi`;UG5^ zO)h8IK8fd=y0LX3@-=$pzVSUp`*y|LQyp){mn16rNiSSTcUOpEjHBcZ;UmFhdog>q zKJN!lINj@#>N6(Hi&AGp--)JoBzH9g^mw+?d98)taO6I+SN#D0^WoY<|8LDPS90!H zE8lhXGwjtX_bW|nVgFd6i;3VPOBJr2m9LqF3nsl^0;GS7Nkd2nXtICi5xPoULfJhY zUQQ={efkt6Nofi{wD?VW^@dRup3XsCG|Q>eU<_o({xlbO8k|;RE-u9Uf?|&@utVqp zg8PV~Wt5z$`1|}A!cui+STbzeUf;Lgs10W<-#WP#Z=d;KA8e0H#wsh8$a<8&tk1>3^#{=xr+U`1hIEBM_8zZV^m& z#uG!wfKJXAl$V}BVC2-+OsyTF)N1NsRrIjTz^J;VJrdc^T@tG|#AH_&rFu*EkOK92 z==5yPpz^dz3=eGz)4=iuHSav7!kOsM61;aMk%V#?$I|bSsVnhrt4z{3@2T0`NZy3a z%)89M$PD&%8JRe*#|j&b`qIuEp<#FRb$p$&CUe!fUO-EK7!fxt8QG5f+6-mMjm>`~ z*2v4gIuq;(Md%qD8!Utmq0h`&2kF@U_@JAx*0K}_pC%z1;-IPW6w5mD%TLrs5z;sB zgFa6&OKnd}sqpHMxAdGMITtAdbbTTtvu>~uM~s6mrY@54P9x>6Yw!tEZ9eO}o?x%y zj8FF{&m@P1dA$eKgZgxE*&aeQIAd=_#t#F7Ul$vxbKiO*He@bH$a6pWTbq~48Sb^B zoDc}abnPW&zo{Y$X2_P74IwQuP@GHf`6ds$iC@0?Kt%A8=9PsYQSa)T3Wa|X5&4CE z+!x4o#Urd_>Hwc)94ty3DwQ%Xs|a~H`}aDE9UCorFy3eX+oI^aV(TZ zjgzKTX)9Yz#R^!S2RbnJB>F%mu#rrgRbWhdHp7Qm$OvvRJ#)$oz7&w!orEi~=&2qd z2a73=2(d0xYV@L9eD^-&Mb(dCG(e{@>#ilV6)|~FpQ_gfYBy4W9C1UVHe;DC8zf{9<(2RVW1!Bn3aNi2xfMwZ zAW4*pvxvS5g(Ag+8>n6Tx1QEKUxXYihX*aAo!L4LtRiauk&KNxN&4qgqoM z)Gl`4<8R#+Vmp$kBUi-)``GM~xhDM@xOfao`38?#($F(Cyt&jOCWBn88}jN=rsDY) zEc#pWH6HN#&T*K10n`^xY~S_{J?HTA?#x04G;Iy~fTou)3gb4<5)y8R@L zln>?wW(|gCxmdx=5)m}fK;nkRKQEbTl0DfhKRX$wn>Q)ebwPm2dkZ+;_3&{>=Yd>^ zQ8thyLDd1=8};;GFLAGcRknMktS3h9K9KX_7Tn9Zz=IQs400)SIPuz_cuXQSR zuHN^YN;9w5+*Z_4l#npG`*~((TUrDIUk^vGtO9!h++$()j_FKr&zP@lu&dC8d`JC= zDOLTyPqhPEPC`-jPK#J$BgTCRAyyd9xO6UGG<24gH~=dummQ{f>|1gh`ktXtYO zm-x>+J2uGKJr9riDQkgvf#t;gH7Jd z*aIEkuUTZ-arGvUo))ssA9bCH%Ko_1sog7{@kdwSa16#sbMnobx+_FUGMlW7JW(j= z&+vBrC7pCNp7{grn#@18UjDPOPE638JJuVf-l4`m0jcXK4(fc+?ywJF(j+J6c(*@( zW*;CA%q5Ob-#QVwgwjTyxsHIB48Cp5$U}BWR*3rqax|@Rc5TXN|J*DoV(ot~2c`hJVvbP7yLj;4jac}a-+{q<67^YnI>4$%;=sVJ35rzm#e zQP)Bwnp!_7v77A~eGADqnxdXnG=$w>grsv?xdRus004UH_8aq53SfJXps_%LoBJ`fK*Sl_BkPvA%n%Un-O=HVS+XYhrwDY$Vq5 zL;i;xKNEWXH-)wMk2@&=;fvNT(qrOJa?xOZAqUm57*9<$jpB zLmKFaXO0H0m-45N=b3I8WX7H4mPe5bE>y}D=GwT@*sUg4BqOsd3&Z?&>ujeAV4EKm zg>tBT*PSGAsL!^lGXE`@To4qif#(ItKP&m#{*9Q|-C~M_zB8L|E>Dv>dSynPXDjBhQstU!~ zoF?ZJ8r+=FAgsw#x9CVYIE25c23`qS;H#-kh=-`BOE4waaWFORP8*uq3Wunmwu>jn z&jrE8J*QHPHbgyF>V?u{K$Of`?)cx*=nGSo_Xn2eW8CF4*3p(8RraUW4}`+hQfAlk z?o(92zD1e_r^qx70~OfrcvCSdD|9wVh|6!NaAp|IF6aSKt~6nRPCRAM@5$03t-E+O zt``;&yf|U@!Ti72jbab&?~SwDIA#ZZg%imi0C`^s$503WAl~J`Mb3TlkXZExWLy{h zj}3cfS;4~yw)>*WESD~OgoAtn?d<%QoQ{2FM#-~V>tJX`)!FS{JWn(e;jL`rvNxII zF8@0@w^u-zMe|e{Y`@%fW|oltbUo&4@S)gx^~lJMGOq*JU(7oqx&YC6T!b2v)@t^H zL`52mPqgJl)xaKgZE=maPW7WGudL$&XFFs$o9G^lQMpO$m*8uz@b0Nb%#2EI%BgE3 z#Zb|fP0O4LL3%IF&(U0)xtT81qLl^M6UU9$ZN!PQkWyBYCO3UmTAWduYGey5`UO2d zKo{KGKu(nr5;!4k{j5F&lhv{<7q1MCatXdF*zOPNH8+@sh&8%bHfRvVBie zjt$wSZbhw7;w2WaQ!ksg6v}M2F*=H5+%8 zvxeU9zwVLAs)O;H5*%@q2Aa?x%Y-c-MurLy0EjyB#ux-pb9QlP#V&GcI-&iBH>^@_ zhbvjZw}Ni8@X@nTJ6?<06TRZkMJ6wItPJ$#v}1ANYv2u}H#yjWr~&^4tFb8 zDj7K{M`326>btkYN09#rBZM*v{B@D6sJ43$k6I8Zs~$D9vMIKH5_E6-O|*#7(C@Wr z2M#i4SvgVnRbZY7BX>q8+z#Dsl~wm%xO=EDr_hui;Tbgr5KwzVsbTZcUaG$)g}xfE zr;;wnsMS~6B=I0Y*CiT?c zS)(nB>qIi@J{kumz8Tn+eaFfXz`X=?$@q<+wq-HBwz0frceV4;3h_nEz}3+b=3B+- zJ#r#+y@wP#U&M{G3j<($u3vub(=L(>(c2Y$A9t&N$8O@X9-iZH@umT(P|-MV;?bd_st=Ob zZ-pmW6X_i1_pO?(42{3DOlmFI7Shu3h!8D0@AP{~#VCn|rE zs}0@L3e3y*JwLVcWpa(T;G4(p(Oq#eEqL5yCy^gGGF?%{IiAUmCK5usw5>tPMZEEF z0nG)r5?gZxN>SnFLc%_!C|Oio>YbvQ+qdMqLrxjk!cz0y&k06EXBdD1-N`6nHNle( zN+%DpJFm6Rp3mLIeB5^|xKU@<93IiyCADS~_t_`6!Fos9R340brvJ)dCmxxDmuHWr z5TBM-a4+L2|2tl-`}ChW%fgv|Y$Y^EX;4$l@?i&|Z@TGZW3T(r|tDZ}U)Y~9lu zeBo%q@C)l$9=`7E$i2jYdab<+O0+$^{TwssIOfLjUi@o>t;YMG+cooyDFntRwFu-e zcg4>9dAD1;C+3_HHxOL>WFp=rUNuPfMION~3TG0wfR6JALcNUM|~>OLjMEoTrcl3BL|3>TWz;+t(eSi zq4r7PyH~_44ZwP6m`!ktSvjWRj-216PzWRuw)e4nmdzV9_WqYrK0GsvlA|`%&5T$N zp8-X%Ug!H2D}(+>?n>hXv$|WA z_3oMP3>mxZ>aMDm6&CLCV~K@PZbwmOvzN_LO10F;Nl=#UJh*B>2Ieb_i{7dg{;iam z9s#q)3Fmu`d7@Zq#FcGQ^Pe2bBYxcpwF>wa-XR`=y55pTkkYd#90Wnk(1-lzQ*%|9 zpJ7>Ea621w@3*6mtwB$Uy2p3qTpzSOc?;36Ov1$D7mYUutq#J`o&6e!0|vYnRtcO3XBLr zDfHO;D@J}>Sz7gx?~jo}JE1C);#nblKD9^4NZ3D0jG_an_t8sj-z~`RZg$($GG~96 zQN8|V{4lhmsod)9A(fo1wxxZlYwO2tZg)nRmlYAkX52m?(Ft|dw~X)P-c z?w=7>QaoEsCZVK@V+CF%5dqtUQzEjz=HI=i`g3HAbZq$(LGo0!L~6k<=I7sADBWcV z$F-UgbJ)}+cRGuUCKO_4!d54zwjycBW9oR87=sT@owiRB=bG^>|J;wjD@0ya8LxVd zDWa31f9UYfKNH)>9Qu_JWQTj?j9;FoNI$(-j{aLMfgj`rhtj*_;ID0kO78VLj#3w@ z8Z2jL*psX?Y61cxCY-!bT@Tcx5SI&%KcC&cTdyGZxL1%ZMz;3CUPK0UJC4|@LM2T+ z9+HH8o+C%0buCv-$(!^qKAPFc62yo;URfbah>h(fAPO3tcbk=}aR%4gy!7VG?D#Mh ztMo$Zj8w)wa&CjzF2C%tGQVjMehAf0&D*{m4$Vk!F0*pvVWWJ(cCBVeMP*HqEIJTI zDX08in61?S=h*$4^3XiKEXvD-ml;n_(tGjMY$_)FB*RVCFK$JelhWh~O3c`lpHDz+ zj$sP*iUI(h0&#IuFL^<17_8`~>7GNl10$V`oz41g5YXrNh{0aLAP?qKy;=TuSDvMe zRg1jhxQo``b;DQvFiPJKA;%RiX)_mE{rbmBnFII@2lD(fbfTRw%~H|lap9B} zOJ|}rotbGW4<=wE3X7aU_*u6~noPQJhCR-yS6?WvV|~ym>4ZUnQKPUml1@;_%kl}A z`aNIawjg4dk`j$E;+b~>e-?4ACjbCG8Oi(Q`*9i9?0rNdi534-^h~vQA27p|#B`)7 zeiIU9$K5VatsK1PrY1a`KE>HVD60TcYVbcf+yKV$OFC&mY9(De4m0HXkTZLRcF=)Y zCC9wzYK-RV{%mg*nWW8NA>;y#_78;~2dlTi2Fnw)9*YjH^_*^#aFmeP>?Zdnoe{P6tYLP3+h-Hk@Wsz`7u^JY#}JEO65G;!+o%eQweLeGV#)+i@u{D$VoV=#f>t%J)~H=#F`8rVIZQw z$*){N|oZ`YI3TS-AxlmzWiPJMFZ!P-jiLpSu)Gu?XprgMiaR zo^X^vbBinwuif>>e)g5ToM$J8?>SCM@PQadyc?8KV`ru=z>`qY5>D_AcYdl0(<)yH zN((uZasP$*DHUZlu;4kQdB@gyTvYcTfZQJU4#opjRh@d^heb#J{6-WGv#8pM5I1UE zgu8hQlcOv4ct1I&kRU?aM*5tu7=cP4owa;_ScKXl94`W_Vp{uKPPS_BnEze{# z*81?3CQ*URMmC;yf;LL)QxC{UEC6)MpDKc_0OF*>DV8T`AyeF`>k<%)?Wjma62cl!wlGUCxDIMRy!k^@aO1bsK<1V#JUi}`MdlwM zgS#CsHU9(r*Ly|D<@L(?NvQGl}3#uIYP$=W`4_Lc--t{!9o8`Ts5u|KAshQt6+Yw+G7sL}qn- zBFp%kYyfOt8?oy~jF7z$Tvs)_AS66(8TPsNx_3%eHws^xN#!C=@uUlyMukbUCATDE zCftIZWY3>ISR$g>FShwW-2*rdW;PQ^5Dy}|(v*7^&dmDct*iI}MW&ztx!1F> z((HtaSJP4^=w;T|8|lmD$6+^%lbA-D4l*9y4ZdEN_4OnZrxN$R&w$z}<|T*|!Tu*{ z-uLM~Wv!o{X*CMyzS_NT4`CLR7aMVN?C{hECaPA;|JIp)z4CWOmP9SON3QNWuND0v zOFXR#uQMwkQ7o9!xr;@j+Rk)73S{D>-#EHp)ZQ>G7MV`(L(UsQ%1+i5LI=G2Xl6^g zoQ&KOx=yo0`oQfFoBYwo1WP^C(coec%-+%@Fj(g{lFGID{cAniCYJd`#+~vGYz1gR zRTtQk^v)V#F(TyOciNiq#(`rbeok3Jfi9S>&eQ5@0e5zJub!el7 z_Ip^E_~yXY$ZU=Ce6IchoFaHXpn*-t_5`eq5#uC_RwGRA>)@-0 z6```evfN{cgMr|1cpj-GB}giLbHH;y}@|ri<9&jtwJXJ zuyKP&MDt1A{H!ib4(gdo&#J$0BhzK0+g7Vm6Qt&3-TlYryIuk3mLK>1$yk9QtdOb= z-30F%VGDO+smx;dhWZ?a4jUbSB1DN_(bQVhx1dWFl^%lNdi|<4j^D(bIG9ZrKJO^b zh0uvUwKVo1h_IQ{?`q&^Xiph(uDB!H%^FrkYZ#-XatTa~LT<|1GCQ|(sW`B5FM9M5 zwg(KbX5*z6n%3?-Nhwyq>XN{Fkf0JF<%f$SQHP*Lve@;`6N@UBu0$@W!2+h_)pPj` zu<%Xbodv`SaOIN>GQ&yv6K{U!E(eFr#t+M|B_`8YR*2Ip?Cg*`W_h$felty%e^Snq@PEFfb2&IN_e)tR95G5_8>K%SqV2WCg! zNsh57MY}>1R!e|M;$3wW7&6nEHHr?%S`+lB_ZM%lnzusFIilzWy7E6?@s4 zDB`L7i8478@7~e%krL2l7S$X7%?EJkWR9I*H~8oavI$?25WNEo7vO^wS#`9Qv)v(a zryvZXc3HzOoVnOfOmET}HrFbed7ABp4tQ)bJ0AF`Z8=;u{odykxMuh?2_5&}Hx;tD z`~FPgU9)3qev2boVW4q7V!?(HV-|_plV{JPMM?H@_n$gxa~*0o>z)`K9dHZNEaZM+ z>lmzw^7h%Q5X1V2qQqur-zK(wxM=Dn3}K}k*;qZrL&_baYGpqfPS!G;p6JDFxIR|$ zep}t;b&+BQi^;1x3b8|H@;!iC=)Z=Pe>Jx?M zrJ54W{e}B5ddQE#+TS}dB$aw}z@!&?D6YJ~TF@^q&5)awsDMM&9yP~@mC3+RPxttw zx|tW*EIOF2`|{V9xt1M9gnbW788cGLe11iNw$lUv^pM88DVQ`=ke2vZ)CCZ*8IFwZ z&-$XFc#v1bKjD9Ayl^3HnAzd!CC(t;05C zRnp!*$9n`~(1m-fCGtvd;0bb~KJaETI;+bO%BN2=yh6g#SPlai^BdhR%snzdVf9Q` ztHPkhs~T*KoKf_UBYel|$N{^YcK6Jq$%1XcSBl4~Ulio4J=xH(F4il`EM~}B6T7e_ z-u)9!Grw~Hi`+}(KX059ZC7P-?zk)rjn{FoJOqwMb7pKY+nu61dRdY+6z)@AQ6Mjc z{6Zf+D#Gv1XnZf5F>eeAJo4(&IYuqc80>pF1~RLG&t>OX%^NW9hRJ=D9Zsq4QJgWE zMMul-n0f2;{9pL#1vp^wY2D&Y9`gh~%2i`7h3FjmokLwEY=r)VdpZkIQ&$S&Y;lYrV#0BekA+6)joWjH z0^bSKFB;71-HiG1(R^k{4mNV0&!I8-Au#2KfOXl94xcU($^Xnop1!s1r&X;^1u*6#zxe%wwi@=Q#`pw9iT+R36e?H)W)*rl!WXa7av^vqolXc^$tl=>( z`bP7v#EPJQb@OIl!i z$4#k;5$Tx7m$3C@u}Jj69dbd8RlqI1u({mhOUB?qFs$JA-OOy$_xz6Kq1L7ozrd_y z`4{$&ua#PJswY2DrNq<&F(dTrmrLW*l=AGrydb=CG+0Ejq@$SRTP!?dJz1v5bFu8f*B4K-_=B1hM^G|5@l*vuT&z~)1d7IF( z+$-DT`@O^^>2K65P7h1IPTglU)xN;n*L%BFDaR3NS*M?}A=K@8e>0ZocfZ=CZvD2B z+kox7#+xkAnLp5yHuA><%TvBxb4Ps$A+MAZ69em+R$M)Y&xe12R-#SVW?Lyj9PJ>H z0ZZDLRuk@Oktk38^Bnpd2A??lOIuJ8muFFtn<5<%h#y^UE)Qd!^CF_#t3OOO+!Btg z!}!n^i<>oPj*}16+nw|ZWE3(N`UM$|cZ?m*vO;{xaq!}?>zG@^d^cD9a*mW3u>w>| zX|b!IXn+4POInm<6FBbuL9?~R*)U2kz1_wE_z&Y&_KT@n05}HX(e^@EIW73=G9s>!|UE&%^}4IN)nWM^JHCKEMpq5 ziAitqh`3n0F~YoqpKh_)0CE8i<<>>^A@NtT5-l3lGoXV1ak$|)gG zH8*0rs|v!!+2XV>yRa)Nm4js2zIywDrxDp@W*O1tgq0*Z$S1IetsnHET+I-Sgnw1r zBPBOi#!vH2T)dvlANlZGsc-MjPi#IS{H$%lyThTTJZaHfgp>;Zt3j`=!bd3^A@7}^ zD}7NEW&K@UG3fD}Yx$sSfyIad@wr$~U3D|yN~z5VVGKt8Eq=S{Df}@OGk=N52+|uL zo7-Vq=szVv;r*ij0Nchy4{sT2qx=zUr~F&T}amO;;kDX|02KNZsY6^+TmN&$WP>uRG<-atd}YjQTY$Bum#(}Z@`K;x}3kqJe~DyflCWs*WMjMRTIM=@N1j;Ya^^|dZ& z#JuXG+fB-IUg#BD4-%hmq=4Y__2`|E>U356ImnG_<$Fy{y*-mqy{2M1r6P-O5$2~2 z9(8%b6_o1~&M5l(vH?4hwMrl^AurUt?ZoI$z+T=ER4F+AU{E#F8M>ae%qYF%R|9%| zS!_SHAk?bfXC?e@ulU68GJFjfKV%8oW)l|rt*QQ2U0KMv^CclRMiht#*FWh%5mEO( z$4~!qBN~K%mY@9<#&7>y-3^{thKs!Q^YgvMt`!FFz@DqU{;tvWr!>3Wqx_F0mHn5X z=z6IL31~STF=sG~cyU}DqbD#83fa+B9p~A4DLyeej>kERg$w@X1D^pc;5@T`)16TY zbsu89@sKFP>LpU@nn-5R@cI?A9x_?uhKAw_#XVB^pB7-ROf|7a4Ih zs_>0L=^!dZ)P+9_pAAex}-_5UNdSFW2LC&?ux~%Q;F>h^}IWYt$MPZ=EVEBbuyf zRb+G`UCLg;thR#Ri^?!0I~0EWH-x(V$l2QFR+gUIEuu$Fx#HJ#ampx zfxkE}~#y-+$kI7v-5*uSkCm z8?UHXeM^%}{%GxGE2Dmg1Z|^IBLvA4IjZIb{p4Hs-pUil{Z^mR8WBF#mb>Q_HFR>+ zw1(ie{cesqh_&#RpJUD~ByYA!Q~)L7H>7Yn#twWd7p~D&g{@T-XAE6g<~6DE2ML98 z3xmZwM`J14avT&D72I2L8CX-X~)7TLwYrA-U^dl6l%6b}Xn$fUF?`3naqy~ryO0Iyts@`l+yCY4mA z^owGcfZN?JV>Hb_K%u4dB!2dX`%8Y-+h<-Bb-?Rg(f9@p(N&ZBh9VADUbAmQR)@qM z&X;#c_YqL9ESFn%xeJBJah|hrAL9f3NmwaI7U8U3!GB@=98;7h_fQruor{M=P5e_Ys=3#Fe&HTk}3i}5Jf2U>o_ z{v8PV1??tUhi#20-V?8{8y}phk0L8CLWyz5C{Yd4o!d)TG+xNHtYB{tRH~&Q^!>L9 zK^UcsoX`{rkD3wJ2yzxan9l#Gu1weYS`3Nfmba>mg32_z&pF&%y}LfqodqczgC}nR z*7`tsMUOClVG(qZ{|G)B8rdTKfbwk=mCaI&6HfBZH07|MS&_veU&Be(Nj~s9qpGN@1Odx^$Ax1Kwqaw@Zc+;Qw1B9gUx!rrcaq$}L<6XpVn= z34Aa_Yz)-SyiofQ5Rc*aP3$h`5E$nH*Q)a~%|4iZ#h%tUxSI1dAGva8zRF z=JIo^JJ-=yqk63>yUP4N7<9>)d(B+MquM%$iJBk9tnq82l??$79Dv^06pl^+2gc%%YIScv+ zu$3g5d!#kEgTJi|)ohkemE3EqtO=&qIY(?e5jwFMt)d+SNXaLQUA5(hyzLUY3fwG+ zzoN>6UK~zKma_Z2bLixMthVmxC+&sxjD6V5}wwCC-;5_6t-?kB; z)TVKA*N-9<9}FQn2Qc~qQ(GmA%<^_vJc^>kMCxN=JWl&+U(Z~63esPVDrJO=7(Oa? zyPpTQ$7nG$brV``B`D#mu4A5>xE*u%i^H8fx1dEL>O!(%CJm{1E;p(k^*^L%VV`77 zsz>|Sa%%N=K8i~)nDa%-lkkv$c}t}J9K`$_K7dkR?s7^6J~+yaZ8*Q59dbz#=kwkl zDGl5D2PhGZw7)Nh51@Abt@(iXcxH8Lvmobbz|KCI*h!Z*>h5VzkdhO6grDb@@f@cDsW9wuF+Z}Oi0Ev)D&9-CB{iYZj za!sttulH^ePwiX^DH?x<%y|_qgS(a*SiLC-z-5sbz@`S#!i0 zvm7NW*eJw0*olAQBt?+kC9R9~o{nWH74we>zGppXY3>YTGhy!8iZz@fM7^rTCif|` z5itlB8j{teGuaFL{BcB7lAk`aZ*MR~bFmFs&QCs@|oE?JaSJU~ephHV- z*L!KFf?5NCvXX+ceOMBSJvYXNh=#pP)0;PDBI$@%tjk6C$sZW_;EhAaG%bLXgOafWZE@4haMl0U=G74 ze|qAFQ6PAVxp3>Mqvo=p@OKq3$MPv}iSBjM81iqb`eit*@S2cHLT2pBZt_zIm6s55 zghhi*$nG4vWIm+ay0sj8VodD2YaYGIaMhZhaC$nC6|etcO5~Oxi|4v+vsXzKj`Vqh zLB8xKHzC+xa!wJPjbpao_02sHwbL6%bURHvA~Gz^&C74-dJ+`F%G#xOpRpq#8Y{^G zDtd+*LciQEReZ0G-m{WO+3X;z6Q!l0cZctT4~e&;92`&LsCeyaYbPYlrtlj-zcC*$ z%X>LNbUJi>GqXz!Q?(8N0Dv%t^0gP8kZ7({6ydoHoP@j9omV1nvSLs+? z=MCZLy3hT0QqKTLBfKhw$S4-w`<5U15AebdHw>HKwfS37XK`%$X(}tN?`d#}sv(gV zP;s7V6L-4EmL74yje0uGB4TF$3#oIR!Jv|}Qx|%xwHYmElI=`bHEea#({M->ymkbW zR`awUZ=GL!>WXKcZPHyPjUo)L(+??T-Wpvr><0V|rMXgrmly3Ze(@ir_5I{*l3!Tg zIpwMhrvE5!Lr1#NvL$3u^Bl4?$tXVupR3Eii^3Lhk~C|}DJa2%WXRdfwS#IOiv|#~ z_PD7?swtDFx@ga8#pe{dPEEK%ha!meQp3K5G&i_Wxf43~iHTh)k}%fq>gj>1_w+b9 zEv@jqx41DGGA=SxTiYXY8$B`n$s_0oX5HRTp&v_?CphAa?A7Ln)w+t3i#l_hr?rQu zc^o3A79*(KV7VmgwhyIu_hE>$X>usNu-k=EZf|B67`F9sSROuFJ0JPPEuZ6RDhs#q zpTty>9)p_K$GMIDFZK2#x_{4@GqO&!t*8`?=b3YZJO&qGe#LjI$&LBYb)xmuhm%QSYr1$F&>~5s>+>h8-`-iyFz0ZPg?Fs}$z>ZV$^0u}k<{vl1&&`OK zX0(#qU6SUy2li@}4tzCB=BbKGP%lIQyliqr${UOxVll)Hm^t?-6>{pDbn={Hlfv<9 zy=lAM9-^uakYGzi{H%8*-UPli$$IO2wtUR{*C&MCLe_7J@Qoi$=Vj5;_7Wwzmm-k` zFNZJGg|kN+g2^}Et@(;Yw+oQtMnB^o&FAK)B-e;2l)F9>at3(R;wqxE@O4bG;3awC zX@!)=qI!aIJmt1$T6Z(>!51{FacqZ&a2&zpm0?QWISBC-E#AD!4C>^gfs3~caOdiYjVBwZ zUK5eUJiM!JxOYA8dovn8TSJ=TE;xaWRn=rsy{16^OCnSk65-%Lqm(V%+G4X9Uax=q zF5aC{+2-J=IDUR4J;H>!SM0o*a*^#=vI*ajzV?5MKmPX{SyJ=ogZ_0PLrdZVK5+yZJ7{6OgK}TAC@Ju?3e{4ef+la$=0?V9J1&#q z+#h@H*wC|f(H)jby{w9j6u2-R637gj4(1VYcYy~rm3O71=wH^9#;UMcb$}&N_mVv< zcpnYqeS5~cfb9UR)PyH6xt|+C-2mc3D|1^Z0ogh}$o zTbyg5Fk~V=8uOtWB*{pqH9}>0?|fnB)Fev7%o&)I|dRG zvX|OxbO^RguhTmBs4|@xY>Hf%n>01AI^>wferVJFwdI<;(m~IF=*EM>8t^0YtF#U3G(>YHsn8nRku&tJ4pcjS^y z7qTH>MJ^UG6r*y|WG1}7my(f4P%c2+-eV&J8%Yf5*FlHt{?-$%4olOAw|ktI zB%_ST63HE7L~C43V+6#pNxDo6n^eE2@2v32dVG~Vo=x1n)BlIMB$xGnb(D`qGWcs5 zmwz{a=Rk~? z&|{E%zhN_D1R-(`t&%j143zJC@@$f;BLX~ z$}I?DnM@In*xzv4-!4L!5B%6PTXzC&jh9a-1mO>V6WI={Z-3?^h=)f1B@Wngw-=V0R<*RUeR)kTgDM2 z`G?m)_+D{CMx;pO#5#SP;KZ~{WY7gElg@iLEi(7@dTO^4{{f<9R2p~lP39j~!&+b+ zfRlY}Ke^Ik?+=ID#bJxE85sHHRh*&tVbeZkc&+^dgRS3UCl1Y4I3mFCjcsRJl;b4n?G}_bgKxh5;R{!cW zn9?~-xBF*onnlX=J4{|{8c3Bfn96zU!z$;m(iMbAxIHsyL*mKA+NSI%Da08;&`*jX zpYD5F7?n|eC|O8U%opZVa?J>G^%=XAWMaKuTMdfx$>)knEvsJ6=RPZYFombh^0R+06tz}<>onLXUtoko75&Xr)J6IlHk1&WNI`pk!7mjYd)HFI7)1R$$Wt<1q z-TaYbULag*S@^REt!iBm_jH|ST>SLpX^Kio+BXx)ib2O10*(;YU>=##7LkPpn?d+R zJCA7y+#2y3QBL1In-$euy8m)ppDum=u+wUR((+KO<4;&U-Cld5 zt;2yxK4MxGB>8kHd6KV&!Z9g!i-T??+qGr7%Uyc+>JfTjK<%J^m%crczIzx>0ZAjK zWpo&9tHnD07}^;+%h67h?`JsVp)g)FsTmC5h-8oWLgDrzU1esWS3^Lj#ju}P2HDcY zoS~@8VZ&6Na>~S_tjK2T8F%PpX}KcVWHDal(jCe$VBXCY)x{X(uvsflm?n8U;uo)F zvpza-FeRfl+P6STV|4Dw%JMqAQT|%K(|PNQbFT+h%9a8WTCKklvwTm%I^`q&bJ@L7 zqW&u+8@~wqC|*3c$%E2Qx**}D9h>d{B`(YKrli*n3!z9KfH)#z;;28NRCi> zXdir<7$U1mv)v|A`elCC(P!w(%qeTewEWoQ)d)+rtE&#K(!HFzQ7|Mm@x<`7 zSpFwHn9C-uw>J@f%rq=G1e^T0DYdAkBNME3C#7%rfDD%vJlt8;`IS z4Ay&u4Y_5tB5+5%;0Y7{dD}tqRkWoJZD1d?Mry z)~LA6#kZ^|Kdjs}r|mv+PCSTwdqFNqQQ_ncQr;^~qB>@=T=;QxX?*mcM?q*otmn*9 z%$?g!iWB`O?kNHYm;YD;!I(uM#@4Y+?a05N7ndcgumb42;c|2*O&jHSt!}9>VZ?f`4mxPn@SN#|CDs?zdSt&- z(|$I~;GOcT0a_rlpr(ArY_aWmijhsQy=k@MSk{!>`HxT|Ch>atWqtm5*$%qomzs=s zXs7JxzQAMG9~_OIN`q;tsg*>`!8`NZg(|aFwo{5E&$-X4LRJxv;dNPLUaFoDRcrFQ zyMa^VGL?;%8^vGag+(pNsKr;LUX7ltjr|IU&e%ttJ;vw2k+_sLKO9;6?%6gQHpE6L z5-flm`WPsXIVM{0ZHx7#-0hV56_uA3QvWQ=TX*b2pO%@qP9DlZKxBXukw5=ANj^ej zg-33@o1iHNrlcg;x-9z4UND^Sww77`34y+ZDY<)_)J{Qr$!#e)hR|xB?W48<KZAL7vZDhyE$OAgbUWfjN;`J*+S|Z3p*KH&LAdgVd4;pMM9%Avf1z14 zXiDeTWP*i~7hb}<#5Y&l^Zx*z_`Z1t%mn6(%T#UT($t5{h!|fI_Bj&m-8ieOd8cu` z;_#(HA3^;MH|Su>VU_WiB+QPnCjQNGWVpG0qGco zJQ(9ERN*);A!;45RadPkl9BK%_Hb}3671dehtFvw7D< zvlag0r#i#825FbDe=f?JXK%YS>E@oA=;)VR|2AwhziowQ!afJb-98YGAg-KINf*M@ zO}eGXAH-MLn~k+S4id_&H?j#hxj-Q8z(G>QQaM@CbE=9mf}adYQ_$J|$KO!ork*#S zSuUhB7+EH+9o#zjkL(|@ZsG;n2OwbLjZwJ}=q2woX)5|f-TOG?k-ixC4-DT#$u+lm z3M+K6Tf1^DHWOxl#8lnSIt(BvBpguaAgqm|@*EsZze#^~_6_o_j0MEB4HblKh!oP2 zC)@o+zo&kr=ckquk|Hb7(<^dAnLM;8WdX)=UrGV8+R%FbnKphj#G$hW$?=CO+!a)2P`e*k^vy}vG0d-?wWa;eO}_BFiP z1h227I3Raq&loEjr(K+@8IeopozQm=hy5NH z+g5apI7kkGI!vmFf4_n;`>Kfsx%fHz-YzA#3*wCg7C14=e}L@f?ZXKHmYWt5wi6Pi z-Gu&hSWeDGZ5{k_nRXQE>%#A+JC-TejFw3Fqp42Whjaj+W)@-tcE~jd*5=KgOFJo& z9@GGFsY2r?-h0BVZDKmeA;b2$y;^Pg2$ku#ll|m)bb;}VNsLMx#ES`-_K-Q%atLNW z>Gff{nEOM$-plxxoKK&0tcaP`UcvfUD-l$NQTWS|$}<{6VUO2@hV*$`iVCiZvst2n z1>3ClCG>?`Xj`qAW0j#J-HPZTX^Qvq)3U0IXd#B1iMdI>Zru_Wvo}MwvGp$_SShFB z8!^`opD#m63y{onX2X&^!>;Ue+I11Rbs9s7Ol0*OR8kNkD!D9*nBq3Orj$sRP;RIK z+c+c~$yMg^&LWe-yFCgydd6(&0?UMQy8N2Ga23w96I12Ax8mMS z)UJ4cx_I~YAYfqG)2rBi>5U)fJ!uU&)e+~JgSHEmp;Zes|LN}wenkxPm;D~-bG}S< z3ymMs*5$O2A=~f#2E`^EVg4Y4!Z936cvf-|e|nh#w#K$u(-3cHn$w4BWHqkPlB5T0 zaR59ONyK-3cQ{k0<_wD)Mq2g8KUCNq$# zR(rmo(JhC5zx5KcBlqg|A>+TP1wA2TgkO zM?(AL{{Sr-ECUGBGjBiL%Jh4Odw21{B0W5CX|c84*?8_?`5%B{Iuez>N+g97&5Wq9 zCb`9ZJ-jS=a;>In%0O6%nOll{N_)S6l@ z^i=r6MZ1YaeY~0G@BWwseOEgRY?cbFak4D3qwW$+4X0iuxcM7%kL(}7RFZ8>pQoXp zIH^JM$Cl+I?R$y1cwxGWkq&?bYVQ@Oae(aje*jHlf^o`M5&5<$r}?>DcDB*qwwVu= zi^7itBaPhdE9_G|ha7C*czy|<|C?CRbflIdS(I0{C%f~t+MHgrxj|+zQ-D%K?fu7! z^Hg@0pe1;m)|}zW61u|e#}GC)Vv9R+k{-$!MwIrxeNB8hTKb*V(k+Q5Y zhfvB`TvH+?CuoAmZ=ft8$FQA>uJiVq(4j;tMTvCh!X3Dp?v7DOLCJR%DZSuRn~#gr zQL5pTY>aL}6$$7V2{dPtb#XrY%=z{2bBKE|1reU9A%!F4W+W)8I|>lqZNr;(MnF@N z6^^IA@`UGItwdhiv^CZd?`y}(U*b)8m_lEa$FW%{_jRh=mlesa#vu2sGthrFUVFvM zten#r#(u^6Q@tM1h*Z-olw*xk=6#K#C+?+ZILC^DNDZ z8~5;e_Nw0x6Rv|MRkqyWvMP|nj-%(iH=L7)(<#p)HScqqWn?ssxN<#$gKV-Xp2Ubz zkS`H}O@FiE%bW8Fh~D88Y#TURS@L<~jt8#qyBfX`*3acOPOdr>UtBP87~yILWfO~! zX2RzL<+oEJsLKwYj&55ozkjRE%Cv22bDZ#C)ZKuIw0{M*)fEE2=~?EQE~zOLk&}DY zFj3v`lS=k-yBNq*@0kW50}b^N%5qT<3p;r^iC(XX6}E?*(kI~NZ2sc zeMF}DzQzL+94tPv#z(PtAGXg!hYh4I%^_Z>r-L+2V{HFOW`p}$|SLc!~rf#S=&LphUD&^4z!aYg3QxZ<`IPEYd zILb>Wxs_e{h2+w6CZ!~&m8H=ww-u^UU+VKeLkXH1R^{(OZ{|MN!yCRlJ5rG0?{Mz& zYzic38T)AhriprOKXYDQqqNvsH?`2t;xrFFUD!QiPoJK6O! zhd`Z=yBVzcS=C}HY@TA40+Cdv7Y}?wL?2Q_k5-NMutwF=@=1ET;44$DDW!bXuD3bQ zj}?dnfNiL5Ricjnhq3p7YU=6Q#Umg=rKu<#K|mA%k=_DEdhZ~CC`bt{^w6;o1!C<4+!I->Bq@qOR#```Qh*Inx-Yn_wiWSw(n_MAO4d-n4@_dE^- zCM^E}JW$EfxaKo%Qh)t2T1LpxkDS2X^hFjJpXY8J+B1QKaUM=iQ)g8Wrse!D9`x#r z9>q0Zfr-*Hf3Si!Whw??0p zJ+n|ijvM)eFX!QCuEc}@K^VX63JI;St*j5xxSo<1+0xE-BB$Wx&M6~I#Vo}KH~`D; zr1{_kCsyJ01VjamEquUtW5Y7|(aY1m19I?{wkNl{ngQNRl>N`Zck6pAcKl_FXu~U; zja7ABy)zk%4W*X8q!bj>ct%^!Z}#)OqsZ*K75D!W$a)Va3G=?FQyHjgcudq16xG+( z)ztaJXf$+kw_c)Qt1&inDbAOIg>mW_mpC%4=z$0QNY!`+ee{vNMw*iCJZSNBFxr1j z{C(^1`~%LIWRip>eoIGhbBEn$l94m;?wUHU7>YbXGK4%df$iohm0S*92-RjU_zGGm zPV+dsB0nZ-o4r5fxJEeB+3h=B-e)cfQtDw;y`Vz*iG#zJIib2KeA2i!JG-*jL5RHf z7nd3n7;#UGdij&L=g_UYF6pvHlUR77g%^}&BB}Jkf9~C6Cucy(A{}kOLbPWLag6R3 zG`250GUK)c$OEtQHMbEv)<+a{%BY<&QtO-^`9ZHNt2@KU=4u`9;TIcolvz`lib^>) zPP}Q@!8Ev$MchlQ=#;BsX!{y-v3Qfzjtm^P5A6CMuQ|v$8aT2C9GyUz?}WJtRZUZKHW7JAWm-0DW3Y;1 zDDBFvR+Q5$M=#0caw21%)A7|$S5~F|1F%mvU;SR0YvOBEo>!FERi6YnY+{A@0w_i2 zJ#=pctK$4!+fo;_wV|~ypgj6$RFEK{%!<>x+v>wEYN^G2KDhE_`dIWty)Abe{tS2t z2EQu8xXzY7wnklKSKdAMp=TH8?LZ5;CL@NT6?!c zNNYizxMRQ+^lo4Z2KvG2JJS$<5@u;U;jS#PZB39GQB}f_NRyz9Wg=IMPzPjI%t`+Q zSIRJKvdX6trZJe`UU}$obydR~rTjmfNqihB_D|daHj&hszEmKN`uXh!S*KkSLTg)n zh}_=PRI1FY$-DXfrg$15e=%Jl z%N<M;5oC}l;LyPlllpWq11Jt0zIrF!jt{24ILZD zXWD5u;!?c_=1y(%KXCXS{VI08;M%$mi~^A)(boio{^o!gZ~APuDij^7lxDZRw1-DG z8cfQ3o}Q9;FktO@fK8^q(N;_=y$tH((bbCZ!Xxuc@`CbH+e#9SD>iA*;vQ)Af^ckj z=9cZtRbaY|>JcTA98%i9)fahQCj-2l9%wvt3>b_3*(EyD%u;(9q25!AKP&yE$aI zucROr6)dfGYUUbwLJQ+c2i}r?_whIQcnkL<`$V0ar}ccza4P~AHDiRR+)^VhMeXcb z(Cc0z@tK|S?Ov;)Gi5%Nbv4E+=b{E9Ep~;b4P7IrcN;m>B6sjsvlE<(+ln%Zr- z*G>DUjZ9SfK^@#Qd_0*<0C(_;2c4G8BPS@IX*CVIqg_Fr{~8Ue!z-oDzOJ3vNrULHI+%Y~iw?WqrrqdLbdI_DE z17v+c**|>}n>gNlyKQ}>xvhm~_h6YPYrnP`c+34Mi10Dx=-?nbB6Sj%tO=?@pF@b^ zl*wq(j@;5Rrtnk|kBxgMO4FbFEb8s{D>q`aE>O;!oi!IXwF?CVJ@LKFj*j^Nb;GBp z2C^KMfNcOBKXu6Qn`#_O?@L#SE&G^Tou)>8KGmbFUADj^**DGl3lcNsLiOjxrR$qQ zlb`v*I)-B3cLBvv6!cOzhd2{o7LC+QU@H<|3M2<9J2sd`tRzwgS5``8o-I%a(%QQ- zvkti}BJGa`>x~vJi3Hz#|9EY7>gryhy!9PwCT1^~U^&O`qE=F(E zn<$$Bd~*E#TZ&z zDQg~z#@3@qT)JR*ytYNr^h{}9v$9j|WSd!$9~-3_4XLMFp-yMx3}qLwo~gpq)U4Gp z+b=cF3Fi6-*ph^GN%=3JiqN<53o)AMQnz$ypT0}WxLfw9%wOKV=~1Cg1q#RZgy<$) zWd~Ud%nnAfZ$#G&R1`XQ$qzG{zo}8%#5{aASmfZs^TE#oz}-4zzXQH;F1Hi+51<-u zY}7l}Z|Yd;i`sBb_&h%&9NRYZJB+kUAIYKmbDxvvyRYPhC!Xkmr$z#*M^ja6P z|9f?N7Mho`oRCyBmF9~ZKB-lon8JB`zRu5F()Xx{tTFHU`EfU_kIH-qPz5A}f(+PbC-^P4D?_;Y?b#;Em zHZ5mUcZL0r?Pj)cny_&Nm~omI3Eq&o*};y-z~&w=13^YLlr_5BTVvCsC1dS~ zkK4iKN2P7`}dRr_7agV#1q9yw^!vnr|x@k_Smr!8&l3y36> z5T6xt@qn%$@Yn8p7Fz#spcA0krg3n%$8rbHOab@I;)dR2A_}r*`{~QJp<|>}xw+ll z7TND{{koGh*x0!0-i#{!EV<@nG09^_A?f>5-lc2saU#(?abWk?4N0EO?}hVD?D!kt z-NW+S{K;N%i3=q-^HS6$DRF+x^qb~F&4RJ>$4L4AO zTH_5&lFo+3Oj6^a1MTSQ%NEefyy@tYoq}fU#{Cjv-=M`cE4IL`mSZU#ab|5WqOc|@ zXPWjtV-jjlWP_9t;^!0{&ygimoSjVeaM?4fPm)a?+JKuGTuF-9QOcF7I1G^r*}J>U z5m;`K7VC{vH}1WeLTI&QV}d4I{uw|h7S>#62RQ`8XAqO1Jgx)xTL7sTAb>6rR*9Zu zeAXjgVd-F<(s$+idy;nm8Ex2ryura`PAn_)O?RrrbP?xrE4v&x2&k9 z&9R9$`<5z|>x)Hf%-mXxwA9|xV721{Zil^QWX^{#(Ws4?sfhF23k%8U`yzhsYrl;5 zcwEi2eFBG~OPu2-Q`)^D7sQEC1&;1=nM!kP{}YpKeCCRSt*6RA0OOlI{I3&SVI(4> z8`55IluqWt=5|I@Q4zbbR>&iOy-;L-Coo!m{?Z}|9l5WS-{W28<~1Z+-G6)IeZR9U zq08Ibx24I}ef#hXVXSN{sC1t;zn4jhhwQ9_yDm$zEBULPQ=!jPFUKmk%#V}Sw#Vj~ zZyqU}55&Qvr1ZvhW#>2R7aQHBDNu{FcmBi`Z!Be029il!sIRt+a!9u;oIf7#7#vTk z3e5{m%iTQlPSR}(6PY_fSjK5(yKx#^()B=YB-^C)?hLB zPBS#C)ySnHll#3<;b@RN7$?S$D`vBbc?@afdL z&i5+17k0QWt3Qb~=LEtXP_PCsYqrBRUYHYi?o)%!67|^7E;d}|AMc!{*+8*?&)?nT z!gx4Iqy$vJ8BEoGP&%U%DN z@KZYfAHV>|#AV0r=;NhgksdZI z8^V1BLnil4yrWOtHG zn*~=ArzAgDRMn3m?_Wlm^3i#;iB)11PO=dpx;aM`iNIs{rf(t0AOFJkITvf=ns|s7CD$?99DYHW%&gxiP57Z zO4O$Gz8&J7jX0s}-CekLDhtIeJuvZw ztf3KyeUEHhjeu9aX37QlMPIl>t5<8AE9FuTY6c58bA;$@G9?A9+NgFA95o<( zH3l9ti#OlTVqWP-We`SFU*sjl<&3xs_XqoZ#Cuo=5vxbdaygVg4){hSE`&T8@1COW@deV`A|S8T5wEp|2&1sTUxR0M68_iY52Bfjz@q zxlyk~x>tGv3PzcCck|=?>yI-OKRDYx$u_3n2V3Z+)>Kl!X@Av#?rv6jylnccwUCsZr|S(DWJt9v1m~@>fYIt0u^I zi{sq#Rnq4IrUV<$UcX-nUxii+MLy5{ZZf^X>L13>KHa#-eiqRq+U^PqHsd)M@ia8o z>)99$(=+3dW5ITv(l4x9`bj7DcaQUkyOzemFtlYpvL|as&ZE-Tl!POhEx^BX2j)>3Pa)t-gP*nW6`mmdLn@x)P{=?n6 z>NAFkq^KXy7boY0_0$3wf8F{IDE<=_7oYA$?5H-vWop|fZ3@8^GoQwE!LJ|E`;>iz z$pN&~_KR|1{ZYlEWBJYvff3*1PMv|xM|j=a%)I*w!x+uL{e-(58Te>>qm#!bG2`BZ z^eNL%g@_UV>t?(O)dktgE$u##o#o64N@*MVkM7O{`(pKKB=Ud zy~N<0ZcWPi<+NXutj&~?e?mb|XRx7N{7SrF(u5|ghuvx3UZ9B6a{M(Wd*)x#=b5}d7zsz zae5}8?9q*Ei7mw+??(f!S#AMoeMdd09#v~TXdVkNn#8nyg{8JZWDzgoyu0nvTY4an zi@7>79}71TdVkhh?Q8;K#dyMe8y}2Y)FIKv;O90?Wdj0ObLO{Li$HVq5R8_xseA__ z3UpQM*jUs&gTbwnIbhyG(Tzna)1J#!`Fe(S&2X`-{(={6bt+EZH7OisfGZ5ZwfvA{ zqrbu&35#~Twp_4h5|nFS!k=MZg~GkWIl%HTaEH` z3US+#H_(OGqp#%@H=sw$ayVBj0)UY|L1&~{`f?ogpyJV3E8*dC{njvx)7I-NsM5UT zjuk&Pk@fTm$>^9mKQihc(JrjEc&DqBgWl$XNsmw)Z7*$vf*+hT+D5tj+@;h-Kjcw~ zXduEN1~}I?VwMl4QwNJRY07C0Y#f{;CH1E-TEF{t14BlmIQirc9uc}{w6LX@{XT%c z8Lq2|opB_lP0VfHZ(vIEv=yVxWPD2Ku1I}4T!grk#O`+h!>@5$ZX~`bkJS5WgFu{m zFIA$#n---P9HyFv4{fshSZjw%;Rj2q9{9aKdJ_ya*GlSESw9sQgHQ=1A{<(gU2YW1 z+$u%fB-ZI=W{rWFK!Wg?dGYd1!^v-R;!*d``}x9n;=3ui>nchhb%GO*;dU9*K8|4} zEnJy(kSv2CSLx=0_IK<_nZPd}INofO35{2zK^wNtqtYGMRIeTxfjPC$%c~d16NB}PiVsZhZD}<^w&aID^^eyr+i_r z3$56w<4`oNek5ipfcq8l0-gTjYdFhk#`8f`?F_<)ic2W({g2ELvYDoF!)N2)YdLLK zYS^RDm)>JUliP_$sH%5o6 zR_mo1k8W6Zb{*NXH-0EJ5D-`2+~9=a$CL%-UN|$5}OwxqL$7lWk?r+m4It{VMG0P0cej)+WsC z0`lIz=tXzYi^v&BuYCdw?wY$z9!Y50PUB52v<4$=z4R1c$4;tFe{~CE&7zMVlg6h57k)E0sdk=}LgAXO{+*5-W!)Zd0wgLCcQR+~P z(2Tlz;RgDKi3;K(C&tUuDa zj*(zjf(vOaE@~WQ7*|(@#g15~&WLvmzuBV|{7z>D7O8(*S|XmA8gilRf+6H2?!oju z3d9cU>K0c&q|>f29#K$m1f1t8RJGpQr%^br<=n$%5>9%n1B?ZWOdK44_hfkq#Dz6b z_Oqtk1T>TscfPlyT2y?uNGZ*U$BxAQHpJh)T5Ffak;&ixjFhPRxD?7O2DosSjco{h zn!Ml3-B0OPEr?VsIA$ZU+P#FLN@ox*TRaspb}XhhgYN@Vdc)bCwFAV&JZWYOA6phB z`G}7=J3ryd<9R3A?wxRxuRv(hQ6jzuCzceAyKGG@EUjVYjmzzP%)GWZHZ#kGtIkSl)hW&|C?(J+~N zO47tLe=RD*eRU#ca^!}4e53kOZ>FB%j_Y&0cXYN3MB}IA{W3eNbV;G2loqqcf!QZ+ zeSIr>&wkSgP0I+vpUyaLF-)5zUpy~V>mW&6(d;tCkTG43r%Q2I27|B3+HZJPZxS>e zOPwmG#6RYViI}ehHqRePzx#4A21age-5r)Ka{!p8BCg~D=%sDcJPrTZU|DLX>$JMPjvCvh6olKDFQJIxkj zs2W|-hr3=?TRZ4VyHmpl!jNru0k=if&-;Q@oCR0Q;KY04@w*JzvW%w1Bz0~suOsnl zWPf+t<4{*N>8A4uBx1cXRyGh%zELh?4Z|i`@Q`oEJ>wRFku zzD)SdP(GPTJ8Z6gXZgj}icg!q;>T~s>Q*ZYH(*U6>M!tiDLe(~fSFqzz3#KL^UNJQq~Mp=_ErIQ ztUM_kF77iC2tXAM%!(0jB^(zBQB zStm9pz0={)A&p2FYvDmIGhWlRgzeMcu=lOyvB^#WB^KWo)rhpGilGcFu!23+@TfdB zqIF){4FoCpwCV72v1g{bZH-orm0Oimr^45msJQ0`yt~n$cN#n5#a=`ktkt9Y1W%M2 z`_0iv%a~vQUo@ZCAvsSRD+V`lUZq!^fHAc3*+P%Jx)al_-`2h-%guwjyh3?6JM2B~ zlKRpqX<{ddpgmGpFk09!9(g7%53mntn7h$WD|cq&u|g(#RJGpiTQPM9vj$_(F0-{B znm+l|sDabP#NF)g=naDjtM`E0sbO{*k0g+_j%s!FV_x0b^ZZYzRUA(@9>2C{qH*`s zxm55XZ|(=zJ@nVx611OGt_4LAD~;pCD2=AIwB>~4B2FQ!&8s4kBS;@-J3`%cnx|sF zHChels;1FG8RG`%ieMB78}e;P493KhDW@ws^uhkCQVxiYat5{71RRtwU4_DzR z!)wm9GS4(oR2?zM*iI^54LZ4V2ZtcDz>S-M#b}2J;IB`b z=hr~vr;agm0xX(}7Dpjp&@Xf9yH&-|Nj}}0Unw|5F`ex|1dN%jkLsZe#Q9pYadz-U z(JNi`QhV;Fb%Wn)>N$9n)`Fbg^C9LMV|?i$H{(5z@_GA90ye zJe{WT6Qtk}B%0f>f!Di%Uz0AXNSV`7Q~}KYSpMD+OVjcWNsl)f6HKLLVHT2z0(<efB7#&18Djw+N!%}m`%A4u7&kA80-WGf3 z0}&0@(-tIez&jD)x&2-^?3lnQOFvhk7h1w|aVWM+@`3ht2wBj${Zcn2@hcvFy2T4m z+R+#&y}o|$s?w8{6DiB+tW-J>x@}M*V|>kl-tpq8uAv8dT*oG_sq_|VFwUWhuk@XnjGbx|*arV5ohZcM>=DG^D#G?vkp!ea` z_N{3SX^Ca3(`vnQ2partUAAF|d77w}x%OvrBI*G4v1?qd5|3-mIR?c*@~JgHV0+9? zk2%_L{DpG!i_)~uXxoAEJRhqZenWG{eXcjlid9y&Sl~3Vom=pn!*8cj?AR3GmEJ55 zD(-652d!h~CX@J{rP@|&!8>hbZ?cvD&dGi>MH2^~@zL@zQ-J{E1f9Cg0GiEx&DT>$ zPtCrIjM99=o;^sQl%5R>jTm830XmSQDWDt3a-nAPnitM^N!a<17we@qCB;d(-J(}` zo6Bk1c@Dk(ygkA0># z%Kbnk`t?ngd4WN7pcF7oM->o@mn@_l*sb^0ExzYIc?wu4os>^JrWV?@UIuaxEKZSP zp04M6`EY6$QJBBuGHe`itHvCa-TckcRuSTZw04ygrl+M;cVi|3;#k+LWu>Z}n-wP= zA~;2M;{~DSc#1^BdkF68!5Dxy0LWo4s>ISz;1VY@Xo*iEQa^wUK;F_70Bngie1RdT zQ!&uj0q{ML&T!^{tLgAtue>->m2uaGFl+A3=qnQ~usTWirrm%TZ6i_wr`-qd%Gt?1 z2BY27wIaJa?v#>Gyo5UK><_FFYo~Qg(IvQ?6|}?SA9ale{db@P+4=^@tC@Rf6eW|JLr#~MeF zLM_pb;4G$Z@C;TnG}9>D)ZGPelg!+9U;S`PGcRPCSus~EB)Dz8)ybs=%wV#nDW0S< zNk+THW+RstX%q9b8wgV)mUbKFqC=3?>qMA)i;>|V+&KnkgLo>mZ?Vt$gE-;#Oj-)e zhT$76t=Fz=I;PCU{XhrRR1yRkLQ?xhGrz6%oHSEVNA{wEiuq8%(?%CK9 zV)R1DyB>$8rcWU-cXic zUg>RWKe6V@f@{JsFb9Y?D`i<>W^M>e;k0!2q64O1 z9>1agi-X>XHvBg=vG>b{`ra|NN&%Z)l$`sfD{I$_=={pbv-nTdLkVp3BsPP+;Gx%X z4k{Su5?b~_lgr)d3SUIDJS+@MRp03~#m-m1p`CxEd83XPJMuBHJO5ixBdWe+t%;ER zw589!=i0*uZ-&H_qhYE1NDYTG%}0+|m(?ysbh*C&;s~%<-ghGh0FVzzP*ZT&j_%(w z`1`Zc{#O~Q|3?`R|0zRi(|^kFU_Gyz@pp!(DI=c9ukd()CZjg$jwS9gF;r`#_(3p% zIyyEo$&mYfKtskdhupx8)&qjJU(F2UvCJrCWno;ZOT{W`EDri>;GjC_@}LUP90FDB;V<^$REEa{Jo zW`}6$ifSyfq zVr+oP%B@e=XfvALL5ROU^(T=tuxn#qQ3-%Ph?2>nI-6tXk?yo?q|oAZSz;+Jkd$)g z%D`}ZbVqA0Gc#BCY{k_bxD3vzgwlC~O+9`#nioHO{X|Ht?s%~qdE6$;_UG;6hmy1- zbwY`_%PiYybv#$Y1bHi$YZTAO>4e1-4_)B{Y%|VS1EzDmmw$3iPXtKIdlB*hU>j4 zX^z!uSg;bC=k#75k5I1=8&IG*mAdMPX*?y@QzP=^R&Ss>!-8G*>Y}GisP7A3huo<57AAeY%N+h zu6?+vxjMyCW8YSH_%yDL z#BJ%RgH}SbE2@tiaoVUYb&oo8p#)C@BauQbcC5$niIkLWLD$U~DF)Us$|}4>hc~>A z-QYsA6mE?00eoi?RHK*N(0KVx{e8kk0B&#yia47y9XTWU}&BseXIi+6PA(AhHW1Zuz%%yQr zPP-6~X@Lew;oha`TEwJy(Pvix7FJhBrb>pi%jU$&8qcZ>pCo!8uNmM=wI@rRs0K^{FRT$rV45RXQRU|iiI}rl;+S7 z`|7xRrGr|YStKcWw0!9hxN#p;DDw zS`yS0Cz4fC8u$#DlnnF9YN8U(8JB!*X}NKJxGE|A4?r5o=%q1RvTD;LIqZ>qkiZ&z z=v8CC^GI-D$DF-w+_{L|`S6yKvpo%mfgb>PON~4X3_vR<>v$mvPCEqdi8wP>(FJ2K zjIoxIuH9*r^amT&I2C}jJ2zL02F(ocxi&SYB}p+=a)3p0uIC#z9{)^0ibE?)hPHI% z14Mdi56)5dRq-hY_iD%^7P`c2v8+hWPXt@s#h{%zxY2<%L(AB;kQgZbR196Kw4bB^ zjO`_pS_~HP%T8{k5-`F~=8>q$G#w?h#dAv!K~mN>0zO8s->-%YBnrW{n#jFGfj^0$v`EpoowOq-N5DMoLHQ&t<0%1t;<39BH|xXW*al4shB z$ycrW)ewmD=24i^Q>)twep7XxD(kEZjWb`8el>iNrIg~tHM8Pq!*Rxy8qlZDPmOiI z6)qVmC5lF_kSzjeIF7Sv=V0N~27BWH)-z7ii0@0*m6?^8LXDI;7f~_B*6tBbAhkR1 zRg;)?Vok=QQuujNuYE;PqxtGq$=v3zmt)&EyQI<&!Nzq$(aj<=sr5xhj^@U;+5-jU z&L~^w*t!rg@wUfm+gGk;WH6j?up$c_EdquoiWI~?@e6>MP845HnGlXk`^|Ns@UrmA zl=;S?AN6YU921J^9wI;r))bOX%g zG8#;)MM-gQD)w8xQtVT3urFrEN{oCYJSnVlKK9Abhu*NDDk3e(igz}3R|BnwAbM(o zkBXfA4LY@7Pu33v!0S_*tHI=MKtH~;biZV_IN!M7O(X!{(|aU8#SfomX$vVVIr*VB z@TRn6AHV^DW=!_ZePHr}GSqX9A__|Le>)ZEuK0q#xr7mJ#m{ZvXWJ&$6jt5A82g>6 zg!)f#flu-%7VpV=X*o-48e#{DQG)yA|G{u+|EJ+DMcv8-;|i_P-&p{zn;g0FJ&F}kl!m>g_z)=ZRk3cq^S%CeOnMt z%^0alB*}KLDTa-T-3d@7Np06cvmHqqgoX9kDGR%(*w%4uo5b!Hs}`1km={1LV%RcA z@78GY%wJD&bx`fd38#`cefL7$7H!(;)-d#-$g^xEKrvJx*f)FBJ2B^IckHMo)zyeZ z^Wz#={<-E+#_fjB9<&fWCy67y*-v&Glj1J&XGDI{vomnAbD1@S&Q6klD$N-mkYOXJ7MR_6}R z8f5cSIxDcYArXlMu>A`vnRQFN}FJd`74EJ7S9oZT;Wb^=&`kaR_V ztCHx7CyXQ@Ta`tP=*m%JUL*bL&caj$UyQvPyTfgnSJ(cBnOggSy4uRi z(_19Mz=sLUtf@0%=yvIR%U~&bq_UGvIP3kX2D8eiV;0UHLpvMHj>XRUumLtCRMhUeK0uJAGG~d#W5A6UbrJZC4S^06d4gYYQ6zvE^wt-%}UIW2EFK`93%WedHhyiz73=$x$g z64r8^6A%@vgSqF%bgyM*C<54E_s+duY0y=S<8!7Cucw(? zmbCx0SJra5m3}q{?sSvd|IyOYlEL=b>a^hk)oR9mbG^c`_x5&BsKU`~TjIvV&b(M= z{k`8Zqshugxw2dnnC{BKqrq1sg6r4UBR+~}y_lp{%v-WkE8o_{8-y%`e2)eTWGh&v8kaTdgb!hr`c|a$ zBc(qtUyXg;yd1#^p08JzM{9h;HZW1P-OtK>^XQ!VJQxXedAIWjNEhH1N%yVb=xx|J z-Gy#dgOeota$b(m_Jh@%-@fL);agWYehZTrcd`oxeNyqnyXdp=t!MrHucAFV8xTMj zdHQ3Ok>TR@z5@6kK-q73P31}pD!cfw)`g#u8gD|+va@VfVf>M9S6k@Y?u)GZx!CIDCd_lt>F*-e1f}!aq$3wME~~b` zKNK(0v-Xa)LGj5>SS)*kt|}_1tDUe27j<)XK)o2u>S<#|P)?^)zB9bR=USlDMA zC;ZWf*RGIkNXfIbBHwa(N~baReZ+TohL-K;ep-YBdhoSpP?*Zg@9J+W^*v2j4}$i# z7gYHcE=L6NW@w^1XValpavVZWsrd$1elN_flQuX48_TR}(}U=!KZg+s+I^t(yRNj} zdleC#{coe@&W=6vHZPDWfYpdPzq9?s^j7h~5v>L7#KZVVq{S!50Q??whaf_l?j<88qzt$A$!%3LD5H z0ywy0c=Y5v`RG+QPJ8?0^M$I0Fs(0QfE$@PdckmUW1$3AI1^r)S_IJ;?p@a~_~x;{ zm0-sARcf&TB-BdkkBa&O%Zjm+m@FS+`FX}tyZ2|bJ3*~r=Ny1QE)>( z$S~V%R{PqFeIE}s?Y$T)%?-)jk-*!JSMmJfyNlL!aEU$oZ3}DGWv0%i70Z+SqtyMk zwXgU`?+`RiD;+kn82p6<8dvUFEL~}{B&(e?6Bn`Y#n{F*)htzZfh)%u2y-ewo0OzD zh62?=LWK<%(aAU^^YXd1FflDkNlDhoCZ!QMsTJzelaumM)vCAKYaoT?i}cqK5HNM@ zr2P`(3*o&ph$MOEfaqb-`rG5Tc5jvcSlDM{6TWCOjSt84ACF>swyl%N6E5iXb;lJL z?*XwrZ<_G(!au<-t0NC0e+5kVD|C?#dUqk#ZGz$46e#yW3!$e`lM94y1;s3*w&;CB zMa?Rv(^k9%BZ$xyk)XKoGE-hY64Baf;XC&fOFU4mn4{f|wpL$@NVj-nJ3c;f4)s_g z-_}Qdy}T6>&S`&K?dLwB%{S;31-$l9ygY?&Lco)%!=b7B!`<@=@v;Z*UjE84&9&aE z%*==P`hsK6H6iKCI-;xNK@TPBLvu>&H&|`2Izx@M=qc5P7q@S&veCcP`%f|{u{;uf z_xShOA3db?k)y&-?UlFt%YO`z@PEg}dQYO@<<0BOQJ4k#)Iz&2D&H38mUj5Umiic2 zs?R0ON$k$BS%sbPpvRJT3n7T^TtqETz;LjnE8yu;tT$|M)l?m=S}h2F2SW9BUS=>( zlyY<-D&HE${=qyc0Bo>3s(?_UU;p?&DIn8kEg`A_>cwXE&Zg#Xa!~l5n&W!qnO>R= zwgq&bIdAP18Oex3dPz-ho21qgvGFoPh&bPMT>o_2JxeHJ!YNd8wfZjBy1x%H;r7xpUO zDxp?3f9^h;Y{JCO%$7-=P1;X~hk2twa`&kAXg-fZVvU}Y8E8H>YEITg|4wgm_<=WJ zbhz6uz*Q#;B3|MREr9$$#!PxfTyZBkK(~MSn>9homVoyx5L)KN&GqP2QX68(3<+A} zQmnjo6|ZqmxUq+U)O!B`{mbP@Q!#onG_2q?>>q&Jr;_t~-@oR(o%+RFYxdPg zMmZbkN>9kQ=6yA;aGUhlf30okK#cryn{bbee4CIx&LA@#!;~{25Xr&&ZSAi5-oTr%v#gvT zkHFN03Z9SEzv&|cId)E&GIe{Z)*JTj<-DD~2!HJTCI6i=N7SeN!E_gQ-~MyK!>NXG zg3r{B7=8{`I&o7;?VJ#)cq4y#C9C%$qx$PFVA;y?==Qr$3L0AbBQ`u*cXh-$M$^p}@fu9R!s?Am2TPqP{BJ_# zi`KIu3KB5irEzjH8dB*1TAC&$^7hr(`K%mLclI^+Qb-#K73%|qsl2#!mVEe=E>@S+ z*D5IgF=mL{+H@AjXrm&%Wma$U_`vSP^5sp>^_K^Mdb@r4^~>`E{D*-WFGfAaJwMTV z(8>9c=#P|lD*gf3T^gMR#uZt}FY>p3>=71b5sLMb{@JlQm*TJPa`IAebsEhxg#D4N zO&M+DD@{a9M+5nI_NDum_8$fDv~4fw3eHc{WkLH${u=`wvUan$PaJ(itKv&>ach+M ztzDb(IqBi`e2kd#f*09Ee%f8*Jyk>b{tCVNR=E`f(mX&%_L$-xA5X;~T*n!@V#r5H z{gv>gWP^rhVIxufX&OH%ZRh4=S29O+mCR0uX!uyX@f>2Vaw+R=b+zzYr2#_ z$n|z)^#&8+X&;5fcOu}I0;!@$|2FFFe*n>K*O|99ZVLYcNMvOCdS&!A$v%G%Z4?yD z2&-TN7$~S${MYW%4VhLkmz17ZH;F@|L(Q{1^SSMJ8Ku6|Rpw|``kc0gi_tE5gaJEL zD{9my1bEW-F)GLpNjtE|nsyU6`zHKkR`1fA!zRv~c7-A|sG@x;^`)#Qf>C8ETV^E% zp|gjqZQth3yi}PsK{tpm&UP zLVS7cJ$bA{Zm7w1P~GoFT4PRM2assMoUy5z^O3Da5=m`glYsLV79RfJcCFGa`lWvo z<+pmSS&~M=$jXufRc(QoZ?MF2AscWc9Lg`4yre}{@O93 zc>4+0A0~I!SF`tBC|QTk1{-g;-0A{Q0^0x0BKhB2aQAr68hY1Sldx-{dh-XkpG1T~ znYEF=I3Ic5o;AA>+G|V&E@;*2r7e2ZP$x6@7W?MIZQlP7iTs~CAY(75vl8%)*r@R5UH5?(z+T(B+f8vAY*gP>D%`n%wY|GFfw9UICB5b;a@8yI|tT>d+0 z8>R(*=6?Uo34#r&qkP{EkfOM!NADgdwd%4R=|o6h>f{3QP*AYjWu{MEM^ZrDm~Oey zZ2Q1cX}d_e1^@jbyTZiHnZ3-)%u3E}{bIaN%#wobKd=jW{hDcKThoss1QmQVPKk!@ zY(L@7r~lkN)x%}9Id|#LLi1vR{_n?@_HTP5v&;XxqW|*&oQr|MU+&bhXO8z4@iLqa z4l8CC6$?0FKFwZas zAuQZ1#alruw6<(5Ma83W!=!w&UfbBJwA%3of)qP2`qs~t@(#t#3{0~S?dbd@_nb}+ z^9aIUks(xJlKM!q8&luLYy;#P@1-8*S^l!Xbcwz!P%w|ZmJ-$eaxfW*qq@2HsK#J ze!X! zGA^TrB?ow4bmXl88!57^Dyzu!3;SrdUorj~?~t#K!lv);a96_(y&C)4c^Wj;by=&A z%?hlnnSid0HovZbK5BCND-)7H|x63>S)WvNMGZ4nmaQ%|ioNcTk5 zIX3i^n2Vh$UeRxq1lXf;$@)RmRlv{-4W6l1n68DG)&#j3Kxgv$EB5d0YK89wIG|8S z-9N$HKOo&dUhlj!i?QFTSzCWP@i6-j8hpOV@BVXCUcJW$0oAwTFaO5UFaN8%|4%H4 z#^c|nRI&DN3=0P$%Ss>K9^c9!#q|l{M||@|!(3Tr$bb5PKS$U9_L=zub~Leg_SsYK zMG)i1Rl>9R6KdF4{PY75?M=VLU4J6%te++L~i z_3|Hxyq$s|2mW>W|5pYfPwA>ybg_DQ;tm^p&!p$#ZQC%JD~^jW_2&XMW5bn+jlck% zNA#&08e%rH0&5+&pQ_7WF!`TG*FQdI%6nSDrs=;Ql`aWZ9y_dp&N5A;z26KoWFkbt zH~orKT2r9wnfbzf9%hF0Prr5XTmNtO=6|{HoV99V8!j|1ROQ$@tJ0R=1Yio)YT5#W5IhD|@N>?XxndLU5 zwH`)B4sV^PzPA-EXd}(6LZ?lnptY~4>+<7igIhz}D_|O};CTryHe~{fmxU0mYemD< zdeQrh`?yTtVZTweT53x~SY&he*1*>Jm4{CNqx&jc)J} z?%KWA7~V{}RDx`$SxJu4F8K2X_js%9Xj-A3Ob1V>gi`EsgF)u~7fVkvl(_kRNX8X0 zuS8ksaVK&hwUm@mFn;>;pU;z`v;Rvs{r5M_r-Yp1T7_|OmlEQEk4=E)`2cS@y0M8m zMEZLq(B}()cA*`q$tcu7DTF_tPDBgcLMa%9jAP)w3RkVkUM^YnjS=i&ceQ$NGRon% z_l#ZDXYuP_4f)G)v?z({;7&Ear1k}NwH^PEkl;{GN31Fj$#5z_2(;nFmu=&mnnK>s z_8XSbIJ+!zg_8pj8KNx8E1EpY!k9u#CdQ6fdF*rIq>g5%99|?|q!W)|gEZ@IT z#V0Le0~#~dI2-h^pCu=EQqwkmB*F8n@qHU zv&Re3ezop;OZ4_Hvz4?sgu%9c5MKbN=NLUzGzA(ijdLj4nPg!zZk>^__&H}}!XtFC z(+SogNKh`AKTIh2bf`<9mVF?g4Xb3s*KuT64G*JrTz0es}#r&oiK6~ zd*Ba<1Q9GgcITh=4h+QZWk;DpPhKA-in+9mYXkfzjUlGj#D+F(e~=a#gO?;2#u#t1pmim>>1$gpz`=h_wY#{N;Bn1K_rsEE!;)u}p0OXqW}eXQRiZEwfV z5k0jyGf$b~`(~Us z)^x!2Nokn}rV6E)eR#}WNB`WBpjYl8^)pl%Mm6yp1VyrrV5rPpk3&MjHCp+wIF zmS2?WTk6TDGC$I{{MD8Jp#jmb`~9Hs{~mU}ZhQQP-}Beykc+skTbP`lorK@D6>_tQ zOux8(-2RdLl&N6mPjL6Qvy|0uyR@UoAC|Eq->IzPji*z;L4HRHf4ZFi^K;4j8EDO6 zD7m%Y*GNOdNWwtBgi9}!gqSOb(s$?ATtMT^avOXe`pD&6lPEfZ~Ff$+nn6^M8;Y&$vU8BtX7GP<4ilgP>S~%%6sreS$_^+b*AXD&=}2a0lV+v-DnDl3lGFAj_*BrzRTk zbP|-<-G``~hOVtv*qN=zsbkC49IYq3numshUJYqCLyT%voT2fOsQh71;?cE12KjDj z)J^?v&=!W~NKadwP{f0UOku>vM(6X4F=+*LYdh1bn ziw$&(pbbw?m4d~`hvLwRXY^hTp!ek3eW51UhGh)~9d-uQI0~t>JmX zhsu!hIFF@jcoT(*%H(VALyAU?|^r9wJ*hPlO&| z4u5K<*nDYqNtsfnz#$R5`6K@o)BSHhNb9w6RuwBTX9vM(t!1<^Wl8X5dmsl`Sn3j! zo&mK2j-jaXfM?iKAohXDge5M<`U+^jzVWHDFu;0R&sM!mOHo^%Kcf=$8JcKwrLFm{ zy3~i+D69Xc*2e`kR(H{f-j9L(U&}u6bh~=@S$e%0+X>l{f$jo~V8AQ=QJwcj5t^o& zFzW7{29vi`MuYIpm$8L4%yN{x%`{hQ+QAGxn45qK4%65v%sPGr{JUz;mUfFK@(U#Q zuck*4E~FQGOQ_3J6a8Oaknm{PjTb{22ZEZa&HhNaEJYn~lec1)7;Wjnv%7g(WaoR` zqwiolma#5YqBTYEGeKz?;g&Ve5`uSq7DG~|1d}{NhfO^!i+Q5-Jmu9tK=d@AvPx$i zOOqk7eMrL|i#x-tO&3zyV>qbviq;!Yfwqm3gEyu!AFnc5Lae2yFDz1060Z9s7M7OR z^eXj=QN^<*;{Jq3ECG8bPWAU#8(Uf#uxb5M4gq!=Pq=gzY21Te_K72D89q?~B~wpx zjRRsvU?L&akcL^x!?Fc*oN|z^TFW++t!&5gwImN+k5;6}r>DxQ-aWVf&wa`hFT39G3?meUt!3KV(?o+144Du6Lp2*9& z4PL{vv{lqS_%VLoT$$LGuRf{HuSafDee{ueB|<48S?wZrwt%G72gN=rDJd$i$uEND z%qRF;iHQX+9|8=|`UD0qMX}{l7b7B~>B+)zW26b9?!7WxwBKl|hFG5b{>>e{&mG#5 z*t!J&d4zGuI6Tw|_iE>G6m8$qVzp-ol;wdkjHd=L zsip+?1}z|Ee&U)U4XnV{ww6svGi5Pgj-nA zTS*)g0NwjAP9-0v7#}+S0_uaek-O!QX@}xrLKAPxBr{6GuQQ3$2(_#pX%){JRy549KXTTVNFqU9O)VR5w5;^yR>CFM|$7-nd zu-l77C-`ye*rvM{4O~<{!TmSF(;yd=nVAV(9-{JU}?Rkth}Zq8;NGFk}gji9b~QH za7ys$%wEo?=hPAX4q*v5PUI-r|C*#bv%j2!nJ!DOD&ik(L#p^nQ5<8w*;7fZmejs7 zo?l03OnB~T|Ni7$`E0Ih?l3tN5G4$spNheZhYn@f!dT#qnQyiFt?@cKa+=G04qGsF zIUP}l_Yh$-zDLo5eB&g6oxlm}wpWLhZmaJZQ)9I0q+u!V!jfoyymy4s>@IHG%5pW+ zd#+_PR@LSaw2LvhiC!g5rUwn?E9$go#m|hMh}HSN^<(ty5}jy0rvNI(y(oQWJ!dzf z7giZCxL?;}Vj}9Laq*~ki@-9oBnf^J;`)}G>$VGmV^mdTOmPGC#yLRTGTX(pEoGcx zw|z75mf%6RtrVf<%c)Q($WQ&(p?x+*UfBm50;jzb2oH(eqBn{p6PHmS=d#0~m7(!uJG z(mjcNM{(DtVLYPY)E_ooi)^8p?P+;$_BQ+0Pfi^w^!wMrS#1ed8k_X2nwTW4>p98~ zh9jt|AlkP-E;`QIE;D*O(&1}~f7GJqSl~DUnmZ{j|6ZN3A z2Rupc`BRtSrM1f%5G4^V<}7qu8mR%+@|1{wM1d7Hz}72WHymzTRJ^H)(*8jJFrGyC zjDSm?bFKaJVPj~pcyyUavfg@@%{R=0j&tkj`bd{QHTB3^juhk*CF>zr^7I`EH!HPy zW*Pz|mZcY2KB(h&3EYq+tQjgrC;9!2ff zQT{A^p?L8Hl}Fd?ANTM7?KS#5S-rTDpei*kkos!V*_iB*PgM5sfAF#Bes+(wuyeX4pSt#diD2%ck*r?GPh-O|UW$=JgBya!Jl@!*a$A9f z+a5Gh^_yh<67o`%y6A96ERIEZ@DNsr3otTePb7{VzB?y6^zCRsJo5|77yrD-w8&i6 z*Zh8e1~(2FcNAZq5#dRy;P?>ks~pxAo`NrP)p|tr8=HV!&TZL z??>4r+)D5kL~?aeb%6PGQ|0=hhfgSTP^Cacq}*(@Bb=`E+tVa@^pfxe|Ei4PSjJ~{ zQFs2tUD3ZQ*=wqE%wd%CfE)~b%wRyli@PEtgfo&i>||5C61eP^^8N1Bv08<(+UOO${KkO_jNCeIJ}Pa3S-pIOa209 z!A&Wj7!^mWbto8_F3e$iTL*yes^pNHm{a5eDqJ&_@DVRd%mnf63q zJuScBk82^GV7_!NRhAud8jaD@pZ|lVY-r-@VNk=5>l4z)Ios4_a->TOM_FV+K&oPM zPe?6nvrjDE7@A~y@J36AerK6BQQ zz~Pb}Ub0F03Zn`rPhOOs1EC6Qgq-BCC3SQ=wqXxcAv+zk%j&UXN8y6iKvH_ogX7TS zv*hc}C{ZO2cux?v6DWq^ik?Umd|EuNa-Uc!MfUul_i+2D$-Kn6lo$=rAMMx}R`FlvS z=Z2Z_jMp11d<--chvYBw&!SU=P#kqTwX>MYEJD4{U`9umgfv;>x2>7JK+K{)vuOyc zJf7^C3fPZcdMBlJ`#%i$e_al_XY$*e|1CG~xk-Q$*}RArl1LDJz7=4((V*gvOxt1|El z=HC#&|JoE&AayI`1^q!&`MdO`oMA#wOo2$phwsK-{}}TBaOd3D|Dci4J!$`StuyK8 z097U7_vSN!W<<`v#`s^BPd2oWWHE;cy1~Z7e*!?<;X({~7LL)9BdFBr!u`0sVuc)N`cjG4$LfkpSoyu1Jz#ny?IzeKc%f5tem4FvaU*WdZrPvW!S2?oec&^!BF0-e&I-(50tTQ0A*clB(T<1HUqpJ7LZYsX!mj(Iif_o&4>Tg=U+>X)wcKRLY-F|8vL zhu)JLYRWpZKevxxGJTubm569k@Kqb2@%2b1x=z8Ef2}*Lkg}pqTH@c+W1jsdDkTa#%Z3e zo}rVQZnMen5}24HYB-zo+`SraQB|DKas~!n@V~QjDK%~POf&*&=U4{%l-O7+9a4rL zX(pHH=rSO?gB}s+GB?k6vOsj9^^%J7fp>vu6Jk|FDleu4w6k zIK97M>GW_KGiYHAgkG=pcO~#%C2f55B;c<~8fY85yc~vPV;Bzc($ZNR`NA(btuR`s zV9rWsYH1)5prKdTIC@jh`0!+laL3)hosW|P;L5;=ZrC53HgI;duW58ccz7votQ5c6 z#RTP}v{e^jkPrK91!%W;3AGI)J87@L^~lUB=~)1Amcv)5U>-TfColX2-s5UXFn!qA z7A&+&q$>2B4H`My(kfh;)Yd#MlFQLcg(6+J3``zhLykRae3BGO^G*MzZ`k*xS*@9- zpSzKyyKGXSu+7Gg_zw>ceB(20=3oCo6O9_Weehf`-Z{s7q(#3tJzNZdL_zP!5p;+` znp9rjAV8ouYtmKLsbpI52qsx$2YiNGjv^89@c?z5J5?@MvNNygJPllVksSv(T4mtg4ZU3nmj%heSK1$M@~N8Vi7}X2g>X8G#BI#F3JY` ze`H&w&MKmg5DgF4J{hd2Wg@j7gFeNi>?Ytv*c_MlwFr;GX&DsyaPLZRZy9E*@Ap|r zNL0CW0`F-GnTpH60w128?Pi)}ENDM?tH+kShChzG=)P?^Js*>-UKoSeq9-U{(R z#pknL7=mT zk2Kk~yo3Q;9eQ51&W3bj554h;X(yZ!{JpKT=l)H_Q0urX8-Rz<*PaMSnU|0xCVEb> z-tJm0HXN)xSA&_JS@(^OUQ)sw`#u*sW-2)x2(bH#vs&L)@%!?VUO(!<@Y3uvAmy-m z5H`%Jgejmvuj7g4YlHkx(vPZcaO0|&oA_M=6_Z-swfR(!fb{ua1ZwjxLs4ekAM`vr zVFJhrj(DG9bbgV=3VpX8dgrC+&$43^58O&fK=u}JL(kTFm%qH#_@d6UR*4r2p z0p?>w6C%C{RdhAjYP;mkLaldhJ}qO*L{8we0(E9>dw@lS6#qeU;CA+&S;+}y>O1}^ znU+zb5IY`kvALIKM`*JN&o1M?GWTxgukecx&+8kUdB_mPy|()q0!j!2^v7 z)Rtpo*kvU0)`h0;LQV<3Ka!nooK>XC{O03nbR|*kTPKxAe4N z`fy}(44o{Nj~nZa9QIBW-CXLVGH-kiEG<+>(fNr<{GE?`n9~Zn7KtpnG$4~W6)4vk z>=a_`@}Li3qGI)EYRO*4Ki5Zq2_|(@$PSnHW(_Kyx`V2T-2EPvU1Bzvzl{Q}ggG#H z4F_hF9-yK!Y;9JuV|uvLKnHv@QyMnsJM+Vy&>{SE_NYJHjXl#w6lZoI??P4mqn(m9 zF^*{%KCrBN`-%~P_H6Q4fi(mR=eF|NcIqYKaq4BobgzI+(Yxd(JLH(41j9SCbwS~D zv{C4o<$W9HHrlK!70ICDCiXo9O`lpMV_8y(9cqL7jkThy>fQ0cWiEz~b1v!}lI-kD zxf;3JfvZv~9;ebcN6^AVxQ1{60rXi^{TijI%X(=lh~+43yB+f0Ayv81X%wukh*3rX zUVoUwsVvxVuXNju?Zc}21|z;nkxi3YqX|A|=AmH;yCDB0hxn|N|&LE>I2 zVa*-}_!Y$aCFG7+e{@X3njU)Nbk)l10R@8%2~N-sE#+(sJLJO-v3~ym7oDZ%zekpn zms64<^LIHan597C$)CzmvSxaKn{if(b7IlfqxfK|$cnJ<{^j(Tj1skM{F0S{E&~W; zdOZEr!;}8wGQ0Sax-5sLVD)}ZIg)WbUaa)ZLQ0)wm+jGo2%6bN-AxDrQj2@j$d(H| zw`0Ad*kB$6X28vzudE#Qbq~II#B~1kMIf>CQ4U74f1rCvAZK7%4U1$20eIx zg>xc)R6MPny-1$l3%lluR#WuPr?8n%oL=X+j@W_^hS{{wM;x_AcJ|L87mXhWJ|-wS zw?LZjx#1|~IErN8rhJf+=8e}!p!VkHzgG}f>O{#E%%EigZnyx><_^qoFL{%Zbz2W> z^8^I)TFAfd-Mr_0o(fEUFAy5wsTgb+#;Csp2zF+ipFV6R zg#PZ^=uT-hrAX5?I^FvE?$zwUrVl%8kCW30%B*s21G=?8RQayDyd<)1-RcV~bU&XN zglk-*MXO2ZuU!i$#p4~4rE62qHQOTE%9DwQUG)6jug2s<8+1rmP}|j)FqzjW<9GXG zVtOaQPE0g9LmUoLSKle-sHL;F?FJMyYMe;eXSkgefD)*R=ZNQ-~Lkof~#01*1P!lZ=UJQI!TBjh+AD8^3j{QdyDddNB1iD2Ph_r9Er-_@@*t}5~*|1u`zjL#iwp@uQYwTXOEP=(K2Q= z!!t*R@`LxwvL~$jmCkaRTh+3s<~6M>HDQ+eX@$*1;M(_r>FavE=t(0uk&g+iHTBNy zBX7pr+Bx^!i9cwrV;Og-N@vPUDUgJ9&qAo3+=QaBI|~m^=X)#9J-BC@SSIVxuKFEL z$CF!R!x)lbMe{@W3v*{g?bu?7Tb}-t$o7^Xw%N{C!`pZE3O*^sQva8=>>o71RO{-z zbyU6~s(>`_l=5-j$NJF`hD$ZbpEAfu9>vGZRm;~lKClkmp=~zB6|rM;l4hvna+^{z zz5h1<6cf?+#6bnZ->w_v5^Uf4je$JASzRhk3VHp`BT;5U*oRiI#H&$U*j_X-@4{h= z<1~Budx|%XoCr7HHz-fUKwb>`1P2;^&*`M4mA5RZ|~V*>83Dzo3Mr#|O%+|vaR z7^7%?-2poMqOL-P3^~y7>j8$DrJqlD+otoRDN%@}FOe^%hMU)8j%b3J==p|XPMjuk ztlHKm-C{=+vSY5gJ|GfI4?JGJA874LUCJB%Ol3JlwT{(6PbKUs);%-ya?Ly)#r2^Cuq8zTp6ap!8BC4Wh~}VmZhG>0Z)d@c=~!{W2m(EJAWm=;RhpUMFut@*{i5z zLo6IxPI}auey#=UY_2bFW;V!~oq^K^rC@wJ?*MH5BUBA(*=Ry-x1N5jvJdA@x4sW6 zXLV+QYD~u}(XhOlyVB1LQ3IuyG{D$yJ+1^XI7)3{ZUv;>-+3v|KFM{5##cNd`VMrk z)HBWVfCt;6T#kk2T`{=zBE#m*?HA^T-xxKlwv{<`x*2`n-)BLV62qnTw^%1x7zs7m zt)s!e>C9cCQgxZ2E~_2tcNbP5eyioUL=EgSCyOnEa+s&$wX-kM@JwojJITE)`rdsG zu$L>{;FFut@}%x5IOFFh?g8d&^_IGPHf(KqG1gf&skE$sNYRKD-h}8+OgR(4$L@vX zTABA1rPbkRHZ7TMM#clm!-@?JAH(g#TjYepf(!zDYI?-`Rq26gl7CUT$j?$L1*;+? zj2JjTgt?UP?E9KCOLqUdtHtEi0+5x9e$GeFEfDqHjd|Zen|R$ z(3)D|p(py9Rx*AH%Vr)RSPmx;KAnBltvkCLMU@ktl=lU6K*SDNa4nKkcEJI01AzrG z<72PHYtKg<>3)cyObUzntPF8Fsalf^-%Q731{|4LWM(hg7#MJ}=U2`nUXt_GvaZm$ zzG9Z2$ea|qtk9z4ts*&Ij*-bu`GaQuO^}7UTXqa$`3zx_LuN@^m|Y2?fyyC}?;7hp zjW(Ua<}uuq9X4XXN%l|Brs_XYQ10yQ;S1rkRZ-ioMsEz1Dr8S^8$Y~(rPnr)_m)hp z(&&puBzUPsq;dc^lbLljsiHx8<3dEx>lTfAx9+YbjmKWxUcmrCc_aTiBNrPn-^21| zM)%RjCEbZdBMP;AsA@YG6!xw(tlBAYs63zdTLRaJ9$;eOy%zhba$oz|Tjij(#IZzJ zom-2by*Op|$%r3EazQUAr*>-vys(kFVX6B?i}LvRBU)1lx%Dc0ZVXx(2^N7=(vYhdCpFkFBjrS9vo3+y3+OzsoF7JiRWqDbD-o@lCdnintdjYqV` zh_=?rav7@L_y-j5JQMw+AKv(!1Lk3>)Mybc>*jfw_5y*z?a1^;~PMPmOELPRSF z&3qeJX8*BA9RPr}44(iJiwn^c6BB3Yl~YUa|P6h5bmz5PkFIeIQb{=#+;T9yYC zYFYZ?o^+K9aX(zbLhl7YVHtk|yCFgwG`I$-%^^H?SCyF%)Avle|6l@CpiF##(U4oZ z@;s%vl7ms$=iDVwz`hPu3P{^CBPZ3aK^SZNy=&DM&utfeQq3GAB{Di zQN`95KRnz2^>%|(^sN*#Gx+F010`#|HI)9mSKmwldT}C<%x_YbUe1v^JNjK9GP-AP~7oGWAum-hFZ3{X#>KT|cut=u2JisxjR0-yM@mRhS z%>3<8@!}46(WmOMRcHjC6+77WV5^4%Up45tH=hf z#*<5IiXpu4PBN5eZcA*;S9C*({3E^ zf*spxR17UP+U{vuqW1>+_#Uq)qa1%_`klQPrQ{h8J-vkUb;GZ_QRE6X;1mh14avv@ zMwhOibYeGP$-cYU?2NLAWE-3yj;(deZmXFD&rc{JezTB0hsUQF6Bd%4JRX~=4zsCE z^)ZVpwDONketXJV`Ma_g{Bu=I+-Ey<4Te zu4%MM!WunHW!d{;kPtui+-K`1Cm@8xt8@!5BHQE69*N26}6fh<^2p3KisFgZ28k#>QKEVJV~Y zL7CRH>aouSZ3?$XLF&XnnBSN+$_?huADW$giT;eF>?Lj)HX8p9L{skDt863Dk3Hi( z1g<&b4s|Qs^MD^6s0GfVT;@ho%wAd>{s%*%K~CQwW$*CsN>P}E8F*kq@#tY=;yQHw ztsxcR96j-G|AXdI1?Xud`NsY5%rTA4S%BtIa8fPKwCyZM>xMmT$xph5=UgZD$Akrp z+G{J&iy<-_zG}XYrQpTa&w{CKHy83nRsE^j7T={rGYqL4__id%_J|LjRoBy_N$E2{ zvN9pvh5;FQoMtsnUXaISyWll0u6Jxmunt7@aE>mi_JZxtZ&+-7FFDOB+6}HVUpomA zJ+(1Zx%w0w8CH8`2OUk7lU{QduKZxK=2<{q17fjB9`cP>^>Js#!E{cJuda*FGo8^g zl0-^LgiEC)Nwa&9C4j3eXS&SMklg3)WDgY?oT!aySOeff-s2z zWeSM0(lLRmuR=UxU<*ZxuIdTDU`TUMOG8#WeF2dd7~UvUM{HYbKp4Ee2Ya$ba?jh1 zajU93%P?BUBqvN|7X;7G-`XmgIX2%!lO@Zm#}tHMPNkCf%X+*Vg;*VP^1Edf8H3WB zma^IxsoR{r$XoI5W9Sj}jEOv5T|O(5yN}=Z@h7YF=8PF|k6l_%1bsn*;N7(xQ+L^sX$60~dv*!+lYOi< z#dVq1vQIZf$){Y{mkx_bnXIKWm>%jA| z4+d-;N#kiIh7&vIt_}dW3s+{bgRp(4$l1H>`3X5*6QL*8vlxXYB6oUAYxWz$m;r5= zYdBg~wnuYoQ$$d;V``zDTG`79^(=tDc)9+);WTXui5W-wI_CE*#=K5~Kl&DCKRd&V z@tYl{=Wb-XL1;tK*{~D#JsC_?KSt%x2+;^1)r84B``uj7F5h#X&9@NLiE){MZ~EY` z#0=Q!@_wnuoMf>G=t;P~$y^u^cc5=+oOm!JCB3ogCRSNm`3l`B?=|a@;4@&$0Tqpk zlJ}%5?FxO$FQkE{mQEHIu*o~ zC@{zK)5tuvwOzDbidhmWPhO0E;CZ7=0pB!N?h+Ff*9T4fa%XLgtfo20M7fOsdTCEY zc7liHxi*U1s#@K{6V|p&E5bx3ReqF)bu%Ab401sTX!!Z2W1IKB{#kSLZ<+3YnZXI7 zJyg-(`!5%s+O7xP_MsN6F?>^2_M0CD+&~}?e*IFi@x?!aUJjG5aYD+3?B?ojfi0)@ zXM&QD`tO2lU5ZeeR2ps`o*>%t;<87kUNZo$_6ZYUbrfErh z`g>AgsO!fcZH<4>JWG3gRRvZ746t*Jw&2H?r{AtlK~a2`*_m!%eprXZ+=XmvkVq{hM)NR#W_(ZC#noD1r8Lp>YWO@gG!i7Kv zzkL;^JlL0U#c0=xcsdgl_~By*KtF*i=nnt29fu?>Igw&awx9KX-=f8+W^lfFvUly# z{Af>XU@*ha-!iHj%C-H6K53{U%i{sPo#h`rBdv2)Kc4=*U!Gl67X->E=_+=sKR>nn zbnxNiSJE5qiK1hh;x(4W>_zQQT|CSCK{6cFO8l%&ob_Wqa^U~;_o<)T3%X9ryde$Z zqN2^zmjG}s^@l>*N{JmqG=Q%trsPe?vLSK*mx>YeI7y$VcO7%sl6O!1#_OmftvUhs9NGkg9PmP2xK@M)%v=V z7=+k|QCd+4p~BeuFA)R@QQuxs`-SOlh}Ye-K0`0Et*eOQlX;#M>j$j!ZEmCE2QsgB zWv=_{QMwL4TzN10f~-jxKfYo^*)JWWsvUY%!Z}iJ`-=jscfSBdm-?fg?Q@P{N%8h( zBQsZ7cN!-3JYNkR-Ic^9IT~f^2!JElyZB>u!;AVFgi>v>LLz2fsmhr2<-Sj?VOgE^ zWcYoaBN!({W=(qMXj zLw*bQ$*T;5R8spT6*vQo8G!nL7$zpj|IdS_`Wd@x6wD@?H z)37z5bW4S(JGmCW={Ml@&faP3PyWM!_`4ixp-(o8^*75ct)Q5OjbB^~nrkJ_W*_fP zV!s5J)5Y9s|H>G??%vso!a8fIeL_oyk2U{6<4pg76qw((o+oDFL?oe$?~jiu7fzlF z^}U{$w2?i>Us`f94-t9^{!IS;Tvd_uW>_}|)97#5TMA13G>$hF_Y4vDR>gMtD?>1$ zO8ahwq@m%*Rc;{9dzD+L^o$DRD|EuG8ddVArTnAofufW{nHYp>2@%U}i6|wl_#tvv ztCyZdAJ|6-j0)Qlqt5mX`9;wx@it)+IDL#me-?fKosFiXl;GVfD)3|gc`XQxr>ZnPzdzp^?rj9765n_-!70`0S=FY_HTaN`9 zyrUjKtPUQ|Da?nVbtav_i&~BdF^QghX0}M8k)wbzSsFEA9oRw5CDnXN?OnepNauFR zzf*V;TX06}n~yL5u5Z4S*bU9rXO9aNhF#XzZOL}CWvb!bT!u?o)C|R*>eM2D1MJOC zh$hD2UrI|mS5>}A?qFd}?fo88U*MFAprK{T4Zj?CT6x$I_B6L%-6k*-BxC>r7y-kB z5@XsNJC)}()Ove|bo$RaH#|+q0TQzxq(&W-t?o>kGJhkHT30f9wG*4w+COLpXJdbStlk~*o&=n^Go;F?ar$cCr+N~IUq5X@pQ>$#_Gq(-AG|=_!f*%; z0eo~X6>!pczqSY3T?qxQ4c;iI#^y(*<1cu4+gN#5WT4y^df5?xFqib`)U(PodtxuO z)tF004fatYtUWR+yK-d=J~%A7wGJ$SNlk6~!i(yMZI{c1rN*LJSZ zq&#N+Xujb4N||~W2G>_ee3NZawEP3*U4bl8>B|vyuuo|8iNPenH&?(>tbD}=Z*APv ziar>ux_6+*?WCN_-o5k2mlw}EmimVPzSh#gqx=&hbZI4T2%VL$rh38gns@r|8J*M2 zWv`ev|F!@XwqH0YPB=V#eq~G{dxPQkf@AZiajM#!Q)z{Ze~TEvdLe&Sv|#^35pU_c zaXS$><>Q*M+ckS9j9+g^(><}w&qsOfpYw@S6_GoT*ex*^6+!67m+q>pL62!S7;eG$ zx*X>ya~+9;D^0WEz2I@u@2tkPaQtKVr!qbb?~;~GSdst0fS3$JZQr5~GrzKwnzfi1 zHTl4y@?`V23trBV=w^4NoZqd9IC-a2>}pwXn72e}>AMg>uX1;=Xom{l8W4iHCR0Q( zdT(Ye@91{9;{6YiSEfFQZ0ml9D-%62N-Y4xJ6rQym90X!>*U9^v+bVURJy#qpR6b3>X^R5SK7@>uNv<4*1_N=^8REnPWZw}C9&WrH-thA&jZvy~KH+9dBkCvNR zx&vRV*=hKv5GICoR$brp$fSJh{h>GfrW^cLg)J^3`aDT%P+oo1>Mq6A0l6uqGR!cW z|M0l=l=3UU%gg`ooj@T=WD^^Wj`;CG;l$F))G|RIUw4M< zcXFH9{d6N(l6ZHLmFO=JCLtPbji%&UjE~7E@uoH_rxriJ6A*2!L=$yAv=9Ntm_e%y z3P&Gk7zGqpIfFdvyJ;(9ATb#!pRpYU7p4|flb!O;D7<)Fqwv_WeEUGA5=HdaruX|0 zpLjh{Qgn#~aZ3CSs*vxV1#t_klm!&ucf%*Z5atuJu)y-jMK5aO8&645xwAEd0o!5bsOsI9-Z^4M3|lC`zGW}sGkQ>$791B zHnDnQR12RJP_~l?X6?zhCea0Zr)o2?&-eh83#KW87~TTXY_A8mH345V*RWv{W)_&O zm^l}WaQ4r;zDJiL_()H~1_`_pNs~-@BP4WqL#={r7>Pq)=M+yQC^&rGplkfT24M}g z+!QuQp-6ij-p`I3l=FSvL$};xrKiAxFHhM<(*gq-gLJ^?yC!f!lKIot>9E5VifI+< zIMl^dJ*Ww5<4tW*@+N%@6Y2L=v7G+Vni0JBKT|oiKKl-B z#JVw86LXxh`CQY(<@`s}A+P{D{cq+VELZRJ&57pnb!6bJCBGhdzS&o*s_#hY{jiFF z#O@;CSvS-h%tV|vUc|PF1>e)B+A(|G>zlhZK`AQue3#-^a&dmQj6%5$rLY2KZG)e# zeDq`4VTXggPdyB|&w0%Qudr4RZ0PgA+DXb9>+%GknjFwxBK*&nV!nxD4uuH5(a(i* zpaabxR!@LGy2TW)h4DB?Z-n-eeub@Gx~*?uvYAn`m3DV-ea@(~7G!qIT)WNsv!P=c zQP?)Lna+Poz&GLbh5R`^T@45W5B+&l0z}X;Mk-sN`z9;Rh!V{iHZh`}%kX5*)o}Cd zj~nTwxG~LRnWCGnaIavG1g0!6q4(O`e$hdrUD6c}(GlmhCc-qBMGb2wg1l0N#DSqa z8PfKnp3Q2Q{ZXZu0eYbSm#nGfqk1Ie%FGTmS9NyI0b{+X5a)g`J1ReF?tTY=``gW1 z3Es&Zr`+cU$`6Nue4ZJ)@9axs1P9ZhnpoBZrZLmr!%t0%N_mrNDEd8G%Bpm$QFx){ zI`9H~G{Y@p7#KN3=6s_C3=!&^DsI<*aeg33IIAN`=9uEdFN*gdDj&l=WdhAq<8`rj^bFFbKmerbH-eK!VN#>B}Zk5ONST=YH88{NLXN0s7 z93KAiKgN>TIbH`TrQwN(JvqjvaPjGId}jm6;8{=^vcYt&v+9%6EI7IS`yv(vj*mrB z|Kcye0)0$%d3iNeqM(YoJjx~<>^|Qm?+xngT~wyOaDlo}*Kl0HN;j`v5c06=YbpS`(Y`x*ZSaeTnN!f=Pb16Q#l}ZcjQ|{|q>Z3PU zebFGKjI}GAsj<#G_*`6yX{(J%H4!}Skk{vzD31}|7IwP80)aoC&X1qqrI^A3wyihd zWe){SEhc+f@pr@-S(lUnArVnz;`d*(RUZ=8o?R?RqHxF$)sSTJT2~)>eYb+^xslDo z@{_m6E%@qgz5eXm>#mcK;q!md_1q8QOEI%oN8-`5s~$uDyTZy2?Tk^&z0G zy!w&Iale^~kY|hQcxzn7x7DN)vc~DdKcHr&kP}1CS<#J6xA!=k^_F+@mk{IqQC51V zWZgD`_5L@839539`aJfTfqGAty-UMj5-tt+36nMva^cj>GD8pM*nEJ`5Ie=Q|Lj3h zswY^mWfy<}`31WJ{^HBAZ~9Ftu0rUvHI#V zg_kuWtBTzko2QA1jm2Py=%hxwDfbv@q+Jqoya-Iqd3gfW+mLWVtG<3{?`9xSPn%oh z+TWxLC9~?NHu(W1NmVJ0kNcHsElD!=>*qgP1vbe1FDSduR+tpWEkh=ifo7At9y2vrfK5q?v4T6GzdY16jyzdNxo4xSDvgawzL-8l=KbVO-DE0;2XVVmMT;2nVz>V?fKR;@4(Mx(91SKM`v}M)!{*u zs7rRVxXYV^%^EaG^)2+Tnz9K>vZBI061@9<=C2uGMk62&2x5MzVE!e zt*&l8r0)A7tM_d8FLE7p1q2}ud2g;FDM9<0^`y($Rgn| zxdxZmW>jAsOBOCK>&){Hs2pWhoeBQHMlcUne~mXXv59raxORBadzp0);{rucNZJ_Hn|lz zSai187veJ0Z8o@sW`bJ4P}P$Q9%X2f~Ciswr31 zGb+a=b@N%TG#r!HJQ<-7x@Ww6)o^A}*pE4R))Sr>KvS`y*I&tLTWg%dkK;04^KgGV z?jHM;47P<6MI)m=eq^$^L?&7uNsIABWf9zaF<-ay8MbE)z0BX@r`p>B>_XL9?t$Ua zPnhgd-x@Zc%ajB>vnp`bWh$)2)0mXZ(jO$Bx1@}g5QR=DjFqD{ynHL+;W?D*nR%fB zTaWCz8qDd3Zxu}B^gMhOE8d%f{WNr@%C@UQ-?sTRD12_26#fNw!*l7pV2n`2h|2w- zGfB_#=zU#8J_>#{X}bC9rJv3nq-Ic1pO~CBUxC@l(mkdhOs@*!V0urNsZugXIaWwu ze?W?g%%{x7c{BV9i-?snNWh?S;wK}L(Hn}m*-4(KuYI03&+V1N-%ewu{LbMdjmUDH zx@EJoTuBuBhEUK$A$apPBWgs6LM_5W zLtg!sVCiOga5s9kpTwiS$Pd~ERn0OqHh@pa_IdKV zRf0i?mjXw{+&Bb!$*!~oL>jUJ$7Mix+h?a6%&bnK^D zNpyq`x>%UxOXQRQY7wzoQKf8SXMyB)sCDd-(}j6)U^39cRjgo2I|Kvin;VD2pb1IK zgnk`Hu>p-EZowOI%~_FSZZ-_Bm%JhmMX0z9cP2urhEA|_o+c@d2=q?6M1jHQKs2S?pTE^K~t}yS-?w%}DK>3LNTNdGV#?H1?;-GEzex{rcph zM9sk=>4|R`liF8g=Hr^_2ObYzx;v5l2#xpgN}i%tuUB%oog(h~J+U^}M2Sb(sII=I zp&7SsZpF~choTvi>RGAO{hqJNsiZS8Ztx&(SodA+cTH~G<_A}o(9m*3LmLZ~sJaJN2*ywZzbO+uYk&CsD^BYdj4xUl*QE6;olYlY` zC3^m+C$d;?4qQd|^H!%}*MO;F zuTw?N+cK5y)9CoYKOk2E;cK7pbA`DpWG8=jc@Rrgs*#MiJ5|YFh@~DnUX?O~e>Nndjm^RsFyCfAQ>(%`y)M-(#CD;5x?6*&c@c`g1QYek{%5X10%8$nh90z2Vlp|)NN&Q zgMP6^K`O;b-3MB?%J6dfs$49_1GL#q7dom^Z(z~zuoro6A9;|yE%@2RUL28DNzHPg zVR?Z;2@64Vwt@n3y-v6k77#U_RRy#CMnVmQ)iJjH%9ud~CNybmEEAJ@bbSx(BlT#; zO`xWBWALzK-@UhXcw+vh-`-A-aq(SYWIW?YN3EzpD4w32Gl@dM{>0J&S(c)jWAif9 zw)WJ1V6aS!A+dNSF z_7G!w+&&|X(hAb}Mf)(5ve$u;-%78m$tsk2q`h4A_F)8~h9bb=JK(J3d*hoa;|(7}S}?1IgNzVeqY1H-4nOmlsSdU@I21_Z?NLRR6O14h z;m5KNkJ>VR=(h4y#m|e&q9Gz7m&hf`zy0P7ojhmec`zt=AgMOScg>Q6weRCs75!uD<$87& z;(wROK=_qp%ot=;3uEO;BI-N%#}FB}2XZ8q63rvu>#6Kmhq0{|5( zy1!;Xs4tJ@$w30_(fe*bfi&*xAyit?)YMOcbZQeL>sP|R&A^mx+dBX(%cp^&h$`PJ z3N-^GQ(NQQgp`XomKd^A1bMwyr=_r#b?x7#V!1$5e{-N|O)UWJGtfE+G`)|zNNm}K zudS|WI-@e{{j9$%{T2)m@UXzJXwCGoa2&m&xIT0-Ar<|#U)PXv(Jiy`MY1bE_@kr9 zdec6pkitJ?7Qeau+ zP${Y|B;U%XAmGy-(Kmr!pjjmq*;lp~XtqE^pc(6XHJjwa`0Jwy|F%Nbjc^J8 z*!yDWlYaf%+Hw6meuWA5tmoJk_Id5toqm~n!(^z<0|e*HaSRofdx*zJtP_6k3c_|R zNT04CGXhEl>)X_Ewj2jM6pu$ua`8T9MedGw$-gKtq-59n6 z#|1pwZU-XvFMQ4a_m~s!c5aZt&5y*AxqKmI1WHv4-5tEK1JQFa7YygWg=$?7dW-+^ zpGa4yXbcA&^Z+MOi;YvNNtjB9ps|G@o{M=$#(;zFl7FwO<=Uufmfz0u3&6- z7FhrLLiX6@%4|KCbzg};Ajsd-)rn7L3}PN>5B{FSd8Qc8#b6j#3;%uf9^lojx`L{c zL!;~oTcxf3Rj2QVA^LsxCz~(YkbT=Tn;bo&kR1KA^DqB26JX9UmTF@?b~>bW9@t1U zJrHI2`)dI|i>d!ywoD5s+hjq;oB?-*I9 zIBaVZ&zcH$JsST5O1(&1nG2jut*AzMR6U2@XTGB0Kl}`1!>7WeK>iczjQ_biO9izE zz*zLDy~yRIOqx+ukt8L)EDB)TA;&Sf%tv2h_3Bwb$mZFmAhZSD?$XqzN_~4&$26HK z()a2pHS=uY439Q-h&Z*bEd1MZ%P(rfwqX~&{|Y7GV5p!q;6D>Qo7{-9T*WcPTOIU)U+r-hPo`06$GW9*q%PG&>$DEpJ%dh(1A-D zAj9Mjm>K)dKcLdF3#0R2Qv!aL`sZi`;H^34FfHYTIe^_E;_r=}hb6z;9iKuir9*)c z7R$h}I9%)5Zoxdix|r1WS8|cr|0|X#`?|1yr>s3Nz5b6_ti@HT1OB~v4{Y3vs^qY+0$MD5r6KpLC4>kt}3sxS>vt^t8 zbo|)5&jr(89VEjRG_)}Qedp8>v)ih4@cOqC9i=7*EdJN{NPg%3&z*X}HvdO>Gyf&*<^K}4O~Ps;)(tCbC9n<@nR#1dRFIe#xd;&7=3t`0MY7V^6#8utzc~WKXcn( zT&s|T^I!E#ayc0OUum3fVDt~f`r?CJgscJO`;U+W)&FYQ$Uj=90NBs5f6VGQpcB3k z__0&|Gyc=?^qvA;$)+M~A=@7iR=OJX!$IiBF7~gj3U_e-Z!PPyp8(YFpJ_fNXiAAK z2yXk=I0Aw>wH%E)PyTBTQ#7z2JTsmz$3w(==Em&)TI=Io-FC!ZDkNW@nd;vT!b}ciq&odFH%bR)FKZtBIa$nic7~- zF9wdTBCh$~7ZA^q3a11`86!^H;QRN$i7A3MZ-tct^q4ly1 zW7_c%7M~t^k@uDrBK5We($cb);a1l~O)Z7oNgoOzUHFv3W*-?PUZyo%sU~eSBymAa ztw^O4xF#snReqi$yjfPcHKGh2C7<^MCqD%DQ(MDAcyc6J*IR?IOiFrYr-9kyr?>@J z3_M&a@3B?IK|C0DLOAoO%}i@Y>H4OSh`ZJJ2oV2(MzQHc2q}DD8Q+>WP<(j?&s8KpbRE~?;%0Qv;v4{H% z%Uju~G;+9=JR&ukk@aYrr5QEM2H+l|a*)C&0(L-FM{|z!O&xYpl9i2NR88NRG=!GbMtXdOiXKQ zg5;Knoy@!vXEY++Gjb4XF=6=Ckm>2Cq_36yb$>wM@@oN`c>Z^!KF^`lb{lRLJoOvb zEl=K$Y{Y4ext9ZQwtB`g+^`oBqrbJLqR=7xvo8__|uYiG=7#|h)iMsaDLq%qXTaW8K zMnVx^i>3Rv}}-0E69e(tZrxWqGhoiBOSL4_#9Lc zjhRx3PCsHx8xL#L7ZJ7n)YLvjgM6v?i$4qd8pyv&+E-v|^LD!f-cBcG10^i%rjk`= zwIlf{z4i^?`{><#A`doccSO=(pVMSbkosvQP6~x|N$!nwxK8HX<;4U_uA8CiQ)c8f zRN9MEc#JlQ)7@#y@#!o{I`jua0%=MqIo3%%tbtYb6CpFtS8%MWOL;WqW%57FVz))g zNm}AHOi%9GOKaH&oP-3(dRB}`t#^8siQQIQ`qpaB7JE=7wG~E5WW?rpDfDOtjtGiB z9iV$ydu0A>zcb{n*g<=1=v7vy(U6fU9tKZ@i0CY%m)gdfW3o`JxMV=@tO4j}M&m$2 z^`-HIU@nq);n(ECdVRk31L|x7wOdLJao(>_CUuh688#j@wu0Pd4_WSBbuh1)+|mnI zsn0LI-+8UwNKj(uOQpPs`Hd9>q+XjW*uB4`jTYj3lmZ?^1-eUv+#LtfDS}YSLD+Vb zefnU4i1liIt)Q)vEo0A#!99-PUfALVEt80k%8R*G1Sa6wi6OeqMDM6M%`=qO7zz;i zrF{lC(K)d&ykuKeV4?e_3mxEjGpUbMM1M2$;Rgr}R~=rf6yQ!n!faTcf|_ql3EKJ#~olG^ze7`;~yQ->@+=~?$B z(a<`{2KikXw5l2v4a!HP5^0b|0}Y*qk4$v+Oco{m+Ga125fRH<`Hw*#9EEBW&MH%b z+j=>3SzeRU%D#-^vsZu8?o+2`)Nw3e&AO#(5^T$Z42&{eNisFIlVJEZ<*?yQ^Mij% ziC$`DbDO8vUvC!rkrAxskmi_tpJ4w<_ z-)SL*!9%FnV7|l`ffZ49M9OiZP@)G2la}kyor>{t-r9vPdx;?U=4;(69Z85w-C27b z8dN>^uM71TGILgNrYD& zf%|t(K?{IjKgMOsdZ_5_spQ9mLz7gHqGb^F!$Em=RonL(sncJ-z;t<4UZ~f9A4+S8 z2-JbSgYP9{hFg87qlZ71)wGIT_jo{!Y8NPPcUg^2PcfpUhD2JYU7<&fom1&AZF{~X zdl4dd@>Q=r|9~Cg@)#uuA<&E-gi47r&Mk3z&67VW(H65sk^R7kw+`+09u-A#x3 z{A8g<@M%!LGO{_h5-j-xQXd7TR6VKCzHo9%5dnPo+*nHN9Y8KLP8zg&eBq=k-Rj;L zq4BaIr%vHpfZ-3?`xjjp6;22?=fITVus0sVB9JT4`+cRVk~zb!09`bcpnBUrzq);# z(}8XH%Ii>oI$4DZsUYlz5YDu*cd&7B0bK_2gmcLy4)$e#GI?k3j^+IU6(y1atdAt- zz5A?~ta;rU64p@uc@GgDVnidKYimI914_$^LWGFa|U}iiC zU_jLRP8^;d{#Gp}hUvzVtnu(IW_As=yG8N$C6b~h;`1`9-MxoSzN?Ow<;Q2L4XZ0? z-*zPOUc$|Wc%yz%BNjqHM7_Y8D7#0ERvP0=jn_nLD{)r|zCR!rPnp*Pb!cyKV^l1+ z1HX)aO!c{c={OtlYC=9~RkYlJ)@AT^mt~K&!y%}NKRqc+8P~xCZ{qb{Y8ulpu4P?k z)m{%>^{Xau*XI;YG8*59B&cB}eJ?16A&T|L>aRo+WulvRB{_b%>}*AwitTQ{5v zY~P&}dX6D&cEz;R=SgWl{l6e<$qH5-WmXmo_fC}>M@mU;_JtG=nul4dM&g5vhiLQ2 zf>(ECR(6aQs|PPc5ryZ^n#Jk?O6|$UGp(y1L!iDnPrZ3VnClLynx3KT-5Kl@ zK^(r#TlcmTr8%e_iS!LaM8P=giMw^mrg)d^eCr3FKCi)}UF;(`4VoT_7?zcw9T->XMNc$2yl?c~Iu_W)nl=KWBWcXD*RCiCL zuwV9mR?wOHy`wB2#Ohz(5^_~SLQsOc`nF+X>wD7IE55kt$Xb!0fgEY(r`cpJBTlK3 zEWQDcI6NnpA0uZx9NYdv9Dk^A(R4=*@INzTT+4ESY#I$-Zao9QhSg*ckaKNDOU8h! z`tk2c)-oj*Zd^M47AU}=kk>@IJ`OqYO3UpC^h3flNyXciS!k}x{H;zwX%Q<1;_FSm z;p9(hMHY+72UJ`#(%e0w8#uP=+z&;Icv!0>XW?Nfm$UM$6bszU*yK;H<@BL?QeMah zeWVX@cUTGjw&9gl+7)(E*Z)LadwKs4u-Uf0FCEE9^_1EyHCwGM!_ZYCJeFC|AVsTHQGp+)f4tj9+9{tztTwSC!PUao`K zmRf(0sbKMKE#rH0Fa1LKDNN_F;|R-DeN0s~F9)ijXVwxeD_x}f%y5CH?#ooSykh2?P-l^x7pSAElB0}MaU248_+Yz-Jn955dU;Id@l$S`4B~ntW$~bR%K>u@P9fI z^bO^8lC;k>L907xMXdXxh1~esc1q43PIdp}nc96Jz+^8lC%hj&1Jct#PDp)rP{{#;7P_5cYp~$p%89$)6~lp#IIHJc-O{Go z77!d71|B;kPi8t6cs@xFi-J?m$=;pQOt?vY8$m7%rW5n7q!|mA40yFxU&cD-lEMat zYrtR5$=jJZ1=2q10Z5*`C@kp>s$m}1vCVMihTHl_G3ng_>Q5+}ICftUq-of0;-uJ< zq|p1_fD3GFW5hYJwY(jgJ`|V}X|FjWSYKXKZ%-U@EBB0VT{U!B=#D&&R{aRc_Yb41yh;QgN5$5Q=VW*&Uy#sWap!~!ilWUETuGBz` zJI1lblxYH}1iu*W13n7BPy_Db^KCu94Q-%~O!*fqF&)0UWv#~Ywc)^ztUN*b0hi=c z8N_14aErlUl%^R-GQLy2Q;ADb5wT!F!LRS|g#5l8XH}o3uN_<7yK^nDnE&na1@9hC z)~H7z9!&#SgC``fRw3ma0fjr~nruf-DsM;zyb6&=2cHlB&q&<9GDUMa@*A3l`} zy4^KWFs$#pb#*(B<-rb#K;7i;L7FyE0AF^QQ=(r<007Ep9Oh$fb|>GMst#l{XL3r9 zI<7Wod^`LHWW2yMOnPr$Wg0Rm%U_N#3>20HO6TjZ04txemb1Gh=dYeJA&qR3 znE3;8Zr)mZ!*MTpLR>b<4?0K^ybh7~ zGtJyq?TRQia+yqRv!!p-vE6t~=h(vVD6R?WAL;ojs5eB0=(K9;-?+x@89i}RkRk-n zZIkEtabRD~zE{NhQzGt88wn4ji8UB1<9?E(mMnJl^IfVVndNVFXDqvcG$@9Zw`Iw_ z_2cKw8#WU;d4quv_W<#gjX24eI)bK%qL;Z7Z9Ur5klKm-L~1RRf-*)N!P=#L=Zr5s zqtRVoEQ#J`-*HTE_$2lAenfaNrqGT#!XjhwC)C`ETqyO|fo9Hu3Wl&g;rMk?`=*J) z8&!7qLcgv{Lh{{nor*D>= zqZas<{@)JD+L9fc!2S!;8wWGg+s~(cHs6L%>4ZA(=4Mz0b)()}_bSjX$}mVcYq&bP zblkw|Dziu6QFTiM22FSbvJd~YURc+U-$++BszB;eyE?1_cbw+4Mbn%#L)F+ z<=rT+UndO{Y|4DkKre#-9e~m2)}{NzSXOqik`;1$uq^&od-JGLi1BiKDk~b)2ZNc@ z8IA=!sXG#Hyy>s5dEpww$$fy=b3DAPKk94z#;QDhCH0HQ*0=b^AKc~GH|7cS(}OJI zXgL9q&DVcG4AmgF4a9yrjjYH=78uoomtYEK#2(ZqU!(>Dy>`t8S2w?>`zhdx=p6U? z08}DaMd@ZSDTSZ~24;M8_cJe-s9*HEdHmRA?tJ+$H0wN~7hLC85bcc%tJgC*LL7R~ zHM1^Vqxvit&`en~&BP#~Zq{ZCY55N9+nHdF`1Qt2HGo(=aLD6oBOLD5b#mry58^ji}de7KQa`gp|4(UwI7MdV|_=q9I7rDI&}#4Ma@~kL=oE&t_*VG ze5hzJ{hb>sCQ1#sm9_|}pu0nPuVOh+;}?rs;5olb z2_=In2c>M4@9i$v?;m%yYnqZM&1<+yh`2pR;MAx&Ie*+-2YBk`6~W&>wc4lI;#q#?3-_d*#VDM%NYnA~N+}_1;}6KF z8alu8=m;%+_iA6ir|Lz-iABS%a_b+^bhh-TE7EGCp+u+p%K^i>aF)LEi>K6?U+Y@L zWUapj(pVo&%%X70aDXWr z=g%SmvQ$wjkk#jiOEaN@$D7kmzK|-y`{(x^jbN42tC?=UzY^MX%>3SEBNKlFB@9O` z!r#_GN3`uvZAO?)=`1yY0IU1fd~*=$47*tDFX#(@&DEIGvs& z%-eCBU0A=uT}pC^YvdM$cXmDE{)OLct_!v@o=h5J)nAx7``vLv8IIhhWIBT?uFs`f zKQ7TOnoIVm7B~+~%eB7nB{`<{y%s{{o9()+x3a>&$#tJ)r+wg}lTs?D@U215B zZ4qBKY2~Y}sGf!tD@isdWNmzOQ2MK@JOu9_;%39DVDW^B&@|4WIq6TNk$x!p<i&r=tQm=vSLvp*pG^0R8=eEl6LtAD^_mQx?LoH{$B|z3Zfc05W-2|QJLSn7 zSRy;*WL#g(&Np5Nuh`~I{ElyZ34X`WyShQoC8(fo;)CI-gO?0YR=4mRZ1G4fLLDjn zHQV^v`4qu5PVYcKs*x4=5|x;MghJH@HGa}NxRI$8;JE=RCQ+J1U~fsN9(nqUW$iJ1 z?=%xTehcR=5i40})-Y(%D?&mjLJ$b#%Y@g2P8FeFy-EDSEfrUcHOn3r6EgfP{LY$s zA{#pq1(NDT@uNewN|kAzneKWgidmQn21Z1ZRpe;r)SjK8@zg;A)Grp;7T7(_Uij)5 z%h<88a360q)xs2X_o^Quu%mI{IPx65p*8bM`V$zIRvW);Hs;1v^t}UIBFwd7`=S}~ z$ir2#r*HEEBl*UaCQ{uMZCPZ=D%H#IQz%VEM3SN65~yMr5)tn#aTRJTkq!rz9$P{M z9KR~w9NHdn;d8$aYdx{>6zj-(yJ7AC?RwApdT;j%_%q`*`Ih2Bn#QTJ^}I!nrZ>DB1XmItEyYm&MVhQ zYY5nb#Qs~V7g2N$hY5^1=iAbs$S#0%xJ5wK4N3>Sbb8WUyq%^)0UZA!QbsCF-J!3z ze$~v>J)^_pvv-fuv`votC(5M#+}_VXO*at_qGi)`TIIu;!M8`nln<#M(E*D}NI}2J z9FFM$$jw5|OqwhDLWc?9y#gmm!Y$iW)_#p2-kxx(zX3d9aDje$$bE0$v1cEa_`b({ zRNS68AUc)I`dRksF4!!6&o5J`G|DpBquhAQCo9vw3<#LCM!!Thz2x0sLgQR^1=9B^ zIm@0;vN_p}Z9_)|7N~uwHC$y7uU90$GOJcVyuPM5qLatUKSrWmgm&_1<(Ea`XB{`= zgS(fx_?d=Nv3_4YAcRpl*KDuakYchfhP{fPZ>UQ!dadP_5!jJ>o2;T8gBk4?T(-Fx zo_7L?PJZS{sv1`35HKZcm_+F5iYCNglF9vN$;_2$nj@0qcacxuHlPONNRQadM+Xw$~}%Xv3_^4;CGd`Qv!2gQj4 zD?7J*r`!3tnA9YWtsgRN-jP4?KaRb;6ddP($ezi~0|$<7PX$@)5;KSSily2GGRlQM z5c#eo-f-m5Tm)@>=TP0@p7yKB3f1*re?XTT2Y>5QeBSYGeI&)y@Oe5nWAfA)MjWon!$X3enw~jFLSGpz!9-VZL@i&aFt+oJ0+**2(*V>^CqT zq#=D9%N<^C7F!L6-q49#m?!pPICYm$MP6YWQ@8wZM3}rekY1pmdS%hp=|@q4(}`BleaLnQ$T!m!>`>d^)RW{1@?ZLzo}S2b z$vdz`;EvNBjJ3jV5`YI{08{zSvCeU5QrM$bq~0POQ)r=)%$r;UVY`J46>fumWXK+w zbga{q3SUL2m@5APc|o4>#GnCThJ>)V&yD4TVSQ;dtdq-) zUAthCsad2bl#E1V#o|>_JyET=%ow(^TD)s~FVA=QuHz&=250AIfUTfKH_jx(FQC6J#*G(V&iGn}_p)z(u;cz%{`}AfmB!K)CDGd`et3mu;0z}(xi9ip4iNvgqOX{!{(n&(epF6CD*xx zJO6quRFaY!Bg#GX+O>$#hBmd8v!XQ)mN#^?3Yoa31l3UM@JdM_^8R}Dm0OYt^8;mPuqvOA7K73 z2k`FAgF1`(_e5bk5BBCy7ldoMMh_hSnXOF3#j(nFgA;sl#x~;Sw+z#$EZB8UL% zhBh(hic?bqyg3gECsKA+UK3ePZNbMH^3vJ{M>8*D|0bCs6P6&%-tv^LZq>PX)FPsu z+EyyI?n&MHL7JSdAt5~{6rX34yGa?(@qH!_Pz~RJWAo5OnXJ6&|dEClRLobPI7%=qe zjHSZtQNPn>sK>|s6sB?vs=I^YMju5w?16Xcv+_eIwf`^pKA;w%D4 z59S>b_&sTUiY%@mpCPR*c%5IRxOrDm_HZ^DHhrmP6OMif#w3dj$KzZwHW>4V4wCF5 z`7Nd>JKi7d;H7Kr%CL*%e5BNN!<0WDvgNpYU+p&nJX%9j7W9Yyt3g`CeHCWG2-U>yFO<(HQ9VN@jeFVp({O=+Y<Ia5GK3q;|6-D8`D^Re@qLE1oODb;ZFrg#|HMum z_s-PV)TZQOW(8UKzLcktk!7X61IPZe6CcNDZ=PaNrZ8_Q*|dkSw)k@4_CX&Jc(k}@ zc6`;Vr0IAntob*+Q1srA1RmQ#O1h%ypH)hH|E-}mN6ebrK$5|)m#N_hS3Pz7f)V`j z4J;wO-$Xzt$__ipS8Lt*#IEAzE?RL?0W{-I_tVl~fn=)ukvPM0Uo;!3?Y=bI)avDt z(^EN>Ku;EcsfZ2c?tTt9Xh# zwaZuCzW4Ar4T#+x$mVhQ%~P59O>nF!rsYE_kgD$nR1neC>5bk>`LZI8E~)3Uxo4d; zB}Y!C^kSK;G_s?OMgi6oHx}}69oB-WRdl#~Uhd#xU*2}5RvxSUJa^vSujywD&(p}3 zMakEx<}ew@^w?TE3noFVM?_JXwH<_6Cve_#pmdPG6N+H%*RZrEzpI|lpOIfI=G#`n zbuWe0!Gh=o7BDZn2c=M#uA!QS`CPv4l-E(b`j&mqN;gh0E-}C@oziRdbw%MPRHyLs zb;?6nbBH;-$ydf!S(URiMc2FF%Tu{Z>wCM-CIS%;A~SoJspJ6+<`jb8`b06lFkdLf zCCkmBvU*0{$*)yxA|Y~Aw0_n285_u#&W+s_Q+IIJ@0-H*ifo z%{y%&{gmLWW5isReExv)!>GuXymI`4)4p2hV+QG(E_0GjXo&Jm$*sC8Uvsv6OE5s0 z-*Z#Rr@Lg2QJw0u8(b3gtB(t81bZi(0F(g*eHA%_A@4_d5v99N+v!_7YJI?=VNt9= z*0;mV!im##^3i3W?kP~MBy+RUD3I)Tlg@epHa&tfeQDWNlo~|IMOY(``CE2j-~!1T?2+JCj@0;E6JlN{(P+h>Or^e za_A~!5-m|zCUTtQ7p?Xl){b`vTo>dew=ekDpd}^5LT{1Bi+;~8@7UiY`T2rZPP_)> zXG+#EE@rzFA};F)f@27F=tSk|xchJJs`-lk-^wfzPVtW}Z;8Uwlqp#3Cw=?H?^n0k z4rv?T=Pkoti`N{`cKXq3yi}ebQh{Pe&()_wtKZy)ggD$c$zM5%)DpnS#fG(*W4^9o zXvA`aE+vXwilVQn#{b5ILqY+6i*}MS-mzlbGjs5F@Srgl8=7L5_EP-~qGST+!u?G<(ls$AXB;jTe$GH8s;) zB_By@x3~=%`@{k2uxN)Wx!>i?@utMgiRs$1k4gICarYVUzt#^RKc1^>4QKSoyn4u7Yoq{dUMtv2EOi)-?8?sBVv(Bnpzdk1|#1hgErmZ#HK58rk(Kq zq!2Gx^tjgE%KP5{P7nplF!A#ss!wZ%IC*0y<)+1TCW!NX4#Xu?a( z@MQzo1yiAYkNC7bMLKZ@Z8rvM0}8?6sAzy0LZWa2@a--JYeO*-lAnhfr4QQZV0pmi z!FPMXOE@+`_UM?}>n4Bc_256}@i`UD^K0t*S3Z6$31+-!C1v%_34xQiVH} zH$IFQ7-<9SdQ}E0vwaa`3wFkB$m*1xWg7%r_FwE<#s9*-1*Zgv2)%b2J(bD0b*tfP zhZWk8%kdH>zaY)0IJv-!Q?Mq&+y~&bt1Z!R~?9TR{jBHyPV}dJm(g~?O7Rd z24-QgzaegRt8>$_ci>ZQ=~C$=o6l&36fMmBot!uYB0?m|Z$3iksf}{zn zhhOhkNVUIgG@6UGtryj@HAj*u<#^*h;txfT@7E!&kemJ7wt5>(g~g13JM?_Q$N|VN z5x{oNj?Lv;%20B?rUEl;*(umk$xu_fYv>J(Vvpn?#y2&#YEsPkz*Rn36)mix2+|v4 zPap`a#c2wIpc9ODTPP}C2KCf8$rY)!ruhB$kb7}k;x4dcBmCbs34m+=yHCJ)Ex3oy z1=T_URsQXuJ0FdjWA3CB!FPp&F11UA;)Ca3A3l!U`SQ3!Q`VT#7}^w<#uWCdl*NFg z7vx0YEQ%mvJI27t_Z>`;Inj0Rtf9v_^He$B^Gx+iTo|pT9XG|@H&El{%bE3kE_L#hVu1y|4g@5e!zp{5RB9+nZ{zXek%bXx$oA?T*R z>3`z?6Kyby{nW6j%ehAeKfl1|9z5{#J`3o$r&H7=m2)ArKeoKA3(chJWn@PCS92As zp%rMZQ>EPj-_};7qKHP#=0wBj@r(M_bLF^aJH`7kd*xfSyHK4+lPfbtZ$l zvoaJkr_v69=l?$HMbt(A;}anL)X$$7Uks#;2$JR6B?ouAw80pjJB-h#A1QcU0YlwH zWFVAK>Hv~&XBL;Xkj~Ie|4+9Fp_D%ysp$6BoAj+W93;ZlT;8xSt3Q+=S=F{(X68TI za>Vzd@OfEal-sHd;Y-V}Td72->->E8HtYLMa`8+v>z|8JV&NO~B%)6P7}&wsXw))| zC>>;)K{8jQLBa*vocWPG`wMdqm~Scg*X!5NW)YG5!G56mZAmVv2pDTDqzXg6X3ntm z^T{y_#i@@1r8KVqUBY$U=KqJd_l|0!?b^kIlz})E0|D12kE`ngx$ldKKV~K~nXF85 z&%XD*_TJaEd|sSl3_>D`oW2EDi6jN%7k#l-!NB3BzLK0C=RhH3+uBp(C4=vxqmp9k z%#%{+a*7o`mY%<<@Vn4N5R`Z{+Qwk(5aDFj# z$&wOyW1U)t1nQHN$Xo0p16VZ1R- zCnwzL>}=^bDhXpkO7`+xUpF-s>sQeR>9lnWcOAhcAGZr<DiMdb(a~I^2h9(J{-< ze3_VgKklrV;crQeA-WS~XRWlzGSApq9Ts zBVs^rv{xl7e*&cYO$d5ofKDn-9S{%!HF&297F=kJv?Ifd+N}qiaA)G zj9q(AYTZdZOR-h_PhW6C+#(GhxNbSLFz2$^Y6+}o zd)|AEEPE9W&R(ULZ3XeV=i`1J|+Lq${m*WR9e=-Nm#S$_ZhG%Q&h z;*2ZVUc>*SfDl+UXBxwR`Ic$fNvd!HQv0Px z)TeD~2~@1#`MK-0KHrofS*ZlNokz#vbD3FRS}mKMQ-8d!)$5v2G7w_Y5O0Q%#pj4O zDJ;d~wOt_z%r#izoYx7~XuHwP$?Icov5?h9S$N5zk7+Ngc;2ra10%L@Czy9ojLkd` z8M~Ak!Qw5n6xN@%sjntIqQhO!LUVPK3&YqgNi-=4-|=cw+uX5}N$`N6z~0HB%+(0< zo&i+r4^mo%QGpYfIcL536)SYdyC_Y4&JnHoZcw-|DW?8Jw5GD^vFytwVhf_v#||JG zlfL`V*(CCett3igp$vLLKVMu{t2dxV&McjL8(<#mN5-8^gu8Ec7}?Hbrj1>SkBwSX zl$Qle`A6kNO54gk0}Wn=?TBeH({#D0afdNg#w2-0%-GgM8O)rz_tvFR#Hmp#1!*4hC{uTStg&p?ODEr&m)$khF9%6J=g&QSGeHHfX$6Cd4uKkAD7SeB4;)e3^%t zmSAIB|M@l2@eX;xp*=@_MWK_TchozcAJ@&)zSEP3%Z7s@b}#cXyU`$<4ej0agvyim zM3Ah+hd8;n^{p*2J+q2c@a|}28K1@lz|gI8{4Mck#zRI<7|0cN0#UvK_{wuBIpqIajPkvc7 zxkQ^|r^wjg_tUyyOnjXXSswdysdx$@Z)LeUsmwRYBW`&Qe-`oHQAwMepEGb713w;y zO4dt&Y9IBb8_qgKkihWximi@)(ij3IJbv_%&o;mq5gBDWHu7(Y%IRrlcfhUZz zl0>i~MZ_~9S|X2VG!(cftZy>f<-JxC{LS;{^Hb;Ew>4k`z5XhbT$J-ThL2mBo_u8= za6tcz!-gvEi*vZM_;ag*>Pc?k{ktZlpgOq$Lp{n6rv%VO}{Z0JJ; zMA3!SUw|~j%HPWjCm-W{^9##wgMWV~(P|e+NL}5Uql9t}I3%b*B zNya}(kdvdz8lM<$8!WkDWG!L-jBU&%{ijsAGNZFlvZvp~#hG4>JsU^qMny66A&DB+ zMO}rFd;8b3X)$fXe(OxwGPOFZjH927YVkde$jr=J)XR~)By575teiXu;6=fFYxdw$ zvr^a8{HrEdrMSc{0bw|s8rC_@3LwZn?_W)vn-00T6Bz9IW)k1IQ{s|(ow-yPEnM`W za=w_gGx4OH>LrQ_cwL(UEdHXJm{@;zEYSfEN}h8uoN;0^NR4_!r8>Wks{m95Sb>1d z8}F}^=QRyj;50u>Y>`?mLe}W|%W9hRA}&sWfGHG=-YIkb)SA7Y;|KAp75qgNaZU?L zRfMz_TbC}{%=-{LAPbqXqHH)1xk_{A#pWDo?v-xXmMb9a&!!oIl@y(m9HSBoZjOCS z=Xwyo-|FMWY!A^)d4>WZ_)~vUbd+1`~-^@F}7~Nqk0TF!cy%NHc6|?R? z<(r4!8^X&W3Ui+di=Adn_NEeGa&t{0_RFv8DD3CfKWy<;8zb)?ePuO8%6%>uQBt=6 z5XD?vZzuPA>{E#VUH$01txfs1NSLhyeaV;I3zlu;8;b!F65~S{)rIKLdJ(yx5C#$1 zZeC)q@NDl%9#_SbpF5kJpSWCXZsZFtMY1FFxDAi}UTT$U`PekO@k{fGN){Xmr;lG5u&4@j!?1MVk8fY?l^37_V*jL8fJ#M&?h+28g48Kp+em@7GlAo7Dsq zaqKrwvoGM1Y8xGAW5^cA%muAWx0Q&|Cx}6A5q9hiyoh*kI!B7X_#{}fetxmqN$&kn zAs15Av*wy_NP*OoVHlNo1W|eqhA6mDQmGNDu=jzMQ*}Bze>ry&C`@%a;eNXmgQ5cw zU0}74jU63hKd3`_{jQ-PK|;BEwdtuj8(nbaLeaA414|Sip`Ih0{=l74y`It>8Hfp~ zUO@&{RQq|U=|2AX7*iNOKsk~u6&j_btU~_gT4|wjKkjs7pH&SnrQL(ZEHGKTk;Ywn z%;gz&pP@vqZg7c2u@I}`wby0icb$#XeR{m+iT(D%eFL5CtCBL3stA+^c}6-UJw$p1 z!uaGd1+)Ap&aifD;yubiD0STNd_86`_1XULNHvf=Xl#-^{YN+As>FKRg~Im0Cv$We z9`JO0Y6@TZC8`np=DDQFe2TKS0y&JOjpjx6$@N!$kjK}&^MOiB6|PJ&eUHZVbS(s^(MY-t_p3Et-BV=Cs{S6WT^K|UXBm|8 zGXHt^R$Af8h?GB}B7I*;P1iNh(~W*}EofD$*7X)<6)YKUbo_NH1}aIoZ8LIn6fiaK z^umKXO19fM)=fTQ5I*e67HeNJ0LmjE@!K-L)zBryf#!jomHWb}MpV&ISi)q`WRUpG z8UnJPq=|Pv%d04u6$({Ue_ct~@Zbr_ED&G1+3qPG#MAFXptw#v`gT3kS+U0NY&qrf z`s`Py?%(%~!4r08qlcnvZFGE3H$i!OmqxSOUZJ+E4<4D=igh@m)oseky?m1QQ7^bU zdRp!I02}<=xF$@}0zw<1sLdoH1Vu(NzqBW@uPL(*133WX)SO)raq`9)<|;@ttH#2i*7RB|2)y&fO8)7Wn50=v z2AeTCdjh(*ffy*GviyySCwg1cro=_hk>IAUkw|cYRo}k$?a^3Y zIB2B{LbVA))DAoSZrH6Jz-54VGwZq?9CKbJE<%&f`USA*v~(Y zK}E<^|I#bAbbRtjA=P-hLf811esHhyiDeUCa2#YkmY<7Ss^ivzMEUx=_-RRC`C4ty zGS;wbalG8y*4AI4(|46YhSnu$nm2pAUJ0%{7l>x-Jf5mNHuRH+Vq4RnO=W67BK2+jAE!tFu!$Z|%#e68P(dG@N%vI0EV6Fxx zXjTf=a%9I0<$gXikS(%UovCal5 zAt9odPl!kSPy&r%2=j6GG;yptw3_!hv>-WQ%>^?>3Cn6*jBu40a$}C)la-1?BHx&M zwHILbKMv34T0cdoDMCD-67M#RHpYJ=l8S@!2Ny-Cff(^s#OKqPLa&9qi>Cyy(%fT@ z&t4@(D+MAQdMt;jZgd(R5W?PR#%6mk0mk9MLM{1Lp0E$Ik+c2gRm$X_)(I=iQT13& z4xsZzF~0EIP(`Zev27Dv$4~h-*~k%31@36;!fh%lP|QGd12f8u3I%S^#wbv82ZoKg zR2tjwPDZL0ZSsF|h8`-5Op4|L7z%L|ep_lIIc&M}JQK6Z1(}3mv(CtmyhoPh1ZH|+ z^81O*EX(v%ZUa=Q!x97mNwIdT+>t4#j*{DKz4!RdQH8dztpd2~a%;$@hiu(L?T4Kz zl1yfr$Q@>WXQ_5^d0U`92Or_Dzp9lqN(dmB#<`S7*_&2GjGgFi3mKS~Jg8xfrK$K_ z>`~c>XXT2?%b1h`Lh3TfgUB*DIF@v8q8ZgF`WYgXljI5$gPBQAIBU3Nn&XV^$lC?P z-2QFm%?&YA;iSE(X4ER+e2CFo3o=Tpr7aTjcvn6*Z!)iWWCD4`kxkk%&%*-FrpWMS zUi2>jAD%`ubaq#&n*l;KH@iQyo2D_0!#}-%Oxt~n(^n=-NVUC80cVbUyEaS1R>YZ< zIrC@15AIZ4abepkpO5Q1x!2JoHI6X7<>UHos6=#NP_c43eX;gN+=5|6Tx#3aqsif2 z;Bz&1ZfF-buYl#j{Xxqv_S5XIGu14mr)gOJ)8HD1q8T<3C**}on8JCEr5nonGlaT_ zJIKsT`!+yIM=eaE%<5TZ7%mq;76f$vTi+H(S(SSBqSm;S3_5XK^|T+@5T9T1^BrQN zc)DUiQVmODZ1uul)H!6XkDBepSeIq;p^jFhTe#Ami!i(*L-2ZmAF5swh=QFXtDmZj z?N>Y+U2M4T<}812W2K?^7zFbQ(2JuIc|s?c7sxw*+MZj4?YPyseII)`C0S)`+pOEY zMf>a&_mSuV#AvzuQrvnKePQ7;$8_?Yx40ISu3gp(rS51GcUWlW z&Sv-X$4rxj(C*VaFxyjdPQtdL+Oe@>I|6BViB=SFIG*@4S1GT23#A~d4q?WoMb@g11 zF}yIS*RRo8!1gWL=HlAU--yG}xVXdyF5>Ex#9T++qW7Tc`W0E{3BtWt_yz$#X3Dmuj}y%+Do~F&ooVY6`E?h%}vZ4r@8|rpJ68iQy5E8(ri9a zJ3#XA>j$_!kRXme*8fG_p0~~dv@-%!orbNNOYfakHJ*?l$*>4nVAPsdR6 zg$c}#R(A_hDwPLDhxbll%(IK$zL=3XMF&KUe=w-9Xc{w-`&sC>P?BNO{XdsYRHUlK zw@z|Q*gtV5VKdrg&Y0m;syV$Sc1j6FlDYC>CUQ0~d#k64#}GFBvDcprA+x{E79$Pu z&x-jS?vkw4<9SI*s3nwv0|CM79$UxSOR3?)qKgZ&$HlNd=J)^HXL^HLAd-JegouBG zlf$IBC2j@bkBg^w@3w2^3ZJFv(-SZlN8nWZodb6T@6-hjug(4SP%|93yA=R>`AtrX`yB~vn!eirZGB)0K+6I1g7>C0x{C$XYI ziTKX2AYfK92Wzg2w`TRu0BzuiqzJF!1L>t)Vltji;~WgAjZVW-0FBIE|7a{%6V0Ln%1+zKt7 zeSGnJNf?K7xKLkVKT=}C``)35nWucaHjj8f1opgP<#GW(++xBJq|^#O-;}vNhR`+? z=q@NvZ&D*Sn>@Hag(BNu1j>4IeA#{YGVRs$$#&C5VOT_M(0rX*+SD)0iQyulCyLVk*37(54Yo*+FQ{kuLI;%%HM+r#%x7C?q$eDo^r_f0gq@A>?R z@=y#<8)ir6qRzgc$XTpaeDFuR`j;t@+5}jLcr>b)wz|Jsd(^Mm&&jZSmS;|D>lC78 zRUaAIHspWfqj~5|!XkJG7*FG`MqQ8>mafK~!#_Lllda**(n?q^@AN%e5jAw-NnNt`THUMh|Tu#XKPYjqXo=aPRjZTAGkV$LI(RGiSGE&fAr zsqyhWqFc;{GQ?eBZ@!ntzY+v4frh0e&lG&E-HzJxNE6ae?B8hBQfR>de5GP<1UL9B zx+AQ%*uKo&nigVgGKn>PaI7JeQ!A0y?wS5E&qetM%?feUT{`ZOtn-TUaoV)zWKNp4 z!*-yOb*5I8-?I`H3E9E5rWUgqE-%q8QuqNRC#xB(+7d6Z?*L`lOd>gcuG|kC-STj5 zyYi~BQmV6im+~{)PlWgMYn2_th{nD$oaU&eak(S6=jS^8(0ba8{?1V~BF9R=Q5Ofv zqP`J+UsKLnGoHBpuT@*$`_3Qv$-a~P)0xnF3vTi61dw!eA z=cpN(Whp|UVy0h|m4=kZkjK5)G39rWmf|3rX0+4Ud6iVt>ouzD+^jXj9bX%W)X%0K zY65wFyP!2+N6h8OK&OakD|FMm#KW(&T~}tQuH0k6aON$#Lj5~&<%1p#GzjiotGh9k zot>4@WaUoEBwYluE6QTe2#{z}NvX+ttu>=>2qQxC%kjgBz^{S5uBE z+TNZ`jmerwS#cvs-0F*VtM)o|?GR5(fJeYqLVUAl{qz()^CxSo_rMkpHJF_H( z2-AR@OzB}=R#Dvb>?#}!m*O*j-p@>CA(NlXuH?R18q)}HD7ka6>bt!1gIbCDeO^&pfFEzU1L5_<}GCtGpfCbSfd-DkZVvBSe4a0D(i}!C|1B)Eohi4V|r+Pl- zOdhFV?hznWV{9jxhj%KXQ+3eS`b|pX?A}?uoK5DQ8k;$#vv5cb4V5VuLwx@!+J{2l|Gllw9B99ZI2ZXHd-j3Dz|} zt09ZeQK~NcI;u!%YwT7Z8xN)nK}m_n$XAfSxur7KHSW~}A5x2e&dYj_netM{`iI4% zQ_?Z_-|l5%%FBpo=w7$eQG9&JdVGA`O7~(=ST!-`H|H^LA=)rHB|4E;)B;&A1~@0p z7gKc=T*;A$H(qfJW_U_{IU{t6?9fvfGmm3foqLyc_!|8Vz0oQ zknX*X+#m9T>z9bawB9`&^c*O}o4qV;&$qMmX^r-qLU>k!O~uDA`sdbv7|+2R9^x&y zys#Qs1~Ep*-*Lx2a}~WO=_a4G$L&k-NiFBxAvskZkoaa6;5FD~`Xfr!hRWnYL}oC1-;V-Xd~ zKXF?=IZb)&U{u27i7AptT_&|Ir_csmXlEY~`wAfU>0|d&2n~hgXQieXY`s_sYoWgW znAr*9g*E8S4N6)wk-atrVP6)?X=aMx{)Fp1!1T1&NSEmg6Ox_?jPBb+mwkwWRBC6N zlx^I~4(pQO*Lg-i+FZ|*8nrET+f=O5gbv9HXjAWT<`US?ZX{?saA(*5O^6tl^(kCe zeH5d9eA;XE$=ny+-?wz_eBhzsHook@s_Y_5*i1(QOTjqgD90?pbeR|WIjIi~$Jz|8 zfRJq#)G-wi(k7+cVOhYb|+YNE`G;k!;g;o3+iF>ZVTtILy@!hiZNtJZ0Y?K-6 z;N$D`)Efg7MU`fflY2b=NoSTLN88jF%_cAMOWu!ZCZ1?vvsh{&UqTi4#;h_pBzxSd z4IHVDHLC@!-NjO`n#|N7d>#DL)gfvm%vZFV1MdvC{e4&Rq0Q&7&$ggElVMebZRx!w zJ!dJrn+`&p<%^1@{p_kdY#9>=*pa54o1$iH@wOJ9{s;RRqLO+0(Fk zrw^x9Jn{j1s=kL1Gte6xTg18F`P}Dj<-5nhs13QI##w}YKImt%+h#PpMJ@1_#`l}9 z(Ww5@+QfwQF2M$k(~QaYVBT1aVf#6cmK$oCtwFc#{#54nhB^=O3am{Jfjgw$0#C<;GF(`%-xk5dH6^@3xPNj}+m3~J1 zJrcN#&QUXFvTluOS2URnWr2b0A!@6k0lTk4T`x?+HMdMpK0h9x7OLz}5i(=aWBsJn z!b%MUk<^aeA#tuZ8N2d~lpFJrK;-S;#TIbKd#zL5_o{>KM=EF2$lrW0 z#J`Ikj3dK)o3~SJ@Jl*UvsB>u_N;WA1`vUTiP~M1om+ZF*OKa5=c=A;LzvTAKt2{pTE>U(yYRTHl2%mb7=#2VDi&=H)nsIBi+awSbjti>rN&guppf_TQ_db(SJ-o`M7b}9 z%2(AF5C*AqpKJ?SnR#oXO@)>Q*jAyi3q=}4)v4l_()=`I1Xd{DNnpUd)Y7R#@_E3m zL{bI{1+z}S5lt1G<&l09JU~W9)iih7w^wgGe8T}h^NYSjno^0<()K9Cl9~cD8K=rs zdq%3&()0A(x|V(Lr*=!gn>FbM*a>;tXPM~Y%XlW*QAi%le1O103%+@sVXsDH&+*pP z>TC@!ElGA)fD%lSF!1`yKvnXCcW!Lm4+8lvWG!%6m4aG>_GL+ZLXnZrD8#j1(mn9d z2CyzKd%K(YB)GflcuZHn-D0Ui-V;v6>e_>Gr>u1JP!{h9od zx1R*2Z)X%cmn3UBT%;j|`~{awi;()U&aO^eaknG}oN5oG^Q^7Hq0GX4rT8bi3mSS3 zeS-s=xDWUcQKtLHXSJM}ur8`E$v2t+E$sZTJ$^ATre^C}u|pQ3pjt&SZ|yzR#fEP~ z2mHm56!k~)ckFibhrS&3o`KWm&9*qE)Px`IUY{nV?rs>GtpVwX@F8d4m2W@XmUq4A zsio-t3tDOSc_s6UcQM&zwJ-G{Rz8sd{i275KIEhAMHA zJ^$02I|RAE0FFAUF?aI!F77;f>JTHO!J_F>;OQBiGPCgdw#}+lRJs~pua3Q3rTu;a z{OQQhXz~*fnL|yVIPb?XLoMr9OMND4^vr_{_YWaDFZ?;CRaDIrEgUN@3~QA7c+A)y zAL);)bGzE3P)oI=)Lb9AQV@JzdV1LHNY)W-pI3TriPiKy%~Ul=4>+{Jj9m=~YoiW~Jdo7Axi(mdat;%iRIJb5cdUAexP?sb9g#x5)Y@iv2AX@EqiUrrg83R0g+Kt<_J z68-!~!MwRoKMY{!^=0gc_v3JUdQa@_!SDVdMQgO`cM=omX@(qWqX0q_lu7CB9v#4e zk@r`qWV?kg9FO_Evp>R%iA1Nlfr`E7cZ{}Nc~X|v`edbuVnsN8VUUxs^bpy{^IuE8 z7mY6BB(h7^LFtG3%Jbo7B)XVV67#*rZ)Db=*g31z$WwtO&zqMA4AKFZMQwHj`k0s~ z>+v%^)1;lYaT4Cpf3z6TaC^iH-6N~n;z0C98L8D6XKd6p%Lu;X>Eiiz)XR{eXGR!q zUC5jO+Q54*(i(@^GK%1#+V;}Bh#5T1caER6q`vT#H2nNx_G)(!q&CxWOY&l~m6;O? zqh_9eQD3{SAX@96?B&i0)K9F8ZLiGY)KjnFpSNBX0miKXxoB0}YqM8pjgpcj3cVrS zEtpbqMtl@axm&UfAAIiRZ=>Z$z^eYwRUxXJP_#5YeyIV# zb?5rflM~6zkl)I)&7nAl+t`2f!Bbr8bF~6L&g#>?y`0_T>Gbe$VE*;U%y|dZ(cc;Z z3W%6JsS}XLrSdDdj??Y2?qTv=jt?=0HEg^>M1WO)PHi(Oi+p|1w_aQ&{J)4`J8fW z*^?D=F!~%(%S+^43o((6fImaI^>gf6$6V}F(riM-d>j3_ zMUyCrUx*rR0y_fA6-n=7hzMXyYx)u5Xm52G_Fl8DT4W?hS}@l&_H6~T5G9a3zrig& z6T(Ofq2X+2o7V9>S7b%GWpOU1n%8}Oz|zgKFOBGK8*4f0$_I+7adt8*$o&$_xL3P} ztX2$Jo{YU`lrNK8kTX8n`7`}c)d2?TM16jOmX6X_%0+*7?^&(DK zGeAcfz%x(R+L=4A+HdEU4U@$S{+PX?KE8cYT&dnPbwIDksZL)=`}TfJPWmDv7av!D zhTu5CF!sCVodddGIwb=CteN~r;pBh2a@bF0pxYcO?Sb`s=B|{!d8N;IJGW-%=u>m7 z!^3h%2E*b1_VRz9eDoJUzh|aoSYzL&<(F;NCZZ9~4ttpEg5f%CXkRXR&oQS;>Uj8n zv&bH7Nd?yK-N`pIk*_M=#f_Rfl#PEmNU9RqsH}Qe?^8E;R3EDHk^!;jdDE~IDOWwG z4&q^hzU1e48(bC>WC;Lrgyd66<5<-LUk#uoc*ezBY_Q|i?u*n;GKDtt{wfb2QOj-n z7?E0AAT`GR(V$|NM+^@6zd*1s0a}Q{){XgeGX=mVMWB`UN#^8hh^b|HZXl16AvSbCK5uYCeQ8sjT zWde5#tt9A=;tv6fvhQ+T(-P|6YyDUW?@X1HOs!n_uEA~u-$cyw7xG2r+IQJLDY|5n zc&tUd0VO5=LLy5T`+d6?6b(k5q2KABGSrdGI8X_0vb@C-+%=z-4@GJ?2-sW{{1C?g zLYP!6f(>!RbtwkUR)qjPaqw_6TVbmG+*DnoUp;l4onUc)Jy!M#nZh1;)odCMz8X+BA5*_kV#fMM z7G~952>G4xd=MV%UB~>ryfir!8p~2oe049^(J#tcEPC&7!@ZNuj*`yBsrb_kE-v;?RCc?j6x%$G+$ux{4vNFAd7I*y!tMY^@7B zSS`E2YYVOLnKF{N8Svougfw&b9F0{lguzGWxlko;ytSjgtKr8wPF6giBvWfAnAwFv ztW>!3Kt^&S%a!7e6f7~Fe%BqLt%fQ68Z0gUo(%(7d_(v9xn#`#uwQs6IV?~hEf6VWh0$=U8C(O}=cI=wS2kHzj102+ zu5h3SIDYi$e=o@_&>KXY32aF&TP9a2Z|v!h?oHkIsFF?olBwA7@QM9g_V9RZa(Gum zz%M41XL;qWcq_KkiVGd~o@cu<_W%c-q+x0!tE>ZofH(A%C$6NVr+Y_+?i7F2@-_+0 zdGd(J`E$QFx481UD*Jo3m_j!fg`t7>kYA8`0-aqdeYf$0Eo*3;^hTwU7qtaZtRklA zqXqGX8jgFdKTg~e;wJlgK2>t}Mh)cIAG5F<%7k&IYb;udv)(>2MD^tRyGcznT)uG3 z5W9kKf|rqS`Tp)xyg$<^vuI4~1)q+G05q)noYr0O~vd_zPNO5lU$p+ltF zb#0bIUonrQbkuiug@~F`;1>)9ho$QkAO$3MMLejdg**Z=%}R5C7}J@o0e7XeUG*>g zDVFDcky!UL4w=nOm{?q^6Hlnb_`j?}-+b?&&`NS( zAyI2+`v;K^KB1P_#w-YV3mN5=k24*g=;@A(tHHtyn?1_>$w@@t+J-u=>~C3>N@<+fjh~(O!A9D zt1lOo1<*Y}gETAyb=ygjxemltwm7$>RjKuFGRm8BftCfx*%O52`2BY|Rgu-Yw2(ha zBXS!I4zdb^hkI;!lE^XR%}euZ<#mpwJUk*UB%&gT08JNotMGD&B(lp%%Dl2&uc|y^ zuH-LGZ#U;(d#EI48&8)6UbzwYE3x&EXS>(p=TWN1?;*pCR;hjFn*(fG zwiB$G6AsMXHcIM`F_(t^g??lR|7ye0`EqOx>%GV0IGrjVZa~Z_3|#Q)!Q) zRrnQw98{gAf{c31i-i$*cC9W7Z-+>uWaH>!)*&mKi18oyt0c;;`VbqKaY#hb3u3E> zTOS#)+rmKbkjn~8Tzq}yYBHi-m?P`nVyfiwxyL|oE2#EdHo&}17LwQlWVx4)n$)+F zRblu<@&qm%|V`@1|Wi z3D6W_gQ3E^vm(c(?#f?)R|hdr(Jg)b+4-#VVu}X*0mFCTrsI(@?Ebb90 z$Pz-M?y#S?vuy|nei5mgITDQyZR`M={kg_WbXxKVD3|^vkX!0iWx!8sRY_??ab@FH7i@Ijkkzb{q zJDN0GUf-p+SbDy3ZR3keRz8qRaK(j<*8L$mwmWpQi2mX70eQm`Y@|uW zhndC0MVFOW9w<_m-pckM`D^8~0gs{adAFIjx=%an$r_|R^aJ8Eg~i15Z|Wa4#_!jL zTV^T&WvN!UG5pdU`0cRJ#zwqq>(X>cuJ@=e8~VOSF1(Q9ZU;2zW0ckz1^9;It309C zt+To6qyMzA)CZ%~R`$R?wcAVXw8_e2e*u{HL;r+5gm4hM{}Bd=67v4!2wT_>bve@A zykbGF+Cv=bH?T3li-|Cr3KSVjm}YL&Wn1nCuj&?^^K)9cwgRpleOhwMw~vKdCm0gI~rJY8{_^ z09`zkWej{^ziJjpEu)ZR>>bJuV86!|o&mh;$VKmw`dof0`CDkl!#BOVbFvn^LQXU*6!v= zO=pORf{XvVHn114o?V0;T^wmvn)D+=_LcS4y9qNI-&fudOY25Dgg|=lChyMFcQtn{ zV!i$zniKW$$!0c>tTq`&rMDucE=eK}+slfgS?Mw7B`_qAhttTkW|gzFfdgZ9g*l)#y}tYvFQp)f zwPTqtW(?TGWpcPW4sT@+k7c!m21nxlh}&`&et}vYawzw_NZih_O7)E+k}vC;kD^`J z#WO|cRSh5>%;5Osx_t;4cR`mPXAzM@MtS86*6NVIf>)sB*EPfQJPjdX%+DuM#{L)vCb zI_2ua)Xrp;VRSF{-JG;wuGd2qJh^6hC(!E?51v|lo=8@w^VCi){~Gi%%uYIolN}hL zb!QpFOurPzsAgW~SZ*wmxiOi{Sct;W)11 ziO#>|EkkyEP4!UU>6)OZpQ}%6RQ9f^wSo-0Hh$O<%HEE8t1jWv$2&4E+S&|yJQcBR zE`Am?zdhTTblB6g-v$Z`H9n4+ZRG97-uK=Z6(jLsl)oQ;k4f|>9c{3qR+@scGxouzk0(^Kp^-;WY#?R0FB5za4Y0SYXb2nsMS*r!p^kGP8=B zAQ(Y>J&vz=$g%Nm-96OAJ~QEi-^B{gXO&%QV##t;S(4;@j+2#(Te9@9OK{?>j@fA; zE~997yInFj+_E}D?g?Sqx>nmGB=5?10OkA33W9K#_z)zL_VXh`j??eLu9A~mU+OyK z=)_w!6*Vcv??&=1?I$vWyFzo%9%sj^{`0SuhlOG5z5%GziAAP7cPCD-2<{m)!%3r0!m! zgFBccKifJl9!!{7GyI&OTsMmLhTUVKVQ%47Y*1U-H}U0&e0q$TC1U5;5)s40WA=+X z^H78F!%n^;m)({pQ;mz!P@o+;H-7mMO#{gf2$?Byz7?ozS@LC}$k-fNYVUk}z%8)| zgIz%YKLUqC$y`+$qj2@Pc9Uhk8gKrHk;}+Azm!ga`dyvxVP0HM>fvt%a$I7;O8){2 zfSS%#ttzs^dh#XDRyvDn*1F;JS}>93!b~>o{z-BB;7cNUJ+{>}aB)L){cr z*JarD%Z@S*LLQ_=d&y{LPJg0YHCcZz%fLxJw}Q#wOl{!awlUZ$I5?VMZx4~0y9*j7 zu|cdvIH{*A0IU0qOqW>#`G%mR-`e7?V7nySbmdu&9e<9@|si{ zuAO>?#n9YOuSUH>aRLLzuO_DWt!wmH{rm(}@1;O=yS?XsF-l>mHt=p|&mUh${OjKS z)0Xn9zQyjv^LC@a=6Q~qIR}l7O#Qc58K3@oDgj1ZJ$(0QW?rwbH1T>&;`gw%vHV zDJPNC+Ds1d&5kmB9`FBR3hel0)BaPQ+|nV#{Q*s(>qM0FExNJJlrJ z#qLtmLQS*~lA1m<5-(Y$(}rRvOi5R`_@JbLEaY6AU;pI`|IclJhhnP9BCTpG1&Uvy zppeA&fMe4usqnix$@?0Q=KalkbRegmO7s0ab3ws$mx_6sLu#X5!01h#;o+LVgOZZW z?8XI?&dTqM8?ZxA*Uf8}MtkkZ5R55i5UXkXZiJC-+k#@O-1CuWm+yBOF6QoKZxmpu zD}^TfONOGyg#Vo}*2o`lyV|K?F_RS5mX@<4ihV3V+KXdA=YRR4|9I&%fOW2jbvT~9 z@Y~ZZz8^n=ZsI8^d)#w&_E6Kofk>EN>H`lRAlCoPV?AZa9nbc-w2kD!gP?oZ{X|pAVOGNIlZ_o5(wg4M ziRV+H({esHdH8MF>k1rk!)|>a+d!>$bvi^LXtI-y23lVtuFB8%V}LQ254}@(I%7yV zDLWc6M^8AZj;JFP@6FvBmx7~fYw?F?s#8~4 z?oe&)#QRZGQ(en!i*=gYhu*(Ox)0Ik?aPr;^iP{fE#WmQnO1TvgqGt?pE3M2`O@)K z-Na2WL0^lAnuk|59H4;7cNvuet;QG}P9`d9jLWJspr?HkvhugJb-}Hz4m%>lh^3JJ z>@0rLCqk=9EHk?+cB#W#>V*}!iQ%NkuHlxht|w+>WNSkXd=%GN=}C>3$T_yrg@CWR zL?Hu>((Ll!#IgP%4{jG02lkMV%Ky_?{^#+(;mL-qzf*K7_Vy}S6!82w%|NeTwNk!}b3*+${D*@r-Z2@Oxc zlweZcBGsdv;{6?)>Mva@nh)6Lmq7R|2E)m4(4T>2*dIzy=RmGZlgBZxAIY;)pvaD6 z7Z^~^0UK~ea2|0>R(ODS9j((XB*+v^YHkj$9fXI_E0v3O6Gq)(IRc95B8u9bC4jnt!7b*!-mA}Gov7C6 zq6#~n_73uH9ab}52pMJJ9Wna901(V>2}Xi!?G0Us$`uA4feul=QfWInj{_3K`EXl# z=5L6zA^V@!K30xXS>lH*R`-v1oRO!?!=r-Lhnp6AII8o1056DGi?5m3#JGswFeKHR#W(bIiJFvD(_PWXDu7f+OQvTw$ zvi~JC4LRZxis2g!Tc89(CilD76Q}8Ye-6(`;BqN6`MpIuxFvT2Oh40kC~HrV{aN#L zM&FqK^^SF9o|R!$6YPfOqz5$nH+PU}3eV3mkT2tE_fSTvTglr27d7mEEIyEaFqUZ* zz8jc9vge781v*OnRe^?I1eNcJ!HW4)Q!l`MR6IWqK_2d-lQ|?B-VsOWVcr`b4 z?&LXJui%bphi-pOhpa9eXC9Q2srOcTPv+Dsg%aUv<;*HX{|oo^L%8jWSf4;Gu>(J! z*au9-OZo7nH>*wM-&Szvz(GJ8UUK_xe5^eQ9YRU}B4r_})Ky2NxVSN+^TC_lq??ww zZ^>DC#3x(#Yt0-S$b|HuI)VFqKdK|aoR2o6Dkre3hZK;kwt|?_Pa%@Aw}d~-`qa?m zy6~na-)0p62y6mDzA>oMXv*nFu4tfd^IuiKoBc8RQw6D6n4CqP= zv7ZgeFNhzoVm|{)`5eF!6ZF(-=o=TF4y?0Pk-P`UD zhNcjTfYeX~1Vs>}LjWU6uhKz8rT5TFKq(4>^iHVKL5P&lLJ>rI4?PeBLJJU(-o)pZ z=Y8MrIWy9Jfp&m?3%YR##< z<>zvZj&n$CCOtt=NxaL=5U!rp!^fpNHCr17Ov~_S(ryKyl*UF%N9ujb z?Ezwb8lm90nv}@elJX_!c3|Rc{q`E&6iWH;^q0QA$EQ!g@zoEBinkQC*R1&!WLnWT zJgR$_5cKNHp~sjCX_K}@@+9ChNB$ZGw$j z5C?nypWb@I=6XAxzQb3Yk6Q-;ornOXOR$9?Oy*vzksdVB=9luURy1U|VN{BITFHhf<*o>j4E{p}d^yz7Ju9NR~+Gxghfz_tDY#dHH6No^E z>;JQk453$i(b^o}SL6!x(>{@sO7QSEnGr9WoKaX6;-^z{p{vb}a=d~#nDU8u>Ii%8 z*{1q_Tf*;`Yv49B@Atj!fi zl$alIaB#ZC#Q|-e0Eq&7O8$SlM*np%Y)%8(g0M9#`jl^GEvps9Jz$pY;uovLu)K~i z)ccuN38_-w?01{sn3zpl&)zemU#h!LF7-YBN1*YaxA~uEdX?f=MJNK1^!v?j!dM%t z4DpE!ovhvT-6vy@&Y_f%WI_5<{O;AfIj=`!^jnRLp-!mC(T25mrJ5*WCG97Ph*MNl z6bmQ|7kZZP7_8cf-OLl{;~XFeDg3V`DFl&gsWRh%srL(f(=q!3(?*e-V({Yo*Wc0W zqO!2;DA_wL5k9#~oXrJUm!bo-*%PO3ilh|6c4U%nd`Q*K#Y<>7UNWhhdLykXskUU) zbB$zGlZt#iIqtH%m@sKNC6-SXS-19bZ@}T*GFPzX(H2B`{J++}|9=n8dnp|E6|ClQ zu1sflED=m;ZdFBa)fBb>7r5DP*}cT0pPrPIlu0y#h1P0AdHs9-I*{^jOvX(X7*7o* zBY_Rp!X-LSQJBTcRf}KMtX)LlJn#Q?Vu+i=H@gL8t!jm0haTO8hF2(f5DQ&}5o?`Y z8g8fQGbcr$M5Jshue^+9Yin3*tPQ7F1R@>|kB7@!Xa-a)$GZ11X#;K4pny;a=Krpa zhl~2u0V=&MEuZs_*v_iAC0lTvqG|x1B?KQ>XGo z1Nr>_bD2u^bm9H8?9&=dNw<+xyM{|?6Sfk34UcSt5~SDC!HPSSOANC8&-W2A*p4uuLaA=UrLQua;fa(<)1o}VTZ%@+zb=HK zaeqSkx>~x-suDR<*f42eRmwQ?+-l|~Pap}n-nSUcX?w#m7B?8Kv%9bTVyhi!k472} z7?2~9Qb*DuQR)`5&GExIIevEJ|DtREAIJY*sp}Di1eH*d)!xd_VPn9hkn;E~C|}}j zN`?_lHJ7uX$au=p7`0{|rA;;=rAZuF6wk_PmL5Z*-U7dg=oC6gt5Uob^3U zAX^}AsFr+bk+kHsAZ5aed54LxL$76y(6@T`EVdlzAYHt-{0dHrQv1czezxzz979=< zA9+Cz;8lAr!6X$esh@S4^Dohy5}no0e5G>EZ=%oR0(4_aXD$fPYA=DvKhD$wxWXpF>5L#g2&RmPF{lL5B}_P*-=KGCTD(LLKW7 z7dEoQ)=!L2*I#<_FxD1Ubis6I6|4(RvgQ(JVeIDnU9iUW*8benT|rHf`}xbLzpo6j zKTCV8I0+)6@ONlZSZYznV@~V_{YFY61Trx1a+8EHA&$};0wn$bpw&@Xs{60sFd#`$ z#6X3?h=yvOqd~f`mU5R*a$SEuDJ+8eJ%wb4=}gy;1n%ZNc_s?LQj|Z!yj`ihJ9#XQ zcG_|Xs|n+btgaRXo$sn5tcQx2Jh?UdGBu|}*{ zLC*d&6tVg5t6tG%i2tuwMQ9RGF0q$C?u+_7EX?nmBXdgy-`Q7=S1VhE{Hj4^=Sr7U z`y#^9>QJ#!;^Zh9GL3pI2pQ4Aj6t7-T%<~3De zGTR;xB_#;*H5fqw2@aAhm-I5cU90TMH@bCkC zQyLpk)7fQSJ@h@hqa&RAuR^9`ty2Ixah(Jm#M*@uQq{pXc;Lc-)Vu zl$rtY>U03UWWW=Krt$J!SxRv2@m=|*Ub^_e@^4|dfPg>XEnool%mD`(3TEutwo= zhB6YOIz1c0Wqp@SvcxsnPPYy)Z1tJV)q}?ZqwN z$NJGkl(i$w#64!B@p2)JL#X&`c`KOJ#(r;$w6@uUUMs@OAF95r#>Dn&!mqtPH*Z!t z!qhnk=4(^PD4kuAY)*ZXN5N0Jc{x343sU(7?^f(#38`@c@xE=wD*CoePAH*De!yiH z_~V>lmQix&l(M{SiR#Df-7g7OwwTA8#?Bqi{n=h6f$`4j_e6`Mu~wjj%uibcXo#&5t#ur7V%|bMjA61p~pDv zA|3O%23S`TH=3dUqGf?vRYW~KOl#U$e|p1SRw^A!X(grhL&`-+H11F$F9*Q8ma2Lwp9)R>N&vg>yZl@g!0=ckb@ zd#J{sUlg~O4<6d%;uSvE1b>p&MJ^0uY&7P4wHIWjW~rag4C(p8>poT|vx_#gVvXWg z!YO2P=vaAvxV1}2rlC=Jzg)*rb&VY*tFlhZwtB${VE8zfhF~)p$B?}R3jdXmCe@_F z0z)HW^!t}lQq{=@vHK))w4*`~Enj2O{KkZNT%-dleL>Xt;Ykxr#pPVZZ*`IPo}Ht5 zG)(NhJ?P8sa>T<%r}ms3j&@k@@6wVOIqtCG6@(ywFJ6`>N$Sj5%RVpfA|Rj%{Q?cI zY|;#P(%Tex(FdhmCHe~N(4QTG_O1Gg9V_-`E@R3vx15FV+PtlRuKi;EiOhkLd9HUR z(tA83BLn&BLyUDqM2y78$cDv-nBr({Fsjt*U@E>aa!Q@T1^4=eH;ov_`)Uh#*64gkoP8^Q^Gm0D zi*1X_oo;TFy^LVaex-@l(WA)tDR#e=nthvVs(tD0O6&6>evv6=1axTrVL)KQ_nxSb z=Chu@2J%N0wG|)Ib4`oZQ(`50yvpnYqv8=NTZ^Cf61ABaR7xT?Fn(C1bdL~!U~#+w zv^AX@O2xm~GV<{o-`RM$G1{<8LyK8NQah5$j4xiAMk)?KLb`Z^7(S4K9X_*SDSa(~ zmX?nh;N#S4TI|QI{E1eQyuI+${4E+o+xMEhDt^{2JZ*H0uA-M+Ln+*gIL*OI(#MYN zR0xjLQE2evacoib$?ONCQIk?ff)b8`Xy#G9zzq z+1F5BTz#gH^i!Z5k{B?u>mQUWQz*Hb)=hq3nDf@$V%9w`m_)XVl1fT| z2p*Q6Mphd-`?~j3iulbclT6+Ebo21$%OB_vDj7O8V9hikM&TN*DEsjAb8yWhy5$7q zTCZubsns4zLgE_$_{B3H6n||y>DMBfan-<#h*9=cG#ZJE7)TDt=ULSc#Mg%ymp%eL zc9><4Jko%?Wr-O)uXMI*Mvrsd@8eoLaTpKx-Kwr2@;xnn-K)b}>8bgD3kMkR`w#+w zv2xX-OIYm2Mtn%Q1V0(OV6mzC)vJDA5w2WzFH1u3abczYU>D$xOU?$8v3WNIr7J!J z+LAhHE$!*}7661}Uv9)Ek;82JF2y1Occ~qlbjls^Qabi2DSG-t`Zi6`4=y*2RhKCA zpxB9aq8^VDO}t6uCEihtpB`U$;F^{}yelbG-i^GU&E)plZ|hOu02>bu2#x_p*-nip zD14d5-vL}X)?Dl9(WnN>n>ZM42yH787BoX}Q8%Rg0A8j&fMHu6KOka`;o8 zgjP4aVWAI5JN+}6jqxiRfx0?4bkLE`d%bHY>~baobCaB6a89YQ8Y4RBit1f)i^m#5 zT}yteu5JJathp@oI6=b)`-F`M;qNais%GS`dR&ND9jD@oOd^z7)PMLEP<&#{!?@LU zIs-1R!!L3NX2oagtF>Pe#kDGyLRHKzrZdaPMx+*sj}(OAcC=RzwEm(1z?r&~9}+Lo;3nlzT{dIMQBfaLZX20bGaxD6dnOr~ zyD2^rNEQ*QO7u-A>R8ee?$t~kN?<$k!dYz6w|tW6I-<$?o;=}~ysb{+$zKrP>VUT? z^f5MS%$1<5YehQvsX@f-_;m>sFF}V2nN+(=%bZ4tEqSwi%!74mOf{0 zCMt|OTyscIx-D?!R9D6FL2q2mL@4cmQ2vxA#hEa z7dGa9DVjX&s6f_fkR|*of%PvwvZ-(DZlgWY<4a1t-9iCE5{mI5c@u^M!4+`l?LJ?h zJA*>8(`gB3wY{==;K$I%PsZpYv|gPaG#>orcHX)OjG060KFF5X=A6Ko&D`i->pCuo zyLvS{E7Czo(X`w~{z+%^Uq;Huj@m(!H6uFyq)RqMV8qmbOOA>{G1AW&@5X(J{m-Sv znMiMOqFPjghZ*j{V-8fD3mxPtOI_Urn;o(aX$2_ru4t#_?VCz^UbRo1!L{7JcJHwW zZB)L)apGlu>fkW)oobkZTsXJWCAB5i*)2%#1=?yG|7EAtPT`dbTjJvWoya4;1`0#Z z>Y^t7F>7dLWO8zDq()iRN^D$#ZObT_1hh_(S-xOWHXUAsadBWq)y1%6j%=VxQYH1E z{0uB+DkWX4ve+)jH*R#9=~k}oh++c)o-KXKiFdRY7=Ckkip-EUxv)6sKaJ%{ZB!`f zICCg!vv9_JEvWifKRL!WWNQ-%p%NxmgfZqtJLXLvTvz_(89v+i8MB%Z9e5A0F;$Hkb@^m68)vbPO)THioPrWy-r zF31q}c%=^<{zZ}Vl|(_rUld4YN3js&v>JA3NC`~I0Zh?Y|X@w+Dd*$^E-4t9#CT0lt6`32I18u|WoD=Qu zN$=b30(=W%V<|Z~J>?)B4a|EJWv)j{kD4A>x^?8XqNj|A`6HKlPHU8p19@UCu1ZUZ z1PrAVHGIs_5#Kxf*NW_}w*iEQ?mKyq>v4}PvYbg4)nAfW#4#rDem1lyrd&l36|3G! zm|SQ3K^@I=L!*;(5UAp};3DcjNKmY6zi;^skxC1!g2PMYoo{);KrjB1FVay&GvZ3_KEQU_v+&8uATCw z>%SG}WOrHtfyG>uB)|DM>0MLF?ua;5N%qDfQTR%aRB5;YG51K5-IlL5ZsTapQGhbv zicRWO&h_nSBKh26>AsuM^6X2p2Hj=+hCpi(+rUqR@&E)Z$u;G})ry*4kc|Hlxo@aO z1usyc35#`-Weaq4*Vv^5-=gI(!1$%jW2MB}jr0t?5Prn4Y!wzObF)Jz2d7Pf5}PdB zO3pIRG^*Pxf`=SgdE{1gjqd^>*?hj9x? z!OG1y%7AJ(X%gjL_n;JMhqbJs{mmxu!2!UN!%1NQdukjC6+LKJ;JTJ^vvU zAH|&f8+@*eH+e1uWYIg!mx!}3Ff@^za0@m3>DAN**$55l>E~X<1qeIHQ3)=WQtb&cR718`zi{lAv`ydE z?B5WZmT#?sX?voy+rvUhRMeMsZ*pqhycYo?#>Q(qYCS?=3h~S|wEm{lV%8$ha%1DA z*T+2f0AryMYHoZU92Rx+_ER${ru9aM4<__YQZ$Si{3N4@7vVI6`>AN zX-VDP7teTp9^aWieUCV)Hc3I728uSMrg~Jt9hbdd)40t204!1*49Bfe^#&9)5cG

e>HBzXYWz7+K>mr;{c*ottny#^b#lkC~I}f{e#GDl%nm zPo~2tr_^*ndqu?su-Spt_FPc|3lkCn79lQHPFAv~v)&Xt0>KdtULa~ldhkkXKnhIR z*?#|N2s#eq3F7QlA#koWfqg4;F{3N{X}L z2F{nZGCe)#130hn0kctZx#d`GlZb5pylw%uvkwMQaE0^v@ct-{+dAG)>EU%`P-xtvXUBA-CD1XFn`I2Nti zkR39$w)(0sF{8_)Ubgv4;~KST0}|E`a@6A4G8E~|n5F0?-r|G4gVMPjqg=+E)$dPp zs$a`AbK4~tBDFl(sM7&YAR|T+kg5$T}Rv#`4V$u#E%ALN&3Ejd-76fE! z0%0Wco*5SlKJ=TX!y`?codW_gKp!k!6)}=_J&2W~`;~(XuQD#i@GZXBK!{~nusei{ zv`@7fWHDCQcya(rlEgx|+0><6`_YOZrwX)`UnITLcyeyxKc96Y6P`twgq5yZKb}LZ zd2N3X3t7W@xbD3c>GP#SzI6TYi{&W1_9Gtp_nmqVKmFiW?@YVXd&r|i5c6&A*t=IB zLPh*uf^+Uw38jB?d#h;cbj5#HU#hTgPvj#oFw(Bz-EfS`RWcqhL2TTxaWE^h`)koC zAS%VVmP#DihB)4BQ1{QI!rqZx%&R?!3smaN99nqemB2%1kPTW7Jrq8l0NeuHF`S}8 zP<)Sn&UuAO3G67TQaZ{@)D+|v>}#{G!@{H(KCV=iVzrIJOKpzpmRrx~?%ud|&S2+5 zjc?R@m0NzMMTOYA(!;|sPHSHcM_JV;_d{LHr_){bwrXQE1imIbTM$)+*b_aRHKWrn zo!X6fT+;QU!1_KX@CdhS^iAI=OQn3`|Ey5>Mo0&Pw znfm5I@t~3Qe$G2)Pho?hW8XUMzdb|uIh)g0(u0(R9i_KmoS~V9`O9Mg}EhyJK+dk48mux~i z{)MEXrjy1mP-=sYu}c4M6ZyY`kyAZU?QU|1Jv~%vNo>MZR&~aCcYcLM+ld4W==Ld~ z+bqiq7(1ilv2Bh{P+NBH8y5yA9Fm|>fw$*fWWqyzwo?K+nqMf6KJ+sK5f>m!Xtj4t zPq&ku>W zPZo>S_+7Ysz;K6VP#CVRegVLEPu9HZzGrik1cE>8ialD+@^LgvbD}q#FKsia-2&*m|4k(^( znDrk=9dlL;vk)l`JGI;jy4yBUElVRtFg}WXP1kO4s)YRr8m0Cw{;1*XrCIL@6|%Xt zm7WnmnzgO4HEGTpfAoc7%SKD=I&~N|F}81O5WxX|C+T&lD9p>NF8xJM?gxTWlP0rQ zT6`KF*B=#LRmMd?XjVE^n)X(zI~Ol@XL*-WU+g?&4Mc`X$*^t+?6`a62b6l8b~aLi z7z2j#M1Vu#rd9ci;xYImDfT@W?ls^&JwJ(yuOdawnQ7|(|koMvyI6XKwNvNYut z*&2iKZ_tcUm*?UwMJE{Xe#FHiEmVOFn{s+>U;F6v7_+e9-BC|0{*dqN=rd^;Rg(LjHy-ED1=b`7l`G z4qz`jlA8PsxaZeC%be65hH#REG6~%v=Y-|jassN|K{|rUdoSYc*eNUP*;pz#N!$Sw z=WnIA`kUU$l@uhpy2La;-x)vlbAXo-@yD$(Kv{s5DZg4Go~u%|6jyU$gkslCnPxRC z^`wV@t;Kv0tE}yeKx;%=$a+yR)%H<)P9Rv8qA8(40tbfWc|eh+y8cI%bjG>;{w^9y z%n7G1gk7rjh@R2g9Qa(cD%dRPCs65{JC$TQ)ePx4 zU9rmvf`|C(B8zwLV&iU!~(9>+#o(v%b(2Wj?5VSe~`&_-^qIXg5YNUfEs3D_*2N$qqoq zjP7Rb3xGY7Mn1jQ$Tb!LOT(ugNO?vd97mn||J5BvyC(;)?s|>nL*W%hugg15k2(%0 zptMG(zouG%VFTf9=51&m+Hb`SL}I$)v{h`QNbxnf=(JIqO2x$9%#eAZs|gWO=BYpB z()Ecp$eZ4!uQYE@;>}^`d!x=Hr5U~A2+nZqJLK*HYjB7-UrD-ncQ#ZznDW(={hiv| zTA`zynbGS)V}9#RjeZDgLr?)X#+W!pgF0HHCKd^}b*XRf{99&hTSygLj_*Jz zsh+JAq79^N^)EhIKpR{2E)6XFwdA`C>c~b%Ux}pp#yO1AlnN5SbPqKN{LN*9cU=S* z%|K?1o<*+4XQi)ouB9iiC6dK}AyrjS*>tILO*iD#WarV~0?ivR>}+VYM-;~RK)~Gf zTa+OUG3lbyq%*eE)DHn_j?l{Af1E5dezHd|cm>2c)T<{snB-R-&~gibH%`ulkipC_ zg<`^T7(CB`FFF2Wx)IAGB&j2@3=3VYdmm^ATz0Ho@v0%yZGLLoB;ZB}z4TrbQ`=0v zgmMU45Rt5)$B>G=sBt}e*J4tWI+y`oLUiGa>aSo1gXQ{nIOb9^?gIZ_JRqq4`{l2u z3ut(AGGL~1Xz-Z-WZe_d;PWc7APPlYydBn=b*K4<41ZpDPH2DL9G=ksN6qoDXaepx zQ4k|S6(is6Jm?C2m1ueMza3G<&f@A+#%?_-`5&Ass)!Kko^;sijk<{(8QwU9Sp0 z4LTh=8_~eWSNiEGBuY#O{EA=qSP$_UPj0XA&7(oHYxbdfboRjKlRK&tsj0px!iQvJ z+J-#?p6Yt4{=bhkmpcySI_H^u4+3@OpO2Rg+i%<2=Y;Cv6H-Wq{Ur<;dPK8Go;@eU z436vM=;jC*MEQZgO*|lu#}!AzNgoFnfMoxSBs$2(ns<|MY3^dBp}p;Ru>dMK_F`s# zR;5T)jp=>C(Q$h6Uz-xuonqb+#kPafME*-PGMAT8&A2ehPg-?+B+nt9uyyxUy}by= z-I!*f!#Di>PE&hH+jj~uB90792zC28GOof-iY~JOjjnie&P+iCCtOu!^lEV+WgCR< z<%(CD-XvCr_OOv>9rcH=TX2)elzV}(dou{CsgPFoXx)2d#>`lLJy4EUt#U|viE9j6 zrf4(MCeE=)-Bi+oN}lr@CZrPaA2YZdX<}jQ(N20`Ef~7Icvb&;H})(z?wQb1yKw|f znJi;1=RJF#TtIvnT3}@;2qlvD(9y7caEmszr$`?(yvzxRcnE*q_VQWaJlXh1+RIv} z)P)G1WXftq66E1;6A_eD?V^6y$st|EwXJYQ?!))OVz2h@Q~U<$Ac}bYbs5psBHKp59 zl~(XdOlUmP*%Dp!whmpiqT(&HXGMWVB1y&|7v=@IQXAnJ?X$pV1S?*zBB`GRf*-}d zdc0Bm?%Sp`hAhZm=f(6<4DStpZ_(16-fxqmiw!{hEUvOY7A`Ox)gJA{h!;es`8*{Y z>Eo^MVpKi~UxDz1m%LzD&vKn+mfeDWyrxmA6raEI#5-X+7Z%RAAKH$l!nFb^d9s*% z6ck-eTP##>Tb5Pv3a82?3DD+_j%4)S#Jx68QLxdId@Y|(F+#}9mK<^UiO7aKL{^dV zeQ0IUT-@s$uYM<1+}?YG{b9@8t$PIjgj3D4{^|Pf|6Bv(ZP$mzvEP&;&mW3YyerIk z`DvW9PUYQ4$-dQG5|m#nJpcH!nSRY%7eWMnX~_xpFZ2qVsz>n)6Fr~aF^$d@Ezk37 z`v}zd~qz=~rdh zhL0o)!9kg;;yAuWB+GZKl@F9k)0p;fTt?x=c)xHzUBre2*4cevBli9(#VpW}64pcF zdKTi7$u5S2ROQ3bAC>WOiRtE+pT5ueXME$BaK-uzpZgW|N}Kl8YS8jwow{Ac4V0Y4OF2uvd%O}Okt{@O#GjWFzh8bL;fcO+(eYLM7A}W_ zG@%g30e*Y>=8*ZhGP|pWpIpaP3!JW2zwk2(O1LiqbO0RF>*<`@%Xu9F;27 zDO?zHqZzn5s6#eb;-gIXS@CRLrYPBGFM$xxf2%BX$8@sMm}SHIc8h{o{Z2lq?xpT{ zRnpuzIaVz7E^*WzZS1J2()99ks`4!tVV=~k*i{Z}%zlJ~=GTEvvG`7!IvN&=R7~b5 zS!o|2V+KfGsQCc|5rnB?Uxh@Y<5~Cl-=>Q(9qav31piwovCp0>_`X|Nd!vp4YCyxP zDEluR=FUR>jQQUy%9>KCVHjbE#c-(roYi&*K7`b$4T4F(lx?Wa_HJ3PA&_X$fxo@e4>Wuww#+~VncH#h^Yvh_K(WhUoO#*8beUypCNC{p96MWZz>%?Eah_o4QtG;_|{ig6?y8MP6^ zG~ujpI}~8cNYNQ;xna#<+vVp>?)_aI9F$)biblT5@wxjL#ftMcMV^D!&QKasx8bLw-&L;%x{A{; z>x@V(dAmpA6}oo6_hON_eo(w+@Qg~5FY0)X7D#;;7_9tsdQgY6ZKDx%@P1M8RayY9TZ_y^GpW5@q>7tK?)Mx198wBsRL|Rryy#TR zAzU?3-AFpyv`rWu#W3#LQ6F;lae!)og9;&ZWG6B$pr5^LeL9cN;~fN(%PDEuawdDo zP0jXTM9$Rpm>naxZmh||ixGD*Z%{TgKGY zb>X6vQrvZ8E$%MGp=fc67N@wodvUj2q`14gyA^kLcXvOF_dE9{_uoxO2nmqDnrn{n z*cd|#x4CeT9g=0OC$&keVO%L%*Nm?88f@p=513`ED}EK|Ee2uLQm#6N6D)s*Tt$@O zFkZ-Lm8$+SY&M#{L0$P8tse|vmMtfWObg*D8^CoBpc>6R>-5)#lL`CCO_2v1QN zqz({G^~m5pfPIW9rvC1u=+Ax2IZ=2C*lEe%w&2*7gwFek;P6Zdo35s<-KXWe5@7B9 z1ZaJ2PZbqJWycvsG*)d7MlE}MXPrYjua{qM!374i192xECzob7m#xngH?F5K+3<)T zD?lXX@UFVp18+~p;xDsLMQLkhLQ=E>QFE?K@hQa&h}KreRJC@|1e73H~)u z#aY!da;pVt81iWhv>9Tm(X}y_H#|-93SbQ{L0|bPGh@cV@ zHM*D47=%@m0VWPoeSLmu>?z+{ zk6w*cf|QEmwhn!7Y@6UwTLT*U=dwk1RKa3CSv5!}Wda;Hz2X?g1K`Jt zsMTt~2t%JzlE&0tk*%--JDKO8T?rtJeui1TSU^?IxXv}N22@rux7?Ik_a?MI8)~Rw zLP+MKpEeyaEZcM=xm+c$h1b^Be!Ypcfh7D~TFCoi8Dz1h>wCOgpuW;F+B(lTFS{19vE%Cq>Ut&SE$4~gW4$Z&FAsM)1 z$Mg0~9v(t0B_1ud3|qHs9{XWT%}xmNVQr|qxL|M-RSe0_l2q^Xiv+irBOccPE7RK4(b@0MJq(m%_VeC+xv z6I|Mu>KuIf#&eA{!;`{hqxpJciga$_z1gl}#ZZPtJK-J8QUyj1ZF43oEEO_MwrNev z+_r*HoU_Az^Kydzh@ilWu2fG>PR#zaSE}3Fej5|c$d`}I{$y~v626DoREt(gCyu;i z`c(2-POf&j5Q)rGG7K1nf_g{8>K{Z$v`2>>zKvf=WgL)+j&xLF#~;Y-I7%}-FlM_2 z*hglwCg$~e^B`JLY@zQ)p!ORlGYT`3=&;y`5xt2i;kpOum72PwdI~f9E90e+)KQSH zbX4Q8v{BlRmSWkKed3@FRvnJbs68Z75*B2w03#WNVhB2rq6j=Qh4#8_Xv7;HFE?T^ zdTb!r?!^7fs;{rNN*eP#wQsoS!;g{8Uz$+%ozIvF$t?XG*|1G=aW`M7_!&XK>(m~J zQsOoJt-ap09#$aegCEUatOYtS4$WoUtwoqD5(|D+a?&0d@kS%+j#Fmx_-oP%MG8a0 z!NPhT)?=j(l;N5k7$6>oidXB6+Xae~?XEj+X(e=c{|=$w9HMdI#x~Vqr$3ixTFU4wpb5j-B>2k$M>?2evsiP z68RePp{gcvd>?DHamS>+lgpsfgWXSf=Z5^GbPvS@nuz(7y0^N(UIf$F(zR2%50EJ4%B%%cOB9HaLjD^uEPeuxFr1NRBI-65|(HoXuGp=L-=md^EEt;q)cIt`?6K}a>Bd#zG@^O>KZOJBF)3o!| zdP%#^|Fxn13e}gW=lbSmBf{E)^!@(U^nSS!r}%?ke$W&d1nfol^1KdnF)oZ^$@}&v z{TZr$#R>oQM(3>-LyIE#+vGmx*Uww?jl%WPTs*F`TMx@f91wnf9h+G;=!R~SGjz=d zN-Z;S=w2{}#pX z5B-_&QZluzG1)#=TT)F8aWU0unz-`Fnivb@snj{s{qE$-i(jfn6d6il4(!&qz3zXG zn|#!#L5}Ea{%V^Ge1CVL^s0C6Ppz;p^Gim zmQm}nsWL(5q`+p=b}po`B0p+KFfh*Kf`KBPRkgnon70(0lfd=p{?hz=^QYQlX-yPR zomDGa^|}9h%ZZwT+dbAX+q}(OwJ=M)waB95C!{`=q<9>+pC^zaJqp>W3rVUzY2CXA5WzYxdp(`JU+ZY_TvFHZ zhPdg^+msjgTTxpR-@mN5yhiezcF<~HgsM3Hu?gOHXu&rCt9+iM-5XKW@60CDVT8Fe zyI+kuY)_X ziLjWYgIIPxFOdSDtw}V@MsZ|8NVy4Z0H-Q5Bj@c^RQq(IqDBeScCv8v|0=x02j}N~g3sKIP~BPn z9;EV^1qq_&8xX3Tk!_v{eglJj9uYUO1 zl^1C8{l0OS=~H!0Yx?kyA!ouVVcBZBv{Mzf-Q|Kxsqun^;Q-pp#SPB>U>7RWF1~a+ z0OxHeBu!f)5bJq(m49d_wF*s4!^g-5Xq@#jAAPDF1k0r$t=JL2@h&%Z-uW8+0(P-4 z%s|?GWeKNYMI;ycyN^JMR>&WbCRNL?RRb__B?eL;X||tT%|OY~re1%x`%I3HJF)() z%z&s~z318tZPFs|gxnVi*#Mp!9CO0uQ90gs682G58i#omr_w`94-w}37D(FPMvuYI zclY%-nhF^KL5O^zsoqd^{8Th;-S?^#E&5+29Me^6KT{hLb38_;3k7yO|Fo$R*n~&e6aH1^7LsJcj>3CWs(#mAmoySM{k+{l$zB@j_ zM{$werdM?fft)mi$*R!;kvI&hQ5|@<&r&rl)Uiu@ApDmkQFTpDb4+U}!;fz7NVC*Y zlokfuO0x{G2wXtN%rrLzP;^mgTHSJE<-{7( z9J`9I&duUG$>!Gl%01orDz;|Cdu~sxoa)-z3!zS7GlE$QHz)Bmez%WXG-V4@VSc2{ z{awx^bX!>yAmD4^Dym9)lf4nBM)1U>zG%Kzt>aj^sPBBzdrepNW@KO>Ngi=3;1D4d z>8AWZy*qCAcgPy4e#(6#BZKUv&>sHUsIAVrdF0m6^-vRo6@{UcKx`A6V~@kE`8j3I zf1>fzfL+_CWbpOxm%r%+r9e|&gFhLf(F>jeU)y(LjWwCLIDV8*Crrq(*6k|Ln1rmX zET8*br0PBH>O*JsoukZ{)P6?#0GgN`*Am&T{OTSz+wOwZaG5{Io!A%!D4gp)6^YUnOI6^xQBGD|F^M zvIO)fAO7xi3@b@+R5Kh95bx4OOg<0KlGh~@8~o`owfSvpYzTfK(4gYzr%N;MvElW{ zzeUmG(t+IjO~XvqH5gctKzksL!?q6%qu&v8fC=2jYe7*+4&NtD)Uag*JmGyEeSMFok+z4jA1v>qY>+{L=T#a<2YbSLL*weV#5}rqw9VGXxakN zB4$AgLj}t=IMTSeaSY25rt;;?HDh{2Np0-j&Uc7xL=>L#G4SKxpz%<+jO%sr_p9z50*>jiSI4 zi`>_WEF6BDGKT4pU3a>S>}3;NL;hz;W?|+ju(D!X3AB?eO>q8WL@)0ik zf57X*jyomx1x~x;zrrEiI&ESV-DMsGoOj9Ha{Y_Pc;-chhMEk-?Z|#ff0S0SIShY;5L6 zCMJ=Z2!9rxvOIAW#g{BX{YKEYp5+>`qcxqyC9N?kx%GA#^`0j)Ll_ld-~{Q|rHz+->*fB_Lgl#}Y6e zgMAZ1)D!`>s_}et1S20~i5kHUAohOE%jy?OeRz>W?V-S7&@6DbvazZ7$VW_LtD$8G z$Qmq1-aLtI%E6MrdWw)K8Q5%y(79H~-mvm-`w#g?+KRGY?s(ULyHmGFzH1-omxp)A z4XO}hY;Is^F-tf`7Y|B6pDR}LEl7#^G-DSvH~bo!-0_nx|XbU$rT=6`vb)GO)ty*Sqtd|RsVg# zjqTYp=1Pq;D%6I*rCpQwJ2e6|q4hjPy2oK4@0V=20kqcBOq^^ZOhYqE|FR&y`hQzt z8fvB8_*-7JFUG?(#P&1K9q$M(#|lFL$tqN~G-KkEZ^7if5PMKHrXnztch0FdVz@vO z5naFHa#)%i?JP%seqS}d23c|qUk7#!&uvrJMr!%GjxW<2P*^PR2 z{#Aos4V4vl4PEBPHDFM_7R4^j!GO$L64V4n_a@6am(syotnu6?%M6^xe|={&XzSh( zYG*h+dq_`STG3Gy`#uOdBmtdGWZkuwS!J`Phr|ma=1BY3*5C=n4~;5iiSV3KXesNL|bd*#^4!l6<7%-RG9r z92noY!TDgP6tEpKT`A{JGKS%3k6C09NF#EqS&d>e@~plsO;vSIp7m~VTVUi zdc;vXf8N=O#E|S3uU~@5{W0_QTtowHgIRI=?2}YMu9SruA8J(iYlS#d3|L1ED4~j2 z?CGkw9ymw1ZB?`!H%TQCgK1d0LXT;32flI9&uSA`V&`{R((2CB@#$cTwvwseh+wun zum3jh%*-EwOCG2oS-#~V-l_bmbv=OP$SaU)C8bf?S31mFtPu8)Ix`~cRP&e@<@5%qqLZKaefQa%S6z)~)_?)pia~BdoSo~l?HhIaT_!v> z+~LHMxIj1YaK`0nFuW^j%mH@z<3D}awm7nOS}O*Z?S#J95&)#|LnSA}o*?EEa$tH) zlU8bw?j^qVN8{u)sxz}=wD_6Um+?ILPxKw-B>GQ?HE886q&RwGFh>gd+&833P2&5O zQ{-;a%9Aas0}Z8@leSppexCEJMVz4=DipD=)f~ltU;`GSxDoyJG-&U9e1IGxPlU4Q z5peEFuoexDCA_1KR4+U?W@}lE8?h?^Gq%W8&!68El=cH%ag1qmFp(9xW6gIvwz;=|1?uNivfK z%i7(oIB#{rd?|4|ty{9Xs*PxDgNUPSBhp8)Qvk?2uQpf}90RGVIN3D^HYWMiG{ zFJJ#M3Ds3_46LxWIYtFuuHS`fxbDuiW#}+_OZ6n^f~XonC$2L9fB{&1l5ao@`02~r zs%gnC`}vL1_ZT`e5H#Bg_e!M-c4@%JXi{6UJ8fhN>sLfJxl;|&2)t!=&S{70zp;vm z@~nvez%Dkj4$Qp_)FYCcvAC!R>d)f-PC9*kl^Z; z6RK*4*7*uYznSOCe>AExZVnDIFllnME5`vrh=R|j12Ba`{W}|YI(3Q4NQxx?#Vsnf zIb|`@dC=p^GbLPZ+?wN%b(iWq*%y+i*so|rwqkQ!Za?H|eg~gE`!n0OuS8Ozn;%_# zFd5^QK-D0uT`+NF1V*RZgR>uo(4jGCuoX(>NEE^&+xp&#G|; zThsldwyo}JK+X%je$A`7{Aw9Fcsu-rA-oRXJ~sElb=IfV7kupnn?0btVZQN2U|$>r zNOK0FKc3XhqL~K&Qh!r}3sQm0&H`U&{@4OvgAMA~+f{*KA=xv*=s!iFRgebDwocRkP!@o+G>hPhhtZP z%j3YoEc|;npz+}`;Q!Va!BbDK&u>pW{gq(aPN2ASYh%;9#)^JW#6DSZ=lWaHwLX*E z;X1PBMFNhKblXz6GQ_(XD@%#M3ROyHzy&9ot4+h{;+W?CUNCNEV1np#b1I@^rUFBW zf{Dt#^A=z2Bb#ncus2(+Yk^_2pWMCnHIO7F^w3!J2Xe-bi^}rnlYL| z`tu84OtUCQaf1tkgL-lD7E?Dt%H&jbM{*L3bYW3pE5TD$9Zj9g)r;C68n6&4h0^|j z>mg5888MdFM&gK`$?(8SX&s-f{f=ABiAbdP?-11V{+djkk@ylFG9!MpcAH9O;^Jz& z(6qK@rxW?Kwhm4%B_oytqXm&VwrU;qIth+2B)`35gYKzyw#A!G_p* zS?QT_1Ow_ZZBXC}S-4m>!2r~E7OR)EE5(ts`W26GGFV?5A*MEY0EPi?UmY<@s%Fod z>p7x>UvkuqgZwC0_+oz(oml|Bnv%lTA^CbKJbFqS^~{iC)lLt8)$mKHujKu4q1%+E ze9CNDkBniG!_tW~QW+}MObWALS7r*X=a?f6#NVM~EqE~yiaug9w_bJuHWM) zgmD|q!E>^w_f{?-MvfTSnDK`#)I#nmek$3iA6?m=i1s(=S@^vt)C5~PG$s1sNoo0{ zLtO4@kVOg+Bv}waNe0`69m3qRm@>PBtjm@)IL`;NO<#G+`vul4fUfpkTg~ILjHGY#t%&OTn5#MTB9c|S ze7)Q1`f{Cv2d6!>*5H0v(SB4B0Ct4q$bknzVGgEPXriNGHX2;)*!3QoQj$J0c#vb*tMsM{ zRP{q&OaaDZ3~cpiLURXo`#P;I@PI_Er?sK}fVy3Dpp3EY>5m5}wq$~Te;Vlk;PVvi zC(N4LxT8}x3{SNFr**S3J`y|HcL!F8)tPSCYQbb()phs44-ExxI6a>6FF#|bYt8}# z+FaZX&MH??RjSG9j9=a&ab=6hN-;!W9`5@EBBMNy^_9n3-(Jr8k96K1<7@6lo!c<# zSKW$>?@~BzA?ugzq@*4(*p^eA!UiWkc1nUQcYX-{_@pQ=;ReBJE7rMhgMmei=Mg+k zD)8;1m$5cAkb@cB_Bb~D?GmPyX;uo+oV)wWnjCO6oGyx}pVC&LXkhh+!RnsglE?XI;hVe8?rx^nY{HBf}LEaTKsIwu!6; zq;ZWw>t>(E=q{$&Bh4zATI$9+WhQ8X&tWj?3f3^;%*O=5>-QFQwI>it&`Crd204^~ zsRet^NXr^H1;UcHw``QulZM z%b56DE*2Kwn3$OO5$|F>N91YxE|X}Jxw(PYdnZ=+^PUSc>lsB5l!{=Q~44<{8)m{*wibo8;VHk|;2!ZVYXcs${(gA5MnUd_3=OioP5ILez=bsrwt1=XCk>C~47*EQA< zl}?4aCcsselB8Cie&_A8{KK+`y?o3be{D@NM7^0aulcm$xoo8 zQop~Vt}f7oEfj#t>rF>x-S_tm<(7n8c2H4#x1hZI{LCY6Xc!pVhn<8iaz%EwezV_8){gl?2Z81$`9>Tq|lxU=N~BUjM$@`k~EaHzu~O%eqPxESE(ZIP(|_^-d>+ikY;m zS}w#qF2Z#D>83<)tpHHGcLSbooir(y8m_l*Bv>xq3Nb!R7XZMqC*6(4nee8RGrUfe z_p2h+^YBozRX;q#{HeMqWdODOQWo2f4z(_m%zqUP7J16A7dn8LqewFhds@j1SA{`N+n9--)sb z7>8IwMZ=)z`pz#C+6e&o!lQj#mEdX>WFI-^vCDeD|6L$dzduqFx;Gd?EMqt}BzZS(+|F-&Ts64nc zIdU2IPPrGB^eZukj9_Q zo!Hlg(Bj)`z*^pOY=)L7w6%s55*!W~#R0rX=nk9Z$NPNV?J{Dn?dRcTZ?W-qT_BILGxc{p1H)6yZ*+BjL_; zu;?_5d^u`B9GQugQGXBlXsv05`xY|xuJqOuVxnr$Ak{j%w#$SvUSLm8mkn*pNWm!G zr?L0ZPgV`&I2E6;RkXA-3D$QO{UV~TR@?p)`iX!d{414&04rstlJAdet9Yx`GXRea zTD0l}LsbU2{Qt8kvCEx!Jq+pe?Ih?#dOzlSSG~hd7uR(k7{JEFvF_}B=gb$EucfBe zS*-J7)^cKLjWL)7QPI#4jN*OY-EcWbYrFjqZSLf~sSYUTWe)ImH^XkyjsMGm*d~v+ z`h2!qQyMQyyFp--_yk_9wA%{w^Pz6OfLGIVtSTS@bO)9!;>JvuX=zipkVNu*tiYzQ z)m*&J2xdj9IFO&kMKp+YXA=6wk^-$(I(l%3gEWvCqN(%ZUn7=omR{btmoA&u1jQZ! z!U5!Gp87>5(^*S&OM2qOjiwjR`3Zbev&Nz-|6->bq78kCb5B3{V?qbYI#9~i!ohW2 zoalFVp@!k?;ru4)cqB-~U1s*UIZN{M6G@h=^~;bP#